ROS2 creating a subscriber in a class
I am using Ubuntu 18.04 ; ROS2 Eloquent I am trying to run this code by defining callback in the class.
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
using namespace std::placeholders;
class MinimalDepthSubscriber : public rclcpp::Node {
public:
MinimalDepthSubscriber()
: Node("zed_depth_tutorial") {
rmw_qos_profile_t camera_qos_profile = rmw_qos_profile_sensor_data;
mSub = create_subscription<sensor_msgs::msg::Image>(
"/zed/zed_node/depth/depth_registered",
std::bind(&MinimalDepthSubscriber::depthCallback, this, _1),
camera_qos_profile);
}
protected:
void depthCallback(const sensor_msgs::msg::Image::SharedPtr msg) {
// Get a pointer to the depth values casting the data
// pointer to floating point
float* depths = (float*)(&msg->data[0]);
// Image coordinates of the center pixel
int u = msg->width / 2;
int v = msg->height / 2;
// Linear index of the center pixel
int centerIdx = u + msg->width * v;
// Output the measure
RCLCPP_INFO(get_logger(), "Center distance : %g m", depths[centerIdx]);
}
private:
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr mSub;
};
// The main function
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
auto depth_node = std::make_shared<MinimalDepthSubscriber>();
rclcpp::spin(depth_node);
rclcpp::shutdown();
return 0;
}
The error I get is this -
colcon build --packages-select stereo_ground_surface
Starting >>> stereo_ground_surface
--- stderr: stereo_ground_surface
/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/simulation_ws/src/stereo_detection/src/multisense_subscriber.cpp: In constructor ‘MinimalDepthSubscriber::MinimalDepthSubscriber()’:
/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/simulation_ws/src/stereo_detection/src/multisense_subscriber.cpp:87:38: error: no matching function for call to ‘MinimalDepthSubscriber::create_subscription<sensor_msgs::msg::Image>(const char [37], std::_Bind_helper<false, void (MinimalDepthSubscriber::*)(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >), MinimalDepthSubscriber*, const std::_Placeholder<1>&>::type, rmw_qos_profile_t&)’
camera_qos_profile);
What is happening here? Is my function definition wrong? Are there changes to the rclcpp::Node::create_subscription
function