ros2 show up "double free or corruption (fasttop)" in the end of program

asked 2019-11-22 09:26:55 -0500

Dear All:

I encounter a problem at ros2 dashing by using Ubuntu 18.04 both on Docker container and desktop.

When I wrote a ros2 code by using a thread to listen from others, I found it will show up

double free or corruption (fasttop)

in the end of program.

The entire code in there:

#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

class SpinProblem{
  private:
  std::shared_ptr< rclcpp::Publisher <std_msgs::msg::String> > chatter;
  void listen_thread(rclcpp::Node::SharedPtr node){

    auto subscription = node->create_subscription<std_msgs::msg::String>(
    "listener",
    10,
    [&](const std_msgs::msg::String::SharedPtr msg) ->void {
      RCLCPP_INFO(node->get_logger(), "I heard: '%s'", msg->data.c_str());
    });

    rclcpp::spin(node);
   }
public:
  SpinProblem(){
    auto node = rclcpp::Node::make_shared("test");
    std::thread(&SpinProblem::listen_thread, this,node).detach();
    chatter = node->create_publisher<std_msgs::msg::String>("spin_problem", rclcpp::QoS(10));
  }

  void send_something(){
    std_msgs::msg::String msg;

    msg.data = "send something";

    chatter->publish(msg);
  }
};

int main(int argc, char * argv[]){
  rclcpp::init(argc, argv);
  std::unique_ptr<SpinProblem> spinProblem = std::make_unique<SpinProblem>();

  spinProblem->send_something();

  rclcpp::Rate sleepRate(1s);
  int counter=0;

  while(counter==0){
    sleepRate.sleep();
    std::cout<<"doing something simulator"<<std::endl;
    counter++;
  }
  spinProblem->send_something();
  std::cout<<"end code"<<std::endl;
}

I also put it into my GitHub

I found if I change rclcpp::spin(node); into rclcpp::spin_some(node) and use while loop to loop it.

The problem won't happen.

So, is there something I mistake understand about rclcpp::spin(node); ?

Or there is a bug about it?

edit retag flag offensive close merge delete