44 ZR300Nodelet::~ZR300Nodelet()
46 if (enable_imu_ ==
true)
57 void ZR300Nodelet::onInit()
86 BaseNodelet::onInit();
88 if (enable_imu_ ==
true)
98 void ZR300Nodelet::getParameters()
100 BaseNodelet::getParameters();
104 pnh_.param(
"enable_imu", enable_imu_,
ENABLE_IMU);
105 pnh_.param(
"enable_ir2", enable_[RS_STREAM_INFRARED2],
ENABLE_IR2);
106 pnh_.param(
"fisheye_width", width_[RS_STREAM_FISHEYE],
FISHEYE_WIDTH);
107 pnh_.param(
"fisheye_height", height_[RS_STREAM_FISHEYE],
FISHEYE_HEIGHT);
108 pnh_.param(
"fisheye_fps", fps_[RS_STREAM_FISHEYE],
FISHEYE_FPS);
123 void ZR300Nodelet::advertiseTopics()
125 BaseNodelet::advertiseTopics();
141 void ZR300Nodelet::advertiseServices()
143 BaseNodelet::advertiseServices();
144 get_imu_info_ = pnh_.advertiseService(
IMU_INFO_SERVICE, &ZR300Nodelet::getIMUInfo,
this);
150 bool ZR300Nodelet::getIMUInfo(realsense_camera::GetIMUInfo::Request & req,
151 realsense_camera::GetIMUInfo::Response &
res)
154 std::string header_frame_id;
166 res.accel.header.stamp = header_stamp;
168 std::transform(res.accel.header.frame_id.begin(), res.accel.header.frame_id.end(),
169 res.accel.header.frame_id.begin(), ::tolower);
171 for (
int i = 0; i < 3; ++i)
173 for (
int j = 0; j < 4; ++j)
175 res.accel.data[index] = imu_intrinsics.
acc.
data[i][j];
183 res.gyro.header.stamp = header_stamp;
184 res.gyro.header.frame_id =
IMU_GYRO;
185 std::transform(res.gyro.header.frame_id.begin(), res.gyro.header.frame_id.end(),
186 res.gyro.header.frame_id.begin(), ::tolower);
187 for (
int i = 0; i < 3; ++i)
189 for (
int j = 0; j < 4; ++j)
191 res.gyro.data[index] = imu_intrinsics.
gyro.
data[i][j];
204 std::vector<std::string> ZR300Nodelet::setDynamicReconfServer()
206 dynamic_reconf_server_.reset(
new dynamic_reconfigure::Server<realsense_camera::zr300_paramsConfig>(pnh_));
209 realsense_camera::zr300_paramsConfig params_config;
210 dynamic_reconf_server_->getConfigDefault(params_config);
211 std::vector<realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr> param_desc =
212 params_config.__getParamDescriptions__();
213 std::vector<std::string> dynamic_params;
214 for (realsense_camera::zr300_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr : param_desc)
216 dynamic_params.push_back((* param_desc_ptr).name);
219 return dynamic_params;
225 void ZR300Nodelet::startDynamicReconfCallback()
227 dynamic_reconf_server_->setCallback(boost::bind(&ZR300Nodelet::configCallback,
this, _1, _2));
233 void ZR300Nodelet::setDynamicReconfigDepthControlPreset(
int preset)
238 std::vector<std::string> argv;
239 argv.push_back(
"rosrun");
240 argv.push_back(
"dynamic_reconfigure");
241 argv.push_back(
"dynparam");
242 argv.push_back(
"set");
243 argv.push_back(nodelet_name_);
244 argv.push_back(
"r200_dc_preset");
245 argv.push_back(std::to_string(preset));
255 std::string ZR300Nodelet::setDynamicReconfigDepthControlIndividuals()
257 std::string current_param;
258 std::string current_dc;
259 std::string option_value;
264 std::vector<std::string> argv;
265 argv.push_back(
"rosrun");
266 argv.push_back(
"dynamic_reconfigure");
267 argv.push_back(
"dynparam");
268 argv.push_back(
"set");
269 argv.push_back(nodelet_name_);
276 current_param +=
"'r200_dc_estimate_median_decrement':" + option_value +
", ";
277 current_dc += option_value +
":";
282 current_param +=
"'r200_dc_estimate_median_increment':" + option_value +
", ";
283 current_dc += option_value +
":";
288 current_param +=
"'r200_dc_median_threshold':" + option_value +
", ";
289 current_dc += option_value +
":";
294 current_param +=
"'r200_dc_score_minimum_threshold':" + option_value +
", ";
295 current_dc += option_value +
":";
300 current_param +=
"'r200_dc_score_maximum_threshold':" + option_value +
", ";
301 current_dc += option_value +
":";
306 current_param +=
"'r200_dc_texture_count_threshold':" + option_value +
", ";
307 current_dc += option_value +
":";
312 current_param +=
"'r200_dc_texture_difference_threshold':" + option_value +
", ";
313 current_dc += option_value +
":";
318 current_param +=
"'r200_dc_second_peak_threshold':" + option_value +
", ";
319 current_dc += option_value +
":";
324 current_param +=
"'r200_dc_neighbor_threshold':" + option_value +
", ";
325 current_dc += option_value +
":";
330 current_param +=
"'r200_dc_lr_threshold':" + option_value +
"}";
331 current_dc += option_value;
335 argv.push_back(current_param);
345 void ZR300Nodelet::configCallback(realsense_camera::zr300_paramsConfig &config, uint32_t
level)
348 static int dc_preset = -2;
349 int previous_dc_preset = dc_preset;
351 static std::string last_dc;
354 std::bitset<32> bit_level{level};
356 if (bit_level.test(6))
358 ROS_INFO_STREAM(nodelet_name_ <<
" - Setting dynamic camera options" <<
359 " (r200_dc_preset=" << config.r200_dc_preset <<
")");
367 BaseNodelet::setDepthEnable(config.enable_depth);
379 if (config.color_enable_auto_exposure == 0)
384 config.color_enable_auto_white_balance, 0);
385 if (config.color_enable_auto_white_balance == 0)
392 if (config.r200_lr_auto_exposure_enabled == 0)
404 if (bit_level.test(5))
406 std::string current_dc;
411 config.r200_dc_estimate_median_decrement, 0);
412 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_decrement)) +
":";
414 config.r200_dc_estimate_median_increment, 0);
415 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_estimate_median_increment)) +
":";
417 config.r200_dc_median_threshold, 0);
418 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_median_threshold)) +
":";
420 config.r200_dc_score_minimum_threshold, 0);
421 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_minimum_threshold)) +
":";
423 config.r200_dc_score_maximum_threshold, 0);
424 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_score_maximum_threshold)) +
":";
426 config.r200_dc_texture_count_threshold, 0);
427 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_count_threshold)) +
":";
429 config.r200_dc_texture_difference_threshold, 0);
430 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_texture_difference_threshold)) +
":";
432 config.r200_dc_second_peak_threshold, 0);
433 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_second_peak_threshold)) +
":";
435 config.r200_dc_neighbor_threshold, 0);
436 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_neighbor_threshold)) +
":";
438 config.r200_dc_lr_threshold, 0);
439 current_dc += std::to_string(static_cast<uint32_t>(config.r200_dc_lr_threshold));
444 if (bit_level.test(6))
446 dc_preset = config.r200_dc_preset;
448 if (previous_dc_preset != -2)
452 if (dc_preset != -1 && current_dc != last_dc)
454 ROS_DEBUG_STREAM(nodelet_name_ <<
" - Forcing Depth Control Preset to Unused");
455 setDynamicReconfigDepthControlPreset(-1);
466 ROS_INFO_STREAM(nodelet_name_ <<
" - Initializing Depth Control Preset to " << dc_preset);
467 ROS_DEBUG_STREAM(nodelet_name_ <<
" - NOTICE: Individual Depth Control values " <<
468 "set by params will be ignored; set r200_dc_preset=-1 to override.");
469 rs_apply_depth_control_preset(rs_device_, dc_preset);
472 last_dc = setDynamicReconfigDepthControlIndividuals();
480 if (dc_preset != -1 && current_dc != last_dc)
482 ROS_DEBUG_STREAM(nodelet_name_ <<
" - Forcing Depth Control Preset to Unused");
483 setDynamicReconfigDepthControlPreset(-1);
489 if (bit_level.test(6))
491 dc_preset = config.r200_dc_preset;
495 ROS_DEBUG_STREAM(nodelet_name_ <<
" - Set Depth Control Preset to " << dc_preset);
496 rs_apply_depth_control_preset(rs_device_, dc_preset);
499 last_dc = setDynamicReconfigDepthControlIndividuals();
505 config.fisheye_exposure, 0);
510 config.fisheye_auto_exposure_antiflicker_rate, 0);
512 config.fisheye_auto_exposure_pixel_sample_rate, 0);
514 config.fisheye_auto_exposure_skip_frames, 0);
522 void ZR300Nodelet::publishIMU()
527 if (start_stop_srv_called_ ==
true)
529 if (start_camera_ ==
true)
537 start_stop_srv_called_ =
false;
547 if (imu_publisher_.getNumSubscribers() > 0)
549 std::unique_lock<std::mutex> lock(imu_mutex_);
551 if (prev_imu_ts_ != imu_ts_)
553 sensor_msgs::Imu imu_msg = sensor_msgs::Imu();
555 imu_msg.header.frame_id = imu_optical_frame_id_;
558 imu_msg.orientation_covariance[0] = -1.0;
560 imu_msg.angular_velocity = imu_angular_vel_;
561 imu_msg.linear_acceleration = imu_linear_accel_;
563 imu_publisher_.publish(imu_msg);
564 prev_imu_ts_ = imu_ts_;
574 void ZR300Nodelet::setStreams()
577 BaseNodelet::setStreams();
579 if (enable_imu_ ==
true)
594 void ZR300Nodelet::setIMUCallbacks()
598 std::unique_lock<std::mutex> lock(imu_mutex_);
602 imu_angular_vel_.x = entry.axes[0];
603 imu_angular_vel_.y = entry.axes[1];
604 imu_angular_vel_.z = entry.axes[2];
608 imu_linear_accel_.x = entry.axes[0];
609 imu_linear_accel_.y = entry.axes[1];
610 imu_linear_accel_.z = entry.axes[2];
612 imu_ts_ =
static_cast<double>(entry.timestamp_data.timestamp);
615 <<
"\ttimestamp: " << std::setprecision(8) << (
double)entry.timestamp_data.timestamp*
IMU_UNITS_TO_MSEC 616 <<
"\tsource: " << (
rs::event)entry.timestamp_data.source_id
617 <<
"\tframe_num: " << entry.timestamp_data.frame_number
618 <<
"\tx: " << std::setprecision(5) << entry.axes[0]
619 <<
"\ty: " << entry.axes[1]
620 <<
"\tz: " << entry.axes[2]);
626 auto now = std::chrono::system_clock::now().time_since_epoch();
627 auto sys_time = std::chrono::duration_cast<std::chrono::milliseconds>(now).
count();
630 <<
"\ttimestamp: " << std::setprecision(8) << (
double)entry.timestamp*
IMU_UNITS_TO_MSEC 631 <<
"\tsource: " << (
rs::event)entry.source_id
632 <<
"\tframe_num: " << entry.frame_number);
639 void ZR300Nodelet::setFrameCallbacks()
642 BaseNodelet::setFrameCallbacks();
644 fisheye_frame_handler_ = [&](
rs::frame frame)
649 ir2_frame_handler_ = [&](
rs::frame frame)
665 void ZR300Nodelet::getCameraExtrinsics()
667 BaseNodelet::getCameraExtrinsics();
691 ROS_WARN_STREAM(nodelet_name_ <<
" - Using Hardcoded extrinsic for IMU.");
695 color2imu_extrinsic_.translation[0] = -0.07;
696 color2imu_extrinsic_.translation[1] = 0.0;
697 color2imu_extrinsic_.translation[2] = 0.0;
705 void ZR300Nodelet::publishStaticTransforms()
707 BaseNodelet::publishStaticTransforms();
712 geometry_msgs::TransformStamped b2i_msg;
713 geometry_msgs::TransformStamped i2io_msg;
714 geometry_msgs::TransformStamped b2f_msg;
715 geometry_msgs::TransformStamped f2fo_msg;
716 geometry_msgs::TransformStamped b2imu_msg;
717 geometry_msgs::TransformStamped imu2imuo_msg;
720 b2i_msg.header.stamp = transform_ts_;
721 b2i_msg.header.frame_id = base_frame_id_;
723 b2i_msg.transform.translation.x = color2ir2_extrinsic_.translation[2];
724 b2i_msg.transform.translation.y = -color2ir2_extrinsic_.translation[0];
725 b2i_msg.transform.translation.z = -color2ir2_extrinsic_.translation[1];
726 b2i_msg.transform.rotation.x = 0;
727 b2i_msg.transform.rotation.y = 0;
728 b2i_msg.transform.rotation.z = 0;
729 b2i_msg.transform.rotation.w = 1;
730 static_tf_broadcaster_.sendTransform(b2i_msg);
733 q_i2io.
setRPY(-M_PI/2, 0.0, -M_PI/2);
734 i2io_msg.header.stamp = transform_ts_;
737 i2io_msg.transform.translation.x = 0;
738 i2io_msg.transform.translation.y = 0;
739 i2io_msg.transform.translation.z = 0;
740 i2io_msg.transform.rotation.x = q_i2io.getX();
741 i2io_msg.transform.rotation.y = q_i2io.getY();
742 i2io_msg.transform.rotation.z = q_i2io.getZ();
743 i2io_msg.transform.rotation.w = q_i2io.
getW();
744 static_tf_broadcaster_.sendTransform(i2io_msg);
747 b2f_msg.header.stamp = transform_ts_;
748 b2f_msg.header.frame_id = base_frame_id_;
750 b2f_msg.transform.translation.x = color2fisheye_extrinsic_.translation[2];
751 b2f_msg.transform.translation.y = -color2fisheye_extrinsic_.translation[0];
752 b2f_msg.transform.translation.z = -color2fisheye_extrinsic_.translation[1];
753 b2f_msg.transform.rotation.x = 0;
754 b2f_msg.transform.rotation.y = 0;
755 b2f_msg.transform.rotation.z = 0;
756 b2f_msg.transform.rotation.w = 1;
757 static_tf_broadcaster_.sendTransform(b2f_msg);
760 q_f2fo.
setRPY(-M_PI/2, 0.0, -M_PI/2);
761 f2fo_msg.header.stamp = transform_ts_;
764 f2fo_msg.transform.translation.x = 0;
765 f2fo_msg.transform.translation.y = 0;
766 f2fo_msg.transform.translation.z = 0;
767 f2fo_msg.transform.rotation.x = q_f2fo.getX();
768 f2fo_msg.transform.rotation.y = q_f2fo.getY();
769 f2fo_msg.transform.rotation.z = q_f2fo.getZ();
770 f2fo_msg.transform.rotation.w = q_f2fo.
getW();
771 static_tf_broadcaster_.sendTransform(f2fo_msg);
774 b2imu_msg.header.stamp = transform_ts_;
775 b2imu_msg.header.frame_id = base_frame_id_;
776 b2imu_msg.child_frame_id = imu_frame_id_;
777 b2imu_msg.transform.translation.x = color2imu_extrinsic_.translation[2];
778 b2imu_msg.transform.translation.y = -color2imu_extrinsic_.translation[0];
779 b2imu_msg.transform.translation.z = -color2imu_extrinsic_.translation[1];
780 b2imu_msg.transform.rotation.x = 0;
781 b2imu_msg.transform.rotation.y = 0;
782 b2imu_msg.transform.rotation.z = 0;
783 b2imu_msg.transform.rotation.w = 1;
784 static_tf_broadcaster_.sendTransform(b2imu_msg);
787 q_imu2imuo.
setRPY(-M_PI/2, 0.0, -M_PI/2);
788 imu2imuo_msg.header.stamp = transform_ts_;
789 imu2imuo_msg.header.frame_id = imu_frame_id_;
790 imu2imuo_msg.child_frame_id = imu_optical_frame_id_;
791 imu2imuo_msg.transform.translation.x = 0;
792 imu2imuo_msg.transform.translation.y = 0;
793 imu2imuo_msg.transform.translation.z = 0;
794 imu2imuo_msg.transform.rotation.x = q_imu2imuo.getX();
795 imu2imuo_msg.transform.rotation.y = q_imu2imuo.getY();
796 imu2imuo_msg.transform.rotation.z = q_imu2imuo.getZ();
797 imu2imuo_msg.transform.rotation.w = q_imu2imuo.
getW();
798 static_tf_broadcaster_.sendTransform(imu2imuo_msg);
804 void ZR300Nodelet::publishDynamicTransforms()
809 BaseNodelet::publishDynamicTransforms();
813 color2ir2_extrinsic_.translation[2],
814 -color2ir2_extrinsic_.translation[0],
815 -color2ir2_extrinsic_.translation[1]));
822 q.
setRPY(-M_PI/2, 0.0, -M_PI/2);
825 frame_id_[RS_STREAM_INFRARED2], optical_frame_id_[RS_STREAM_INFRARED2]));
829 color2fisheye_extrinsic_.translation[2],
830 -color2fisheye_extrinsic_.translation[0],
831 -color2fisheye_extrinsic_.translation[1]));
838 q.
setRPY(-M_PI/2, 0.0, -M_PI/2);
841 frame_id_[RS_STREAM_FISHEYE], optical_frame_id_[RS_STREAM_FISHEYE]));
845 color2imu_extrinsic_.translation[2],
846 -color2imu_extrinsic_.translation[0],
847 -color2imu_extrinsic_.translation[1]));
850 base_frame_id_, imu_frame_id_));
854 q.
setRPY(-M_PI/2, 0.0, -M_PI/2);
857 imu_frame_id_, imu_optical_frame_id_));
863 void ZR300Nodelet::stopIMU()
RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED
RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE
RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE
void rs_set_device_option(rs_device *device, rs_option option, double value, rs_error **error)
RS_OPTION_R200_DEPTH_CLAMP_MAX
RS_OPTION_COLOR_BACKLIGHT_COMPENSATION
RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE
const std::string FISHEYE_NAMESPACE
RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES
const std::string IMU_NAMESPACE
RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD
const std::string DEFAULT_FISHEYE_FRAME_ID
void rs_set_frame_callback_cpp(rs_device *device, rs_stream stream, rs_frame_callback *callback, rs_error **error)
RS_OPTION_R200_LR_EXPOSURE
RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT
const std::string TYPE_8UC1
TFSIMD_FORCE_INLINE const tfScalar & getW() const
const std::string IMU_INFO_SERVICE
RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD
void rs_disable_motion_tracking(rs_device *device, rs_error **error)
const bool ENABLE_FISHEYE
RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD
RS_OPTION_COLOR_WHITE_BALANCE
const std::string IMU_GYRO
void rs_stop_source(rs_device *device, rs_source source, rs_error **error)
const std::string FISHEYE_TOPIC
const std::string IMU_ACCEL
const std::string IR2_TOPIC
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
GLuint GLuint GLsizei count
RS_OPTION_COLOR_SHARPNESS
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
const std::string IR2_NAMESPACE
RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT
RS_OPTION_R200_DEPTH_CLAMP_MIN
const std::string DEFAULT_IMU_FRAME_ID
double rs_get_device_option(rs_device *device, rs_option option, rs_error **error)
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
const std::string TYPE_16UC1
const std::string IMU_TOPIC
RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD
RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE
void rs_free_error(rs_error *error)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
RS_OPTION_R200_EMITTER_ENABLED
void rs_get_device_extrinsics(const rs_device *device, rs_stream from, rs_stream to, rs_extrinsics *extrin, rs_error **error)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
RS_OPTION_FISHEYE_EXPOSURE
const double IMU_UNITS_TO_MSEC
RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD
void rs_enable_motion_tracking_cpp(rs_device *device, rs_motion_callback *motion_callback, rs_timestamp_callback *ts_callback, rs_error **error)
RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE
rs_motion_device_intrinsic acc
RS_OPTION_FRAMES_QUEUE_SIZE
RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD
#define ROS_INFO_STREAM(args)
const std::string DEFAULT_IR2_FRAME_ID
const std::string DEFAULT_IR2_OPTICAL_FRAME_ID
RS_OPTION_COLOR_SATURATION
void rs_get_motion_intrinsics(const rs_device *device, rs_motion_intrinsics *intrinsic, rs_error **error)
GLdouble GLdouble GLdouble GLdouble q
rs_motion_device_intrinsic gyro
RS_OPTION_HARDWARE_LOGGER_ENABLED
void rs_get_motion_extrinsics_from(const rs_device *device, rs_stream from, rs_extrinsics *extrin, rs_error **error)
#define ROS_ERROR_STREAM(args)
RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD
RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD
const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID
RS_OPTION_COLOR_BRIGHTNESS