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

Dynamic_Reconfigure: Set Parameter Value from C++ Code

asked 2022-03-17 08:33:40 -0600

Green01 gravatar image

updated 2022-04-30 13:41:30 -0600

lucasw gravatar image

Hello - I am new to ROS. I am using Ros Noetic on Ubuntu 20.04.

I followed the dynamic_reconfigure tutorial and have dynamic_reconfigure parameters working. I have 1 parameter which is defined as a bool_t in the .cfg file, so in the rqt_reconfigure GUI it appears as a checkbox. In my C++ code, if the parameter value is true (i.e checkbox is checked) I will save data to a file. Once the data is saved, the C++ code should set the parameter value to false so the checkbox in the rqt_reconfigure GUI gets unchecked.

In order to change the value of a dynamic reconfigure parameter in C++ code, I followed these instructions and information in this FAQ. This is my code:

#include <dynamic_reconfigure/BoolParameter.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/Config.h>

dynamic_reconfigure::ReconfigureRequest srv_req; 
dynamic_reconfigure::ReconfigureResponse srv_resp; 
dynamic_reconfigure::BoolParameter bool_param; 
dynamic_reconfigure::Config conf;

bool_param.name = "save_data_to_file";
bool_param.value = false;    // I also tried setting this to 0 instead of false with same results
conf.bools.push_back(bool_param);

srv_req.config = conf;
ros::service::call("/myNodeName/set_parameters", srv_req, srv_resp);

The ros::service::call line hangs. I have print statements before and after that line and never see the print that is after it.

From a command line, I can run this command and it works so I'm certain I'm using the correct node name, the correct parameter name etc:

rosrun dynamic_reconfigure dynparam set /myNodeName save_data_to_file false

Any suggestions as to why the ros::service::call in the C++ code hangs? Watching the values of the parameter from a command line, the ros::service::call does not change the value of the parameter.

Thanks in advance!

EDIT #1: This is my C++ code cut down to the basics. When I run it, I can see the "BEFORE" print statement, but not the "AFTER". The value of save_data_to_file never changes.

#include <unistd.h>
#include "ros/ros.h"
#include "dynamic_reconfigure/server.h"
#include "test/dynamicParamsConfig.h"
#include <dynamic_reconfigure/BoolParameter.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/Config.h>

void callback(test::dynamicParamsConfig &config, uint32_t level) {
   ROS_INFO("Reconfigure request : save:%i number: %i", 
        config.save_data_to_file,
        config.num_to_save
        );

}

int main(int argc, char **argv)
{

   ros::init(argc, argv, "publisher");
   ros::NodeHandle nh; 

   dynamic_reconfigure::Server<test::dynamicParamsConfig> server;
   dynamic_reconfigure::Server<test::dynamicParamsConfig>::CallbackType f;
   f = boost::bind(&callback, _1, _2);
   server.setCallback(f);

   while (ros::ok())
   {
      for (int i=0; i < 15; ++i) {

         ROS_INFO("Loop: %i", i);
         if (i==9) {
            dynamic_reconfigure::ReconfigureRequest srv_req;
            dynamic_reconfigure::ReconfigureResponse srv_resp;
            dynamic_reconfigure::BoolParameter bool_param;
            dynamic_reconfigure::Config conf;

            bool_param.name = "save_data_to_file";
            //bool_param.value = 0;  
            bool_param.value = false;
            conf.bools.push_back(bool_param);

            srv_req.config = conf;
            ROS_INFO("BEFORE");  // I see this print statement
            ros::service::call("/publisher/set_parameters", srv_req, srv_resp);
            ROS_INFO("AFTER");  // I never see this print statement
         }
         sleep(2);
         ros::spinOnce();
      }
   }
  return 0;
}
edit retag flag offensive close merge delete

Comments

Hi Green01. Can you edit the question and include your entire code? The way you are building the conf object and your service calling seems both right. Maybe you are just missing the "ros::init" (ros::service::call documentation)

schulze18 gravatar image schulze18  ( 2022-03-17 11:26:57 -0600 )edit

I do have a ros::init. I will work on cutting down the cpp file to something I can paste into the question.

Green01 gravatar image Green01  ( 2022-03-17 13:42:35 -0600 )edit

schulze18 - can you provide any further suggestions now that I have the entire code in the question?

Green01 gravatar image Green01  ( 2022-03-29 13:30:24 -0600 )edit

Hi @Green01. I don`t know if those are the problems, but i have some recommendations for your code. I never saw someone calling a service in the same node of the service server. Maybe it is not even possible, due to some concurrency problem, I don't know. But it is at least weird since you could just have a method that directly updates the variables without ROS. Try to create a second node that only calls the dynamic reconfigure service. Also, to do "timer loops", try to use the ROS time sources (http://wiki.ros.org/roscpp/Overview/C...). You can use other time sources with ROS, but it is also tricky.

schulze18 gravatar image schulze18  ( 2022-03-29 14:31:40 -0600 )edit
1

You nailed it, @schulze18! I created a separate node that calls the dynamic reconfigure service. Now when the C++ code sets the value of the parameter "save_data_to_file" to false, the checkbox in the rqt_reconfigure GUI gets unchecked. Thank you so much for all your help!

Green01 gravatar image Green01  ( 2022-04-04 14:39:09 -0600 )edit

Great to hear that! You are welcome. Please, create an answer to your own question with a description of what you did. Therefore, if someone ends up with the same problem, they will easily see what they need to do.

schulze18 gravatar image schulze18  ( 2022-04-04 15:10:31 -0600 )edit

I think the problem is a deadlock, since ros callbacks are executed consecutively you get a deadlock in a one-threaded spin. So you must call the service from another node or you can use a multithread spinner.

kourou gravatar image kourou  ( 2022-09-14 17:08:24 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-04-05 12:25:01 -0600

Green01 gravatar image

Thanks to @schulze18 for providing help on getting dynamic reconfigure working.

I now have 2 nodes under a single project. I have my main "publisher" node which contains the dynamic reconfigure server code. Then the code below is the working "dynamic_ reconfig" node. It works to set a boolean value or an integer value (the commented out piece) from this node. For example, if I set "save_data_to_file" to false, the checkbox in the rqt_reconfigure GUI will be unchecked. Or if I set the "num_to_save" parameter to a value, the slider in the rqt_reconfigure GUI moves to that value.

#include <unistd.h>
#include "ros/ros.h"
#include <dynamic_reconfigure/BoolParameter.h>
#include <dynamic_reconfigure/IntParameter.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/Config.h>

int main(int argc, char **argv)
{

   ros::init(argc, argv, "dynamic_reconfig");
   ros::NodeHandle nh;  

   while (ros::ok())
   {
      for (int i=0; i < 15; ++i) {

         if (i==9) {
            dynamic_reconfigure::ReconfigureRequest srv_req;
            dynamic_reconfigure::ReconfigureResponse srv_resp;
            dynamic_reconfigure::BoolParameter bool_param;
            dynamic_reconfigure::Config conf;

            bool_param.name = "save_data_to_file";
            bool_param.value = false;
            conf.bools.push_back(bool_param);

            //dynamic_reconfigure::IntParameter int_param;
            //int_param.name = "num_to_save";
            //int_param.value = 7;
            //conf.ints.push_back(int_param);

            srv_req.config = conf;
            ros::service::call("/publisher/set_parameters", srv_req, srv_resp);
         }
         sleep(2);
         ros::spinOnce();
      }
   }
  return 0;
}
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2022-03-17 08:33:40 -0600

Seen: 1,381 times

Last updated: Apr 05 '22