12#include <yarp/rosmsg/std_msgs/Header.h>
13#include <yarp/rosmsg/sensor_msgs/PointField.h>
39 if (!config.
check(
"period",
"refresh period of the broadcasted values in s")) {
45 period = config.
find(
"period").asFloat64();
49 if (!config.
check(
"node_name",
"the name of the ros node")) {
53 nodeName = config.
find(
"node_name").asString();
57 if (!config.
check(
"topic_name",
"the name of the ros node")) {
61 pointCloudTopicName = config.
find(
"topic_name").asString();
64 if (!config.
check(
"frame_id",
"the name of the ros node")) {
68 frameId = config.
find(
"frame_id").asString();
73 if (!publisherPort_pointCloud.
topic(pointCloudTopicName))
115 poly->
view(sensor_p);
119 if(sensor_p ==
nullptr)
143bool RGBDToPointCloudSensor_nws_ros::writeData()
193 PointCloud2Type&
pc2Ros = publisherPort_pointCloud.
prepare();
195 yarp::rosmsg::std_msgs::Header
headerRos;
202 std::vector<yarp::rosmsg::sensor_msgs::PointField>
pointFieldRos;
203 pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField());
204 pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField());
205 pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField());
206 pointFieldRos.push_back(yarp::rosmsg::sensor_msgs::PointField());
235 publisherPort_pointCloud.
write();
247 if (sensor_p!=
nullptr)
251 switch (sensorStatus)
const yarp::os::LogComponent & RGBDTOPOINTCLOUDSENSORNWSROS()
constexpr double DEFAULT_THREAD_PERIOD
bool open(yarp::os::Searchable ¶ms) override
Device driver interface.
bool attach(yarp::dev::PolyDriver *poly) override
Specify which sensor this thread has to read from.
void threadRelease() override
Release method.
bool threadInit() override
Initialization method.
bool close() override
Close the DeviceDriver.
bool detach() override
WrapperSingle interface.
~RGBDToPointCloudSensor_nws_ros() override
RGBDToPointCloudSensor_nws_ros()
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
bool getRgbIntrinsicParam(yarp::os::Property &intrinsic) override=0
Get the intrinsic parameters of the rgb camera.
virtual bool getImages(yarp::sig::FlexImage &colorFrame, yarp::sig::ImageOf< yarp::sig::PixelFloat > &depthFrame, yarp::os::Stamp *colorStamp=nullptr, yarp::os::Stamp *depthStamp=nullptr)=0
Get the both the color and depth frame in a single call.
virtual RGBDSensor_status getSensorStatus()=0
Get the surrent status of the sensor, using enum type.
A container for a device driver.
A mini-server for performing network communication in the background.
void interrupt()
interrupt delegates the call to the Node port interrupt.
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
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.
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.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
A base class for nested structures that can be searched.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
double getTime() const
Get the time stamp.
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.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
An interface to the operating system, including Port based communication.
yarp::sig::PointCloud< T1 > depthRgbToPC(const yarp::sig::ImageOf< yarp::sig::PixelFloat > &depth, const yarp::sig::ImageOf< T2 > &color, const yarp::sig::IntrinsicParams &intrinsic, const yarp::sig::utils::OrganizationType organizationType=yarp::sig::utils::OrganizationType::Organized)
depthRgbToPC, compute the colored PointCloud given depth image, color image and the intrinsic paramet...
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).