6#define _USE_MATH_DEFINES
25#define DEG2RAD M_PI/180.0
57 m_info =
"LaserFromPointCloud device";
66 m_pointcloud_max_distance = 10.0;
71 m_laser_data.resize(m_sensorsNum, 0.0);
78 m_transform_mtrx.resize(4,4);
79 m_transform_mtrx.eye();
82 m_ground_frame_id =
"/ground_frame";
83 m_camera_frame_id =
"/depth_camera_frame";
86 bool bpcr = config.check(
"POINTCLOUD_QUALITY");
95 bool bpc = config.check(
"Z_CLIPPING_PLANES");
105 yCInfo(
LASER_FROM_POINTCLOUD) <<
"Z clipping planes (floor,ceiling) have been set to ("<< m_floor_height <<
","<< m_ceiling_height <<
")";
107 if (this->parseConfiguration(config) ==
false)
115 if(!config.check(
"TRANSFORM_CLIENT"))
120 tcprop.fromString(config.findGroup(
"TRANSFORM_CLIENT").toString());
121 tcprop.put(
"device",
"transformClient");
124 if (!m_tc_driver.isValid())
129 m_tc_driver.view(m_iTc);
140 if(!config.check(
"RGBD_SENSOR_CLIENT"))
145 prop.
fromString(config.findGroup(
"RGBD_SENSOR_CLIENT").toString());
146 prop.
put(
"device",
"RGBDSensorClient");
149 m_rgbd_driver.
open(prop);
150 if (!m_rgbd_driver.isValid())
155 m_rgbd_driver.view(m_iRGBD);
164 m_depth_width = m_iRGBD->getRgbWidth();
165 m_depth_height = m_iRGBD->getRgbHeight();
166 bool propintr = m_iRGBD->getDepthIntrinsicParam(m_propIntrinsics);
169 m_intrinsics.fromProperty(m_propIntrinsics);
236 for (
size_t i=0;
i<
pc.size();
i++)
238 auto v1 =
pc(
i).toVector4();
275 const double myinf = std::numeric_limits<double>::infinity();
276 const double mynan = std::nan(
"");
326 data_left.set_cartesian(left[0], left[1]);
388 for (
size_t i = 0;
i <
pc.size();
i++)
416 theta = theta * 180 /
M_PI;
419 }
else if (theta > 360) {
laserFromPointCloud: Documentation to be added
void run() override
Loop function.
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
yarp::sig::IntrinsicParams m_intrinsics
bool setDistanceRange(double min, double max) override
set the device detection range.
std::string m_camera_frame_id
yarp::sig::utils::PCL_ROI m_pc_roi
std::string m_ground_frame_id
yarp::sig::Matrix m_transform_mtrx
bool close() override
Close the DeviceDriver.
yarp::sig::ImageOf< float > m_depth_image
bool setHorizontalResolution(double step) override
get the angular step between two measurements (if available)
void threadRelease() override
Release method.
bool acquireDataFromHW() override final
This method should be implemented by the user, and contain the logic to grab data from the hardware.
double m_pointcloud_max_distance
bool setScanLimits(double min, double max) override
set the scan angular range.
bool threadInit() override
Initialization method.
virtual bool getDepthImage(yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=0
Get the depth frame from the device.
virtual bool updateLidarData()
This utility method calls in sequence: grabDataFromHW(), updateTimestamp and applyLimitsOnLaserData()...
yarp::sig::Vector m_laser_data
bool close() override
Close the DeviceDriver.
bool isValid() const
Check if device is valid.
A mini-server for performing network communication in the background.
bool open(const std::string &name) override
Start port operation, with a specific name, with automatically-chosen network parameters.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
size_t width() const
Gets width of image in pixels.
unsigned char * getRawImage() const
Access to the internal image buffer.
size_t height() const
Gets height of image in pixels.
void set_cartesian(const double x, const double y)
void get_polar(double &rho, double &theta)
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
const yarp::os::LogComponent & LASER_FROM_POINTCLOUD()
void rotate_pc(yarp::sig::PointCloud< yarp::sig::DataXYZ > &pc, const yarp::sig::Matrix &m)
#define yCInfo(component,...)
#define yCError(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
double now()
Return the current time in seconds, relative to an arbitrary starting point.
void delay(double seconds)
Wait for a certain number of seconds.
yarp::sig::PointCloud< yarp::sig::DataXYZ > depthToPC(const yarp::sig::ImageOf< yarp::sig::PixelFloat > &depth, const yarp::sig::IntrinsicParams &intrinsic)
depthToPC, compute the PointCloud given depth image and the intrinsic parameters of the camera.
The main, catch-all namespace for YARP.
double focalLengthY
Result of the product of the physical focal length(mm) and the size sy of the individual imager eleme...
double focalLengthX
Result of the product of the physical focal length(mm) and the size sx of the individual imager eleme...
double principalPointX
Horizontal coordinate of the principal point of the image, as a pixel offset from the left edge.
double principalPointY
Vertical coordinate of the principal point of the image, as a pixel offset from the top edge.