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

what(): bad_weak_ptr

asked 2019-08-08 11:57:13 -0500

EdwardNur gravatar image

I have a constructor which looks like this:

OdomNode::OdomNode() : Node("odometry_node","odometry_node_ns", rclcpp::NodeOptions()), _rate(30), _ticks_meter(1), _left_pos{0},
                       _right_pos{0}, _enc_left{0}, _enc_right{0}, _lmult{0},
                       _rmult{0}, _prev_rencoder{0}, _prev_lencoder{0},
                       _d_left{0}, _d_right{0}, q{std::make_shared<tf2::Quaternion>()},
                       _base_frame_id{"base_footprint"}, _odom_frame_id{"odom"},
                       _odom_ts{std::make_shared<geometry_msgs::msg::TransformStamped>()}, _loop_rate{30},
                       _then{}, _odom_pub{}, _odom_tb{std::make_shared<tf2_ros::StaticTransformBroadcaster>(shared_from_this())}
{
    _then = this->now();
    rclcpp::QoS qos(rclcpp::KeepLast(7));
    _odom_pub = this->create_publisher<nav_msgs::msg::Odometry>("odom", qos);
    //_odom_tb = odom_tf2_broadcaster(this->);
    _rate = this->declare_parameter("rate", 30);
    _ticks_meter = this->declare_parameter("ticks_meter", 1400000);
    _base_frame_id = this->declare_parameter("base_frame", "base_footprint");

}

And I also have the loop function of that class:

 void OdomNode::update()
{
    while(rclcpp::ok())
    {
        this->loop();
        this->_loop_rate.sleep();
        rclcpp::spin(shared_from_this());
    }

Whenever I run I get an error that I have a bad_weak_ptr. I have tried to declare and initialzie the shared_ptr in my update function:

   void OdomNode::update()
    {
        std::shared_ptr<rclcpp::Node> _for_spin = std::make_shared<rclcpp::Node>(this);
        while(rclcpp::ok())
        {
            this->loop();
            this->_loop_rate.sleep();
            rclcpp::spin(_for_spin);
        }

But I get an error:

/usr/include/c++/7/ext/new_allocator.h:136:4: error: no matching function for call to ‘rclcpp::Node::Node(odom_node::OdomNode*)’
  { ::new((void *)__p) _Up(std::forward<_Args>(__args)...); }

}
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2019-08-08 12:04:59 -0500

Karsten gravatar image

updated 2023-05-03 03:58:36 -0500

130s gravatar image

The problem is this line _odom_tb{std::make_shared<tf2_ros::StaticTransformBroadcaster>(shared_from_this())}

You are trying to get a shared pointer from this in the initialization phase, even though the constructor isn't fully completed yet and therefore this doesn't point to a correct instance.

As a workaround, you can try to call the constructor for the StaticTransformBroadcaster [0] with a raw this pointer or introduce a separate init function for your odomNode.

[0] https://github.com/ros2/geometry2/blo...

edit flag offensive delete link more

Comments

@Karsten great, I can see that it accepts r value for the object, which exactly what is needed but how then it is created? Does it create a new shared_ptr inside that statictransform constructor?

EdwardNur gravatar image EdwardNur  ( 2019-08-08 12:56:40 -0500 )edit

@Karsten turns out to be that the problem is behind the while loop and make_shared that passed insie the spin function!

EdwardNur gravatar image EdwardNur  ( 2019-08-08 13:30:53 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-08-08 11:57:13 -0500

Seen: 1,370 times

Last updated: May 03 '23