Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

TwistMux Node dies in ROS2 Jazzy #53

Closed
BrainBoxTayo opened this issue Nov 13, 2024 · 5 comments
Closed

TwistMux Node dies in ROS2 Jazzy #53

BrainBoxTayo opened this issue Nov 13, 2024 · 5 comments

Comments

@BrainBoxTayo
Copy link

BrainBoxTayo commented Nov 13, 2024

[twist_mux-10] terminate called after throwing an instance of 'twist_mux::ParamsHelperException'
[twist_mux-10] what(): could not load parameter 'use_stamped'. (namespace: /)

[ERROR] [twist_mux-10]: process has died [pid 188290, exit code -6, cmd '/opt/ros/jazzy/lib/twist_mux/twist_mux --ros-args --params-file /tmp/launch_params_gvyag67m --params-file /home/brainboxtayo/bumperbot_ws/install/bumperbot_controller/share/bumperbot_controller/config/twist_mux_locks.yaml --params-file /opt/ros/jazzy/share/twist_mux/config/twist_mux_topics.yaml -r /cmd_vel_out:=bumperbot_controller/cmd_vel_unstamped'].

@BrainBoxTayo
Copy link
Author

BrainBoxTayo commented Nov 14, 2024

Had to build from source, I made the following changes:

twist_mux.cpp
void TwistMux::init()
{
  // Get use stamped parameter
  bool use_stamped = false; //changed here, since params are not working
  auto nh = std::shared_ptr<rclcpp::Node>(this, [](rclcpp::Node *) {});
  // fetch_param(nh, "use_stamped", use_stamped);

  /// Get topics and locks:
  if(use_stamped)
  {
    velocity_stamped_hs_ = std::make_shared<velocity_stamped_topic_container>();
    getTopicHandles("topics", *velocity_stamped_hs_);
  }
  else
  {
    velocity_hs_ = std::make_shared<velocity_topic_container>();
    getTopicHandles("topics", *velocity_hs_);
  }
  lock_hs_ = std::make_shared<lock_topic_container>();
  getTopicHandles("locks", *lock_hs_);

  /// Publisher for output topic:
  if(use_stamped)
  {
    cmd_pub_stamped_ =
      this->create_publisher<geometry_msgs::msg::TwistStamped>(
        "cmd_vel_out",
        rclcpp::QoS(rclcpp::KeepLast(1)));
  }
  else
  {
    cmd_pub_ =
      this->create_publisher<geometry_msgs::msg::Twist>(
      "cmd_vel_out",
      rclcpp::QoS(rclcpp::KeepLast(1)));
  }

twist_marker.cpp
class TwistMarkerPublisher : public rclcpp::Node
{
public:
  TwistMarkerPublisher()
  : Node("twist_marker")
  {
    std::string frame_id;
    double scale;
    bool use_stamped = false; //made use_stamped a boolean value for the if check
    double z;

    this->declare_parameter("frame_id", "base_footprint");
    this->declare_parameter("scale", 1.0);
    // this->declare_parameter("use_stamped", false); //changed this line
    this->declare_parameter("vertical_position", 2.0);

    this->get_parameter<std::string>("frame_id", frame_id);
    this->get_parameter<double>("scale", scale);
    // this->get_parameter<bool>("use_stamped", use_stamped); //and this
    this->get_parameter<double>("vertical_position", z);

    marker_ = std::make_shared<TwistMarker>(frame_id, scale, z);

    if (use_stamped)
    {
      sub_stamped_ = this->create_subscription<geometry_msgs::msg::TwistStamped>(
        "twist", rclcpp::SystemDefaultsQoS(),
        std::bind(&TwistMarkerPublisher::callback_stamped, this, std::placeholders::_1));
    }
    else
    {
      sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
        "twist", rclcpp::SystemDefaultsQoS(),
        std::bind(&TwistMarkerPublisher::callback, this, std::placeholders::_1));
    }

    pub_ =
      this->create_publisher<visualization_msgs::msg::Marker>(
      "marker",
      rclcpp::QoS(rclcpp::KeepLast(1)));
  }

include/twist_mux/twist_mux_diagnostics_status.hpp
#include <memory>

namespace twist_mux
{
struct TwistMuxDiagnosticsStatus
{
  typedef std::shared_ptr<TwistMuxDiagnosticsStatus> Ptr;
  typedef std::shared_ptr<const TwistMuxDiagnosticsStatus> ConstPtr;

  double reading_age;
  rclcpp::Time last_loop_update;
  double main_loop_time;

  LockTopicHandle::priority_type priority;

  bool use_stamped;

  std::shared_ptr<TwistMux::velocity_topic_container> velocity_hs;
  std::shared_ptr<TwistMux::velocity_stamped_topic_container> velocity_stamped_hs;
  std::shared_ptr<TwistMux::lock_topic_container> lock_hs;

  TwistMuxDiagnosticsStatus()
  : reading_age(0),
    last_loop_update(rclcpp::Clock().now()),
    main_loop_time(0),
    priority(0),
    use_stamped(false) //changed this line
  {
    velocity_hs = std::make_shared<TwistMux::velocity_topic_container>();
    velocity_stamped_hs = std::make_shared<TwistMux::velocity_stamped_topic_container>();
    lock_hs = std::make_shared<TwistMux::lock_topic_container>();
  }
};

@TWALL9
Copy link
Contributor

TWALL9 commented Dec 29, 2024

Hey @BrainBoxTayo I see that this is a closed issue that you addressed by removing the use_stamped parameter entirely. You could have also added that parameter to your twist_mux_params.yaml file like so

twist_mux:
  ros__parameters:
    use_stamped: true
    topics:

or even in the launch file that starts twist_mux like so:

twist_mux = Node(
        package='twist_mux',
        executable='twist_mux',
        parameters=[twist_mux_params, {'use_sim_time': use_sim_time}, {'use_stamped': True}]
)

I'm also working on setting the param to default to false in this PR: #55

@BrainBoxTayo
Copy link
Author

Hi @TWALL9 , that was the approach I took first. But for some reason it wasn't working. Maybe I had a syntax issue. Thanks so much though. This would come in handy to people facing the same error.
Why do you think the use_stamped param kills the node?

@TWALL9
Copy link
Contributor

TWALL9 commented Dec 30, 2024 via email

@BrainBoxTayo
Copy link
Author

Ahh ok thank you!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants