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

runtime error after trying to set parameters in ROS2

asked 2018-09-19 15:58:29 -0500

mpanah gravatar image

When I try to set parameters, I'm getting the following error:

terminate called after throwing an instance of 'std::runtime_error'

what(): Node has already been added to an executor.

I was able to get around this problem by creating another node within my constructor. I'm wondering if there is a better way to get around this problem. Please look at the code snippet below. Thanks.

main.cpp

int main(int argc, char **argv)
 {
     rclcpp::init(argc, argv);
     rclcpp::spin(std::make_shared<TestParameter>());
     rclcpp::shutdown();
     return 0;
 }

test_parameter.hpp

class TestParameter : public rclcpp::Node
{
public:
  TestParameter();
  ~TestParameter();

  void subCB();
  void saveParamToServer();

private:
  rclcpp::SyncParametersClient::SharedPtr parameters_client_;
  rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::ConstSharedPtr test_sub_;

};

test_parameter.cpp

TestParameter::TestParameter()
    : Node("TestParameter")
{

  parameters_client_ = std::make_shared<rclcpp::SyncParametersClient>(std::shared_ptr<rclcpp::Node>(this));

  test_sub_ = this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
      "testsub", std::bind(&TestParameter::initialPoseReceived, this, std::placeholders::_1));
}

TestParameter::~TestParameter()
{
}

void TestParameter::subCB()
{
  this->saveParamToServer();
}

void TestParameter::saveParamToServer()
{
  parameters_client_->set_parameters({
      rclcpp::Parameter("x", 0),
      rclcpp::Parameter("y", 0),
  });
}

To fix this issue, I created another node for parameters within my constructor.

 test_node = rclcpp::Node::make_shared("TestNode");
 parameters_client_ = std::make_shared<rclcpp::SyncParametersClient>(std::shared_ptr<rclcpp::Node>(test_node));
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-09-19 17:12:00 -0500

William gravatar image

Ahoy, Matey!

It appears that we be a missing something in your code example, because the error what(): Node has already been added to an executor. should only occur if you add your node to an rclcpp::Executor and/or pass it to rclcpp::spin more than once. From the code you've shared I only be able to spot it being used like this in one place, i.e. when you do rclcpp::spin(std::make_shared<TestParameter>());.

I do have some other comment for yer, however:

  • Store ye node, do this instead auto n = std::make_shared<TestParameter>(); rclcpp::spin(n);
  • Ye don't need a rclcpp::SyncParametersClient to change parameters on yer own node, just use rclcpp::Node::set_parameters (or a similar method), see: http://docs.ros2.org/bouncy/api/rclcp...

(btw, it's talk like a pirate day: https://discourse.ros.org/t/answer-ro... )

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-09-19 15:58:29 -0500

Seen: 10,163 times

Last updated: Sep 19 '18