ros2 / message_filters

BSD 3-Clause "New" or "Revised" License
76 stars 66 forks source link

How to use message filters in a class with Subscribers as member variables #20

Closed AndreasAZiegler closed 5 years ago

AndreasAZiegler commented 5 years ago

I try to get a time_synchronizer running with an Odometry and a LaserScan topic. The example provided in the README uses subscribers as normal function variables whereas in my case the subscriber are a class member variable.

My header

/* Polygon Explorer ROS class
 */

#pragma once

#include "geometry_msgs/msg/pose_with_covariance.hpp"
#include "kindr/Core"
#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "nav_msgs/msg/odometry.hpp"
#include "poly_exploration/PolygonExplorer.h"
#include "poly_exploration/PolygonExplorerInterface.h"
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "visualization_msgs/msg/marker.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

class PolygonExplorerNode : public rclcpp::Node,
                            public PolygonExplorerInterface {
 public:
  PolygonExplorerNode();

  virtual void updateVisualizationCallback(const PoseGraph pose_graph) override;

 private:
  void subscriberCallback(
      const std::shared_ptr<nav_msgs::msg::Odometry>& odometry,
      const std::shared_ptr<sensor_msgs::msg::LaserScan>& laser_scan);

  void convertFromRosGeometryMsg(
      const geometry_msgs::msg::PoseWithCovariance& geometryPoseMsg,
      Pose& pose);

  void convertFromRosGeometryMsg(
      const geometry_msgs::msg::Quaternion& geometryQuaternionMsg,
      Rotation& rotationQuaternion);

  void convertFromRosGeometryMsg(
      const geometry_msgs::msg::Point& geometryPointMsg, Position& position);

  PolygonExplorer polygonExplorer_;

  Pose previousPose_;

  message_filters::Subscriber<nav_msgs::msg::Odometry> odometrySubscription_;
  message_filters::Subscriber<sensor_msgs::msg::LaserScan> laserSubscription_;

  message_filters::TimeSynchronizer<nav_msgs::msg::Odometry,
                                    sensor_msgs::msg::LaserScan>
      timeSynchronizer_;

  rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr
      poseGraphVisualizationPublisher_;
  rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
      polygonVisualizationPublisher_;
};

My implementation

/* Polygon Explorer ROS class
 */

#include "PolygonExplorerNode.h"
#include <glog/logging.h>
#include <functional>

PolygonExplorerNode::PolygonExplorerNode()
    : Node("polygon_explorer_node"),
      odometrySubscription_(
          message_filters::Subscriber<nav_msgs::msg::Odometry>(this,
                                                               "odom_11_odom")),
      laserSubscription_(
          message_filters::Subscriber<sensor_msgs::msg::LaserScan>(
              this, "scan_11_laser_front")),
      timeSynchronizer_(odometrySubscription_, laserSubscription_, 1) {
  polygonExplorer_.setCallBack(this);
  timeSynchronizer_.registerCallback(
      std::bind(&PolygonExplorerNode::subscriberCallback, this,
                std::placeholders::_1, std::placeholders::_2));
} /* -----  end of method PolygonExplorerNode::PolygonExplorerNode
     (constructor)  ----- */

void PolygonExplorerNode::subscriberCallback(
    const std::shared_ptr<nav_msgs::msg::Odometry>& odometry,
    const std::shared_ptr<sensor_msgs::msg::LaserScan>& laser_scan) {
  std::vector<PolygonPoint> polygon_points;
  for (unsigned int i = 0; i < laser_scan->ranges.size(); ++i) {
    double theta = laser_scan->angle_min + i * laser_scan->angle_increment;
    double x = laser_scan->ranges.at(i) * cos(theta);
    double y = laser_scan->ranges.at(i) * sin(theta);

    PointType point_type;
    if (laser_scan->ranges.at(i) >= laser_scan->range_max) {
      point_type = PointType::MAX_RANGE;
    } else {
      point_type = PointType::OBSTACLE;
    }

    polygon_points.emplace_back(x, y, point_type);
  }

  Polygon polygon(polygon_points);

  Pose current_pose;
  convertFromRosGeometryMsg(odometry->pose, current_pose);
  auto position_diff = current_pose.getPosition() - previousPose_.getPosition();
  // Orientation difference of quaternions
  // (http://www.boris-belousov.net/2016/12/01/quat-dist/)
  auto orientation_diff =
      current_pose.getRotation() * previousPose_.getRotation().conjugated();
  // Transform transformation into frame of previous pose
  auto transformation_previous_pose_current_pose =
      Pose(previousPose_.transform(position_diff),
           previousPose_.getRotation() * orientation_diff);

  polygonExplorer_.addPose(transformation_previous_pose_current_pose, polygon);

  previousPose_ = current_pose;
}

void PolygonExplorerNode::convertFromRosGeometryMsg(
    const geometry_msgs::msg::PoseWithCovariance& geometryPoseMsg, Pose& pose) {
  convertFromRosGeometryMsg(geometryPoseMsg.pose.position, pose.getPosition());

  // This is the definition of ROS Geometry pose.
  typedef kindr::RotationQuaternion<double> RotationQuaternionGeometryPoseLike;

  RotationQuaternionGeometryPoseLike rotation;
  convertFromRosGeometryMsg(geometryPoseMsg.pose.orientation, rotation);
  pose.getRotation() = rotation;
}

void PolygonExplorerNode::convertFromRosGeometryMsg(
    const geometry_msgs::msg::Quaternion& geometryQuaternionMsg,
    Rotation& rotationQuaternion) {
  rotationQuaternion.setValues(geometryQuaternionMsg.w, geometryQuaternionMsg.x,
                               geometryQuaternionMsg.y,
                               geometryQuaternionMsg.z);
}

void PolygonExplorerNode::convertFromRosGeometryMsg(
    const geometry_msgs::msg::Point& geometryPointMsg, Position& position) {
  position.x() = geometryPointMsg.x;
  position.y() = geometryPointMsg.y;
  position.z() = geometryPointMsg.z;
}

void PolygonExplorerNode::updateVisualizationCallback(
    const PoseGraph pose_graph) {
  }

  poseGraphVisualizationPublisher_->publish(pose_graph_marker);
}

#include "class_loader/register_macro.hpp"

When I try to compile it, I get the following errors:

--- stderr: poly_exploration_ros                               
In file included from /opt/ros/crystal/include/message_filters/synchronizer.h:47:0,
                 from /opt/ros/crystal/include/message_filters/time_synchronizer.h:41,
                 from /home/andreasziegler/OpenSource/poly-exploration_ws/src/poly_exploration_ros/include/PolygonExplorerNode.h:9,
                 from /home/andreasziegler/OpenSource/poly-exploration_ws/src/poly_exploration_ros/src/PolygonExplorerNode.cpp:4:
/opt/ros/crystal/include/message_filters/signal9.h: In instantiation of ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const std::_Bind<void (PolygonExplorerNode::*(PolygonExplorerNode*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >&, const std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >&)>; M0 = nav_msgs::msg::Odometry_<std::allocator<void> >; M1 = sensor_msgs::msg::LaserScan_<std::allocator<void> >; M2 = message_filters::NullType; M3 = message_filters::NullType; M4 = message_filters::NullType; M5 = message_filters::NullType; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’:
/opt/ros/crystal/include/message_filters/synchronizer.h:298:40:   required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (PolygonExplorerNode::*(PolygonExplorerNode*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >&, const std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >&)>; Policy = message_filters::sync_policies::ExactTime<nav_msgs::msg::Odometry_<std::allocator<void> >, sensor_msgs::msg::LaserScan_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/home/andreasziegler/OpenSource/poly-exploration_ws/src/poly_exploration_ros/src/PolygonExplorerNode.cpp:20:62:   required from here
/opt/ros/crystal/include/message_filters/signal9.h:296:40: error: no matching function for call to ‘message_filters::Signal9<nav_msgs::msg::Odometry_<std::allocator<void> >, sensor_msgs::msg::LaserScan_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>::addCallback<const M0ConstPtr&, const M1ConstPtr&, const M2ConstPtr&, const M3ConstPtr&, const M4ConstPtr&, const M5ConstPtr&, const M6ConstPtr&, const M7ConstPtr&, const M8ConstPtr&>(std::_Bind_helper<false, const std::_Bind<void (PolygonExplorerNode::*(PolygonExplorerNode*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<nav_msgs::msg::Odometry_<std::allocator<void> > >&, const std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >&)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const std::_Placeholder<5>&, const std::_Placeholder<6>&, const std::_Placeholder<7>&, const std::_Placeholder<8>&, const std::_Placeholder<9>&>::type)’
     return addCallback<const M0ConstPtr&,
            ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
                      const M1ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M2ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M3ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M4ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M5ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M6ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M7ConstPtr&,
                      ~~~~~~~~~~~~~~~~~~ 
                      const M8ConstPtr&>(std::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8, _9));
marting87 commented 5 years ago

For anyone that ends up here with a similar issue:

Change:

timeSynchronizer_.registerCallback(
      std::bind(&PolygonExplorerNode::subscriberCallback, this,
                std::placeholders::_1, std::placeholders::_2));

To:

timeSynchronizer_.registerCallback(
     &PolygonExplorerNode::subscriberCallback, this);
florianspy commented 5 years ago

Try this : class SubscribeAndPublish { public: SubscribeAndPublish():sync2(image_sub,image_sub2,500){ //https://gist.github.com/tdenewiler/e2172f628e49ab633ef2786207793336 image_sub.subscribe(n, "/camera/color/image_raw", 1); image_sub2.subscribe(n, "/camera/aligned_depth_to_color/image_raw", 1); sync2.registerCallback(boost::bind(&SubscribeAndPublish::callback,this, _1, _2)); odom_pub = n.advertise("RGBDodom", 50); } void callback(const sensor_msgs::ImageConstPtr& msg,const sensor_msgs::ImageConstPtr& msg2){ private: ros::NodeHandle n; ros::Publisher odom_pub; message_filters::Subscriber image_sub; message_filters::Subscriber image_sub2; TimeSynchronizer<Image, Image> sync2; };

Harsharma2308 commented 4 years ago

The member initialisation doesn't work for me for message_filters::Subscriber. This is my code-

class MultiSubscriber : public rclcpp::Node
{
  public:

      message_filters::Subscriber<sensor_msgs::msg::Image> image_sub_;
      message_filters::Subscriber<sensor_msgs::msg::Image> disparity_sub_;

    MultiSubscriber(const std::string& name)
    : Node(name), 
      image_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_color_topic")),
      disparity_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_disparity_topic"))
    {

      typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::Image> approximate_policy;
      message_filters::Synchronizer<approximate_policy>syncApproximate(approximate_policy(10), image_sub_, disparity_sub_);

      syncApproximate.registerCallback(&MultSubscriber::disparityCb,this);

    }
    private:
    void disparityCb(const sensor_msgs::msg::Image::SharedPtr disparity_msg, const sensor_msgs::msg::Image::SharedPtr color_msg){
   //dosomething
                }
};

I get this error -

/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp: In constructor ‘MultiSenseSubscriber::MultiSenseSubscriber(const string&)’:
/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:68:120: error: use of deleted function ‘message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >::Subscriber(const message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
     : Node(name), image_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "/multisense/left/image_color"))
                                                                                                                        ^
In file included from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:0:
/opt/ros/eloquent/include/message_filters/subscriber.h:102:7: note: ‘message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >::Subscriber(const message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >&)’ is implicitly deleted because the default definition would be ill-formed:
 class Subscriber : public SubscriberBase, public SimpleFilter<M>
       ^~~~~~~~~~
/opt/ros/eloquent/include/message_filters/subscriber.h:102:7: error: use of deleted function ‘message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >::SimpleFilter(const message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:41:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: note: ‘message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >::SimpleFilter(const message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >&)’ is implicitly deleted because the default definition would be ill-formed:
 class SimpleFilter : public noncopyable
       ^~~~~~~~~~~~
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: error: use of deleted function ‘message_filters::noncopyable::noncopyable(const message_filters::noncopyable&)’
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:40:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/connection.h:51:3: note: declared here
   noncopyable( const noncopyable& ) = delete;
   ^~~~~~~~~~~
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:41:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: error: use of deleted function ‘message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >::Signal1(const message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
 class SimpleFilter : public noncopyable
       ^~~~~~~~~~~~
In file included from /opt/ros/eloquent/include/message_filters/simple_filter.h:43:0,
                 from /opt/ros/eloquent/include/message_filters/subscriber.h:41,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/signal1.h:82:7: note: ‘message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >::Signal1(const message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >&)’ is implicitly deleted because the default definition would be ill-formed:
 class Signal1
       ^~~~~~~
/opt/ros/eloquent/include/message_filters/signal1.h:82:7: error: use of deleted function ‘std::mutex::mutex(const std::mutex&)’
In file included from /usr/include/c++/7/mutex:43:0,
                 from /usr/include/c++/7/future:38,
                 from /opt/ros/eloquent/include/rclcpp/executors.hpp:18,
                 from /opt/ros/eloquent/include/rclcpp/rclcpp.hpp:145,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:2:
/usr/include/c++/7/bits/std_mutex.h:97:5: note: declared here
     mutex(const mutex&) = delete;
clalancette commented 4 years ago

The member initialisation doesn't work for me for message_filters::Subscriber.

I'll suggest you open up a new issue, otherwise this will probably get lost.

Harsharma2308 commented 4 years ago

If someone gets stuck on this, someone answered my question on ROS answers - https://answers.ros.org/question/359614/ros2-message-filters-in-a-class-initializing-message_filterssubscriber-object/