YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RGBDRosConversionUtils.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#include <cmath>
7#include <algorithm>
8#include <iomanip>
9#include <cstdint>
10
12#include <yarp/os/Value.h>
13#include <yarp/sig/ImageUtils.h>
15
17#include "rosPixelCode.h"
18
19using namespace yarp::dev;
20using namespace yarp::sig;
21using namespace yarp::os;
23
24namespace {
25YARP_LOG_COMPONENT(RGBD_ROS, "yarp.device.RGBDRosConversion")
26}
27
29{
30 if (this->topic(cameradata_topic_name)==false)
31 {
32 yCError(RGBD_ROS) << "Error opening topic:" << cameradata_topic_name;
33 }
35 {
36 yCError(RGBD_ROS) << "Error opening topic:" << camerainfo_topic_name;
37 }
40 m_contains_rgb_data = false;
42}
48
50{
51 if (m_contains_rgb_data == false) { return false;}
52
53 //this blocks untils the first data is received;
54 /*size_t counter = 0;
55 while (m_contains_rgb_data == false)
56 {
57 yarp::os::Time::delay(0.1);
58 if (counter++ > 100) { yCDebug(RGBD_ROS) << "Waiting for incoming rgb data..."; counter = 0; }
59 }*/
60
61 m_port_mutex.lock();
62 data = m_lastRGBImage;
64 m_port_mutex.unlock();
65 return true;
66}
67
69{
70 if (m_contains_depth_data == false) { return false;}
71
72 //this blocks untils the first data is received;
73 /*size_t counter = 0;
74 while (m_contains_depth_data == false)
75 {
76 yarp::os::Time::delay(0.1);
77 if (counter++ > 100) { yCDebug(RGBD_ROS) << "Waiting for incoming depth data..."; counter = 0; }
78 }*/
79
80 m_port_mutex.lock();
81 data = m_lastDepthImage;
83 m_port_mutex.unlock();
84 return true;
85}
86
88{
89 return m_lastDepthImage.width();
90}
91
93{
94 return m_lastDepthImage.height();
95}
96
97void commonImageProcessor::onRead(yarp::rosmsg::sensor_msgs::Image& v)
98{
99 m_port_mutex.lock();
103 {
105 m_lastRGBImage.resize(v.width, v.height);
106 size_t c = 0;
107 for (auto it = v.data.begin(); it != v.data.end(); it++)
108 {
110 }
112 m_contains_rgb_data = true;
113 }
114 else if (v.encoding == TYPE_16UC1)
115 {
116 m_lastDepthImage.resize(v.width, v.height);
117 size_t c = 0;
118 uint16_t* p = (uint16_t*)(v.data.data());
119 uint16_t* siz = (uint16_t*)(v.data.data()) + (v.data.size() / sizeof(uint16_t));
120 int count = 0;
121 for (; p < siz; p++)
122 {
123 float value = float(*p) / 1000.0;
124 ((float*)(m_lastDepthImage.getRawImage()))[c++] = value;
125 count++;
126 }
129 }
130 else if (v.encoding == TYPE_32FC1)
131 {
132 m_lastDepthImage.resize(v.width, v.height);
133 size_t c = 0;
134 for (auto it = v.data.begin(); it != v.data.end(); it++)
135 {
137 }
140 }
141 else
142 {
143 yCError(RGBD_ROS) << "Unsupported rgb/depth format:" << v.encoding;
144 }
145 m_port_mutex.unlock();
146}
147
148bool commonImageProcessor::getFOV(double& horizontalFov, double& verticalFov) const
149{
150 yarp::rosmsg::sensor_msgs::CameraInfo* tmp = m_subscriber_camera_info.read(true);
153 params.focalLengthX = m_lastCameraInfo.K[0];
154 params.focalLengthY = m_lastCameraInfo.K[4];
155 params.principalPointX = m_lastCameraInfo.K[2];
156 params.principalPointY = m_lastCameraInfo.K[5];
157 yCError(RGBD_ROS) << "getIntrinsicParam not yet implemented";
158 return false;
159}
160
162{
163 yarp::rosmsg::sensor_msgs::CameraInfo* tmp = m_subscriber_camera_info.read(true);
165 intrinsic.clear();
167 params.focalLengthX = m_lastCameraInfo.K[0];
168 params.focalLengthY = m_lastCameraInfo.K[4];
169 params.principalPointX = m_lastCameraInfo.K[2];
170 params.principalPointY = m_lastCameraInfo.K[5];
171 // distortion model
172 if (m_lastCameraInfo.distortion_model=="plumb_bob")
173 {
174 params.distortionModel.type = YarpDistortion::YARP_PLUMB_BOB;
175 params.distortionModel.k1 = m_lastCameraInfo.D[0];
176 params.distortionModel.k2 = m_lastCameraInfo.D[1];
177 params.distortionModel.t1 = m_lastCameraInfo.D[2];
178 params.distortionModel.t2 = m_lastCameraInfo.D[3];
179 params.distortionModel.k3 = m_lastCameraInfo.D[4];
180 }
181 else
182 {
183 yCError(RGBD_ROS) << "Unsupported distortion model";
184 }
185 params.toProperty(intrinsic);
186 return false;
187}
188
189
196
198{
199 dest.setQuantum(src.getQuantum());
200 dest.setExternal(src.getRawImage(), src.width(), src.height());
201}
202
204 yarp::rosmsg::sensor_msgs::Image& dest,
205 const std::string& frame_id,
206 const yarp::rosmsg::TickTime& timeStamp,
207 const unsigned int& seq)
208{
209 dest.data.resize(src.getRawImageSize());
210 dest.width = src.width();
211 dest.height = src.height();
212 memcpy(dest.data.data(), src.getRawImage(), src.getRawImageSize());
214 dest.step = src.getRowSize();
215 dest.header.frame_id = frame_id;
216 dest.header.stamp = timeStamp;
217 dest.header.seq = seq;
218 dest.is_bigendian = 0;
219}
220
222 yarp::rosmsg::sensor_msgs::Image& dest,
223 const std::string& frame_id,
224 const yarp::rosmsg::TickTime& timeStamp,
225 const unsigned int& seq)
226{
227 dest.data.resize(src.getRawImageSize());
228
229 dest.width = src.width();
230 dest.height = src.height();
231
232 memcpy(dest.data.data(), src.getRawImage(), src.getRawImageSize());
233
235 dest.step = src.getRowSize();
236 dest.header.frame_id = frame_id;
237 dest.header.stamp = timeStamp;
238 dest.header.seq = seq;
239 dest.is_bigendian = 0;
240}
@ VOCAB_PIXEL_BGR
Definition Image.h:49
@ VOCAB_PIXEL_RGB
Definition Image.h:44
bool getFOV(double &horizontalFov, double &verticalFov) const
virtual void onRead(yarp::rosmsg::sensor_msgs::Image &v) override
commonImageProcessor(std::string data_topic_name, std::string camera_info_topic_name)
bool getLastDepthData(yarp::sig::ImageOf< yarp::sig::PixelFloat > &data, yarp::os::Stamp &stmp)
bool getIntrinsicParam(yarp::os::Property &intrinsic) const
bool getLastRGBData(yarp::sig::FlexImage &data, yarp::os::Stamp &stmp)
yarp::os::Subscriber< yarp::rosmsg::sensor_msgs::CameraInfo > m_subscriber_camera_info
A mini-server for performing network communication in the background.
A class for storing options and configuration information.
Definition Property.h:33
void clear()
Remove all associations.
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition Stamp.cpp:124
T * read(bool shouldWait=true)
Read a message from the port.
Definition Subscriber.h:113
bool topic(const std::string &name)
Set topic to subscribe to.
Definition Subscriber.h:62
Image class with user control of representation details.
Definition Image.h:363
void setQuantum(size_t imgQuantum)
Definition Image.h:378
void setPixelCode(int imgPixelCode)
Definition Image.h:366
Typed image class.
Definition Image.h:605
int getPixelCode() const override
Gets pixel type identifier.
Definition Image.h:721
size_t width() const
Gets width of image in pixels.
Definition Image.h:171
void setExternal(const void *data, size_t imgWidth, size_t imgHeight)
Use this to wrap an external image.
Definition Image.cpp:691
size_t getRowSize() const
Size of the underlying image buffer rows.
Definition Image.h:197
unsigned char * getRawImage() const
Access to the internal image buffer.
Definition Image.cpp:479
size_t getRawImageSize() const
Access to the internal buffer size information (this is how much memory has been allocated for the im...
Definition Image.cpp:488
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
Definition Image.cpp:402
size_t getQuantum() const
The size of a row is constrained to be a multiple of the "quantum".
Definition Image.h:204
size_t height() const
Gets height of image in pixels.
Definition Image.h:177
virtual int getPixelCode() const
Gets pixel type identifier.
Definition Image.cpp:390
#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)
For streams capable of holding different kinds of content, check what they actually have.
Definition jointData.cpp:13
An interface to the operating system, including Port based communication.
#define TYPE_16UC1
#define TYPE_32FC1
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.