ros2 control crash

asked 2021-04-18 04:56:21 -0500

olepor gravatar image

updated 2021-04-22 00:57:57 -0500

jayess gravatar image

Hi, I am currently facing a bug whilst implementing a ROS2 controller, which I am not able to resolve:

I am trying to implement a custom Ackermann controller for the ROS2 control framework.

So, right now, I am simply trying to get one hardware interface going, and have configured, and set this up.

I subscribe to a geometry_msgs/msg/Twist, and in the subscriber callback I only have this:

 // Create a subscription to /cmd_vel
  velocity_command_subscriber_ = node_->create_subscription<geometry_msgs::msg::Twist>(
         "cmd_vel", rclcpp::SystemDefaultsQoS(),
         [this](const Twist::SharedPtr msg) -> void {
           RCLCPP_INFO(node_->get_logger(), "Received Twist message: %f", msg->twist.linear.x);
           // speed = msg->twist.linear.x;
           // turn = msg->twist.angular.z;
           // rt_command_ptr_.set(std::move(msg));
           // std::move(msg);
           RCLCPP_INFO(node_->get_logger(), "Wrote message to the");
         });

to handle the received Twist message.

Still, upon starting the controller (which works fine), until I send one Twist message like so:

ros topic pub -t 10 cmd_vel geometry_msgs/msg/TwistStamped '{linear: {x: 1.0, y: 2.0, z: 3.0}, angular: {x: 4.0, y: 5.0, z: 6.0}}'

And then this happens, without fault:

[ros2_control_node-1] [INFO] [1618738475.988847289] [PiBotSystemHardware]: Joints sucessfully read!

[ros2_control_node-1] [INFO] [1618738475.988948970] [ackermann_steering_controller]: update()

[ros2_control_node-1] [INFO] [1618738475.989037777] [ackermann_steering_controller]: last_msg in nullptr

[ros2_control_node-1] [INFO] [1618738475.989088236] [PiBotSystemHardware]: Writing...

[ros2_control_node-1] [INFO] [1618738475.989108989] [PiBotSystemHardware]: Got command 0.00000 for 
'left_wheel_joint'!
[ros2_control_node-1] [INFO] [1618738475.989130302] [PiBotSystemHardware]: Got command 0.00000 for 
'right_wheel_joint'!
[ros2_control_node-1] [INFO] [1618738475.989147734] [PiBotSystemHardware]: Joints sucessfully written!

[ros2_control_node-1] [INFO] [1618738476.488851273] [PiBotSystemHardware]: Reading...

[ros2_control_node-1] [INFO] [1618738476.488958424] [PiBotSystemHardware]: Got position state 0.00000 and velocity state 0.00000 for 'left_wheel_joint'!

[ros2_control_node-1] [INFO] [1618738476.488985264] [PiBotSystemHardware]: Got position state 0.00000 and velocity state 0.00000 for 'right_wheel_joint'!

[ros2_control_node-1] [INFO] [1618738476.489001199] [PiBotSystemHardware]: Joints sucessfully read!

[ros2_control_node-1] [INFO] [1618738476.489050950] [ackermann_steering_controller]: update()

[ros2_control_node-1] [INFO] [1618738476.489121653] [ackermann_steering_controller]: last_msg in nullptr

[ros2_control_node-1] [INFO] [1618738476.489158862] [PiBotSystemHardware]: Writing...

[ros2_control_node-1] [INFO] [1618738476.489175453] [PiBotSystemHardware]: Got command 0.00000 for 'left_wheel_joint'!

[ros2_control_node-1] [INFO] [1618738476.489192105] [PiBotSystemHardware]: Got command 0.00000 for 'right_wheel_joint'!

[ros2_control_node-1] [INFO] [1618738476.489206768] [PiBotSystemHardware]: Joints sucessfully written!

[ros2_control_node-1] [INFO] [1618738476.941555370] [ackermann_steering_controller]: Received Twist message: 6.000000

[ros2_control_node-1] [INFO] [1618738476.941706339] [ackermann_steering_controller]: Wrote message to the

[ros2_control_node-1] Stack trace (most recent call last) in thread 28024:

[ros2_control_node-1] #12   Object "", at 0xffffffffffffffff, in

[ros2_control_node-1] #11   Object "/usr/lib/x86_64-linux-gnu/libc-2.31.so", at 0x7fa028194292, in __clone

[ros2_control_node-1] #10   Object "/usr/lib/x86_64-linux-gnu/libpthread-2.31.so", at 0x7fa028469608, in start_thread

[ros2_control_node-1] #9    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.28", at 0x7fa028355d83, in

[ros2_control_node-1] #8    Object "/opt/ros/foxy/lib/librclcpp.so", at 0x7fa028578d33, in 
rclcpp::executors::MultiThreadedExecutor::run(unsigned long)

[ros2_control_node-1] #7    Object "/opt/ros/foxy/lib/librclcpp.so", at 0x7fa028575084, in 
rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&)

[ros2_control_node-1] #6    Object "/opt/ros/foxy/lib/librclcpp.so", at 0x7fa028574936, in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>)

[ros2_control_node-1] #5    Source "/usr/include/c++/9/bits/shared_ptr_base.h", line 557, in _M_dispose [0x7fa020234ad8]

[ros2_control_node-1]         554:       virtual void

[ros2_control_node-1]         555:       _M_dispose() noexcept

[ros2_control_node-1]         556:       {

[ros2_control_node-1]       > 557:  allocator_traits<_Alloc>::destroy(_M_impl._M_alloc(), _M_ptr());

[ros2_control_node-1]         558:       }

[ros2_control_node-1]         559:

[ros2_control_node-1]         560:       // Override ...
(more)
edit retag flag offensive close merge delete