6 #define _USE_MATH_DEFINES
29 #define DEG2RAD M_PI/180.0
86 rosPC_data.
fields.resize(3);
87 rosPC_data.
fields[0].name =
"x";
88 rosPC_data.
fields[0].offset = 0;
89 rosPC_data.
fields[0].datatype = 7;
90 rosPC_data.
fields[0].count = 1;
92 rosPC_data.
fields[1].name =
"y";
93 rosPC_data.
fields[1].offset = 4;
94 rosPC_data.
fields[1].datatype = 7;
95 rosPC_data.
fields[1].count = 1;
97 rosPC_data.
fields[2].name =
"z";
98 rosPC_data.
fields[2].offset = 8;
99 rosPC_data.
fields[2].datatype = 7;
100 rosPC_data.
fields[2].count = 1;
102 #if defined(YARP_BIG_ENDIAN)
104 #elif defined(YARP_LITTLE_ENDIAN)
107 #error "Cannot detect endianness"
124 unsigned char* rpointer = rosPC_data.
data.data();
129 for (; elem<pc.
size()*3*4; elem++)
134 if (elem%12==0) { ypointer+=4; yelem+=4;}
149 m_info =
"LaserFromPointCloud device";
178 if (config.
check(
"publish_ROS_pointcloud"))
184 bool bpcr = config.
check(
"POINTCLOUD_QUALITY");
193 bool bpc = config.
check(
"Z_CLIPPING_PLANES");
213 if(!config.
check(
"TRANSFORM_CLIENT"))
219 tcprop.
put(
"device",
"transformClient");
238 if(!config.
check(
"RGBD_SENSOR_CLIENT"))
244 prop.
put(
"device",
"RGBDSensorClient");
269 PeriodicThread::start();
283 PeriodicThread::stop();
299 std::lock_guard<std::mutex> guard(
m_mutex);
308 std::lock_guard<std::mutex> guard(
m_mutex);
315 std::lock_guard<std::mutex> guard(
m_mutex);
322 std::lock_guard<std::mutex> guard(
m_mutex);
340 for (
size_t i=0; i<pc.
size(); i++)
342 auto v1 = pc(i).toVector4();
360 if (depth_ok ==
false)
379 const double myinf = std::numeric_limits<double>::infinity();
380 const double mynan = std::nan(
"");
403 if (frame_exists ==
false)
435 data_left.
get_polar(left_dist, left_theta);
439 data_right.
get_polar(right_dist, right_theta);
441 bool left_elem_neg = 0;
442 bool right_elem_neg = 0;
444 left_theta = left_theta * 180 /
M_PI;
445 right_theta = right_theta * 180 /
M_PI;
451 }
else if (left_theta > 360) {
460 }
else if (right_theta > 360) {
466 std::lock_guard<std::mutex> guard(
m_mutex);
476 if ((!left_elem_neg) && (right_elem_neg))
478 for (
size_t i = 0; i < left_elem; i++)
489 for (
size_t i = right_elem; i < left_elem; i++)
496 for (
size_t i = 0; i < pc.
size(); i++)
524 theta = theta * 180 /
M_PI;
527 }
else if (theta > 360) {
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 measurments (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.
yarp::os::Property m_propIntrinsics
double m_pointcloud_max_distance
bool setScanLimits(double min, double max) override
set the scan angular range.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool threadInit() override
Initialization method.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getDepthImage(yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthImage, yarp::os::Stamp *timeStamp=nullptr)=0
Get the depth frame from the device.
int getRgbWidth() override=0
Return the width of each frame.
int getRgbHeight() override=0
Return the height of each frame.
bool getDepthIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the depth camera.
void set_cartesian(const double x, const double y)
void get_polar(double &rho, double &theta)
virtual bool updateLidarData()
This utility method calls in sequence: grabDataFromHW(), updateTimestamp and applyLimitsOnLaserData()...
bool parseConfiguration(yarp::os::Searchable &config)
yarp::sig::Vector m_laser_data
bool close() override
Close the DeviceDriver.
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
A class for storing options and configuration information.
std::string toString() const override
Return a standard text representation of the content of the object.
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 port specialized for publishing data of a constant type on a topic.
bool topic(const std::string &name)
Set topic to publish to.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual std::string asString() const
Get string value.
yarp::rosmsg::std_msgs::Header header
std::vector< std::uint8_t > data
std::vector< yarp::rosmsg::sensor_msgs::PointField > fields
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 resize(size_t r, size_t c)
Resize the matrix, if matrix is not empty preserve old content.
const Matrix & eye()
Build an identity matrix, don't resize.
virtual size_t width() const
virtual size_t height() const
const char * getRawData() const override
Get the pointer to the data.
size_t size() const override
void resize(size_t size) override
Resize the vector.
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
void ros_compute_and_send_pc(const yarp::sig::PointCloud< yarp::sig::DataXYZ > &pc, std::string frame_id)
const yarp::os::LogComponent & LASER_FROM_POINTCLOUD()
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::PointCloud2 > * pointCloud_outTopic
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::rosmsg::sensor_msgs::PointCloud2 PointCloud2
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...
void fromProperty(const yarp::os::Property &intrinsic)
fromProperty, fill the struct using the data stored in a Property.
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.