base_realsense_node.cpp
Go to the documentation of this file.
00001 #include "../include/base_realsense_node.h"
00002 #include "assert.h"
00003 #include <boost/algorithm/string.hpp>
00004 #include <algorithm>
00005 #include <cctype>
00006 #include <mutex>
00007 #include <tf/transform_broadcaster.h>
00008 
00009 using namespace realsense2_camera;
00010 using namespace ddynamic_reconfigure;
00011 
00012 // stream_index_pair sip{stream_type, stream_index};
00013 #define STREAM_NAME(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << _stream_name[sip.first] << ((sip.second>0) ? std::to_string(sip.second) : ""))).str()
00014 #define FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_frame")).str()
00015 #define OPTICAL_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_optical_frame")).str()
00016 #define ALIGNED_DEPTH_TO_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_aligned_depth_to_" << STREAM_NAME(sip) << "_frame")).str()
00017 
00018 SyncedImuPublisher::SyncedImuPublisher(ros::Publisher imu_publisher, std::size_t waiting_list_size):
00019             _publisher(imu_publisher), _pause_mode(false),
00020             _waiting_list_size(waiting_list_size)
00021             {}
00022 
00023 SyncedImuPublisher::~SyncedImuPublisher()
00024 {
00025     PublishPendingMessages();
00026 }
00027 
00028 void SyncedImuPublisher::Publish(sensor_msgs::Imu imu_msg)
00029 {
00030     std::lock_guard<std::mutex> lock_guard(_mutex);
00031     if (_pause_mode)
00032     {
00033         if (_pending_messages.size() >= _waiting_list_size)
00034         {
00035             throw std::runtime_error("SyncedImuPublisher inner list reached maximum size of " + std::to_string(_pending_messages.size()));
00036         }
00037         _pending_messages.push(imu_msg);
00038     }
00039     else
00040     {
00041         _publisher.publish(imu_msg);
00042         // ROS_INFO_STREAM("iid1:" << imu_msg.header.seq << ", time: " << std::setprecision (20) << imu_msg.header.stamp.toSec());
00043     }
00044     return;
00045 }
00046 
00047 void SyncedImuPublisher::Pause()
00048 {
00049     if (!_is_enabled) return;
00050     std::lock_guard<std::mutex> lock_guard(_mutex);
00051     _pause_mode = true;
00052 }
00053 
00054 void SyncedImuPublisher::Resume()
00055 {
00056     std::lock_guard<std::mutex> lock_guard(_mutex);
00057     PublishPendingMessages();
00058     _pause_mode = false;
00059 }
00060 
00061 void SyncedImuPublisher::PublishPendingMessages()
00062 {
00063     // ROS_INFO_STREAM("publish imu: " << _pending_messages.size());
00064     while (!_pending_messages.empty())
00065     {
00066         const sensor_msgs::Imu &imu_msg = _pending_messages.front();
00067         _publisher.publish(imu_msg);
00068         // ROS_INFO_STREAM("iid2:" << imu_msg.header.seq << ", time: " << std::setprecision (20) << imu_msg.header.stamp.toSec());
00069         _pending_messages.pop();
00070     }
00071 }
00072 
00073 std::string BaseRealSenseNode::getNamespaceStr()
00074 {
00075     auto ns = ros::this_node::getNamespace();
00076     ns.erase(std::remove(ns.begin(), ns.end(), '/'), ns.end());
00077     return ns;
00078 }
00079 
00080 BaseRealSenseNode::BaseRealSenseNode(ros::NodeHandle& nodeHandle,
00081                                      ros::NodeHandle& privateNodeHandle,
00082                                      rs2::device dev,
00083                                      const std::string& serial_no) :
00084     _base_frame_id(""),  _node_handle(nodeHandle),
00085     _pnh(privateNodeHandle), _dev(dev), _json_file_path(""),
00086     _serial_no(serial_no),
00087     _is_initialized_time_base(false),
00088     _namespace(getNamespaceStr())
00089 {
00090     // Types for depth stream
00091     _image_format[RS2_STREAM_DEPTH] = CV_16UC1;    // CVBridge type
00092     _encoding[RS2_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1; // ROS message type
00093     _unit_step_size[RS2_STREAM_DEPTH] = sizeof(uint16_t); // sensor_msgs::ImagePtr row step size
00094     _stream_name[RS2_STREAM_DEPTH] = "depth";
00095     _depth_aligned_encoding[RS2_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1;
00096 
00097     // Infrared stream
00098     _image_format[RS2_STREAM_INFRARED] = CV_8UC1;    // CVBridge type
00099     _encoding[RS2_STREAM_INFRARED] = sensor_msgs::image_encodings::MONO8; // ROS message type
00100     _unit_step_size[RS2_STREAM_INFRARED] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
00101     _stream_name[RS2_STREAM_INFRARED] = "infra";
00102     _depth_aligned_encoding[RS2_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_16UC1;
00103 
00104     // Types for color stream
00105     _image_format[RS2_STREAM_COLOR] = CV_8UC3;    // CVBridge type
00106     _encoding[RS2_STREAM_COLOR] = sensor_msgs::image_encodings::RGB8; // ROS message type
00107     _unit_step_size[RS2_STREAM_COLOR] = 3; // sensor_msgs::ImagePtr row step size
00108     _stream_name[RS2_STREAM_COLOR] = "color";
00109     _depth_aligned_encoding[RS2_STREAM_COLOR] = sensor_msgs::image_encodings::TYPE_16UC1;
00110 
00111     // Types for fisheye stream
00112     _image_format[RS2_STREAM_FISHEYE] = CV_8UC1;    // CVBridge type
00113     _encoding[RS2_STREAM_FISHEYE] = sensor_msgs::image_encodings::MONO8; // ROS message type
00114     _unit_step_size[RS2_STREAM_FISHEYE] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
00115     _stream_name[RS2_STREAM_FISHEYE] = "fisheye";
00116     _depth_aligned_encoding[RS2_STREAM_FISHEYE] = sensor_msgs::image_encodings::TYPE_16UC1;
00117 
00118     // Types for Motion-Module streams
00119     _stream_name[RS2_STREAM_GYRO] = "gyro";
00120 
00121     _stream_name[RS2_STREAM_ACCEL] = "accel";
00122 
00123     _stream_name[RS2_STREAM_POSE] = "pose";
00124 }
00125 
00126 void BaseRealSenseNode::toggleSensors(bool enabled)
00127 {
00128     for (auto it=_sensors.begin(); it != _sensors.end(); it++)
00129     {
00130         auto& sens = _sensors[it->first];
00131         try
00132         {
00133             if (enabled)
00134                 sens.start(_syncer);
00135             else
00136                 sens.stop();
00137         }
00138         catch(const rs2::wrong_api_call_sequence_error& ex)
00139         {
00140             ROS_DEBUG_STREAM("toggleSensors: " << ex.what());
00141         }
00142     }
00143 }
00144 
00145 void BaseRealSenseNode::setupErrorCallback()
00146 {
00147     for (auto&& s : _dev.query_sensors())
00148     {
00149         s.set_notifications_callback([&](const rs2::notification& n)
00150         {
00151             std::vector<std::string> error_strings({"RT IC2 Config error", 
00152                                                     "Motion Module force pause",
00153                                                     "stream start failure"});
00154             if (n.get_severity() >= RS2_LOG_SEVERITY_ERROR)
00155             {
00156                 ROS_WARN_STREAM("Hardware Notification:" << n.get_description() << "," << n.get_timestamp() << "," << n.get_severity() << "," << n.get_category());
00157             }
00158             if (error_strings.end() != find_if(error_strings.begin(), error_strings.end(), [&n] (std::string err) 
00159                                         {return (n.get_description().find(err) != std::string::npos); }))
00160             {
00161                 ROS_ERROR_STREAM("Hardware Reset is needed. use option: initial_reset:=true");
00162                 _dev.hardware_reset();
00163             }
00164         });
00165     }
00166 }
00167 
00168 void BaseRealSenseNode::publishTopics()
00169 {
00170     getParameters();
00171     setupDevice();
00172     setupErrorCallback();
00173     enable_devices();
00174     setupPublishers();
00175     setupStreams();
00176     setupFilters();
00177     publishStaticTransforms();
00178     publishIntrinsics();
00179     ROS_INFO_STREAM("RealSense Node Is Up!");
00180 }
00181 
00182 bool is_checkbox(rs2::options sensor, rs2_option option)
00183 {
00184     rs2::option_range op_range = sensor.get_option_range(option);
00185     return op_range.max == 1.0f &&
00186         op_range.min == 0.0f &&
00187         op_range.step == 1.0f;
00188 }
00189 
00190 bool is_enum_option(rs2::options sensor, rs2_option option)
00191 {
00192     rs2::option_range op_range = sensor.get_option_range(option);
00193     if (op_range.step < 0.001f) return false;
00194     for (auto i = op_range.min; i <= op_range.max; i += op_range.step)
00195     {
00196         if (sensor.get_option_value_description(option, i) == nullptr)
00197             return false;
00198     }
00199     return true;
00200 }
00201 
00202 bool is_int_option(rs2::options sensor, rs2_option option)
00203 {
00204     rs2::option_range op_range = sensor.get_option_range(option);
00205     return (op_range.step == 1.0);
00206 }
00207 
00208 std::map<std::string, int> get_enum_method(rs2::options sensor, rs2_option option)
00209 {
00210     std::map<std::string, int> dict; // An enum to set size
00211     if (is_enum_option(sensor, option))
00212     {
00213         rs2::option_range op_range = sensor.get_option_range(option);
00214         const auto op_range_min = int(op_range.min);
00215         const auto op_range_max = int(op_range.max);
00216         const auto op_range_step = int(op_range.step);
00217         for (auto val = op_range_min; val <= op_range_max; val += op_range_step)
00218         {
00219             dict[sensor.get_option_value_description(option, val)] = val;
00220         }
00221     }
00222     return dict;
00223 }
00224 
00225 namespace realsense2_camera
00226 {
00227 
00228 template <typename K, typename V>
00229 std::ostream& operator<<(std::ostream& os, const std::map<K, V>& m)
00230 {
00231     os << '{';
00232     for (const auto& kv : m)
00233     {
00234         os << " {" << kv.first << ": " << kv.second << '}';
00235     }
00236     os << " }";
00237     return os;
00238 }
00239 
00240 }
00241 
00245 bool isValidCharInName(char c)
00246 {
00247     return std::isalnum(c) || c == '/' || c == '_';
00248 }
00249 
00254 std::string create_graph_resource_name(const std::string &original_name)
00255 {
00256   std::string fixed_name = original_name;
00257   std::transform(fixed_name.begin(), fixed_name.end(), fixed_name.begin(),
00258                  [](unsigned char c) { return std::tolower(c); });
00259   std::replace_if(fixed_name.begin(), fixed_name.end(), [](const char c) { return !isValidCharInName(c); },
00260                   '_');
00261   return fixed_name;
00262 }
00263 
00264 void BaseRealSenseNode::registerDynamicOption(ros::NodeHandle& nh, rs2::options sensor, std::string& module_name)
00265 {
00266     ros::NodeHandle nh1(nh, module_name);
00267     std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec = std::make_shared<ddynamic_reconfigure::DDynamicReconfigure>(nh1);
00268     for (auto i = 0; i < RS2_OPTION_COUNT; i++)
00269     {
00270         rs2_option option = static_cast<rs2_option>(i);
00271         const std::string option_name(create_graph_resource_name(rs2_option_to_string(option)));
00272         if (!sensor.supports(option) || sensor.is_option_read_only(option))
00273         {
00274             continue;
00275         }
00276         if (is_checkbox(sensor, option))
00277         {
00278             auto option_value = bool(sensor.get_option(option));
00279             if (nh1.param(option_name, option_value, option_value))
00280             {
00281                 sensor.set_option(option, option_value);
00282             }
00283             ddynrec->registerVariable<bool>(
00284               option_name, option_value,
00285               [option, sensor](bool new_value) { sensor.set_option(option, new_value); },
00286               sensor.get_option_description(option));
00287             continue;
00288         }
00289         const auto enum_dict = get_enum_method(sensor, option);
00290         if (enum_dict.empty())
00291         {
00292             rs2::option_range op_range = sensor.get_option_range(option);
00293             const auto sensor_option_value = sensor.get_option(option);
00294             auto option_value = sensor_option_value;
00295             if (nh1.param(option_name, option_value, option_value))
00296             {
00297                 if (option_value < op_range.min || op_range.max < option_value)
00298                 {
00299                     ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option
00300                             << " outside the range [" << op_range.min << ", " << op_range.max
00301                             << "]. Using current sensor value " << sensor_option_value << " instead.");
00302                     option_value = sensor_option_value;
00303                 }
00304                 else
00305                 {
00306                     sensor.set_option(option, option_value);
00307                 }
00308             }
00309             if (is_int_option(sensor, option))
00310             {
00311               ddynrec->registerVariable<int>(
00312                   option_name, int(option_value),
00313                   [option, sensor](int new_value) { sensor.set_option(option, new_value); },
00314                   sensor.get_option_description(option), int(op_range.min), int(op_range.max));
00315             }
00316             else
00317             {
00318                 if (i == RS2_OPTION_DEPTH_UNITS)
00319                 {
00320                     if (ROS_DEPTH_SCALE >= op_range.min && ROS_DEPTH_SCALE <= op_range.max)
00321                     {
00322                         sensor.set_option(option, ROS_DEPTH_SCALE);
00323                         op_range.min = ROS_DEPTH_SCALE;
00324                         op_range.max = ROS_DEPTH_SCALE;
00325 
00326                         _depth_scale_meters = ROS_DEPTH_SCALE;
00327                     }
00328                 }
00329                 else
00330                 {
00331                   ddynrec->registerVariable<double>(
00332                       option_name, option_value,
00333                       [option, sensor](double new_value) { sensor.set_option(option, new_value); },
00334                       sensor.get_option_description(option), double(op_range.min), double(op_range.max));
00335                 }
00336             }
00337         }
00338         else
00339         {
00340             const auto sensor_option_value = sensor.get_option(option);
00341             auto option_value = int(sensor_option_value);
00342             if (nh1.param(option_name, option_value, option_value))
00343             {
00344                 if (std::find_if(enum_dict.cbegin(), enum_dict.cend(),
00345                                  [&option_value](const std::pair<std::string, int>& kv) {
00346                                      return kv.second == option_value;
00347                                  }) == enum_dict.cend())
00348                 {
00349                     ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option_value
00350                                               << " that is not in the enum " << enum_dict
00351                                               << ". Using current sensor value " << sensor_option_value << " instead.");
00352                     option_value = sensor_option_value;
00353                 }
00354                 else
00355                 {
00356                     sensor.set_option(option, option_value);
00357                 }
00358             }
00359             ddynrec->registerEnumVariable<int>(
00360                 option_name, option_value,
00361                 [option, sensor](int new_value) { sensor.set_option(option, new_value); },
00362                 sensor.get_option_description(option), enum_dict);
00363         }
00364     }
00365     ddynrec->publishServicesTopics();
00366     _ddynrec.push_back(ddynrec);
00367 }
00368 
00369 void BaseRealSenseNode::registerDynamicReconfigCb(ros::NodeHandle& nh)
00370 {
00371     ROS_INFO("Setting Dynamic reconfig parameters.");
00372 
00373     for(rs2::sensor sensor : _dev_sensors)
00374     {
00375         std::string module_name = create_graph_resource_name(sensor.get_info(RS2_CAMERA_INFO_NAME));
00376         ROS_DEBUG_STREAM("module_name:" << module_name);
00377         registerDynamicOption(nh, sensor, module_name);
00378     }
00379 
00380     for (NamedFilter nfilter : _filters)
00381     {
00382         std::string module_name = nfilter._name;
00383         auto sensor = *(nfilter._filter);
00384         ROS_DEBUG_STREAM("module_name:" << module_name);
00385         registerDynamicOption(nh, sensor, module_name);
00386     }
00387     ROS_INFO("Done Setting Dynamic reconfig parameters.");
00388 }
00389 
00390 rs2_stream BaseRealSenseNode::rs2_string_to_stream(std::string str)
00391 {
00392     if (str == "RS2_STREAM_ANY")
00393         return RS2_STREAM_ANY;
00394     if (str == "RS2_STREAM_COLOR")
00395         return RS2_STREAM_COLOR;
00396     if (str == "RS2_STREAM_INFRARED")
00397         return RS2_STREAM_INFRARED;
00398     if (str == "RS2_STREAM_FISHEYE")
00399         return RS2_STREAM_FISHEYE;
00400     throw std::runtime_error("Unknown stream string " + str);
00401 }
00402 
00403 void BaseRealSenseNode::getParameters()
00404 {
00405     ROS_INFO("getParameters...");
00406 
00407     _pnh.param("align_depth", _align_depth, ALIGN_DEPTH);
00408     _pnh.param("enable_pointcloud", _pointcloud, POINTCLOUD);
00409     std::string pc_texture_stream("");
00410     int pc_texture_idx;
00411     _pnh.param("pointcloud_texture_stream", pc_texture_stream, std::string("RS2_STREAM_COLOR"));
00412     _pnh.param("pointcloud_texture_index", pc_texture_idx, 0);
00413     _pointcloud_texture = stream_index_pair{rs2_string_to_stream(pc_texture_stream), pc_texture_idx};
00414 
00415     _pnh.param("filters", _filters_str, DEFAULT_FILTERS);
00416     _pointcloud |= (_filters_str.find("pointcloud") != std::string::npos);
00417 
00418     _pnh.param("enable_sync", _sync_frames, SYNC_FRAMES);
00419     if (_pointcloud || _align_depth || _filters_str.size() > 0)
00420         _sync_frames = true;
00421 
00422     _pnh.param("json_file_path", _json_file_path, std::string(""));
00423 
00424     for (auto& stream : IMAGE_STREAMS)
00425     {
00426         std::string param_name(_stream_name[stream.first] + "_width");
00427         ROS_DEBUG_STREAM("reading parameter:" << param_name);
00428         _pnh.param(param_name, _width[stream], IMAGE_WIDTH);
00429         param_name = _stream_name[stream.first] + "_height";
00430         ROS_DEBUG_STREAM("reading parameter:" << param_name);
00431         _pnh.param(param_name, _height[stream], IMAGE_HEIGHT);
00432         param_name = _stream_name[stream.first] + "_fps";
00433         ROS_DEBUG_STREAM("reading parameter:" << param_name);
00434         _pnh.param(param_name, _fps[stream], IMAGE_FPS);
00435         param_name = "enable_" + STREAM_NAME(stream);
00436         ROS_DEBUG_STREAM("reading parameter:" << param_name);
00437         _pnh.param(param_name, _enable[stream], true);
00438     }
00439 
00440     for (auto& stream : HID_STREAMS)
00441     {
00442         std::string param_name(_stream_name[stream.first] + "_fps");
00443         ROS_DEBUG_STREAM("reading parameter:" << param_name);
00444         _pnh.param(param_name, _fps[stream], IMU_FPS);
00445         param_name = "enable_" + STREAM_NAME(stream);
00446         _pnh.param(param_name, _enable[stream], ENABLE_IMU);
00447         ROS_DEBUG_STREAM("_enable[" << _stream_name[stream.first] << "]:" << _enable[stream]);
00448     }
00449     _pnh.param("base_frame_id", _base_frame_id, DEFAULT_BASE_FRAME_ID);
00450     _pnh.param("odom_frame_id", _odom_frame_id, DEFAULT_ODOM_FRAME_ID);
00451 
00452     std::vector<stream_index_pair> streams(IMAGE_STREAMS);
00453     streams.insert(streams.end(), HID_STREAMS.begin(), HID_STREAMS.end());
00454     for (auto& stream : streams)
00455     {
00456         std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() << STREAM_NAME(stream) << "_frame_id").str());
00457         _pnh.param(param_name, _frame_id[stream], FRAME_ID(stream));
00458         ROS_DEBUG_STREAM("frame_id: reading parameter:" << param_name << " : " << _frame_id[stream]);
00459         param_name = static_cast<std::ostringstream&&>(std::ostringstream() << STREAM_NAME(stream) << "_optical_frame_id").str();
00460         _pnh.param(param_name, _optical_frame_id[stream], OPTICAL_FRAME_ID(stream));
00461         ROS_DEBUG_STREAM("optical: reading parameter:" << param_name << " : " << _optical_frame_id[stream]);
00462     }
00463 
00464     std::string unite_imu_method_str("");
00465     _pnh.param("unite_imu_method", unite_imu_method_str, DEFAULT_UNITE_IMU_METHOD);
00466     if (unite_imu_method_str == "linear_interpolation")
00467         _imu_sync_method = imu_sync_method::LINEAR_INTERPOLATION;
00468     else if (unite_imu_method_str == "copy")
00469         _imu_sync_method = imu_sync_method::COPY;
00470     else
00471         _imu_sync_method = imu_sync_method::NONE;
00472 
00473     if (_imu_sync_method > imu_sync_method::NONE)
00474     {
00475         _pnh.param("imu_optical_frame_id", _optical_frame_id[GYRO], DEFAULT_IMU_OPTICAL_FRAME_ID);
00476     }
00477 
00478     for (auto& stream : IMAGE_STREAMS)
00479     {
00480         if (stream == DEPTH) continue;
00481         if (stream.second > 1) continue;
00482         std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() << "aligned_depth_to_" << STREAM_NAME(stream) << "_frame_id").str());
00483         _pnh.param(param_name, _depth_aligned_frame_id[stream], ALIGNED_DEPTH_TO_FRAME_ID(stream));
00484     }
00485 
00486     _pnh.param("allow_no_texture_points", _allow_no_texture_points, ALLOW_NO_TEXTURE_POINTS);
00487     _pnh.param("clip_distance", _clipping_distance, static_cast<float>(-1.0));
00488     _pnh.param("linear_accel_cov", _linear_accel_cov, static_cast<double>(0.01));
00489     _pnh.param("angular_velocity_cov", _angular_velocity_cov, static_cast<double>(0.01));
00490     _pnh.param("hold_back_imu_for_frames", _hold_back_imu_for_frames, HOLD_BACK_IMU_FOR_FRAMES);
00491     _pnh.param("publish_odom_tf", _publish_odom_tf, PUBLISH_ODOM_TF);
00492 }
00493 
00494 void BaseRealSenseNode::setupDevice()
00495 {
00496     ROS_INFO("setupDevice...");
00497     try{
00498         if (!_json_file_path.empty())
00499         {
00500             if (_dev.is<rs400::advanced_mode>())
00501             {
00502                 std::stringstream ss;
00503                 std::ifstream in(_json_file_path);
00504                 if (in.is_open())
00505                 {
00506                     ss << in.rdbuf();
00507                     std::string json_file_content = ss.str();
00508 
00509                     auto adv = _dev.as<rs400::advanced_mode>();
00510                     adv.load_json(json_file_content);
00511                     ROS_INFO_STREAM("JSON file is loaded! (" << _json_file_path << ")");
00512                 }
00513                 else
00514                     ROS_WARN_STREAM("JSON file provided doesn't exist! (" << _json_file_path << ")");
00515             }
00516             else
00517                 ROS_WARN("Device does not support advanced settings!");
00518         }
00519         else
00520             ROS_INFO("JSON file is not provided");
00521 
00522         ROS_INFO_STREAM("ROS Node Namespace: " << _namespace);
00523 
00524         auto camera_name = _dev.get_info(RS2_CAMERA_INFO_NAME);
00525         ROS_INFO_STREAM("Device Name: " << camera_name);
00526 
00527         ROS_INFO_STREAM("Device Serial No: " << _serial_no);
00528 
00529         auto fw_ver = _dev.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION);
00530         ROS_INFO_STREAM("Device FW version: " << fw_ver);
00531 
00532         auto pid = _dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID);
00533         ROS_INFO_STREAM("Device Product ID: 0x" << pid);
00534 
00535         ROS_INFO_STREAM("Enable PointCloud: " << ((_pointcloud)?"On":"Off"));
00536         ROS_INFO_STREAM("Align Depth: " << ((_align_depth)?"On":"Off"));
00537         ROS_INFO_STREAM("Sync Mode: " << ((_sync_frames)?"On":"Off"));
00538 
00539         _dev_sensors = _dev.query_sensors();
00540 
00541 
00542         std::function<void(rs2::frame)> frame_callback_function, imu_callback_function;
00543         if (_sync_frames)
00544         {
00545             frame_callback_function = _syncer;
00546 
00547             auto frame_callback_inner = [this](rs2::frame frame){
00548                 frame_callback(frame);
00549             };
00550             _syncer.start(frame_callback_inner);
00551         }
00552         else
00553         {
00554             frame_callback_function = [this](rs2::frame frame){frame_callback(frame);};
00555         }
00556 
00557         if (_imu_sync_method == imu_sync_method::NONE)
00558         {
00559             imu_callback_function = [this](rs2::frame frame){imu_callback(frame);};
00560         }
00561         else
00562         {
00563             imu_callback_function = [this](rs2::frame frame){imu_callback_sync(frame, _imu_sync_method);};
00564         }
00565         std::function<void(rs2::frame)> multiple_message_callback_function = [this](rs2::frame frame){multiple_message_callback(frame, _imu_sync_method);};
00566 
00567         ROS_INFO_STREAM("Device Sensors: ");
00568         for(auto&& elem : _dev_sensors)
00569         {
00570             std::string module_name = elem.get_info(RS2_CAMERA_INFO_NAME);
00571 
00572             if ("Stereo Module" == module_name)
00573             {
00574                 _sensors[DEPTH] = elem;
00575                 _sensors[INFRA1] = elem;
00576                 _sensors[INFRA2] = elem;
00577                 _sensors_callback[module_name] = frame_callback_function;
00578             }
00579             else if ("Coded-Light Depth Sensor" == module_name)
00580             {
00581                 _sensors[DEPTH] = elem;
00582                 _sensors[INFRA1] = elem;
00583                 _sensors_callback[module_name] = frame_callback_function;
00584             }
00585             else if ("RGB Camera" == module_name)
00586             {
00587                 _sensors[COLOR] = elem;
00588                 _sensors_callback[module_name] = frame_callback_function;
00589             }
00590             else if ("Wide FOV Camera" == module_name)
00591             {
00592                 _sensors[FISHEYE] = elem;
00593                 _sensors_callback[module_name] = frame_callback_function;
00594             }
00595             else if ("Motion Module" == module_name)
00596             {
00597                 _sensors[GYRO] = elem;
00598                 _sensors[ACCEL] = elem;
00599                 _sensors_callback[module_name] = imu_callback_function;
00600             }
00601             else if ("Tracking Module" == module_name)
00602             {
00603                 _sensors[GYRO] = elem;
00604                 _sensors[ACCEL] = elem;
00605                 _sensors[POSE] = elem;
00606                 _sensors[FISHEYE1] = elem;
00607                 _sensors[FISHEYE2] = elem;
00608                 _sensors_callback[module_name] = multiple_message_callback_function;
00609             }
00610             else
00611             {
00612                 ROS_ERROR_STREAM("Module Name \"" << module_name << "\" isn't supported by LibRealSense! Terminating RealSense Node...");
00613                 ros::shutdown();
00614                 exit(1);
00615             }
00616             ROS_INFO_STREAM(std::string(elem.get_info(RS2_CAMERA_INFO_NAME)) << " was found.");
00617         }
00618 
00619         // Update "enable" map
00620         for (std::pair<stream_index_pair, bool> const& enable : _enable )
00621         {
00622             const stream_index_pair& stream_index(enable.first);
00623             if (enable.second && _sensors.find(stream_index) == _sensors.end())
00624             {
00625                 ROS_INFO_STREAM("(" << rs2_stream_to_string(stream_index.first) << ", " << stream_index.second << ") sensor isn't supported by current device! -- Skipping...");
00626                 _enable[enable.first] = false;
00627             }
00628         }
00629     }
00630     catch(const std::exception& ex)
00631     {
00632         ROS_ERROR_STREAM("An exception has been thrown: " << ex.what());
00633         throw;
00634     }
00635     catch(...)
00636     {
00637         ROS_ERROR_STREAM("Unknown exception has occured!");
00638         throw;
00639     }
00640 }
00641 
00642 void BaseRealSenseNode::setupPublishers()
00643 {
00644     ROS_INFO("setupPublishers...");
00645     image_transport::ImageTransport image_transport(_node_handle);
00646 
00647     for (auto& stream : IMAGE_STREAMS)
00648     {
00649         if (_enable[stream])
00650         {
00651             std::stringstream image_raw, camera_info;
00652             bool rectified_image = false;
00653             if (stream == DEPTH || stream == INFRA1 || stream == INFRA2)
00654                 rectified_image = true;
00655 
00656             std::string stream_name(STREAM_NAME(stream));
00657             image_raw << stream_name << "/image_" << ((rectified_image)?"rect_":"") << "raw";
00658             camera_info << stream_name << "/camera_info";
00659 
00660             std::shared_ptr<FrequencyDiagnostics> frequency_diagnostics(new FrequencyDiagnostics(_fps[stream], stream_name, _serial_no));
00661             _image_publishers[stream] = {image_transport.advertise(image_raw.str(), 1), frequency_diagnostics};
00662             _info_publisher[stream] = _node_handle.advertise<sensor_msgs::CameraInfo>(camera_info.str(), 1);
00663 
00664             if (_align_depth && (stream != DEPTH) && stream.second < 2)
00665             {
00666                 std::stringstream aligned_image_raw, aligned_camera_info;
00667                 aligned_image_raw << "aligned_depth_to_" << stream_name << "/image_raw";
00668                 aligned_camera_info << "aligned_depth_to_" << stream_name << "/camera_info";
00669 
00670                 std::string aligned_stream_name = "aligned_depth_to_" + stream_name;
00671                 std::shared_ptr<FrequencyDiagnostics> frequency_diagnostics(new FrequencyDiagnostics(_fps[stream], aligned_stream_name, _serial_no));
00672                 _depth_aligned_image_publishers[stream] = {image_transport.advertise(aligned_image_raw.str(), 1), frequency_diagnostics};
00673                 _depth_aligned_info_publisher[stream] = _node_handle.advertise<sensor_msgs::CameraInfo>(aligned_camera_info.str(), 1);
00674             }
00675 
00676             if (stream == DEPTH && _pointcloud)
00677             {
00678                 _pointcloud_publisher = _node_handle.advertise<sensor_msgs::PointCloud2>("depth/color/points", 1);
00679             }
00680         }
00681     }
00682 
00683     _synced_imu_publisher = std::make_shared<SyncedImuPublisher>();
00684     if (_imu_sync_method > imu_sync_method::NONE && _enable[GYRO] && _enable[ACCEL])
00685     {
00686         ROS_INFO("Start publisher IMU");
00687         _synced_imu_publisher = std::make_shared<SyncedImuPublisher>(_node_handle.advertise<sensor_msgs::Imu>("imu", 1));
00688         _synced_imu_publisher->Enable(_hold_back_imu_for_frames);
00689     }
00690     else
00691     {
00692         if (_enable[GYRO])
00693         {
00694             _imu_publishers[GYRO] = _node_handle.advertise<sensor_msgs::Imu>("gyro/sample", 100);
00695         }
00696 
00697         if (_enable[ACCEL])
00698         {
00699             _imu_publishers[ACCEL] = _node_handle.advertise<sensor_msgs::Imu>("accel/sample", 100);
00700         }
00701     }
00702     if (_enable[POSE])
00703     {
00704         _imu_publishers[POSE] = _node_handle.advertise<nav_msgs::Odometry>("odom/sample", 100);
00705     }
00706 
00707 
00708     if (_enable[FISHEYE] &&
00709         _enable[DEPTH])
00710     {
00711         _depth_to_other_extrinsics_publishers[FISHEYE] = _node_handle.advertise<Extrinsics>("extrinsics/depth_to_fisheye", 1, true);
00712     }
00713 
00714     if (_enable[COLOR] &&
00715         _enable[DEPTH])
00716     {
00717         _depth_to_other_extrinsics_publishers[COLOR] = _node_handle.advertise<Extrinsics>("extrinsics/depth_to_color", 1, true);
00718     }
00719 
00720     if (_enable[INFRA1] &&
00721         _enable[DEPTH])
00722     {
00723         _depth_to_other_extrinsics_publishers[INFRA1] = _node_handle.advertise<Extrinsics>("extrinsics/depth_to_infra1", 1, true);
00724     }
00725 
00726     if (_enable[INFRA2] &&
00727         _enable[DEPTH])
00728     {
00729         _depth_to_other_extrinsics_publishers[INFRA2] = _node_handle.advertise<Extrinsics>("extrinsics/depth_to_infra2", 1, true);
00730     }
00731 }
00732 
00733 void BaseRealSenseNode::publishAlignedDepthToOthers(rs2::frameset frames, const ros::Time& t)
00734 {
00735     for (auto it = frames.begin(); it != frames.end(); ++it)
00736     {
00737         auto frame = (*it);
00738         auto stream_type = frame.get_profile().stream_type();
00739 
00740         if (RS2_STREAM_DEPTH == stream_type)
00741             continue;
00742 
00743         auto stream_index = frame.get_profile().stream_index();
00744         if (stream_index > 1)
00745         {
00746             continue;
00747         }
00748         stream_index_pair sip{stream_type, stream_index};
00749         auto& info_publisher = _depth_aligned_info_publisher.at(sip);
00750         auto& image_publisher = _depth_aligned_image_publishers.at(sip);
00751 
00752         if(0 != info_publisher.getNumSubscribers() ||
00753            0 != image_publisher.first.getNumSubscribers())
00754         {
00755             std::shared_ptr<rs2::align> align;
00756             try{
00757                 align = _align.at(stream_type);
00758             }
00759             catch(const std::out_of_range& e)
00760             {
00761                 ROS_DEBUG_STREAM("Allocate align filter for:" << rs2_stream_to_string(sip.first) << sip.second);
00762                 align = (_align[stream_type] = std::make_shared<rs2::align>(stream_type));
00763             }
00764             rs2::frameset processed = frames.apply_filter(*align);
00765             rs2::depth_frame aligned_depth_frame = processed.get_depth_frame();
00766 
00767             publishFrame(aligned_depth_frame, t, sip,
00768                          _depth_aligned_image,
00769                          _depth_aligned_info_publisher,
00770                          _depth_aligned_image_publishers, _depth_aligned_seq,
00771                          _depth_aligned_camera_info, _optical_frame_id,
00772                          _depth_aligned_encoding);
00773         }
00774     }
00775 }
00776 
00777 void BaseRealSenseNode::enable_devices()
00778 {
00779     for (auto& elem : IMAGE_STREAMS)
00780     {
00781         if (_enable[elem])
00782         {
00783             auto& sens = _sensors[elem];
00784             auto profiles = sens.get_stream_profiles();
00785             for (auto& profile : profiles)
00786             {
00787                 auto video_profile = profile.as<rs2::video_stream_profile>();
00788                 ROS_DEBUG_STREAM("Sensor profile: " <<
00789                                     "stream_type: " << rs2_stream_to_string(elem.first) << "(" << elem.second << ")" <<
00790                                     "Format: " << video_profile.format() <<
00791                                     ", Width: " << video_profile.width() <<
00792                                     ", Height: " << video_profile.height() <<
00793                                     ", FPS: " << video_profile.fps());
00794 
00795                 if ((video_profile.stream_type() == elem.first) &&
00796                     (_width[elem] == 0 || video_profile.width() == _width[elem]) &&
00797                     (_height[elem] == 0 || video_profile.height() == _height[elem]) &&
00798                     (_fps[elem] == 0 || video_profile.fps() == _fps[elem]) &&
00799                     video_profile.stream_index() == elem.second)
00800                 {
00801                     _width[elem] = video_profile.width();
00802                     _height[elem] = video_profile.height();
00803                     _fps[elem] = video_profile.fps();
00804 
00805                     _enabled_profiles[elem].push_back(profile);
00806 
00807                     _image[elem] = cv::Mat(_height[elem], _width[elem], _image_format[elem.first], cv::Scalar(0, 0, 0));
00808 
00809                     ROS_INFO_STREAM(STREAM_NAME(elem) << " stream is enabled - width: " << _width[elem] << ", height: " << _height[elem] << ", fps: " << _fps[elem]);
00810                     break;
00811                 }
00812             }
00813             if (_enabled_profiles.find(elem) == _enabled_profiles.end())
00814             {
00815                 ROS_WARN_STREAM("Given stream configuration is not supported by the device! " <<
00816                     " Stream: " << rs2_stream_to_string(elem.first) <<
00817                     ", Stream Index: " << elem.second <<
00818                     ", Width: " << _width[elem] <<
00819                     ", Height: " << _height[elem] <<
00820                     ", FPS: " << _fps[elem]);
00821                 _enable[elem] = false;
00822             }
00823         }
00824     }
00825         if (_align_depth)
00826         {
00827                 for (auto& profiles : _enabled_profiles)
00828                 {
00829                         _depth_aligned_image[profiles.first] = cv::Mat(_height[DEPTH], _width[DEPTH], _image_format[DEPTH.first], cv::Scalar(0, 0, 0));
00830                         _depth_scaled_image[profiles.first] = cv::Mat(_height[DEPTH], _width[DEPTH], _image_format[DEPTH.first], cv::Scalar(0, 0, 0));
00831                 }
00832         }
00833 
00834     // Streaming HID
00835     for (auto& elem : HID_STREAMS)
00836     {
00837         if (_enable[elem])
00838         {
00839             auto& sens = _sensors[elem];
00840             auto profiles = sens.get_stream_profiles();
00841             ROS_DEBUG_STREAM("Available profiles:");
00842             for (rs2::stream_profile& profile : profiles)
00843             {
00844                 ROS_DEBUG_STREAM("type:" << rs2_stream_to_string(profile.stream_type()) <<
00845                                 " fps: " << profile.fps() << ". format: " << profile.format());
00846             }
00847             for (rs2::stream_profile& profile : profiles)
00848             {
00849                 if (profile.stream_type() == elem.first &&
00850                    (_fps[elem] == 0 || profile.fps() == _fps[elem]))
00851                 {
00852                     _fps[elem] = profile.fps();
00853                     _enabled_profiles[elem].push_back(profile);
00854                     break;
00855                 }
00856             }
00857             if (_enabled_profiles.find(elem) == _enabled_profiles.end())
00858             {
00859                 std::string stream_name(STREAM_NAME(elem));
00860                 ROS_WARN_STREAM("No mathcing profile found for " << stream_name << " with fps=" << _fps[elem]);
00861                 ROS_WARN_STREAM("profiles found for " <<stream_name << ":");
00862                 for (rs2::stream_profile& profile : profiles)
00863                 {
00864                     if (profile.stream_type() != elem.first) continue;
00865                     ROS_WARN_STREAM("fps: " << profile.fps() << ". format: " << profile.format());
00866                 }
00867                 _enable[elem] = false;
00868             }
00869         }
00870     }
00871 }
00872 
00873 void BaseRealSenseNode::setupFilters()
00874 {
00875     std::vector<std::string> filters_str;
00876     boost::split(filters_str, _filters_str, [](char c){return c == ',';});
00877     bool use_disparity_filter(false);
00878     bool use_colorizer_filter(false);
00879     bool use_decimation_filter(false);
00880     for (std::vector<std::string>::const_iterator s_iter=filters_str.begin(); s_iter!=filters_str.end(); s_iter++)
00881     {
00882         if ((*s_iter) == "colorizer")
00883         {
00884             use_colorizer_filter = true;
00885         }
00886         else if ((*s_iter) == "disparity")
00887         {
00888             use_disparity_filter = true;
00889         }
00890         else if ((*s_iter) == "spatial")
00891         {
00892             ROS_INFO("Add Filter: spatial");
00893             _filters.push_back(NamedFilter("spatial", std::make_shared<rs2::spatial_filter>()));
00894         }
00895         else if ((*s_iter) == "temporal")
00896         {
00897             ROS_INFO("Add Filter: temporal");
00898             _filters.push_back(NamedFilter("temporal", std::make_shared<rs2::temporal_filter>()));
00899         }
00900         else if ((*s_iter) == "hole_filling")
00901         {
00902             ROS_INFO("Add Filter: hole_filling");
00903             _filters.push_back(NamedFilter("hole_filling", std::make_shared<rs2::hole_filling_filter>()));
00904         }
00905         else if ((*s_iter) == "decimation")
00906         {
00907             use_decimation_filter = true;
00908         }
00909         else if ((*s_iter) == "pointcloud")
00910         {
00911             assert(_pointcloud); // For now, it is set in getParameters()..
00912         }
00913         else if ((*s_iter).size() > 0)
00914         {
00915             ROS_ERROR_STREAM("Unknown Filter: " << (*s_iter));
00916             throw;
00917         }
00918     }
00919     if (use_disparity_filter)
00920     {
00921         ROS_INFO("Add Filter: disparity");
00922         _filters.insert(_filters.begin(), NamedFilter("disparity_start", std::make_shared<rs2::disparity_transform>()));
00923         _filters.push_back(NamedFilter("disparity_end", std::make_shared<rs2::disparity_transform>(false)));
00924         ROS_INFO("Done Add Filter: disparity");
00925     }
00926     if (use_decimation_filter)
00927     {
00928       ROS_INFO("Add Filter: decimation");
00929       _filters.insert(_filters.begin(),NamedFilter("decimation", std::make_shared<rs2::decimation_filter>()));
00930     }
00931     if (use_colorizer_filter)
00932     {
00933         ROS_INFO("Add Filter: colorizer");
00934         _filters.push_back(NamedFilter("colorizer", std::make_shared<rs2::colorizer>()));
00935 
00936         // Types for depth stream
00937         _image_format[DEPTH.first] = _image_format[COLOR.first];    // CVBridge type
00938         _encoding[DEPTH.first] = _encoding[COLOR.first]; // ROS message type
00939         _unit_step_size[DEPTH.first] = _unit_step_size[COLOR.first]; // sensor_msgs::ImagePtr row step size
00940 
00941         _width[DEPTH] = _width[COLOR];
00942         _height[DEPTH] = _height[COLOR];
00943         _image[DEPTH] = cv::Mat(_height[DEPTH], _width[DEPTH], _image_format[DEPTH.first], cv::Scalar(0, 0, 0));
00944     }
00945     if (_pointcloud)
00946     {
00947         ROS_INFO("Add Filter: pointcloud");
00948         _filters.push_back(NamedFilter("pointcloud", std::make_shared<rs2::pointcloud>(_pointcloud_texture.first, _pointcloud_texture.second)));
00949     }
00950     ROS_INFO("num_filters: %d", static_cast<int>(_filters.size()));
00951 }
00952 
00953 
00954 
00955 cv::Mat& BaseRealSenseNode::fix_depth_scale(const cv::Mat& from_image, cv::Mat& to_image)
00956 {
00957     static const auto meter_to_mm = 0.001f;
00958     if (abs(_depth_scale_meters - meter_to_mm) < 1e-6)
00959     {
00960         to_image = from_image;
00961         return to_image;
00962     }
00963 
00964     if (to_image.size() != from_image.size())
00965     {
00966         to_image.create(from_image.rows, from_image.cols, from_image.type());
00967     }
00968 
00969     CV_Assert(from_image.depth() == _image_format[RS2_STREAM_DEPTH]);
00970 
00971     int nRows = from_image.rows;
00972     int nCols = from_image.cols;
00973 
00974     if (from_image.isContinuous())
00975     {
00976         nCols *= nRows;
00977         nRows = 1;
00978     }
00979 
00980     int i,j;
00981     const uint16_t* p_from;
00982     uint16_t* p_to;
00983     for( i = 0; i < nRows; ++i)
00984     {
00985         p_from = from_image.ptr<uint16_t>(i);
00986         p_to = to_image.ptr<uint16_t>(i);
00987         for ( j = 0; j < nCols; ++j)
00988         {
00989             p_to[j] = p_from[j] * _depth_scale_meters / meter_to_mm;
00990         }
00991     }
00992     return to_image;
00993 }
00994 
00995 void BaseRealSenseNode::clip_depth(rs2::depth_frame depth_frame, float clipping_dist)
00996 {
00997     uint16_t* p_depth_frame = reinterpret_cast<uint16_t*>(const_cast<void*>(depth_frame.get_data()));
00998     uint16_t clipping_value = static_cast<uint16_t>(clipping_dist / _depth_scale_meters);
00999 
01000     int width = depth_frame.get_width();
01001     int height = depth_frame.get_height();
01002 
01003     #ifdef _OPENMP
01004     #pragma omp parallel for schedule(dynamic) //Using OpenMP to try to parallelise the loop
01005     #endif
01006     for (int y = 0; y < height; y++)
01007     {
01008         auto depth_pixel_index = y * width;
01009         for (int x = 0; x < width; x++, ++depth_pixel_index)
01010         {
01011             // Check if the depth value is greater than the threashold
01012             if (p_depth_frame[depth_pixel_index] > clipping_value)
01013             {
01014                 p_depth_frame[depth_pixel_index] = 0; //Set to invalid (<=0) value.
01015             }
01016         }
01017     }
01018 }
01019 
01020 BaseRealSenseNode::CIMUHistory::CIMUHistory(size_t size)
01021 {
01022     m_max_size = size;
01023 }
01024 void BaseRealSenseNode::CIMUHistory::add_data(sensor_name module, BaseRealSenseNode::CIMUHistory::imuData data)
01025 {
01026     m_map[module].push_front(data);
01027     if (m_map[module].size() > m_max_size)
01028         m_map[module].pop_back();
01029 }
01030 bool BaseRealSenseNode::CIMUHistory::is_all_data(sensor_name module)
01031 {
01032     return m_map[module].size() == m_max_size;
01033 }
01034 bool BaseRealSenseNode::CIMUHistory::is_data(sensor_name module)
01035 {
01036     return m_map[module].size() > 0;
01037 }
01038 const std::list<BaseRealSenseNode::CIMUHistory::imuData>& BaseRealSenseNode::CIMUHistory::get_data(sensor_name module)
01039 {
01040     return m_map[module];
01041 }
01042 BaseRealSenseNode::CIMUHistory::imuData BaseRealSenseNode::CIMUHistory::last_data(sensor_name module)
01043 {
01044     return m_map[module].front();
01045 }
01046 BaseRealSenseNode::CIMUHistory::imuData BaseRealSenseNode::CIMUHistory::imuData::operator*(const double factor)
01047 {
01048     BaseRealSenseNode::CIMUHistory::imuData new_data(*this);
01049     new_data.m_reading *= factor;
01050     new_data.m_time *= factor;
01051     return new_data;
01052 }
01053 
01054 BaseRealSenseNode::CIMUHistory::imuData BaseRealSenseNode::CIMUHistory::imuData::operator+(const BaseRealSenseNode::CIMUHistory::imuData& other)
01055 {
01056     BaseRealSenseNode::CIMUHistory::imuData new_data(*this);
01057     new_data.m_reading += other.m_reading;
01058     new_data.m_time += other.m_time;
01059     return new_data;
01060 }
01061 
01062 double BaseRealSenseNode::FillImuData_LinearInterpolation(const stream_index_pair stream_index, const BaseRealSenseNode::CIMUHistory::imuData imu_data, sensor_msgs::Imu& imu_msg)
01063 {
01064     static CIMUHistory _imu_history(2);
01065     CIMUHistory::sensor_name this_sensor(static_cast<CIMUHistory::sensor_name>(ACCEL == stream_index));
01066     CIMUHistory::sensor_name that_sensor(static_cast<CIMUHistory::sensor_name>(!this_sensor));
01067     _imu_history.add_data(this_sensor, imu_data);
01068 
01069     if (!_imu_history.is_all_data(this_sensor) || !_imu_history.is_data(that_sensor) )
01070         return -1;
01071     const std::list<CIMUHistory::imuData> this_data = _imu_history.get_data(this_sensor);
01072     CIMUHistory::imuData that_last_data = _imu_history.last_data(that_sensor);
01073     std::list<CIMUHistory::imuData>::const_iterator this_data_iter = this_data.begin();
01074     CIMUHistory::imuData this_last_data(*this_data_iter);
01075     this_data_iter++;
01076     CIMUHistory::imuData this_prev_data(*this_data_iter);
01077     if (this_prev_data.m_time > that_last_data.m_time)
01078         return -1;  // "that" data was already sent.
01079     double factor( (that_last_data.m_time - this_prev_data.m_time) / (this_last_data.m_time - this_prev_data.m_time) );
01080     CIMUHistory::imuData interp_data = this_prev_data*(1-factor) + this_last_data*factor;
01081 
01082     CIMUHistory::imuData accel_data = that_last_data;
01083     CIMUHistory::imuData gyro_data = interp_data;
01084     if (this_sensor == CIMUHistory::sensor_name::mACCEL)
01085     {
01086         std::swap(accel_data, gyro_data);
01087     }
01088     imu_msg.angular_velocity.x = gyro_data.m_reading.x;
01089     imu_msg.angular_velocity.y = gyro_data.m_reading.y;
01090     imu_msg.angular_velocity.z = gyro_data.m_reading.z;
01091 
01092     imu_msg.linear_acceleration.x = accel_data.m_reading.x;
01093     imu_msg.linear_acceleration.y = accel_data.m_reading.y;
01094     imu_msg.linear_acceleration.z = accel_data.m_reading.z;
01095     return that_last_data.m_time;
01096 }
01097 
01098 
01099 double BaseRealSenseNode::FillImuData_Copy(const stream_index_pair stream_index, const BaseRealSenseNode::CIMUHistory::imuData imu_data, sensor_msgs::Imu& imu_msg)
01100 {
01101     if (GYRO == stream_index)
01102     {
01103         imu_msg.angular_velocity.x = imu_data.m_reading.x;
01104         imu_msg.angular_velocity.y = imu_data.m_reading.y;
01105         imu_msg.angular_velocity.z = imu_data.m_reading.z;
01106     }
01107     else if (ACCEL == stream_index)
01108     {
01109         imu_msg.linear_acceleration.x = imu_data.m_reading.x;
01110         imu_msg.linear_acceleration.y = imu_data.m_reading.y;
01111         imu_msg.linear_acceleration.z = imu_data.m_reading.z;
01112     }
01113     return imu_data.m_time;
01114 }
01115 
01116 void BaseRealSenseNode::imu_callback_sync(rs2::frame frame, imu_sync_method sync_method)
01117 {
01118     static std::mutex m_mutex;
01119     static const stream_index_pair stream_imu = GYRO;
01120     static sensor_msgs::Imu imu_msg = sensor_msgs::Imu();
01121     static int seq = 0;
01122     static bool init_gyro(false), init_accel(false);
01123     static double accel_factor(0);
01124     imu_msg.header.frame_id = _optical_frame_id[stream_imu];
01125     imu_msg.orientation.x = 0.0;
01126     imu_msg.orientation.y = 0.0;
01127     imu_msg.orientation.z = 0.0;
01128     imu_msg.orientation.w = 0.0;
01129 
01130     imu_msg.orientation_covariance = { -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
01131     imu_msg.linear_acceleration_covariance = { _linear_accel_cov, 0.0, 0.0, 0.0, _linear_accel_cov, 0.0, 0.0, 0.0, _linear_accel_cov};
01132     imu_msg.angular_velocity_covariance = { _angular_velocity_cov, 0.0, 0.0, 0.0, _angular_velocity_cov, 0.0, 0.0, 0.0, _angular_velocity_cov};
01133 
01134     m_mutex.lock();
01135 
01136     while (true)
01137     {
01138         auto stream = frame.get_profile().stream_type();
01139         auto stream_index = (stream == GYRO.first)?GYRO:ACCEL;
01140         double frame_time = frame.get_timestamp();
01141 
01142         bool placeholder_false(false);
01143         if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
01144         {
01145             setBaseTime(frame_time, RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME == frame.get_frame_timestamp_domain());
01146         }
01147 
01148         seq += 1;
01149         double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;
01150 
01151         if (0 != _synced_imu_publisher->getNumSubscribers())
01152         {
01153             auto crnt_reading = *(reinterpret_cast<const float3*>(frame.get_data()));
01154             if (GYRO == stream_index)
01155             {
01156                 init_gyro = true;
01157             }
01158             if (ACCEL == stream_index)
01159             {
01160                 if (!init_accel)
01161                 {
01162                     // Init accel_factor:
01163                     Eigen::Vector3d v(crnt_reading.x, crnt_reading.y, crnt_reading.z);
01164                     accel_factor = 9.81 / v.norm();
01165                     ROS_INFO_STREAM("accel_factor set to: " << accel_factor);
01166                 }
01167                 init_accel = true;
01168                 if (true)
01169                 {
01170                     Eigen::Vector3d v(crnt_reading.x, crnt_reading.y, crnt_reading.z);
01171                     v*=accel_factor;
01172                     crnt_reading.x = v.x();
01173                     crnt_reading.y = v.y();
01174                     crnt_reading.z = v.z();
01175                 }
01176             }
01177             CIMUHistory::imuData imu_data(crnt_reading, elapsed_camera_ms);
01178             switch (sync_method)
01179             {
01180                 case NONE: //Cannot really be NONE. Just to avoid compilation warning.
01181                 case COPY:
01182                     elapsed_camera_ms = FillImuData_Copy(stream_index, imu_data, imu_msg);
01183                     break;
01184                 case LINEAR_INTERPOLATION:
01185                     elapsed_camera_ms = FillImuData_LinearInterpolation(stream_index, imu_data, imu_msg);
01186                     break;
01187             }
01188             if (elapsed_camera_ms < 0)
01189                 break;
01190             ros::Time t(_ros_time_base.toSec() + elapsed_camera_ms);
01191             imu_msg.header.seq = seq;
01192             imu_msg.header.stamp = t;
01193             if (!(init_gyro && init_accel))
01194                 break;
01195             _synced_imu_publisher->Publish(imu_msg);
01196             ROS_DEBUG("Publish united %s stream", rs2_stream_to_string(frame.get_profile().stream_type()));
01197         }
01198         break;
01199     }
01200     m_mutex.unlock();
01201 };
01202 
01203 void BaseRealSenseNode::imu_callback(rs2::frame frame)
01204 {
01205     auto stream = frame.get_profile().stream_type();
01206     double frame_time = frame.get_timestamp();
01207     bool placeholder_false(false);
01208     if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
01209     {
01210         setBaseTime(frame_time, RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME == frame.get_frame_timestamp_domain());
01211     }
01212 
01213     ROS_DEBUG("Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
01214                 rs2_stream_to_string(frame.get_profile().stream_type()),
01215                 frame.get_profile().stream_index(),
01216                 rs2_timestamp_domain_to_string(frame.get_frame_timestamp_domain()));
01217 
01218     auto stream_index = (stream == GYRO.first)?GYRO:ACCEL;
01219     if (0 != _imu_publishers[stream_index].getNumSubscribers())
01220     {
01221         double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;
01222         ros::Time t(_ros_time_base.toSec() + elapsed_camera_ms);
01223 
01224         auto imu_msg = sensor_msgs::Imu();
01225         imu_msg.header.frame_id = _optical_frame_id[stream_index];
01226         imu_msg.orientation.x = 0.0;
01227         imu_msg.orientation.y = 0.0;
01228         imu_msg.orientation.z = 0.0;
01229         imu_msg.orientation.w = 0.0;
01230         imu_msg.orientation_covariance = { -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
01231         imu_msg.linear_acceleration_covariance = { _linear_accel_cov, 0.0, 0.0, 0.0, _linear_accel_cov, 0.0, 0.0, 0.0, _linear_accel_cov};
01232         imu_msg.angular_velocity_covariance = { _angular_velocity_cov, 0.0, 0.0, 0.0, _angular_velocity_cov, 0.0, 0.0, 0.0, _angular_velocity_cov};
01233 
01234         auto crnt_reading = *(reinterpret_cast<const float3*>(frame.get_data()));
01235         if (GYRO == stream_index)
01236         {
01237             imu_msg.angular_velocity.x = crnt_reading.x;
01238             imu_msg.angular_velocity.y = crnt_reading.y;
01239             imu_msg.angular_velocity.z = crnt_reading.z;
01240         }
01241         else if (ACCEL == stream_index)
01242         {
01243             imu_msg.linear_acceleration.x = crnt_reading.x;
01244             imu_msg.linear_acceleration.y = crnt_reading.y;
01245             imu_msg.linear_acceleration.z = crnt_reading.z;
01246         }
01247         _seq[stream_index] += 1;
01248         imu_msg.header.seq = _seq[stream_index];
01249         imu_msg.header.stamp = t;
01250         _imu_publishers[stream_index].publish(imu_msg);
01251         ROS_DEBUG("Publish %s stream", rs2_stream_to_string(frame.get_profile().stream_type()));
01252     }
01253 }
01254 
01255 void BaseRealSenseNode::pose_callback(rs2::frame frame)
01256 {
01257     double frame_time = frame.get_timestamp();
01258     bool placeholder_false(false);
01259     if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
01260     {
01261         setBaseTime(frame_time, RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME == frame.get_frame_timestamp_domain());
01262     }
01263 
01264     ROS_DEBUG("Frame arrived: stream: %s ; index: %d ; Timestamp Domain: %s",
01265                 rs2_stream_to_string(frame.get_profile().stream_type()),
01266                 frame.get_profile().stream_index(),
01267                 rs2_timestamp_domain_to_string(frame.get_frame_timestamp_domain()));
01268     const auto& stream_index(POSE);
01269     rs2_pose pose = frame.as<rs2::pose_frame>().get_pose_data();
01270     double elapsed_camera_ms = (/*ms*/ frame_time - /*ms*/ _camera_time_base) / 1000.0;
01271     ros::Time t(_ros_time_base.toSec() + elapsed_camera_ms);
01272 
01273     geometry_msgs::PoseStamped pose_msg;
01274     pose_msg.pose.position.x = -pose.translation.z;
01275     pose_msg.pose.position.y = -pose.translation.x;
01276     pose_msg.pose.position.z = pose.translation.y;
01277     pose_msg.pose.orientation.x = -pose.rotation.z;
01278     pose_msg.pose.orientation.y = -pose.rotation.x;
01279     pose_msg.pose.orientation.z = pose.rotation.y;
01280     pose_msg.pose.orientation.w = pose.rotation.w;
01281 
01282     static tf2_ros::TransformBroadcaster br;
01283     geometry_msgs::TransformStamped msg;
01284     msg.header.stamp = t;
01285     msg.header.frame_id = _odom_frame_id;
01286     msg.child_frame_id = _frame_id[POSE];
01287     msg.transform.translation.x = pose_msg.pose.position.x;
01288     msg.transform.translation.y = pose_msg.pose.position.y;
01289     msg.transform.translation.z = pose_msg.pose.position.z;
01290     msg.transform.rotation.x = pose_msg.pose.orientation.x;
01291     msg.transform.rotation.y = pose_msg.pose.orientation.y;
01292     msg.transform.rotation.z = pose_msg.pose.orientation.z;
01293     msg.transform.rotation.w = pose_msg.pose.orientation.w;
01294 
01295     if (_publish_odom_tf) br.sendTransform(msg);
01296 
01297     if (0 != _imu_publishers[stream_index].getNumSubscribers())
01298     {
01299         double cov_pose(_linear_accel_cov * pow(10, 3-(int)pose.tracker_confidence));
01300         double cov_twist(_angular_velocity_cov * pow(10, 1-(int)pose.tracker_confidence));
01301 
01302         geometry_msgs::Vector3Stamped v_msg;
01303         v_msg.vector.x = -pose.velocity.z;
01304         v_msg.vector.y = -pose.velocity.x;
01305         v_msg.vector.z = pose.velocity.y;
01306         tf::Vector3 tfv;
01307         tf::vector3MsgToTF(v_msg.vector,tfv);
01308         tf::Quaternion q(-msg.transform.rotation.x,-msg.transform.rotation.y,-msg.transform.rotation.z,msg.transform.rotation.w);
01309         tfv=tf::quatRotate(q,tfv);
01310         tf::vector3TFToMsg(tfv,v_msg.vector);
01311         
01312         geometry_msgs::Vector3Stamped om_msg;
01313         om_msg.vector.x = -pose.angular_velocity.z;
01314         om_msg.vector.y = -pose.angular_velocity.x;
01315         om_msg.vector.z = pose.angular_velocity.y;
01316         tf::vector3MsgToTF(om_msg.vector,tfv);
01317         tfv=tf::quatRotate(q,tfv);
01318         tf::vector3TFToMsg(tfv,om_msg.vector);
01319         
01320 
01321         nav_msgs::Odometry odom_msg;
01322         _seq[stream_index] += 1;
01323 
01324         odom_msg.header.frame_id = _odom_frame_id;
01325         odom_msg.child_frame_id = _frame_id[POSE];
01326         odom_msg.header.stamp = t;
01327         odom_msg.header.seq = _seq[stream_index];
01328         odom_msg.pose.pose = pose_msg.pose;
01329         odom_msg.pose.covariance = {cov_pose, 0, 0, 0, 0, 0,
01330                                     0, cov_pose, 0, 0, 0, 0,
01331                                     0, 0, cov_pose, 0, 0, 0,
01332                                     0, 0, 0, cov_twist, 0, 0,
01333                                     0, 0, 0, 0, cov_twist, 0,
01334                                     0, 0, 0, 0, 0, cov_twist};
01335         odom_msg.twist.twist.linear = v_msg.vector;
01336         odom_msg.twist.twist.angular = om_msg.vector;
01337         odom_msg.twist.covariance ={cov_pose, 0, 0, 0, 0, 0,
01338                                     0, cov_pose, 0, 0, 0, 0,
01339                                     0, 0, cov_pose, 0, 0, 0,
01340                                     0, 0, 0, cov_twist, 0, 0,
01341                                     0, 0, 0, 0, cov_twist, 0,
01342                                     0, 0, 0, 0, 0, cov_twist};
01343         _imu_publishers[stream_index].publish(odom_msg);
01344         ROS_DEBUG("Publish %s stream", rs2_stream_to_string(frame.get_profile().stream_type()));
01345     }
01346 }
01347 
01348 void BaseRealSenseNode::frame_callback(rs2::frame frame)
01349 {
01350     _synced_imu_publisher->Pause();
01351     
01352     try{
01353         double frame_time = frame.get_timestamp();
01354 
01355         // We compute a ROS timestamp which is based on an initial ROS time at point of first frame,
01356         // and the incremental timestamp from the camera.
01357         // In sync mode the timestamp is based on ROS time
01358         bool placeholder_false(false);
01359         if (_is_initialized_time_base.compare_exchange_strong(placeholder_false, true) )
01360         {
01361             setBaseTime(frame_time, RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME == frame.get_frame_timestamp_domain());
01362         }
01363 
01364         ros::Time t;
01365         if (_sync_frames)
01366         {
01367             t = ros::Time::now();
01368         }
01369         else
01370         {
01371             t = ros::Time(_ros_time_base.toSec()+ (/*ms*/ frame_time - /*ms*/ _camera_time_base) / /*ms to seconds*/ 1000);
01372         }
01373 
01374         if (frame.is<rs2::frameset>())
01375         {
01376             ROS_DEBUG("Frameset arrived.");
01377             bool is_depth_arrived = false;
01378             auto frameset = frame.as<rs2::frameset>();
01379             ROS_DEBUG("List of frameset before applying filters: size: %d", static_cast<int>(frameset.size()));
01380             for (auto it = frameset.begin(); it != frameset.end(); ++it)
01381             {
01382                 auto f = (*it);
01383                 auto stream_type = f.get_profile().stream_type();
01384                 auto stream_index = f.get_profile().stream_index();
01385                 auto stream_format = f.get_profile().format();
01386                 auto stream_unique_id = f.get_profile().unique_id();
01387 
01388                 ROS_DEBUG("Frameset contain (%s, %d, %s %d) frame. frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
01389                             rs2_stream_to_string(stream_type), stream_index, rs2_format_to_string(stream_format), stream_unique_id, frame.get_frame_number(), frame_time, t.toNSec());
01390             }
01391             // Clip depth_frame for max range:
01392             rs2::depth_frame depth_frame = frameset.get_depth_frame();
01393             if (depth_frame && _clipping_distance > 0)
01394             {
01395                 clip_depth(depth_frame, _clipping_distance);
01396             }
01397 
01398             ROS_DEBUG("num_filters: %d", static_cast<int>(_filters.size()));
01399             for (std::vector<NamedFilter>::const_iterator filter_it = _filters.begin(); filter_it != _filters.end(); filter_it++)
01400             {
01401                 ROS_DEBUG("Applying filter: %s", filter_it->_name.c_str());
01402                 frameset = filter_it->_filter->process(frameset);
01403             }
01404 
01405             ROS_DEBUG("List of frameset after applying filters: size: %d", static_cast<int>(frameset.size()));
01406             for (auto it = frameset.begin(); it != frameset.end(); ++it)
01407             {
01408                 auto f = (*it);
01409                 auto stream_type = f.get_profile().stream_type();
01410                 auto stream_index = f.get_profile().stream_index();
01411                 auto stream_format = f.get_profile().format();
01412                 auto stream_unique_id = f.get_profile().unique_id();
01413 
01414                 ROS_DEBUG("Frameset contain (%s, %d, %s %d) frame. frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
01415                             rs2_stream_to_string(stream_type), stream_index, rs2_format_to_string(stream_format), stream_unique_id, frame.get_frame_number(), frame_time, t.toNSec());
01416             }
01417             ROS_DEBUG("END OF LIST");
01418             ROS_DEBUG_STREAM("Remove streams with same type and index:");
01419             // TODO - Fix the following issue:
01420             // Currently publishers are set using a map of stream type and index only.
01421             // It means that colorized depth image <DEPTH, 0, Z16> and colorized depth image <DEPTH, 0, RGB>
01422             // use the same publisher.
01423             // As a workaround we remove the earlier one, the original one, assuming that if colorizer filter is
01424             // set it means that that's what the client wants.
01425             //
01426             bool points_in_set(false);
01427             std::vector<rs2::frame> frames_to_publish;
01428             std::vector<stream_index_pair> is_in_set;
01429             for (auto it = frameset.begin(); it != frameset.end(); ++it)
01430             {
01431                 auto f = (*it);
01432                 auto stream_type = f.get_profile().stream_type();
01433                 auto stream_index = f.get_profile().stream_index();
01434                 auto stream_format = f.get_profile().format();
01435                 if (f.is<rs2::points>())
01436                 {
01437                     if (!points_in_set)
01438                     {
01439                         points_in_set = true;
01440                         frames_to_publish.push_back(f);
01441                     }
01442                     continue;
01443                 }
01444                 stream_index_pair sip{stream_type,stream_index};
01445                 if (std::find(is_in_set.begin(), is_in_set.end(), sip) == is_in_set.end())
01446                 {
01447                     is_in_set.push_back(sip);
01448                     frames_to_publish.push_back(f);
01449                 }
01450                 if (_align_depth && stream_type == RS2_STREAM_DEPTH && stream_format == RS2_FORMAT_Z16)
01451                 {
01452                     is_depth_arrived = true;
01453                 }
01454             }
01455 
01456             for (auto it = frames_to_publish.begin(); it != frames_to_publish.end(); ++it)
01457             {
01458                 auto f = (*it);
01459                 auto stream_type = f.get_profile().stream_type();
01460                 auto stream_index = f.get_profile().stream_index();
01461                 auto stream_format = f.get_profile().format();
01462 
01463                 ROS_DEBUG("Frameset contain (%s, %d, %s) frame. frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
01464                             rs2_stream_to_string(stream_type), stream_index, rs2_format_to_string(stream_format), frame.get_frame_number(), frame_time, t.toNSec());
01465 
01466                 if (f.is<rs2::points>())
01467                 {
01468                     if (0 != _pointcloud_publisher.getNumSubscribers())
01469                     {
01470                         ROS_DEBUG("Publish pointscloud");
01471                         publishPointCloud(f.as<rs2::points>(), t, frameset);
01472                     }
01473                     continue;
01474                 }
01475                 stream_index_pair sip{stream_type,stream_index};
01476                 publishFrame(f, t,
01477                                 sip,
01478                                 _image,
01479                                 _info_publisher,
01480                                 _image_publishers, _seq,
01481                                 _camera_info, _optical_frame_id,
01482                                 _encoding);
01483             }
01484 
01485             if (_align_depth && is_depth_arrived)
01486             {
01487                 ROS_DEBUG("publishAlignedDepthToOthers(...)");
01488                 publishAlignedDepthToOthers(frameset, t);
01489             }
01490         }
01491         else if (frame.is<rs2::video_frame>())
01492         {
01493             auto stream_type = frame.get_profile().stream_type();
01494             auto stream_index = frame.get_profile().stream_index();
01495             ROS_DEBUG("Single video frame arrived (%s, %d). frame_number: %llu ; frame_TS: %f ; ros_TS(NSec): %lu",
01496                         rs2_stream_to_string(stream_type), stream_index, frame.get_frame_number(), frame_time, t.toNSec());
01497 
01498             stream_index_pair sip{stream_type,stream_index};
01499             if (frame.is<rs2::depth_frame>())
01500             {
01501                 if (_clipping_distance > 0)
01502                 {
01503                     clip_depth(frame, _clipping_distance);
01504                 }
01505             }
01506             publishFrame(frame, t,
01507                             sip,
01508                             _image,
01509                             _info_publisher,
01510                             _image_publishers, _seq,
01511                             _camera_info, _optical_frame_id,
01512                             _encoding);
01513         }
01514     }
01515     catch(const std::exception& ex)
01516     {
01517         ROS_ERROR_STREAM("An error has occurred during frame callback: " << ex.what());
01518     }
01519     _synced_imu_publisher->Resume();
01520 }; // frame_callback
01521 
01522 void BaseRealSenseNode::multiple_message_callback(rs2::frame frame, imu_sync_method sync_method)
01523 {
01524     auto stream = frame.get_profile().stream_type();
01525     switch (stream)
01526     {
01527         case RS2_STREAM_GYRO:
01528         case RS2_STREAM_ACCEL:
01529             if (sync_method > imu_sync_method::NONE) imu_callback_sync(frame, sync_method);
01530             else imu_callback(frame);
01531             break;
01532         case RS2_STREAM_POSE:
01533             pose_callback(frame);
01534             break;
01535         default:
01536             frame_callback(frame);
01537     }
01538 }
01539 
01540 void BaseRealSenseNode::setBaseTime(double frame_time, bool warn_no_metadata)
01541 {
01542     ROS_WARN_COND(warn_no_metadata, "Frame metadata isn't available! (frame_timestamp_domain = RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)");
01543 
01544     _ros_time_base = ros::Time::now();
01545     _camera_time_base = frame_time;
01546 }
01547 
01548 void BaseRealSenseNode::setupStreams()
01549 {
01550         ROS_INFO("setupStreams...");
01551     try{
01552                 // Publish image stream info
01553         for (auto& profiles : _enabled_profiles)
01554         {
01555             for (auto& profile : profiles.second)
01556             {
01557                 if (profile.is<rs2::video_stream_profile>())
01558                 {
01559                     auto video_profile = profile.as<rs2::video_stream_profile>();
01560                     updateStreamCalibData(video_profile);
01561                 }
01562             }
01563         }
01564 
01565         // Streaming IMAGES
01566         std::map<std::string, std::vector<rs2::stream_profile> > profiles;
01567         std::map<std::string, rs2::sensor> active_sensors;
01568         for (const std::pair<stream_index_pair, std::vector<rs2::stream_profile>>& profile : _enabled_profiles)
01569         {
01570             std::string module_name = _sensors[profile.first].get_info(RS2_CAMERA_INFO_NAME);
01571             ROS_INFO_STREAM("insert " << rs2_stream_to_string(profile.second.begin()->stream_type())
01572               << " to " << module_name);
01573             profiles[module_name].insert(profiles[module_name].begin(),
01574                                             profile.second.begin(),
01575                                             profile.second.end());
01576             active_sensors[module_name] = _sensors[profile.first];
01577         }
01578 
01579         for (const std::pair<std::string, std::vector<rs2::stream_profile> >& sensor_profile : profiles)
01580         {
01581             std::string module_name = sensor_profile.first;
01582             // for (const rs2::stream_profile& profile : sensor_profile.second)
01583             // {
01584             //     ROS_WARN_STREAM("type:" << rs2_stream_to_string(profile.stream_type()) <<
01585             //                     " fps: " << profile.fps() << ". format: " << profile.format());
01586             // }
01587             rs2::sensor sensor = active_sensors[module_name];
01588             sensor.open(sensor_profile.second);
01589             sensor.start(_sensors_callback[module_name]);
01590             if (sensor.is<rs2::depth_sensor>())
01591             {
01592                 _depth_scale_meters = sensor.as<rs2::depth_sensor>().get_depth_scale();
01593             }
01594         }
01595     }
01596     catch(const std::exception& ex)
01597     {
01598         ROS_ERROR_STREAM("An exception has been thrown: " << ex.what());
01599         throw;
01600     }
01601     catch(...)
01602     {
01603         ROS_ERROR_STREAM("Unknown exception has occured!");
01604         throw;
01605     }
01606 }
01607 
01608 void BaseRealSenseNode::updateStreamCalibData(const rs2::video_stream_profile& video_profile)
01609 {
01610     stream_index_pair stream_index{video_profile.stream_type(), video_profile.stream_index()};
01611     auto intrinsic = video_profile.get_intrinsics();
01612     _stream_intrinsics[stream_index] = intrinsic;
01613     _camera_info[stream_index].width = intrinsic.width;
01614     _camera_info[stream_index].height = intrinsic.height;
01615     _camera_info[stream_index].header.frame_id = _optical_frame_id[stream_index];
01616 
01617     _camera_info[stream_index].K.at(0) = intrinsic.fx;
01618     _camera_info[stream_index].K.at(2) = intrinsic.ppx;
01619     _camera_info[stream_index].K.at(4) = intrinsic.fy;
01620     _camera_info[stream_index].K.at(5) = intrinsic.ppy;
01621     _camera_info[stream_index].K.at(8) = 1;
01622 
01623     _camera_info[stream_index].P.at(0) = _camera_info[stream_index].K.at(0);
01624     _camera_info[stream_index].P.at(1) = 0;
01625     _camera_info[stream_index].P.at(2) = _camera_info[stream_index].K.at(2);
01626     _camera_info[stream_index].P.at(3) = 0;
01627     _camera_info[stream_index].P.at(4) = 0;
01628     _camera_info[stream_index].P.at(5) = _camera_info[stream_index].K.at(4);
01629     _camera_info[stream_index].P.at(6) = _camera_info[stream_index].K.at(5);
01630     _camera_info[stream_index].P.at(7) = 0;
01631     _camera_info[stream_index].P.at(8) = 0;
01632     _camera_info[stream_index].P.at(9) = 0;
01633     _camera_info[stream_index].P.at(10) = 1;
01634     _camera_info[stream_index].P.at(11) = 0;
01635 
01636     _camera_info[stream_index].distortion_model = "plumb_bob";
01637 
01638     // set R (rotation matrix) values to identity matrix
01639     _camera_info[stream_index].R.at(0) = 1.0;
01640     _camera_info[stream_index].R.at(1) = 0.0;
01641     _camera_info[stream_index].R.at(2) = 0.0;
01642     _camera_info[stream_index].R.at(3) = 0.0;
01643     _camera_info[stream_index].R.at(4) = 1.0;
01644     _camera_info[stream_index].R.at(5) = 0.0;
01645     _camera_info[stream_index].R.at(6) = 0.0;
01646     _camera_info[stream_index].R.at(7) = 0.0;
01647     _camera_info[stream_index].R.at(8) = 1.0;
01648 
01649     _camera_info[stream_index].D.resize(5);
01650     for (int i = 0; i < 5; i++)
01651     {
01652         _camera_info[stream_index].D.at(i) = intrinsic.coeffs[i];
01653     }
01654 
01655     if (stream_index == DEPTH && _enable[DEPTH] && _enable[COLOR])
01656     {
01657         _camera_info[stream_index].P.at(3) = 0;     // Tx
01658         _camera_info[stream_index].P.at(7) = 0;     // Ty
01659     }
01660 
01661     if (_align_depth)
01662     {
01663         for (auto& profiles : _enabled_profiles)
01664         {
01665             for (auto& profile : profiles.second)
01666             {
01667                 auto video_profile = profile.as<rs2::video_stream_profile>();
01668                 stream_index_pair stream_index{video_profile.stream_type(), video_profile.stream_index()};
01669                 _depth_aligned_camera_info[stream_index] = _camera_info[stream_index];
01670             }
01671         }
01672     }
01673 }
01674 
01675 tf::Quaternion BaseRealSenseNode::rotationMatrixToQuaternion(const float rotation[9]) const
01676 {
01677     Eigen::Matrix3f m;
01678     // We need to be careful about the order, as RS2 rotation matrix is
01679     // column-major, while Eigen::Matrix3f expects row-major.
01680     m << rotation[0], rotation[3], rotation[6],
01681          rotation[1], rotation[4], rotation[7],
01682          rotation[2], rotation[5], rotation[8];
01683     Eigen::Quaternionf q(m);
01684     return tf::Quaternion(q.x(), q.y(), q.z(), q.w());
01685 }
01686 
01687 void BaseRealSenseNode::publish_static_tf(const ros::Time& t,
01688                                           const float3& trans,
01689                                           const tf::Quaternion& q,
01690                                           const std::string& from,
01691                                           const std::string& to)
01692 {
01693     geometry_msgs::TransformStamped msg;
01694     msg.header.stamp = t;
01695     msg.header.frame_id = from;
01696     msg.child_frame_id = to;
01697     msg.transform.translation.x = trans.z;
01698     msg.transform.translation.y = -trans.x;
01699     msg.transform.translation.z = -trans.y;
01700     msg.transform.rotation.x = q.getX();
01701     msg.transform.rotation.y = q.getY();
01702     msg.transform.rotation.z = q.getZ();
01703     msg.transform.rotation.w = q.getW();
01704     _static_tf_broadcaster.sendTransform(msg);
01705 }
01706 
01707 void BaseRealSenseNode::calcAndPublishStaticTransform(const stream_index_pair& stream, const rs2::stream_profile& base_profile)
01708 {
01709     // Transform base to stream
01710     tf::Quaternion quaternion_optical;
01711     quaternion_optical.setRPY(-M_PI / 2, 0.0, -M_PI / 2);
01712     float3 zero_trans{0, 0, 0};
01713 
01714     ros::Time transform_ts_ = ros::Time::now();
01715 
01716     rs2_extrinsics ex;
01717     try
01718     {
01719         ex = getAProfile(stream).get_extrinsics_to(base_profile);
01720     }
01721     catch (std::exception& e)
01722     {
01723         if (!strcmp(e.what(), "Requested extrinsics are not available!"))
01724         {
01725             ROS_WARN_STREAM(e.what() << " : using unity as default.");
01726             ex = rs2_extrinsics({{1, 0, 0, 0, 1, 0, 0, 0, 1}, {0,0,0}});
01727         }
01728         else
01729         {
01730             throw e;
01731         }
01732     }
01733 
01734     auto Q = rotationMatrixToQuaternion(ex.rotation);
01735     Q = quaternion_optical * Q * quaternion_optical.inverse();
01736 
01737     float3 trans{ex.translation[0], ex.translation[1], ex.translation[2]};
01738     publish_static_tf(transform_ts_, trans, Q, _base_frame_id, _frame_id[stream]);
01739 
01740     // Transform stream frame to stream optical frame
01741     publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _frame_id[stream], _optical_frame_id[stream]);
01742 
01743     if (_align_depth && _depth_aligned_frame_id.find(stream) != _depth_aligned_frame_id.end())
01744     {
01745         publish_static_tf(transform_ts_, trans, Q, _base_frame_id, _depth_aligned_frame_id[stream]);
01746         publish_static_tf(transform_ts_, zero_trans, quaternion_optical, _depth_aligned_frame_id[stream], _optical_frame_id[stream]);
01747     }
01748 }
01749 
01750 void BaseRealSenseNode::publishStaticTransforms()
01751 {
01752     // Publish static transforms
01753     const std::vector<stream_index_pair> base_stream_priority = {DEPTH, POSE};
01754 
01755     std::vector<stream_index_pair>::const_iterator base_stream(base_stream_priority.begin());
01756     while( (_sensors.find(*base_stream) == _sensors.end()) && (base_stream != base_stream_priority.end()))
01757     {
01758         base_stream++;
01759     }
01760     if (base_stream == base_stream_priority.end())
01761     {
01762         throw std::runtime_error("No known base_stream found for transformations.");
01763     }
01764     ROS_INFO_STREAM("SELECTED BASE:" << base_stream->first << ", " << base_stream->second);
01765 
01766     rs2::stream_profile base_profile = getAProfile(*base_stream);
01767     for (std::pair<stream_index_pair, bool> ienable : _enable)
01768     {
01769         if (ienable.second)
01770         {
01771             calcAndPublishStaticTransform(ienable.first, base_profile);
01772         }
01773     }
01774 
01775     // Publish Extinsics Topics:
01776     if (_enable[DEPTH] &&
01777         _enable[FISHEYE])
01778     {
01779         static const char* frame_id = "depth_to_fisheye_extrinsics";
01780         const auto& ex = base_profile.get_extrinsics_to(getAProfile(FISHEYE));
01781 
01782         _depth_to_other_extrinsics[FISHEYE] = ex;
01783         _depth_to_other_extrinsics_publishers[FISHEYE].publish(rsExtrinsicsToMsg(ex, frame_id));
01784     }
01785 
01786     if (_enable[DEPTH] &&
01787         _enable[COLOR])
01788     {
01789         static const char* frame_id = "depth_to_color_extrinsics";
01790         const auto& ex = base_profile.get_extrinsics_to(getAProfile(COLOR));
01791         _depth_to_other_extrinsics[COLOR] = ex;
01792         _depth_to_other_extrinsics_publishers[COLOR].publish(rsExtrinsicsToMsg(ex, frame_id));
01793     }
01794 
01795     if (_enable[DEPTH] &&
01796         _enable[INFRA1])
01797     {
01798         static const char* frame_id = "depth_to_infra1_extrinsics";
01799         const auto& ex = base_profile.get_extrinsics_to(getAProfile(INFRA1));
01800         _depth_to_other_extrinsics[INFRA1] = ex;
01801         _depth_to_other_extrinsics_publishers[INFRA1].publish(rsExtrinsicsToMsg(ex, frame_id));
01802     }
01803 
01804     if (_enable[DEPTH] &&
01805         _enable[INFRA2])
01806     {
01807         static const char* frame_id = "depth_to_infra2_extrinsics";
01808         const auto& ex = base_profile.get_extrinsics_to(getAProfile(INFRA2));
01809         _depth_to_other_extrinsics[INFRA2] = ex;
01810         _depth_to_other_extrinsics_publishers[INFRA2].publish(rsExtrinsicsToMsg(ex, frame_id));
01811     }
01812 
01813 }
01814 
01815 void BaseRealSenseNode::publishIntrinsics()
01816 {
01817     if (_enable[GYRO])
01818     {
01819         _info_publisher[GYRO] = _node_handle.advertise<IMUInfo>("gyro/imu_info", 1, true);
01820         IMUInfo info_msg = getImuInfo(GYRO);
01821         _info_publisher[GYRO].publish(info_msg);
01822     }
01823 
01824     if (_enable[ACCEL])
01825     {
01826         _info_publisher[ACCEL] = _node_handle.advertise<IMUInfo>("accel/imu_info", 1, true);
01827         IMUInfo info_msg = getImuInfo(ACCEL);
01828         _info_publisher[ACCEL].publish(info_msg);
01829     }
01830 }
01831 
01832 void reverse_memcpy(unsigned char* dst, const unsigned char* src, size_t n)
01833 {
01834     size_t i;
01835 
01836     for (i=0; i < n; ++i)
01837         dst[n-1-i] = src[i];
01838 
01839 }
01840 
01841 void BaseRealSenseNode::publishPointCloud(rs2::points pc, const ros::Time& t, const rs2::frameset& frameset)
01842 {
01843     std::vector<NamedFilter>::iterator pc_filter = find_if(_filters.begin(), _filters.end(), [] (NamedFilter s) { return s._name == "pointcloud"; } );
01844     rs2_stream texture_source_id = static_cast<rs2_stream>(pc_filter->_filter->get_option(rs2_option::RS2_OPTION_STREAM_FILTER));
01845     bool use_texture = texture_source_id != RS2_STREAM_ANY;
01846     static int warn_count(0);
01847     static const int DISPLAY_WARN_NUMBER(5);
01848     rs2::frameset::iterator texture_frame_itr = frameset.end();
01849     if (use_texture)
01850     {
01851         std::set<rs2_format> available_formats{ rs2_format::RS2_FORMAT_RGB8, rs2_format::RS2_FORMAT_Y8 };
01852         
01853         texture_frame_itr = find_if(frameset.begin(), frameset.end(), [&texture_source_id, &available_formats] (rs2::frame f) 
01854                                 {return (rs2_stream(f.get_profile().stream_type()) == texture_source_id) &&
01855                                             (available_formats.find(f.get_profile().format()) != available_formats.end()); });
01856         if (texture_frame_itr == frameset.end())
01857         {
01858             warn_count++;
01859             std::string texture_source_name = pc_filter->_filter->get_option_value_description(rs2_option::RS2_OPTION_STREAM_FILTER, static_cast<float>(texture_source_id));
01860             ROS_WARN_STREAM_COND(warn_count == DISPLAY_WARN_NUMBER, "No stream match for pointcloud chosen texture " << texture_source_name);
01861             return;
01862         }
01863         warn_count = 0;
01864     }
01865 
01866     int texture_width(0), texture_height(0);
01867     int num_colors(0);
01868 
01869     const rs2::vertex* vertex = pc.get_vertices();
01870     const rs2::texture_coordinate* color_point = pc.get_texture_coordinates();
01871     std::list<unsigned int> valid_indices;
01872     for (size_t point_idx=0; point_idx < pc.size(); point_idx++, vertex++, color_point++)
01873     {
01874         if (static_cast<float>(vertex->z) > 0)
01875         {
01876             float i = static_cast<float>(color_point->u);
01877             float j = static_cast<float>(color_point->v);
01878             if (_allow_no_texture_points || (i >= 0.f && i <= 1.f && j >= 0.f && j <= 1.f))
01879             {
01880                 valid_indices.push_back(point_idx);
01881             }
01882         }
01883     }
01884 
01885     sensor_msgs::PointCloud2 msg_pointcloud;
01886     msg_pointcloud.header.stamp = t;
01887     msg_pointcloud.header.frame_id = _optical_frame_id[DEPTH];
01888     msg_pointcloud.width = valid_indices.size();
01889     msg_pointcloud.height = 1;
01890     msg_pointcloud.is_dense = true;
01891 
01892     sensor_msgs::PointCloud2Modifier modifier(msg_pointcloud);
01893     modifier.setPointCloud2FieldsByString(1, "xyz");    
01894 
01895     vertex = pc.get_vertices();
01896     if (use_texture)
01897     {
01898         rs2::video_frame texture_frame = (*texture_frame_itr).as<rs2::video_frame>();
01899         texture_width = texture_frame.get_width();
01900         texture_height = texture_frame.get_height();
01901         num_colors = texture_frame.get_bytes_per_pixel();
01902         uint8_t* color_data = (uint8_t*)texture_frame.get_data();
01903         std::string format_str;
01904         switch(texture_frame.get_profile().format())
01905         {
01906             case RS2_FORMAT_RGB8:
01907                 format_str = "rgb";
01908                 break;
01909             case RS2_FORMAT_Y8:
01910                 format_str = "intensity";
01911                 break;
01912             default:
01913                 throw std::runtime_error("Unhandled texture format passed in pointcloud " + std::to_string(texture_frame.get_profile().format()));
01914         }
01915         msg_pointcloud.point_step = addPointField(msg_pointcloud, format_str.c_str(), 1, sensor_msgs::PointField::UINT32, msg_pointcloud.point_step);
01916         msg_pointcloud.row_step = msg_pointcloud.width * msg_pointcloud.point_step;
01917         msg_pointcloud.data.resize(msg_pointcloud.height * msg_pointcloud.row_step);
01918 
01919         sensor_msgs::PointCloud2Iterator<float>iter_x(msg_pointcloud, "x");
01920         sensor_msgs::PointCloud2Iterator<float>iter_y(msg_pointcloud, "y");
01921         sensor_msgs::PointCloud2Iterator<float>iter_z(msg_pointcloud, "z");
01922         sensor_msgs::PointCloud2Iterator<uint8_t>iter_color(msg_pointcloud, format_str);
01923         color_point = pc.get_texture_coordinates();
01924 
01925         float color_pixel[2];
01926         unsigned int prev_idx(0);
01927         for (auto idx=valid_indices.begin(); idx != valid_indices.end(); idx++)
01928         {
01929             unsigned int idx_jump(*idx-prev_idx);
01930             prev_idx = *idx;
01931             vertex+=idx_jump;
01932             color_point+=idx_jump;
01933 
01934             *iter_x = vertex->x;
01935             *iter_y = vertex->y;
01936             *iter_z = vertex->z;
01937 
01938             float i(color_point->u);
01939             float j(color_point->v);
01940             if (i >= 0.f && i <= 1.f && j >= 0.f && j <= 1.f)
01941             {
01942                 color_pixel[0] = i * texture_width;
01943                 color_pixel[1] = j * texture_height;
01944                 int pixx = static_cast<int>(color_pixel[0]);
01945                 int pixy = static_cast<int>(color_pixel[1]);
01946                 int offset = (pixy * texture_width + pixx) * num_colors;
01947                 reverse_memcpy(&(*iter_color), color_data+offset, num_colors);  // PointCloud2 order of rgb is bgr.
01948             }
01949 
01950             ++iter_x; ++iter_y; ++iter_z;
01951             ++iter_color;
01952         }
01953     }
01954     else
01955     {
01956         sensor_msgs::PointCloud2Iterator<float>iter_x(msg_pointcloud, "x");
01957         sensor_msgs::PointCloud2Iterator<float>iter_y(msg_pointcloud, "y");
01958         sensor_msgs::PointCloud2Iterator<float>iter_z(msg_pointcloud, "z");
01959         unsigned int prev_idx(0);
01960         for (auto idx=valid_indices.begin(); idx != valid_indices.end(); idx++)
01961         {
01962             unsigned int idx_jump(*idx-prev_idx);
01963             prev_idx = *idx;
01964             vertex+=idx_jump;
01965 
01966             *iter_x = vertex->x;
01967             *iter_y = vertex->y;
01968             *iter_z = vertex->z;
01969 
01970             ++iter_x; ++iter_y; ++iter_z;
01971         }
01972     }
01973     _pointcloud_publisher.publish(msg_pointcloud);
01974 }
01975 
01976 
01977 Extrinsics BaseRealSenseNode::rsExtrinsicsToMsg(const rs2_extrinsics& extrinsics, const std::string& frame_id) const
01978 {
01979     Extrinsics extrinsicsMsg;
01980     for (int i = 0; i < 9; ++i)
01981     {
01982         extrinsicsMsg.rotation[i] = extrinsics.rotation[i];
01983         if (i < 3)
01984             extrinsicsMsg.translation[i] = extrinsics.translation[i];
01985     }
01986 
01987     extrinsicsMsg.header.frame_id = frame_id;
01988     return extrinsicsMsg;
01989 }
01990 
01991 rs2::stream_profile BaseRealSenseNode::getAProfile(const stream_index_pair& stream)
01992 {
01993     const std::vector<rs2::stream_profile> profiles = _sensors[stream].get_stream_profiles();
01994     return *(std::find_if(profiles.begin(), profiles.end(),
01995                                             [&stream] (const rs2::stream_profile& profile) { 
01996                                                 return ((profile.stream_type() == stream.first) && (profile.stream_index() == stream.second)); 
01997                                             }));
01998 }
01999 
02000 IMUInfo BaseRealSenseNode::getImuInfo(const stream_index_pair& stream_index)
02001 {
02002     IMUInfo info{};
02003     auto sp = _enabled_profiles[stream_index].front().as<rs2::motion_stream_profile>();
02004     rs2_motion_device_intrinsic imuIntrinsics;
02005     try
02006     {
02007         imuIntrinsics = sp.get_motion_intrinsics();
02008     }
02009     catch(const std::runtime_error &ex)
02010     {
02011         ROS_DEBUG_STREAM("No Motion Intrinsics available.");
02012         imuIntrinsics = {{{1,0,0,0},{0,1,0,0},{0,0,1,0}}, {0,0,0}, {0,0,0}};
02013     }
02014 
02015     auto index = 0;
02016     info.frame_id = _optical_frame_id[stream_index];
02017     for (int i = 0; i < 3; ++i)
02018     {
02019         for (int j = 0; j < 4; ++j)
02020         {
02021             info.data[index] = imuIntrinsics.data[i][j];
02022             ++index;
02023         }
02024         info.noise_variances[i] =  imuIntrinsics.noise_variances[i];
02025         info.bias_variances[i] = imuIntrinsics.bias_variances[i];
02026     }
02027     return info;
02028 }
02029 
02030 void BaseRealSenseNode::publishFrame(rs2::frame f, const ros::Time& t,
02031                                      const stream_index_pair& stream,
02032                                      std::map<stream_index_pair, cv::Mat>& images,
02033                                      const std::map<stream_index_pair, ros::Publisher>& info_publishers,
02034                                      const std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics>& image_publishers,
02035                                      std::map<stream_index_pair, int>& seq,
02036                                      std::map<stream_index_pair, sensor_msgs::CameraInfo>& camera_info,
02037                                      const std::map<stream_index_pair, std::string>& optical_frame_id,
02038                                      const std::map<rs2_stream, std::string>& encoding,
02039                                      bool copy_data_from_frame)
02040 {
02041     ROS_DEBUG("publishFrame(...)");
02042     unsigned int width = 0;
02043     unsigned int height = 0;
02044     auto bpp = 1;
02045     if (f.is<rs2::video_frame>())
02046     {
02047         auto image = f.as<rs2::video_frame>();
02048         width = image.get_width();
02049         height = image.get_height();
02050         bpp = image.get_bytes_per_pixel();
02051     }
02052     auto& image = images[stream];
02053 
02054     if (copy_data_from_frame)
02055     {
02056         if (images[stream].size() != cv::Size(width, height))
02057         {
02058             image.create(height, width, image.type());
02059         }
02060         image.data = (uint8_t*)f.get_data();
02061     }
02062     if (f.is<rs2::depth_frame>())
02063     {
02064         image = fix_depth_scale(image, _depth_scaled_image[stream]);
02065     }
02066 
02067     ++(seq[stream]);
02068     auto& info_publisher = info_publishers.at(stream);
02069     auto& image_publisher = image_publishers.at(stream);
02070     if(0 != info_publisher.getNumSubscribers() ||
02071        0 != image_publisher.first.getNumSubscribers())
02072     {
02073         sensor_msgs::ImagePtr img;
02074         img = cv_bridge::CvImage(std_msgs::Header(), encoding.at(stream.first), image).toImageMsg();
02075         img->width = width;
02076         img->height = height;
02077         img->is_bigendian = false;
02078         img->step = width * bpp;
02079         img->header.frame_id = optical_frame_id.at(stream);
02080         img->header.stamp = t;
02081         img->header.seq = seq[stream];
02082 
02083         auto& cam_info = camera_info.at(stream);
02084         if (cam_info.width != width)
02085         {
02086             updateStreamCalibData(f.get_profile().as<rs2::video_stream_profile>());
02087         }
02088         cam_info.header.stamp = t;
02089         cam_info.header.seq = seq[stream];
02090         info_publisher.publish(cam_info);
02091 
02092         image_publisher.first.publish(img);
02093         image_publisher.second->update();
02094         // ROS_INFO_STREAM("fid: " << cam_info.header.seq << ", time: " << std::setprecision (20) << t.toSec());
02095         ROS_DEBUG("%s stream published", rs2_stream_to_string(f.get_profile().stream_type()));
02096     }
02097 }
02098 
02099 bool BaseRealSenseNode::getEnabledProfile(const stream_index_pair& stream_index, rs2::stream_profile& profile)
02100     {
02101         // Assuming that all D400 SKUs have depth sensor
02102         auto profiles = _enabled_profiles[stream_index];
02103         auto it = std::find_if(profiles.begin(), profiles.end(),
02104                                [&](const rs2::stream_profile& profile)
02105                                { return (profile.stream_type() == stream_index.first); });
02106         if (it == profiles.end())
02107             return false;
02108 
02109         profile =  *it;
02110         return true;
02111     }
02112 


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Sat Jul 6 2019 03:30:09