ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

create_subscription in main function [ROS2]

asked 2022-03-28 09:11:47 -0500

zinuok gravatar image

< Problem >

I want to define a subscriber in the main function, not in a class. (This is because I'm migrating the ROS1 package into ROS2, maintaining its original data structure) As I know, 'this' command can catch a context of a class member. However, in the main function, I can't use the command. How can I effectively replace the 'this' command in 'create_subscription'?

< Environment > Ubuntu 20.04

(code)

rclcpp::init(argc, argv); auto n = rclcpp::Node::make_shared("globalEstimator");

auto qos_profile = rclcpp::QoS(rclcpp::KeepLast(100));

rclcpp::Subscription<sensor_msgs::msg::navsatfix>::SharedPtr sub_GPS = n->create_subscription<sensor_msgs::msg::navsatfix>("/gps", qos_profile, std::bind(GPS_callback, this, std::placeholders::_1));

[error msg] error: invalid use of ‘this’ in non-member function

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2022-03-29 06:15:49 -0500

ljaniec gravatar image

updated 2022-03-29 06:28:01 -0500

I think you should think about migrating the code with OOP, but overall - this migration guide can help you with change from ROS1 to ROS2. There is a tutorial from ROS-Industrial too.

E.g. this example code:

#include <sstream>
// #include "ros/ros.h"
#include "rclcpp/rclcpp.hpp"
// #include "std_msgs/String.h"
#include "std_msgs/msg/string.hpp"
int main(int argc, char **argv)
{
//  ros::init(argc, argv, "talker");
//  ros::NodeHandle n;
  rclcpp::init(argc, argv);
  auto node = rclcpp::Node::make_shared("talker");
//  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
//  ros::Rate loop_rate(10);
  auto chatter_pub = node->create_publisher<std_msgs::msg::String>("chatter", 1000);
  rclcpp::Rate loop_rate(10);
  int count = 0;
//  std_msgs::String msg;
  std_msgs::msg::String msg;
//  while (ros::ok())
  while (rclcpp::ok())
  {
    std::stringstream ss;
    ss << "hello world " << count++;
    msg.data = ss.str();
//    ROS_INFO("%s", msg.data.c_str());
    RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
    chatter_pub->publish(msg);
//    ros::spinOnce();
    rclcpp::spin_some(node);
    loop_rate.sleep();
  }
  return 0;
}

is from the first migration guide. It's with a simple publisher in C++, but subscribing is a bit more complicated, I guess.

EDIT: I found this example on GitHub (there: https://github.com/ros2/examples/tree...) in not_composable.cpp:

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

rclcpp::Node::SharedPtr g_node = nullptr;

/* We do not recommend this style anymore, because composition of multiple
 * nodes in the same executable is not possible. Please see one of the subclass
 * examples for the "new" recommended styles. This example is only included
 * for completeness because it is similar to "classic" standalone ROS nodes. */

void topic_callback(const std_msgs::msg::String::SharedPtr msg)
{
  RCLCPP_INFO(g_node->get_logger(), "I heard: '%s'", msg->data.c_str());
}

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  g_node = rclcpp::Node::make_shared("minimal_subscriber");
  auto subscription =
    g_node->create_subscription<std_msgs::msg::String>("topic", 10, topic_callback);
  rclcpp::spin(g_node);
  rclcpp::shutdown();
  // TODO(clalancette): It would be better to remove both of these nullptr
  // assignments and let the destructors handle it, but we can't because of
  // https://github.com/eProsima/Fast-RTPS/issues/235 .  Once that is fixed
  // we should probably look at removing these two assignments.
  subscription = nullptr;
  g_node = nullptr;
  return 0;
}
edit flag offensive delete link more

Question Tools

Stats

Asked: 2022-03-28 09:11:47 -0500

Seen: 1,698 times

Last updated: Mar 29 '22