28 commonImageProcessor::commonImageProcessor(std::string cameradata_topic_name, std::string camerainfo_topic_name)
30 if (this->topic(cameradata_topic_name)==
false)
32 yCError(RGBD_ROS) <<
"Error opening topic:" << cameradata_topic_name;
34 if (m_subscriber_camera_info.topic(camerainfo_topic_name) ==
false)
36 yCError(RGBD_ROS) <<
"Error opening topic:" << camerainfo_topic_name;
38 m_cameradata_topic_name = cameradata_topic_name;
39 m_camerainfo_topic_name = camerainfo_topic_name;
40 m_contains_rgb_data =
false;
41 m_contains_depth_data =
false;
43 commonImageProcessor::~commonImageProcessor()
46 m_subscriber_camera_info.close();
51 if (m_contains_rgb_data ==
false) {
return false;}
62 data = m_lastRGBImage;
64 m_port_mutex.unlock();
70 if (m_contains_depth_data ==
false) {
return false;}
81 data = m_lastDepthImage;
83 m_port_mutex.unlock();
87 size_t commonImageProcessor::getWidth()
const
89 return m_lastDepthImage.width();
92 size_t commonImageProcessor::getHeight()
const
94 return m_lastDepthImage.height();
104 m_lastRGBImage.setPixelCode(yarp_pixcode);
107 for (
auto it = v.
data.begin(); it != v.
data.end(); it++)
109 m_lastRGBImage.getRawImage()[c++]=*it;
111 m_lastStamp.update();
112 m_contains_rgb_data =
true;
118 uint16_t* p = (uint16_t*)(v.
data.data());
119 uint16_t* siz = (uint16_t*)(v.
data.data()) + (v.
data.size() /
sizeof(uint16_t));
123 float value = float(*p) / 1000.0;
124 ((
float*)(m_lastDepthImage.getRawImage()))[c++] = value;
127 m_lastStamp.update();
128 m_contains_depth_data =
true;
134 for (
auto it = v.
data.begin(); it != v.
data.end(); it++)
136 m_lastDepthImage.getRawImage()[c++] = *it;
138 m_lastStamp.update();
139 m_contains_depth_data =
true;
145 m_port_mutex.unlock();
148 bool commonImageProcessor::getFOV(
double& horizontalFov,
double& verticalFov)
const
151 m_lastCameraInfo = *tmp;
157 yCError(RGBD_ROS) <<
"getIntrinsicParam not yet implemented";
164 m_lastCameraInfo = *tmp;
172 if (m_lastCameraInfo.distortion_model==
"plumb_bob")
183 yCError(RGBD_ROS) <<
"Unsupported distortion model";
205 const std::string& frame_id,
207 const unsigned int& seq)
223 const std::string& frame_id,
225 const unsigned int& seq)
A class for storing options and configuration information.
void clear()
Remove all associations.
An abstraction for a time stamp and/or sequence number.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
std::vector< std::uint8_t > data
yarp::rosmsg::std_msgs::Header header
std::uint8_t is_bigendian
Image class with user control of representation details.
void setQuantum(size_t imgQuantum)
void setPixelCode(int imgPixelCode)
int getPixelCode() const override
Gets pixel type identifier.
void setQuantum(size_t imgQuantum)
size_t width() const
Gets width of image in pixels.
void setExternal(const void *data, size_t imgWidth, size_t imgHeight)
Use this to wrap an external image.
size_t getRowSize() const
Size of the underlying image buffer rows.
unsigned char * getRawImage() const
Access to the internal image buffer.
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
size_t getQuantum() const
The size of a row is constrained to be a multiple of the "quantum".
size_t height() const
Gets height of image in pixels.
virtual int getPixelCode() const
Gets pixel type identifier.
#define yCError(component,...)
#define YARP_LOG_COMPONENT(name,...)
void shallowCopyImages(const yarp::sig::FlexImage &src, yarp::sig::FlexImage &dest)
void deepCopyImages(const yarp::sig::FlexImage &src, yarp::rosmsg::sensor_msgs::Image &dest, const std::string &frame_id, const yarp::rosmsg::TickTime &timeStamp, const unsigned int &seq)
std::string yarp2RosPixelCode(int code)
int Ros2YarpPixelCode(const std::string &roscode)
An interface for the device drivers.
An interface to the operating system, including Port based communication.
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).
double focalLengthY
Result of the product of the physical focal length(mm) and the size sy of the individual imager eleme...
DistortionModel distortionModel
Distortion model of the image.
double focalLengthX
Result of the product of the physical focal length(mm) and the size sx of the individual imager eleme...
void toProperty(yarp::os::Property &intrinsic) const
toProperty, convert the struct to a Property.
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.