18 #include <librealsense2/rsutil.h>
34 constexpr
char depthRes [] =
"depthResolution";
35 constexpr
char rgbRes [] =
"rgbResolution";
42 static std::map<std::string, RGBDSensorParamParser::RGBDParam>
params_map =
55 {
"None", RS2_STREAM_ANY},
56 {
"RGB", RS2_STREAM_COLOR},
57 {
"Depth", RS2_STREAM_DEPTH}
65 ss <<
"Device information: " << std::endl;
67 for (
int i = 0; i < static_cast<int>(RS2_CAMERA_INFO_COUNT); i++)
69 auto info_type =
static_cast<rs2_camera_info
>(i);
70 ss <<
" " << std::left << std::setw(20) << info_type <<
" : ";
72 if (dev.supports(info_type))
73 ss << dev.get_info(info_type) << std::endl;
75 ss <<
"N/A" << std::endl;
86 if (sensor.is<rs2::depth_sensor>())
87 yCInfo(REALSENSE2) <<
"Depth sensor supports the following options:\n";
88 else if (sensor.get_stream_profiles()[0].stream_type() == RS2_STREAM_COLOR)
89 yCInfo(REALSENSE2) <<
"RGB camera supports the following options:\n";
91 yCInfo(REALSENSE2) <<
"Sensor supports the following options:\n";
95 for (
int i = 0; i < static_cast<int>(RS2_OPTION_COUNT); i++)
97 auto option_type =
static_cast<rs2_option
>(i);
103 if (sensor.supports(option_type))
105 std::cout <<
" " << option_type;
106 std::cout << std::endl;
109 const char* description = sensor.get_option_description(option_type);
110 std::cout <<
" Description : " << description << std::endl;
113 float current_value = sensor.get_option(option_type);
114 std::cout <<
" Current Value : " << current_value << std::endl;
118 std::cout<<std::endl;
121 static bool isSupportedFormat(
const rs2::sensor &sensor,
const int width,
const int height,
const int fps,
bool verbose =
false)
124 std::vector<rs2::stream_profile> stream_profiles = sensor.get_stream_profiles();
126 std::map<std::pair<rs2_stream, int>,
int> unique_streams;
127 for (
auto&& sp : stream_profiles)
129 unique_streams[std::make_pair(sp.stream_type(), sp.stream_index())]++;
134 std::cout <<
"Sensor consists of " << unique_streams.size() <<
" streams: " << std::endl;
135 for (
size_t i = 0; i < unique_streams.size(); i++)
137 auto it = unique_streams.begin();
139 std::cout <<
" - " << it->first.first <<
" #" << it->first.second << std::endl;
141 std::cout <<
"Sensor provides the following stream profiles:" << std::endl;
147 for (
const rs2::stream_profile& stream_profile : stream_profiles)
151 rs2_stream stream_data_type = stream_profile.stream_type();
153 int stream_index = stream_profile.stream_index();
155 std::cout << std::setw(3) << profile_num <<
": " << stream_data_type <<
" #" << stream_index;
161 if (stream_profile.is<rs2::video_stream_profile>())
164 rs2::video_stream_profile video_stream_profile = stream_profile.as<rs2::video_stream_profile>();
170 std::cout <<
" (Video Stream: " << video_stream_profile.format() <<
" " <<
171 video_stream_profile.width() <<
"x" << video_stream_profile.height() <<
"@ " << video_stream_profile.fps() <<
"Hz)";
172 std::cout << std::endl;
175 if(video_stream_profile.width() == width && video_stream_profile.height() == height && video_stream_profile.fps() == fps)
185 static bool optionPerc2Value(rs2_option option,
const rs2::sensor* sensor,
const float& perc,
float& value)
193 rs2::option_range optionRange = sensor->get_option_range(option);
194 value =(float) (perc * (optionRange.max - optionRange.min) + optionRange.min);
197 catch (
const rs2::error& e)
201 yCError(REALSENSE2) <<
"Failed to get option " << option <<
" range. (" << e.what() <<
")";
208 static bool optionValue2Perc(rs2_option option,
const rs2::sensor* sensor,
float& perc,
const float& value)
216 rs2::option_range optionRange = sensor->get_option_range(option);
217 perc =(float) ((value - optionRange.min) / (optionRange.max - optionRange.min));
220 catch (
const rs2::error& e)
224 yCError(REALSENSE2) <<
"Failed to get option " << option <<
" range. (" << e.what() <<
")";
233 static bool setOption(rs2_option option,
const rs2::sensor* sensor,
float value)
242 if (!sensor->supports(option))
244 yCError(REALSENSE2) <<
"The option" << rs2_option_to_string(option) <<
"is not supported by this sensor";
251 sensor->set_option(option, value);
253 catch (
const rs2::error& e)
257 yCError(REALSENSE2) <<
"Failed to set option " << rs2_option_to_string(option) <<
". (" << e.what() <<
")";
263 static bool getOption(rs2_option option,
const rs2::sensor *sensor,
float &value)
271 if (!sensor->supports(option))
273 yCError(REALSENSE2) <<
"The option" << rs2_option_to_string(option) <<
"is not supported by this sensor";
280 value = sensor->get_option(option);
282 catch (
const rs2::error& e)
286 yCError(REALSENSE2) <<
"Failed to get option " << rs2_option_to_string(option) <<
". (" << e.what() <<
")";
296 case (RS2_FORMAT_RGB8):
299 case (RS2_FORMAT_BGR8):
302 case (RS2_FORMAT_Z16):
305 case (RS2_FORMAT_DISPARITY16):
308 case (RS2_FORMAT_RGBA8):
311 case (RS2_FORMAT_BGRA8):
314 case (RS2_FORMAT_Y8):
317 case (RS2_FORMAT_Y16):
320 case (RS2_FORMAT_RAW16):
323 case (RS2_FORMAT_RAW8):
333 size_t bytes_per_pixel = 0;
336 case RS2_FORMAT_RAW8:
341 case RS2_FORMAT_DISPARITY16:
343 case RS2_FORMAT_RAW16:
346 case RS2_FORMAT_RGB8:
347 case RS2_FORMAT_BGR8:
350 case RS2_FORMAT_RGBA8:
351 case RS2_FORMAT_BGRA8:
357 return bytes_per_pixel;
363 case RS2_DISTORTION_BROWN_CONRADY:
364 return YarpDistortion::YARP_PLUM_BOB;
366 return YarpDistortion::YARP_UNSUPPORTED;
373 yCError(REALSENSE2) << error.c_str();
398 if (extrinsic.
cols() != 4 || extrinsic.
rows() != 4)
400 yCError(REALSENSE2) <<
"Extrinsic matrix is not 4x4";
406 for (
size_t j=0; j<extrinsic.
rows() - 1; j++)
408 for (
size_t i=0; i<extrinsic.
cols() - 1; i++)
410 extrinsic[j][i] = values.rotation[i + j*extrinsic.
cols()];
414 extrinsic[0][3] = values.translation[0];
415 extrinsic[1][3] = values.translation[1];
416 extrinsic[2][3] = values.translation[2];
422 m_paramParser(), m_verbose(false),
423 m_initialized(false), m_stereoMode(false),
424 m_needAlignment(true), m_fps(0),
448 catch (
const rs2::error& e)
450 yCError(REALSENSE2) <<
"Failed to start the pipeline:"<<
"(" << e.what() <<
")";
463 catch (
const rs2::error& e)
465 yCError(REALSENSE2) <<
"Failed to stop the pipeline:"<<
"(" << e.what() <<
")";
474 std::lock_guard<std::mutex> guard(
m_mutex);
514 yCWarning(REALSENSE2)<<
"Format not supported, use --verbose for more details. Setting the fallback format";
523 yCError(REALSENSE2)<<
"Missing depthResolution or rgbResolution from [SETTINGS]";
531 m_cfg.enable_stream(RS2_STREAM_COLOR, colorW, colorH, RS2_FORMAT_RGB8,
m_fps);
532 m_cfg.enable_stream(RS2_STREAM_DEPTH, depthW, depthH, RS2_FORMAT_Z16,
m_fps);
534 m_cfg.enable_stream(RS2_STREAM_INFRARED, 1, colorW, colorH, RS2_FORMAT_Y8,
m_fps);
535 m_cfg.enable_stream(RS2_STREAM_INFRARED, 2, colorW, colorH, RS2_FORMAT_Y8,
m_fps);
542 yCInfo(REALSENSE2) <<
"Sensor warm-up...";
543 for (
int i = 0; i < 30; i++)
547 yCInfo(REALSENSE2) <<
"Device ready!";
549 if (
m_ctx.query_devices().size() == 0)
551 yCError(REALSENSE2) <<
"No device connected, please connect a RealSense device";
553 rs2::device_hub device_hub(
m_ctx);
556 m_device = device_hub.wait_for_device();
571 yCInfo(REALSENSE2) <<
"Device consists of" <<
m_sensors.size() <<
"sensors. More infos using --verbose option";
582 if (m_sensor.is<rs2::depth_sensor>())
587 yCError(REALSENSE2) <<
"Failed to retrieve scale";
591 else if (m_sensor.get_stream_profiles()[0].stream_type() == RS2_STREAM_COLOR)
602 rs2::pipeline_profile pipeline_profile =
m_pipeline.get_active_profile();
603 rs2::video_stream_profile depth_stream_profile = rs2::video_stream_profile(pipeline_profile.get_stream(RS2_STREAM_DEPTH));
604 rs2::video_stream_profile color_stream_profile = rs2::video_stream_profile(pipeline_profile.get_stream(RS2_STREAM_COLOR));
608 m_depth_to_color = depth_stream_profile.get_extrinsics_to(color_stream_profile);
609 m_color_to_depth = color_stream_profile.get_extrinsics_to(depth_stream_profile);
612 rs2::video_stream_profile infrared_stream_profile = rs2::video_stream_profile(pipeline_profile.get_stream(RS2_STREAM_INFRARED));
655 yCWarning(REALSENSE2) <<
"Framerate not specified... setting 30 fps by default";
678 yCWarning(REALSENSE2) <<
"needAlignment parameter is deprecated, use alignmentFrame instead.";
693 auto alignmentFrameStr = v.
asString();
750 std::vector<RGBDSensorParamParser::RGBDParam*> params;
754 params.push_back(&(p.second));
758 if (config.
check(
"stereoMode")) {
764 yCError(REALSENSE2) <<
"Failed to parse the parameters";
770 yCError(REALSENSE2) <<
"Failed to initialize the realsense device";
797 yCWarning(REALSENSE2) <<
"getRgbSupportedConfigurations not implemented yet";
880 std::lock_guard<std::mutex> guard(
m_mutex);
892 horizontalFov = fov[0];
893 verticalFov = fov[1];
899 yCWarning(REALSENSE2) <<
"Mirroring not supported";
905 yCWarning(REALSENSE2) <<
"Mirroring not supported";
928 horizontalFov = fov[0];
929 verticalFov = fov[1];
975 yCWarning(REALSENSE2) <<
"Mirroring not supported";
981 yCWarning(REALSENSE2) <<
"Mirroring not supported";
992 std::lock_guard<std::mutex> guard(
m_mutex);
993 rs2::frameset data =
m_pipeline.wait_for_frames();
997 data = align.process(data);
999 return getImage(rgbImage, timeStamp, data);
1004 std::lock_guard<std::mutex> guard(
m_mutex);
1005 rs2::frameset data =
m_pipeline.wait_for_frames();
1009 data = align.process(data);
1016 rs2::video_frame color_frm = sourceFrame.get_color_frame();
1017 rs2_format format = color_frm.get_profile().format();
1020 size_t mem_to_wrt = color_frm.get_width() * color_frm.get_height() *
bytesPerPixel(format);
1024 yCError(REALSENSE2) <<
"Pixel Format not recognized";
1033 yCError(REALSENSE2) <<
"Device and local copy data size doesn't match";
1037 memcpy((
void*)Frame.
getRawImage(), (
void*)color_frm.get_data(), mem_to_wrt);
1039 if (timeStamp !=
nullptr)
1048 rs2::depth_frame depth_frm = sourceFrame.get_depth_frame();
1049 rs2_format format = depth_frm.get_profile().format();
1053 int w = depth_frm.get_width();
1054 int h = depth_frm.get_height();
1058 yCError(REALSENSE2) <<
"Pixel Format not recognized";
1064 float* rawImage = &Frame.
pixel(0,0);
1065 const auto * rawImageRs =(
const uint16_t *) depth_frm.get_data();
1067 for(
int i = 0; i < w * h; i++)
1069 rawImage[i] =
m_scale * rawImageRs[i];
1073 if (timeStamp !=
nullptr)
1082 std::lock_guard<std::mutex> guard(
m_mutex);
1083 rs2::frameset data =
m_pipeline.wait_for_frames();
1087 data = align.process(data);
1089 return getImage(colorFrame, colorStamp, data) &&
getImage(depthFrame, depthStamp, data);
1128 yCError(REALSENSE2) <<
"Feature not supported!";
1132 float valToSet = 0.0;
1185 yCError(REALSENSE2) <<
"Feature not supported!";
1190 yCError(REALSENSE2) <<
"Something went wrong setting the feature requested, run the device with --verbose for the supported options";
1205 yCError(REALSENSE2) <<
"Feature not supported!";
1209 float valToGet = 0.0;
1226 *value = (double)
m_fps;
1246 yCError(REALSENSE2) <<
"Feature not supported!";
1251 yCError(REALSENSE2) <<
"Something went wrong setting the feature requested, run the device with --verbose for the supported options";
1263 yCError(REALSENSE2) <<
"No 2-valued feature are supported";
1269 yCError(REALSENSE2) <<
"No 2-valued feature are supported";
1278 yCError(REALSENSE2) <<
"Feature not supported!";
1297 yCError(REALSENSE2) <<
"Feature not supported!";
1303 yCError(REALSENSE2) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1327 yCError(REALSENSE2) <<
"Feature not supported!";
1333 yCError(REALSENSE2) <<
"Feature does not have OnOff.. call hasOnOff() to know if a specific feature support OnOff mode";
1336 float response = 0.0;
1341 *isActive = (bool) response;
1345 *isActive = (bool) response;
1359 yCError(REALSENSE2) <<
"Feature not supported!";
1378 yCError(REALSENSE2) <<
"Feature not supported!";
1398 yCError(REALSENSE2) <<
"Feature not supported!";
1410 yCError(REALSENSE2) <<
"Feature not supported!";
1450 yCError(REALSENSE2) <<
"Feature does not have both auto and manual mode";
1459 yCError(REALSENSE2) <<
"Feature not supported!";
1479 else if (res == 1.0)
1495 yCError(REALSENSE2) <<
"Feature not supported!";
1501 yCError(REALSENSE2) <<
"Feature doesn't have OnePush";
1515 yCError(REALSENSE2)<<
"Infrared stereo stream not enabled";
1520 std::lock_guard<std::mutex> guard(
m_mutex);
1521 rs2::frameset data =
m_pipeline.wait_for_frames();
1523 rs2::video_frame frm1 = data.get_infrared_frame(1);
1524 rs2::video_frame frm2 = data.get_infrared_frame(2);
1530 yCError(REALSENSE2) <<
"Expecting Pixel Format MONO";
1536 imgL.
setExternal((
unsigned char*) (frm1.get_data()), frm1.get_width(), frm1.get_height());
1537 imgR.
setExternal((
unsigned char*) (frm2.get_data()), frm2.get_width(), frm2.get_height());
@ YARP_FEATURE_FRAME_RATE
@ YARP_FEATURE_WHITE_BALANCE
@ YARP_FEATURE_SATURATION
yarp::os::Stamp m_depth_stamp
bool setActive(int feature, bool onoff) override
Set the requested feature on or off.
bool setDepthClipPlanes(double nearPlane, double farPlane) override
Set the clipping planes of the sensor.
rs2_intrinsics m_infrared_intrin
RGBDSensor_status getSensorStatus() override
Get the surrent status of the sensor, using enum type.
bool hasManual(int feature, bool *hasManual) override
Check if the requested feature has the 'manual' mode.
rs2_intrinsics m_color_intrin
bool getRgbMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool getDepthImage(depthImage &depthImage, Stamp *timeStamp=nullptr) override
rs2::sensor * m_depth_sensor
bool getActive(int feature, bool *isActive) override
Get the current status of the feature, on or off.
std::vector< cameraFeature_id_t > m_supportedFeatures
bool close() override
Close the DeviceDriver.
bool setFramerate(const int _fps)
bool hasAuto(int feature, bool *hasAuto) override
Check if the requested feature has the 'auto' mode.
int height() const override
Return the height of each frame.
bool setDepthFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the depth camera.
bool hasFeature(int feature, bool *hasFeature) override
Check if camera has the requested feature (saturation, brightness ...
bool getCameraDescription(CameraDescriptor *camera) override
Get a basic description of the camera hw.
bool getRgbSupportedConfigurations(yarp::sig::VectorOf< yarp::dev::CameraConfig > &configurations) override
Get the possible configurations of the camera.
bool getMode(int feature, FeatureMode *mode) override
Get the current mode for the feature.
bool setDepthResolution(int width, int height) override
Set the resolution of the depth image from the camera.
bool setRgbFOV(double horizontalFov, double verticalFov) override
Set the field of view (FOV) of the rgb camera.
rs2::pipeline_profile m_profile
rs2_intrinsics m_depth_intrin
rs2_stream m_alignment_stream
int getDepthHeight() override
Return the height of each frame.
bool setRgbMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
rs2_extrinsics m_depth_to_color
double getDepthAccuracy() override
Get the minimum detectable variation in distance [meter].
bool setDepthMirroring(bool mirror) override
Set the mirroring setting of the sensor.
bool hasOnOff(int feature, bool *HasOnOff) override
Check if the camera has the ability to turn on/off the requested feature.
void updateTransformations()
bool hasOnePush(int feature, bool *hasOnePush) override
Check if the requested feature has the 'onePush' mode.
std::string getLastErrorMsg(Stamp *timeStamp=NULL) override
Return an error message in case of error.
int getDepthWidth() override
Return the height of each frame.
bool getRgbResolution(int &width, int &height) override
Get the resolution of the rgb image from the camera.
bool getDepthFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the depth camera.
bool setFeature(int feature, double value) override
Set the requested feature to a value (saturation, brightness ...
bool setOnePush(int feature) override
Set the requested feature to a value (saturation, brightness ...
bool setDepthAccuracy(double accuracy) override
Set the minimum detectable variation in distance [meter] when possible.
rs2::sensor * m_color_sensor
bool getRgbFOV(double &horizontalFov, double &verticalFov) override
Get the field of view (FOV) of the rgb camera.
bool getRgbImage(FlexImage &rgbImage, Stamp *timeStamp=nullptr) override
Get the rgb frame from the device.
rs2_extrinsics m_color_to_depth
bool getImages(FlexImage &colorFrame, depthImage &depthFrame, Stamp *colorStamp=NULL, Stamp *depthStamp=NULL) override
yarp::os::Stamp m_rgb_stamp
bool getExtrinsicParam(yarp::sig::Matrix &extrinsic) override
Get the extrinsic parameters from the device.
bool getRgbIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the rgb camera.
int getRgbHeight() override
Return the height of each frame.
bool getDepthIntrinsicParam(Property &intrinsic) override
Get the intrinsic parameters of the depth camera.
bool getImage(yarp::sig::ImageOf< yarp::sig::PixelMono > &image) override
Get a raw image from the frame grabber.
int width() const override
Return the width of each frame.
bool initializeRealsenseDevice()
int getRgbWidth() override
Return the width of each frame.
yarp::dev::RGBDSensorParamParser m_paramParser
bool setMode(int feature, FeatureMode mode) override
Set the requested mode for the feature.
std::vector< rs2::sensor > m_sensors
bool getFeature(int feature, double *value) override
Get the current value for the requested feature.
bool setRgbResolution(int width, int height) override
Set the resolution of the rgb image from the camera.
bool getDepthClipPlanes(double &nearPlane, double &farPlane) override
Get the clipping planes of the sensor.
bool getDepthMirroring(bool &mirror) override
Get the mirroring setting of the sensor.
bool parseParam(const yarp::os::Searchable &config, std::vector< RGBDParam * > ¶ms)
parseParam, parse the params stored in a Searchable.
yarp::sig::IntrinsicParams rgbIntrinsic
yarp::sig::IntrinsicParams depthIntrinsic
A class for storing options and configuration information.
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.
An abstraction for a time stamp and/or sequence number.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
A single value (typically within a Bottle).
virtual bool isString() const
Checks if value is a string.
virtual bool isBool() const
Checks if value is a boolean.
virtual bool asBool() const
Get boolean value.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual bool isInt32() const
Checks if value is a 32-bit integer.
virtual std::string asString() const
Get string value.
Image class with user control of representation details.
void setPixelCode(int imgPixelCode)
T & pixel(size_t x, size_t y)
void setExternal(const void *data, size_t imgWidth, size_t imgHeight)
Use this to wrap an external image.
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...
void resize(size_t imgWidth, size_t imgHeight)
Reallocate an image to be of a desired size, throwing away its current contents.
size_t cols() const
Return number of columns.
size_t rows() const
Return number of rows.
const Matrix & eye()
Build an identity matrix, don't resize.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
An interface to the operating system, including Port based communication.
bool horzConcat(const yarp::sig::Image &inImgL, const yarp::sig::Image &inImgR, yarp::sig::Image &outImg)
horzConcat, concatenate horizontally two images of the same size in one with double width.
YarpDistortion
The YarpDistortion enum to define the type of the distortion model of the camera.
constexpr char clipPlanes[]
static bool setOption(rs2_option option, const rs2::sensor *sensor, float value)
static int pixFormatToCode(const rs2_format p)
static void print_supported_options(const rs2::sensor &sensor)
static const std::map< std::string, rs2_stream > stringRSStreamMap
constexpr char needAlignment[]
static bool getOption(rs2_option option, const rs2::sensor *sensor, float &value)
static std::string get_device_information(const rs2::device &dev)
static bool optionValue2Perc(rs2_option option, const rs2::sensor *sensor, float &perc, const float &value)
static std::map< std::string, RGBDSensorParamParser::RGBDParam > params_map
static YarpDistortion rsDistToYarpDist(const rs2_distortion dist)
static bool setExtrinsicParam(Matrix &extrinsic, const rs2_extrinsics &values)
constexpr char enableEmitter[]
static bool setIntrinsic(Property &intrinsic, const rs2_intrinsics &values)
constexpr char framerate[]
constexpr char alignmentFrame[]
static size_t bytesPerPixel(const rs2_format format)
static void settingErrorMsg(const string &error, bool &ret)
static bool optionPerc2Value(rs2_option option, const rs2::sensor *sensor, const float &perc, float &value)
constexpr char depthRes[]
static bool isSupportedFormat(const rs2::sensor &sensor, const int width, const int height, const int fps, bool verbose=false)
constexpr char accuracy[]
std::string deviceDescription
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.