ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Refer to code snippet below, this was quite troublesome to get it working but this code is known to be working under Foxy
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::image, sensor_msgs::msg::image=""> RGBDApprxTimeSyncPolicy; typedef message_filters::Synchronizer<rgbdapprxtimesyncpolicy> RGBDApprxTimeSyncer;
// subscriber for color cam in case rgbd camera model localization
message_filters::Subscriber<sensor_msgs::msg::Image> rgbd_color_image_subscriber_;
// subscriber for depth cam in case rgbd camera model localization
message_filters::Subscriber<sensor_msgs::msg::Image> rgbd_depth_image_subscriber_;
void rgbdCallback(
const sensor_msgs::msg::Image::ConstSharedPtr & color,
const sensor_msgs::msg::Image::ConstSharedPtr & depth);
rgbd_color_image_subscriber_.subscribe(
this, "camera/color/image_raw",
rmw_qos_profile_sensor_data);
rgbd_depth_image_subscriber_.subscribe(
this, "camera/depth/image_raw",
rmw_qos_profile_sensor_data);
rgbd_approx_time_syncher_.reset(
new RGBDApprxTimeSyncer(
RGBDApprxTimeSyncPolicy(10),
rgbd_color_image_subscriber_,
rgbd_depth_image_subscriber_));
rgbd_approx_time_syncher_->registerCallback(
std::bind(
&YourClass::rgbdCallback, this, std::placeholders::_1,
std::placeholders::_2));
void YourClass::rgbdCallback(
const sensor_msgs::msg::Image::ConstSharedPtr & color,
const sensor_msgs::msg::Image::ConstSharedPtr & depth)
{
auto colorcv = cv_bridge::toCvShare(color)->image;
auto depthcv = cv_bridge::toCvShare(depth)->image;
if (colorcv.empty() || depthcv.empty()) {
return;
}
// do something with recieved messages
}
2 | No.2 Revision |
Refer to code snippet below, this was quite troublesome to get it working but this code is known to be working under Foxy
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::image, sensor_msgs::msg::image=""> RGBDApprxTimeSyncPolicy; typedef message_filters::Synchronizer<rgbdapprxtimesyncpolicy> RGBDApprxTimeSyncer;
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image,
sensor_msgs::msg::Image>
RGBDApprxTimeSyncPolicy;
typedef message_filters::Synchronizer<RGBDApprxTimeSyncPolicy> RGBDApprxTimeSyncer;
// subscriber for color cam in case rgbd camera model localization
message_filters::Subscriber<sensor_msgs::msg::Image> rgbd_color_image_subscriber_;
// subscriber for depth cam in case rgbd camera model localization
message_filters::Subscriber<sensor_msgs::msg::Image> rgbd_depth_image_subscriber_;
void rgbdCallback(
const sensor_msgs::msg::Image::ConstSharedPtr & color,
const sensor_msgs::msg::Image::ConstSharedPtr & depth);
rgbd_color_image_subscriber_.subscribe(
this, "camera/color/image_raw",
rmw_qos_profile_sensor_data);
rgbd_depth_image_subscriber_.subscribe(
this, "camera/depth/image_raw",
rmw_qos_profile_sensor_data);
rgbd_approx_time_syncher_.reset(
new RGBDApprxTimeSyncer(
RGBDApprxTimeSyncPolicy(10),
rgbd_color_image_subscriber_,
rgbd_depth_image_subscriber_));
rgbd_approx_time_syncher_->registerCallback(
std::bind(
&YourClass::rgbdCallback, this, std::placeholders::_1,
std::placeholders::_2));
void YourClass::rgbdCallback(
const sensor_msgs::msg::Image::ConstSharedPtr & color,
const sensor_msgs::msg::Image::ConstSharedPtr & depth)
{
auto colorcv = cv_bridge::toCvShare(color)->image;
auto depthcv = cv_bridge::toCvShare(depth)->image;
if (colorcv.empty() || depthcv.empty()) {
return;
}
// do something with recieved messages
}