3 #include <boost/algorithm/string.hpp> 8 #include <dynamic_reconfigure/IntParameter.h> 9 #include <dynamic_reconfigure/Reconfigure.h> 10 #include <dynamic_reconfigure/Config.h> 16 #define STREAM_NAME(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << _stream_name[sip.first] << ((sip.second>0) ? std::to_string(sip.second) : ""))).str() 17 #define FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_frame")).str() 18 #define OPTICAL_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_optical_frame")).str() 19 #define ALIGNED_DEPTH_TO_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_aligned_depth_to_" << STREAM_NAME(sip) << "_frame")).str() 22 _publisher(imu_publisher), _pause_mode(false),
23 _waiting_list_size(waiting_list_size)
33 std::lock_guard<std::mutex> lock_guard(
_mutex);
53 std::lock_guard<std::mutex> lock_guard(
_mutex);
59 std::lock_guard<std::mutex> lock_guard(
_mutex);
79 ns.erase(std::remove(ns.begin(), ns.end(),
'/'), ns.end());
86 const std::string& serial_no) :
87 _is_running(true), _base_frame_id(
""), _node_handle(nodeHandle),
88 _pnh(privateNodeHandle), _dev(dev), _json_file_path(
""),
89 _serial_no(serial_no),
90 _is_initialized_time_base(false),
91 _namespace(getNamespaceStr())
153 std::set<std::string> module_names;
159 std::pair< std::set<std::string>::iterator,
bool>
res = module_names.insert(module_name);
177 std::map<std::string, std::vector<rs2::stream_profile> >
profiles;
178 std::map<std::string, rs2::sensor> active_sensors;
183 <<
" to " << module_name);
184 profiles[module_name].insert(profiles[module_name].
begin(),
190 for (
const std::pair<std::string, std::vector<rs2::stream_profile> >& sensor_profile : profiles)
192 std::string module_name = sensor_profile.first;
194 sensor.
open(sensor_profile.second);
204 std::set<std::string> module_names;
208 std::pair< std::set<std::string>::iterator,
bool>
res = module_names.insert(module_name);
224 std::vector<std::string> error_strings({
"RT IC2 Config error",
225 "Left IC2 Config error"});
230 if (error_strings.end() != std::find_if(error_strings.begin(), error_strings.end(), [&n] (std::string err)
268 std::thread
t = std::thread([=]()
284 return op_range.
max == 1.0f &&
285 op_range.
min == 0.0f &&
286 op_range.
step == 1.0f;
291 static const int MAX_ENUM_OPTION_VALUES(100);
292 static const float EPSILON(0.05);
295 if (abs((op_range.
step - 1)) > EPSILON || (op_range.
max > MAX_ENUM_OPTION_VALUES))
return false;
296 for (
auto i = op_range.
min;
i <= op_range.
max;
i += op_range.
step)
308 return (op_range.
step == 1.0);
313 std::map<std::string, int>
dict;
317 const auto op_range_min = int(op_range.
min);
318 const auto op_range_max = int(op_range.
max);
319 const auto op_range_step = int(op_range.
step);
320 for (
auto val = op_range_min;
val <= op_range_max;
val += op_range_step)
333 template <
typename K,
typename V>
334 std::ostream& operator<<(std::ostream& os, const std::map<K, V>&
m)
337 for (
const auto& kv :
m)
339 os <<
" {" << kv.first <<
": " << kv.second <<
'}';
352 return std::isalnum(c) || c ==
'/' || c ==
'_';
361 std::string fixed_name = original_name;
362 std::transform(fixed_name.begin(), fixed_name.end(), fixed_name.begin(),
363 [](
unsigned char c) {
return std::tolower(
c); });
364 std::replace_if(fixed_name.begin(), fixed_name.end(), [](
const char c) {
return !
isValidCharInName(
c); },
372 if (option_name ==
"left")
373 auto_exposure_roi.
min_x = new_value;
374 else if (option_name ==
"right")
375 auto_exposure_roi.max_x = new_value;
376 else if (option_name ==
"top")
377 auto_exposure_roi.min_y = new_value;
378 else if (option_name ==
"bottom")
379 auto_exposure_roi.max_y = new_value;
382 ROS_WARN_STREAM(
"Invalid option_name: " << option_name <<
" while setting auto exposure ROI.");
395 catch(
const std::runtime_error&
e)
402 const std::string option_name,
const int min_val,
const int max_val,
rs2::sensor sensor,
405 nh1.
param(option_name, *option_value, *option_value);
406 if (*option_value < min_val) *option_value = min_val;
407 if (*option_value > max_val) *option_value = max_val;
409 ddynrec->registerVariable<
int>(
410 option_name, *option_value, [
this, sensor, option_name](
int new_value){
set_auto_exposure_roi(option_name, sensor, new_value);},
411 "auto-exposure " + option_name +
" coordinate", min_val, max_val);
427 std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec = std::make_shared<ddynamic_reconfigure::DDynamicReconfigure>(nh1);
436 ddynrec->publishServicesTopics();
450 std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec = std::make_shared<ddynamic_reconfigure::DDynamicReconfigure>(nh1);
463 auto option_value = bool(sensor.
get_option(option));
464 if (nh1.
param(option_name, option_value, option_value))
468 ddynrec->registerVariable<
bool>(
469 option_name, option_value,
470 [option, sensor](
bool new_value) { sensor.
set_option(option, new_value); },
475 if (enum_dict.empty())
478 const auto sensor_option_value = sensor.
get_option(option);
479 auto option_value = sensor_option_value;
480 if (nh1.
param(option_name, option_value, option_value))
482 if (option_value < op_range.
min || op_range.
max < option_value)
485 <<
" outside the range [" << op_range.
min <<
", " << op_range.
max 486 <<
"]. Using current sensor value " << sensor_option_value <<
" instead.");
487 option_value = sensor_option_value;
494 if (option_value < op_range.
min || op_range.
max < option_value)
497 <<
" that is not in range [" << op_range.
min <<
", " << op_range.
max <<
"]" 498 <<
". Removing this parameter from dynamic reconfigure options.");
503 ddynrec->registerVariable<
int>(
504 option_name, int(option_value),
505 [option, sensor](
int new_value) { sensor.
set_option(option, new_value); },
523 ddynrec->registerVariable<
double>(
524 option_name, option_value,
525 [option, sensor](
double new_value) { sensor.
set_option(option, new_value); },
532 const auto sensor_option_value = sensor.
get_option(option);
533 auto option_value = int(sensor_option_value);
534 if (nh1.
param(option_name, option_value, option_value))
536 if (std::find_if(enum_dict.cbegin(), enum_dict.cend(),
537 [&option_value](
const std::pair<std::string, int>& kv) {
538 return kv.second == option_value;
539 }) == enum_dict.cend())
542 <<
" that is not in the enum " << enum_dict
543 <<
". Using current sensor value " << sensor_option_value <<
" instead.");
544 option_value = sensor_option_value;
551 if (std::find_if(enum_dict.cbegin(), enum_dict.cend(),
552 [&option_value](
const std::pair<std::string, int>& kv) {
553 return kv.second == option_value;
554 }) == enum_dict.cend())
557 <<
" that is not in the enum " << enum_dict
558 <<
". Removing this parameter from dynamic reconfigure options.");
563 ddynrec->registerEnumVariable<
int>(
564 option_name, option_value,
565 [
this, option, sensor, module_name](
int new_value)
567 sensor.set_option(option, new_value);
574 sensor.get_option_description(option), enum_dict);
578 ddynrec->registerEnumVariable<
int>(
579 option_name, option_value,
580 [option, sensor](
int new_value) { sensor.
set_option(option, new_value); },
585 catch(
const rs2::backend_error&
e)
587 ROS_WARN_STREAM(
"Failed to set option: " << option_name <<
": " << e.what());
589 catch(
const std::exception& e)
591 std::cerr << e.what() <<
'\n';
595 ddynrec->publishServicesTopics();
601 ROS_INFO(
"Setting Dynamic reconfig parameters.");
612 std::string module_name = nfilter._name;
613 auto sensor = *(nfilter._filter);
617 ROS_INFO(
"Done Setting Dynamic reconfig parameters.");
625 std::string module_name;
633 for (
unsigned int seq_id = 1; seq_id <= seq_size; seq_id++ )
638 std::stringstream param_name_str;
640 std::string param_name(param_name_str.str());
644 int user_set_option_value;
645 _pnh.
param(param_name, user_set_option_value, option_value);
647 if (option_value != user_set_option_value)
665 dynamic_reconfigure::ReconfigureRequest srv_req;
666 dynamic_reconfigure::ReconfigureResponse srv_resp;
667 dynamic_reconfigure::IntParameter int_param;
668 dynamic_reconfigure::Config conf;
672 conf.ints.push_back(int_param);
674 srv_req.config = conf;
676 std::string service_name = module_name +
"/set_parameters";
678 ROS_INFO_STREAM(
"call to set " << service_name <<
"/" << int_param.name <<
" to " << int_param.value <<
" succeeded");
680 ROS_ERROR_STREAM(
"call to set " << service_name <<
"/" << int_param.name <<
" to " << int_param.value <<
" failed");
686 int time_interval(1000);
687 std::function<void()>
func = [
this, time_interval](){
689 std::unique_lock<std::mutex> lock(mu);
704 if (str ==
"RS2_STREAM_ANY")
706 if (str ==
"RS2_STREAM_COLOR")
708 if (str ==
"RS2_STREAM_INFRARED")
710 if (str ==
"RS2_STREAM_FISHEYE")
712 throw std::runtime_error(
"Unknown stream string " + str);
721 _pnh.
param(
"infra_rgb", infra_rgb,
false);
733 std::string pc_texture_stream(
"");
735 _pnh.
param(
"pointcloud_texture_stream", pc_texture_stream, std::string(
"RS2_STREAM_COLOR"));
736 _pnh.
param(
"pointcloud_texture_index", pc_texture_idx, 0);
779 std::vector<stream_index_pair>
streams(IMAGE_STREAMS);
780 streams.insert(streams.end(), HID_STREAMS.begin(), HID_STREAMS.end());
781 for (
auto&
stream : streams)
783 std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() <<
STREAM_NAME(
stream) <<
"_frame_id").
str());
786 param_name =
static_cast<std::ostringstream&&
>(std::ostringstream() <<
STREAM_NAME(stream) <<
"_optical_frame_id").
str();
791 std::string unite_imu_method_str(
"");
793 if (unite_imu_method_str ==
"linear_interpolation")
795 else if (unite_imu_method_str ==
"copy")
807 std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() <<
"aligned_depth_to_" <<
STREAM_NAME(stream) <<
"_frame_id").
str());
828 std::stringstream ss;
833 std::string json_file_content = ss.str();
843 ROS_WARN(
"Device does not support advanced settings!");
846 ROS_INFO(
"JSON file is not provided");
872 std::function<void(rs2::frame)> frame_callback_function, imu_callback_function;
875 frame_callback_function =
_syncer;
877 auto frame_callback_inner = [
this](
rs2::frame frame){
903 stream_index_pair sip(video_profile.stream_type(), video_profile.stream_index());
932 ROS_ERROR_STREAM(
"Module Name \"" << module_name <<
"\" isn't supported by LibRealSense! Terminating RealSense Node...");
940 for (std::pair<stream_index_pair, bool>
const&
enable :
_enable )
946 _enable[
enable.first] =
false;
950 catch(
const std::exception& ex)
971 std::stringstream image_raw, camera_info, topic_metadata;
972 bool rectified_image =
false;
974 rectified_image =
true;
977 image_raw << stream_name <<
"/image_" << ((rectified_image)?
"rect_":
"") <<
"raw";
978 camera_info << stream_name <<
"/camera_info";
979 topic_metadata << stream_name <<
"/metadata";
988 std::stringstream aligned_image_raw, aligned_camera_info;
989 aligned_image_raw <<
"aligned_depth_to_" << stream_name <<
"/image_raw";
990 aligned_camera_info <<
"aligned_depth_to_" << stream_name <<
"/camera_info";
992 std::string aligned_stream_name =
"aligned_depth_to_" + stream_name;
1065 auto profiles = sens.get_stream_profiles();
1071 "stream_type: " <<
rs2_stream_to_string(video_profile.stream_type()) <<
"(" << video_profile.stream_index() <<
")" <<
1072 "Format: " << video_profile.format() <<
1073 ", Width: " << video_profile.width() <<
1074 ", Height: " << video_profile.height() <<
1075 ", FPS: " << video_profile.fps());
1077 if (
profile.stream_type() == elem.first &&
profile.stream_index() == elem.second)
1083 if ((
_width[elem] == 0 || video_profile.width() ==
_width[elem]) &&
1084 (
_height[elem] == 0 || video_profile.height() ==
_height[elem]) &&
1085 (
_fps[elem] == 0 || video_profile.fps() ==
_fps[elem]) &&
1094 if (!selected_profile)
1098 ", Stream Index: " << elem.second <<
1099 ", Width: " <<
_width[elem] <<
1100 ", Height: " <<
_height[elem] <<
1101 ", FPS: " <<
_fps[elem] <<
1103 if (default_profile)
1106 selected_profile = default_profile;
1109 if (selected_profile)
1112 _width[elem] = video_profile.width();
1113 _height[elem] = video_profile.height();
1114 _fps[elem] = video_profile.fps();
1117 ROS_INFO_STREAM(
STREAM_NAME(elem) <<
" stream is enabled - width: " << _width[elem] <<
", height: " <<
_height[elem] <<
", fps: " <<
_fps[elem] <<
", " <<
"Format: " << video_profile.format());
1140 auto profiles = sens.get_stream_profiles();
1150 if (
profile.stream_type() == elem.first)
1161 if (!selected_profile)
1165 if (default_profile)
1168 selected_profile = default_profile;
1171 if(selected_profile)
1173 _fps[elem] = selected_profile.
fps();
1187 std::vector<std::string> filters_str;
1188 boost::split(filters_str,
_filters_str, [](
char c){
return c ==
',';});
1189 bool use_disparity_filter(
false);
1190 bool use_colorizer_filter(
false);
1191 bool use_decimation_filter(
false);
1192 bool use_hdr_filter(
false);
1193 for (std::vector<std::string>::iterator s_iter=filters_str.begin(); s_iter!=filters_str.end(); s_iter++)
1195 (*s_iter).erase(std::remove_if((*s_iter).begin(), (*s_iter).end(), isspace), (*s_iter).end());
1197 if ((*s_iter) ==
"colorizer")
1199 use_colorizer_filter =
true;
1201 else if ((*s_iter) ==
"disparity")
1203 use_disparity_filter =
true;
1205 else if ((*s_iter) ==
"spatial")
1210 else if ((*s_iter) ==
"temporal")
1215 else if ((*s_iter) ==
"hole_filling")
1217 ROS_INFO(
"Add Filter: hole_filling");
1218 _filters.push_back(
NamedFilter(
"hole_filling", std::make_shared<rs2::hole_filling_filter>()));
1220 else if ((*s_iter) ==
"decimation")
1222 use_decimation_filter =
true;
1224 else if ((*s_iter) ==
"pointcloud")
1228 else if ((*s_iter) ==
"hdr_merge")
1230 use_hdr_filter =
true;
1232 else if ((*s_iter).size() > 0)
1238 if (use_disparity_filter)
1242 _filters.push_back(
NamedFilter(
"disparity_end", std::make_shared<rs2::disparity_transform>(
false)));
1243 ROS_INFO(
"Done Add Filter: disparity");
1249 ROS_INFO(
"Add Filter: sequence_id_filter");
1252 if (use_decimation_filter)
1254 ROS_INFO(
"Add Filter: decimation");
1261 if (use_colorizer_filter)
1264 _colorizer = std::make_shared<rs2::colorizer>();
1278 ROS_INFO(
"Add Filter: pointcloud");
1287 static const float meter_to_mm = 0.001f;
1290 to_image = from_image;
1294 if (to_image.size() != from_image.size())
1296 to_image.create(from_image.rows, from_image.cols, from_image.type());
1301 int nRows = from_image.rows;
1302 int nCols = from_image.cols;
1304 if (from_image.isContinuous())
1313 for( i = 0; i < nRows; ++i)
1315 p_from = from_image.ptr<
uint16_t>(i);
1317 for ( j = 0; j < nCols; ++j)
1334 #pragma omp parallel for schedule(dynamic) //Using OpenMP to try to parallelise the loop 1336 for (
int y = 0;
y < height;
y++)
1338 auto depth_pixel_index =
y * width;
1339 for (
int x = 0;
x < width;
x++, ++depth_pixel_index)
1342 if (p_depth_frame[depth_pixel_index] > clipping_value)
1344 p_depth_frame[depth_pixel_index] = 0;
1367 template <
typename T>
T lerp(
const T &
a,
const T &
b,
const double t) {
1368 return a * (1.0 - t) + b * t;
1373 static std::deque<CimuData> _imu_history;
1374 _imu_history.push_back(imu_data);
1378 if ((type !=
ACCEL) || _imu_history.size() < 3)
1381 std::deque<CimuData> gyros_data;
1384 while (_imu_history.size())
1386 crnt_imu = _imu_history.front();
1387 _imu_history.pop_front();
1397 while (gyros_data.size())
1399 CimuData crnt_gyro = gyros_data.front();
1400 gyros_data.pop_front();
1409 gyros_data.push_back(crnt_imu);
1412 _imu_history.push_back(crnt_imu);
1423 _accel_data = imu_data;
1426 if (_accel_data.
m_time < 0)
1447 static std::mutex m_mutex;
1456 bool placeholder_false(
false);
1466 auto crnt_reading = *(
reinterpret_cast<const float3*
>(frame.
get_data()));
1467 Eigen::Vector3d
v(crnt_reading.x, crnt_reading.y, crnt_reading.z);
1469 std::deque<sensor_msgs::Imu> imu_msgs;
1470 switch (sync_method)
1480 while (imu_msgs.size())
1487 imu_msgs.pop_front();
1497 bool placeholder_false(
false);
1503 ROS_DEBUG(
"Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
1516 auto crnt_reading = *(
reinterpret_cast<const float3*
>(frame.
get_data()));
1517 if (
GYRO == stream_index)
1519 imu_msg.angular_velocity.x = crnt_reading.x;
1520 imu_msg.angular_velocity.y = crnt_reading.y;
1521 imu_msg.angular_velocity.z = crnt_reading.z;
1523 else if (
ACCEL == stream_index)
1525 imu_msg.linear_acceleration.x = crnt_reading.x;
1526 imu_msg.linear_acceleration.y = crnt_reading.y;
1527 imu_msg.linear_acceleration.z = crnt_reading.z;
1529 _seq[stream_index] += 1;
1530 imu_msg.header.seq =
_seq[stream_index];
1531 imu_msg.header.stamp = t;
1541 bool placeholder_false(
false);
1547 ROS_DEBUG(
"Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
1551 const auto& stream_index(
POSE);
1603 nav_msgs::Odometry odom_msg;
1604 _seq[stream_index] += 1;
1608 odom_msg.header.stamp = t;
1609 odom_msg.header.seq =
_seq[stream_index];
1610 odom_msg.pose.pose = pose_msg.
pose;
1611 odom_msg.pose.covariance = {cov_pose, 0, 0, 0, 0, 0,
1612 0, cov_pose, 0, 0, 0, 0,
1613 0, 0, cov_pose, 0, 0, 0,
1614 0, 0, 0, cov_twist, 0, 0,
1615 0, 0, 0, 0, cov_twist, 0,
1616 0, 0, 0, 0, 0, cov_twist};
1617 odom_msg.twist.twist.linear = v_msg.
vector;
1618 odom_msg.twist.twist.angular = om_msg.
vector;
1619 odom_msg.twist.covariance ={cov_pose, 0, 0, 0, 0, 0,
1620 0, cov_pose, 0, 0, 0, 0,
1621 0, 0, cov_pose, 0, 0, 0,
1622 0, 0, 0, cov_twist, 0, 0,
1623 0, 0, 0, 0, cov_twist, 0,
1624 0, 0, 0, 0, 0, cov_twist};
1641 bool placeholder_false(
false);
1652 ROS_DEBUG(
"List of frameset before applying filters: size: %d", static_cast<int>(frameset.size()));
1653 for (
auto it = frameset.begin(); it != frameset.end(); ++it)
1656 auto stream_type =
f.get_profile().stream_type();
1657 auto stream_index =
f.get_profile().stream_index();
1659 auto stream_unique_id =
f.get_profile().unique_id();
1661 ROS_DEBUG(
"Frameset contain (%s, %d, %s %d) frame. frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
1667 bool is_color_frame(frameset.get_color_frame());
1673 ROS_DEBUG(
"num_filters: %d", static_cast<int>(
_filters.size()));
1674 for (std::vector<NamedFilter>::const_iterator filter_it =
_filters.begin(); filter_it !=
_filters.end(); filter_it++)
1676 ROS_DEBUG(
"Applying filter: %s", filter_it->_name.c_str());
1677 if ((filter_it->_name ==
"pointcloud") && (!original_depth_frame))
1679 if ((filter_it->_name ==
"align_to_color") && (!is_color_frame))
1681 frameset = filter_it->_filter->process(frameset);
1684 ROS_DEBUG(
"List of frameset after applying filters: size: %d", static_cast<int>(frameset.size()));
1685 bool sent_depth_frame(
false);
1686 for (
auto it = frameset.begin(); it != frameset.end(); ++it)
1689 auto stream_type =
f.get_profile().stream_type();
1690 auto stream_index =
f.get_profile().stream_index();
1694 ROS_DEBUG(
"Frameset contain (%s, %d, %s) frame. frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
1706 if (sent_depth_frame)
continue;
1707 sent_depth_frame =
true;
1735 frame_to_send =
_colorizer->process(original_depth_frame);
1737 frame_to_send = original_depth_frame;
1754 ROS_DEBUG(
"Single video frame arrived (%s, %d). frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
1777 catch(
const std::exception& ex)
1779 ROS_ERROR_STREAM(
"An error has occurred during frame callback: " << ex.what());
1807 ROS_WARN(
"frame's time domain is HARDWARE_CLOCK. Timestamps may reset periodically.");
1846 std::map<std::string, std::vector<rs2::stream_profile> >
profiles;
1847 std::map<std::string, rs2::sensor> active_sensors;
1852 <<
" to " << module_name);
1853 profiles[module_name].insert(profiles[module_name].
begin(),
1859 for (
const std::pair<std::string, std::vector<rs2::stream_profile> >& sensor_profile : profiles)
1861 std::string module_name = sensor_profile.first;
1863 sensor.
open(sensor_profile.second);
1871 catch(
const std::exception& ex)
1912 if (stream_index.second == 2)
1919 _camera_info[stream_index].P.at(3) = -intrinsic.fx * ex.translation[0] + 0.0;
1920 _camera_info[stream_index].P.at(7) = -intrinsic.fy * ex.translation[1] + 0.0;
1938 _camera_info[stream_index].distortion_model =
"equidistant";
1941 _camera_info[stream_index].distortion_model =
"plumb_bob";
1944 for (
int i = 0;
i < coeff_size;
i++)
1974 m << rotation[0], rotation[3], rotation[6],
1975 rotation[1], rotation[4], rotation[7],
1976 rotation[2], rotation[5], rotation[8];
1977 Eigen::Quaternionf
q(m);
1984 const std::string& from,
1985 const std::string& to)
2005 quaternion_optical.
setRPY(-M_PI / 2, 0.0, -M_PI / 2);
2006 float3 zero_trans{0, 0, 0};
2015 catch (std::exception&
e)
2017 if (!strcmp(e.what(),
"Requested extrinsics are not available!"))
2020 ex =
rs2_extrinsics({{1, 0, 0, 0, 1, 0, 0, 0, 1}, {0,0,0}});
2029 Q = quaternion_optical *
Q * quaternion_optical.
inverse();
2046 const std::vector<stream_index_pair> base_stream_priority = {
DEPTH,
POSE};
2048 std::vector<stream_index_pair>::const_iterator base_stream(base_stream_priority.begin());
2049 while( (
_sensors.find(*base_stream) ==
_sensors.end()) && (base_stream != base_stream_priority.end()))
2053 if (base_stream == base_stream_priority.end())
2055 throw std::runtime_error(
"No known base_stream found for transformations.");
2057 ROS_INFO_STREAM(
"SELECTED BASE:" << base_stream->first <<
", " << base_stream->second);
2068 for (std::pair<stream_index_pair, bool> ienable :
_enable)
2086 static const char* frame_id =
"depth_to_fisheye_extrinsics";
2096 static const char* frame_id =
"depth_to_color_extrinsics";
2105 static const char* frame_id =
"depth_to_infra1_extrinsics";
2114 static const char* frame_id =
"depth_to_infra2_extrinsics";
2128 std::unique_lock<std::mutex> lock(mu);
2135 msg.header.stamp = t;
2162 for (i=0; i < n; ++i)
2163 dst[n-1-i] = src[i];
2175 static int warn_count(0);
2176 static const int DISPLAY_WARN_NUMBER(5);
2180 std::set<rs2_format> available_formats{ rs2_format::RS2_FORMAT_RGB8, rs2_format::RS2_FORMAT_Y8 };
2182 texture_frame_itr = std::find_if(frameset.
begin(), frameset.
end(), [&texture_source_id, &available_formats] (
rs2::frame f)
2183 {
return (
rs2_stream(
f.get_profile().stream_type()) == texture_source_id) &&
2184 (available_formats.find(
f.get_profile().format()) != available_formats.end()); });
2185 if (texture_frame_itr == frameset.
end())
2188 std::string texture_source_name =
_pointcloud_filter->get_option_value_description(rs2_option::RS2_OPTION_STREAM_FILTER, static_cast<float>(texture_source_id));
2189 ROS_WARN_STREAM_COND(warn_count == DISPLAY_WARN_NUMBER,
"No stream match for pointcloud chosen texture " << texture_source_name);
2195 int texture_width(0), texture_height(0);
2214 size_t valid_count(0);
2218 texture_width = texture_frame.
get_width();
2222 std::string format_str;
2229 format_str =
"intensity";
2244 float color_pixel[2];
2245 for (
size_t point_idx=0; point_idx < pc.
size(); point_idx++, vertex++, color_point++)
2247 float i(color_point->
u);
2248 float j(color_point->
v);
2249 bool valid_color_pixel(i >= 0.
f && i <=1.f && j >= 0.
f && j <=1.
f);
2253 *iter_x = vertex->x;
2254 *iter_y = vertex->y;
2255 *iter_z = vertex->z;
2257 if (valid_color_pixel)
2259 color_pixel[0] = i * texture_width;
2260 color_pixel[1] = j * texture_height;
2261 int pixx =
static_cast<int>(color_pixel[0]);
2262 int pixy =
static_cast<int>(color_pixel[1]);
2263 int offset = (pixy * texture_width + pixx) * num_colors;
2266 ++iter_x; ++iter_y; ++iter_z;
2274 std::string format_str =
"intensity";
2282 for (
size_t point_idx=0; point_idx < pc.
size(); point_idx++, vertex++)
2284 bool valid_pixel(vertex->
z > 0);
2287 *iter_x = vertex->
x;
2288 *iter_y = vertex->
y;
2289 *iter_z = vertex->
z;
2291 ++iter_x; ++iter_y; ++iter_z;
2304 modifier.
resize(valid_count);
2312 Extrinsics extrinsicsMsg;
2313 for (
int i = 0;
i < 9; ++
i)
2315 extrinsicsMsg.rotation[
i] = extrinsics.
rotation[
i];
2320 extrinsicsMsg.header.frame_id = frame_id;
2321 return extrinsicsMsg;
2326 const std::vector<rs2::stream_profile>
profiles =
_sensors[stream].get_stream_profiles();
2327 return *(std::find_if(profiles.begin(), profiles.end(),
2329 return ((
profile.stream_type() == stream.first) && (
profile.stream_index() == stream.second));
2340 imuIntrinsics = sp.get_motion_intrinsics();
2342 catch(
const std::runtime_error &ex)
2345 imuIntrinsics = {{{1,0,0,0},{0,1,0,0},{0,0,1,0}}, {0,0,0}, {0,0,0}};
2350 for (
int i = 0;
i < 3; ++
i)
2352 for (
int j = 0;
j < 4; ++
j)
2357 info.noise_variances[
i] = imuIntrinsics.noise_variances[
i];
2358 info.bias_variances[
i] = imuIntrinsics.bias_variances[
i];
2365 std::map<stream_index_pair, cv::Mat>& images,
2366 const std::map<stream_index_pair, ros::Publisher>& info_publishers,
2367 const std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics>& image_publishers,
2368 const bool is_publishMetadata,
2369 std::map<stream_index_pair, int>&
seq,
2370 std::map<stream_index_pair, sensor_msgs::CameraInfo>& camera_info,
2371 const std::map<rs2_stream, std::string>& encoding,
2372 bool copy_data_from_frame)
2375 unsigned int width = 0;
2382 height =
image.get_height();
2385 auto&
image = images[stream];
2387 if (copy_data_from_frame)
2389 if (images[stream].
size() != cv::Size(width, height))
2401 auto& info_publisher = info_publishers.at(stream);
2402 auto& image_publisher = image_publishers.at(stream);
2404 image_publisher.second->tick();
2405 if(0 != info_publisher.getNumSubscribers() ||
2406 0 != image_publisher.first.getNumSubscribers())
2408 auto& cam_info = camera_info.at(stream);
2409 if (cam_info.width != width)
2413 cam_info.header.stamp = t;
2414 cam_info.header.seq = seq[stream];
2415 info_publisher.publish(cam_info);
2420 img->height = height;
2421 img->is_bigendian =
false;
2422 img->step = width *
bpp;
2423 img->header.frame_id = cam_info.header.frame_id;
2424 img->header.stamp = t;
2425 img->header.seq = seq[stream];
2427 image_publisher.first.publish(img);
2430 if (is_publishMetadata)
2432 auto& cam_info = camera_info.at(stream);
2443 if (0 != md_publisher->getNumSubscribers())
2445 realsense2_camera::Metadata
msg;
2446 msg.header.frame_id = frame_id;
2447 msg.header.stamp = header_time;
2448 std::stringstream json_data;
2449 const char* separator =
",";
2454 json_data << separator <<
"\"" <<
"frame_timestamp" <<
"\":" << std::fixed << f.
get_timestamp();
2464 name =
"hw_timestamp";
2467 json_data << separator <<
"\"" << name <<
"\":" << val;
2471 msg.json_data = json_data.str();
2472 md_publisher->publish(msg);
2483 {
return (profile.
stream_type() == stream_index.first); });
2498 int time_interval(1000);
2499 std::function<void()>
func = [
this, time_interval](){
2501 std::unique_lock<std::mutex> lock(mu);
2524 auto option_value = sensor.
get_option(option);
2525 option_diag.second->update(option_value);
2527 catch(
const std::exception&
e)
2529 ROS_DEBUG_STREAM(
"Failed checking for temperature." << std::endl << e.what());
2537 std::chrono::milliseconds timespan(1);
2540 image_publisher.second.second->update();
2541 std::this_thread::sleep_for(timespan);
2548 _updater.setHardwareID(serial_no);
2554 status.
add(
"Index", _crnt_temp);
2563 realsense2_camera::DeviceInfo::Response&
res)
2571 std::stringstream sensors_names;
2577 res.sensors = sensors_names.str().substr(0, sensors_names.str().size()-1);
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
void FillImuData_Copy(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
std::map< stream_index_pair, int > _seq
int get_bytes_per_pixel() const
RS2_OPTION_PROJECTOR_TEMPERATURE
std::map< rs2_stream, int > _image_format
BaseRealSenseNode(ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
void monitor_update_functions()
const std::vector< stream_index_pair > IMAGE_STREAMS
GLboolean GLboolean GLboolean b
const std::string DEFAULT_BASE_FRAME_ID
void load_json(const std::string &json_content) const
void clip_depth(rs2::depth_frame depth_frame, float clipping_dist)
bool supports(rs2_option option) const
cv::Mat & fix_depth_scale(const cv::Mat &from_image, cv::Mat &to_image)
void registerAutoExposureROIOptions(ros::NodeHandle &nh)
TemperatureDiagnostics(std::string name, std::string serial_no)
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
RS2_CAMERA_INFO_PHYSICAL_PORT
Quaternion inverse() const
std::vector< sensor > query_sensors() const
const char * get_info(rs2_camera_info info) const
_linear_acceleration_type linear_acceleration
const std::string DEFAULT_ODOM_FRAME_ID
void ImuMessage_AddDefaultValues(sensor_msgs::Imu &imu_msg)
unsigned int tracker_confidence
std::vector< NamedFilter > _filters
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK
ros::Publisher _publisher
rs2_format format() const
void start(T callback) const
void publishPointCloud(rs2::points f, const ros::Time &t, const rs2::frameset &frameset)
std::map< stream_index_pair, ros::Publisher > _info_publisher
RS2_CAMERA_INFO_SERIAL_NUMBER
void pose_callback(rs2::frame frame)
tf2_ros::TransformBroadcaster _dynamic_tf_broadcaster
void summary(unsigned char lvl, const std::string s)
std::map< stream_index_pair, rs2_intrinsics > _stream_intrinsics
const bool PUBLISH_ODOM_TF
RS2_CAMERA_INFO_PRODUCT_ID
void reverse_memcpy(unsigned char *dst, const unsigned char *src, size_t n)
std::condition_variable _cv_tf
double frameSystemTimeSec(rs2::frame frame)
bool call(const std::string &service_name, MReq &req, MRes &res)
void set_sensor_parameter_to_ros(const std::string &module_name, rs2::options sensor, rs2_option option)
double _angular_velocity_cov
const std::string DEFAULT_UNITE_IMU_METHOD
#define OPTICAL_FRAME_ID(sip)
std::size_t _waiting_list_size
_orientation_type orientation
virtual void registerDynamicReconfigCb(ros::NodeHandle &nh) override
std::string _base_frame_id
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
RS2_DISTORTION_KANNALA_BRANDT4
RS2_OPTION_ASIC_TEMPERATURE
Extrinsics rsExtrinsicsToMsg(const rs2_extrinsics &extrinsics, const std::string &frame_id) const
ros::Publisher _pointcloud_publisher
_angular_velocity_covariance_type angular_velocity_covariance
struct Vertex vertex[VERTEXNUM]
virtual void publishTopics() override
std::shared_ptr< rs2::filter > _pointcloud_filter
const stream_index_pair INFRA2
double get_timestamp() const
static void vector3TFToMsg(const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v)
virtual void toggleSensors(bool enabled) override
_orientation_type orientation
std::shared_ptr< std::thread > _update_functions_t
const char * get_option_description(rs2_option option) const
IMUInfo getImuInfo(const stream_index_pair &stream_index)
stream_index_pair _pointcloud_texture
std::map< rs2_stream, bool > _is_first_frame
const char * rs2_stream_to_string(rs2_stream stream)
rs2_vector angular_velocity
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _image_publishers
bool deleteParam(const std::string &key) const
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::atomic_bool _is_initialized_time_base
rs2_notification_category get_category() const
void registerDynamicOption(ros::NodeHandle &nh, rs2::options sensor, std::string &module_name)
void publishStaticTransforms()
GLenum GLenum GLsizei void * image
void imu_callback_sync(rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY)
std::queue< sensor_msgs::Imu > _pending_messages
std::pair< rs2_option, std::shared_ptr< TemperatureDiagnostics > > OptionTemperatureDiag
std::map< stream_index_pair, sensor_msgs::CameraInfo > _depth_aligned_camera_info
virtual ~BaseRealSenseNode()
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
std::vector< OptionTemperatureDiag > _temperature_nodes
GLboolean GLboolean GLboolean GLboolean a
void Publish(sensor_msgs::Imu msg)
float get_option(rs2_option option) const
std::map< stream_index_pair, rs2::sensor > _sensors
tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
std::map< stream_index_pair, int > _width
bool getDeviceInfo(realsense2_camera::DeviceInfo::Request &req, realsense2_camera::DeviceInfo::Response &res)
bool is_checkbox(rs2::options sensor, rs2_option option)
double get_timestamp() const
void open(const stream_profile &profile) const
void publishMetadata(rs2::frame f, const ros::Time &header_time, const std::string &frame_id)
std::pair< rs2_stream, int > stream_index_pair
void updateStreamCalibData(const rs2::video_stream_profile &video_profile)
std::map< std::string, int > get_enum_method(rs2::options sensor, rs2_option option)
GLfloat GLfloat GLfloat alpha
const stream_index_pair CONFIDENCE
sensor_msgs::PointCloud2 _msg_pointcloud
std::condition_variable _cv_monitoring
bool is_enum_option(rs2::options sensor, rs2_option option)
T lerp(const T &a, const T &b, const double t)
std::shared_ptr< rs2::filter > _colorizer
const char * rs2_option_to_string(rs2_option option)
void publishDynamicTransforms()
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::map< stream_index_pair, rs2_extrinsics > _depth_to_other_extrinsics
void publish(const boost::shared_ptr< M > &message) const
TFSIMD_FORCE_INLINE const tfScalar & getW() const
float _depth_scale_meters
std::map< rs2_stream, std::string > _encoding
static void vector3MsgToTF(const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
ROSCPP_DECL const std::string & getNamespace()
_point_step_type point_step
std::map< stream_index_pair, bool > _enable
RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR
const stream_index_pair GYRO
std::map< stream_index_pair, cv::Mat > _image
void frame_callback(rs2::frame frame)
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
std::shared_ptr< std::thread > _tf_t
GLint GLsizei GLsizei height
#define ROS_WARN_ONCE(...)
bool _allow_no_texture_points
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
const stream_index_pair DEPTH
rs2_timestamp_domain get_frame_timestamp_domain() const
void publish_frequency_update()
std::shared_ptr< SyncedImuPublisher > _synced_imu_publisher
const char * rs2_format_to_string(rs2_format format)
std::string create_graph_resource_name(const std::string &original_name)
ros::NodeHandle & _node_handle
GLenum GLenum GLsizei const GLuint GLboolean enabled
const char * get_option_value_description(rs2_option option, float val) const
const std::string TYPE_16UC1
float get_depth_scale(rs2::device dev)
std::map< rs2_stream, std::string > _stream_name
std::shared_ptr< ros::ServiceServer > _device_info_srv
#define ROS_WARN_STREAM_COND(cond, args)
RS2_CAMERA_INFO_FIRMWARE_VERSION
TFSIMD_FORCE_INLINE Vector3 quatRotate(const Quaternion &rotation, const Vector3 &v)
std::string resolveName(const std::string &name, bool remap=true) const
void publishFrame(rs2::frame f, const ros::Time &t, const stream_index_pair &stream, std::map< stream_index_pair, cv::Mat > &images, const std::map< stream_index_pair, ros::Publisher > &info_publishers, const std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > &image_publishers, const bool is_publishMetadata, std::map< stream_index_pair, int > &seq, std::map< stream_index_pair, sensor_msgs::CameraInfo > &camera_info, const std::map< rs2_stream, std::string > &encoding, bool copy_data_from_frame=true)
void imu_callback(rs2::frame frame)
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _depth_aligned_image_publishers
std::map< stream_index_pair, cv::Mat > _depth_scaled_image
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void multiple_message_callback(rs2::frame frame, imu_sync_method sync_method)
const texture_coordinate * get_texture_coordinates() const
rs2_stream rs2_string_to_stream(std::string str)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
const bool ALLOW_NO_TEXTURE_POINTS
RS2_FRAME_METADATA_FRAME_TIMESTAMP
unsigned long long get_frame_number() const
void publish_temperature()
imu_sync_method _imu_sync_method
bool getEnabledProfile(const stream_index_pair &stream_index, rs2::stream_profile &profile)
void registerHDRoptions()
_angular_velocity_type angular_velocity
std::map< stream_index_pair, std::vector< rs2::stream_profile > > _enabled_profiles
#define ROS_INFO_STREAM_ONCE(args)
GLdouble GLdouble GLdouble q
rs2_log_severity get_severity() const
const void * get_data() const
bool is_option_read_only(rs2_option option) const
const std::string _namespace
std::map< stream_index_pair, ros::Publisher > _imu_publishers
virtual void calcAndPublishStaticTransform(const stream_index_pair &stream, const rs2::stream_profile &base_profile)
bool supports(rs2_camera_info info) const
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &status)
#define ROS_INFO_STREAM(args)
std::map< stream_index_pair, ros::Publisher > _depth_to_other_extrinsics_publishers
long long rs2_metadata_type
std::vector< rs2_option > _monitor_options
std::vector< std::function< void()> > _update_functions_v
const char * rs2_frame_metadata_to_string(rs2_frame_metadata_value metadata)
std::map< stream_index_pair, std::string > _frame_id
std::map< stream_index_pair, int > _height
option_range get_option_range(rs2_option option) const
void set_option(rs2_option option, float value) const
const stream_index_pair ACCEL
const stream_index_pair POSE
void set_sensor_auto_exposure_roi(rs2::sensor sensor)
std::map< stream_index_pair, sensor_msgs::CameraInfo > _camera_info
_orientation_covariance_type orientation_covariance
void readAndSetDynamicParam(ros::NodeHandle &nh1, std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > ddynrec, const std::string option_name, const int min_val, const int max_val, rs2::sensor sensor, int *option_value)
std::map< rs2_stream, int > _unit_step_size
const double TF_PUBLISH_RATE
std::shared_ptr< std::thread > _monitoring_t
void publish_static_tf(const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
_linear_acceleration_covariance_type linear_acceleration_covariance
std::vector< geometry_msgs::TransformStamped > _static_tf_msgs
const bool ORDERED_POINTCLOUD
std::map< rs2_stream, std::string > _depth_aligned_encoding
void setupErrorCallback()
ROSCPP_DECL void shutdown()
const std::vector< stream_index_pair > HID_STREAMS
std::map< stream_index_pair, int > _fps
static std::string getNamespaceStr()
const bool HOLD_BACK_IMU_FOR_FRAMES
std::map< std::string, std::function< void(rs2::frame)> > _sensors_callback
stream_index_pair _base_stream
std::vector< rs2::sensor > _dev_sensors
RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID
void runFirstFrameInitialization(rs2_stream stream_type)
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
void add(const std::string &key, const T &val)
std::map< stream_index_pair, int > _depth_aligned_seq
const stream_index_pair FISHEYE
std::condition_variable _update_functions_cv
std::string get_description() const
const stream_index_pair COLOR
void PublishPendingMessages()
#define ROS_ERROR_STREAM(args)
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
std::map< std::string, rs2::region_of_interest > _auto_exposure_roi
bool isValidCharInName(char c)
sensor_msgs::Imu CreateUnitedMessage(const CimuData accel_data, const CimuData gyro_data)
const stream_index_pair INFRA1
bool setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
uint32_t getNumSubscribers() const
rs2::stream_profile getAProfile(const stream_index_pair &stream)
std::string _json_file_path
void setPointCloud2FieldsByString(int n_fields,...)
const char * rs2_timestamp_domain_to_string(rs2_timestamp_domain info)
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
::sensor_msgs::Imu_< std::allocator< void > > Imu
rs2_stream stream_type() const
rs2_intrinsics get_intrinsics() const
std::map< stream_index_pair, ros::Publisher > _depth_aligned_info_publisher
std::map< stream_index_pair, std::string > _optical_frame_id
#define ALIGNED_DEPTH_TO_FRAME_ID(sip)
bool _hold_back_imu_for_frames
const float ROS_DEPTH_SCALE
bool is_int_option(rs2::options sensor, rs2_option option)
const char * get_info(rs2_camera_info info) const
std::string _odom_frame_id
RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME
void set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value)
const std::string DEFAULT_FILTERS
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
void FillImuData_LinearInterpolation(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
std::shared_ptr< ::sensor_msgs::Image > ImagePtr
stream_profile get_profile() const
std::map< rs2_stream, int > _format
const vertex * get_vertices() const
std::string to_string(T value)