what(): bad_weak_ptr
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)...); }
}