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

C++ Dynamic_reconfigure client API in ROS

asked 2022-07-11 17:06:18 -0600

hck007 gravatar image

If we only implement dynamic_reconfigure in server side, we have to manually calibrate parameters in GUI. Calibrating parameters is tedious if we have a lot of parameters. I'm using ros kinetic to implement a client node in c++ that can subscribe to a topic error and dynamically calibrate parameters in server node based on the data from the subscription of the topic error. However, there is no c++ client API tutorial in official document. I can only look at the header file in [Github][1] for implementation, and I got the error for creating a client in my class. I want to implement a class Calibration to define my client node. The following is my implementation of client node and error message.

//in calibration.h
#include <ros/ros.h>
#include <string>
#include <vector>
#include <std_msgs/Float32.h>
#include <dynamic_reconfigure/client.h>
#include <calibration/HcNodeConfig.h>

using namespace std;

class Calibration {
    hc::HcNodeConfig config;
    ros::NodeHandle n;
    ros::Subscriber listener;
    //dynamic_reconfigure::Client<hc::HcNodeConfig> adjuster("adjuster", &Calibration::adjuster_callback); 

    public:
        Calibration();
        void callback(const std_msgs::Float32ConstPtr& msg);
        void adjuster_callback(hc::HcNodeConfig& params);
};


//in calibration.cpp
#include "calibration.h"


void Calibration::adjuster_callback(hc::HcNodeConfig& params) {
    cout << "this is a dynamic_reconfigure callback" << endl;
}


void Calibration::callback(const std_msgs::Float32ConstPtr& msg) {
    float error = msg->data;
    dynamic_reconfigure::Client<hc::HcNodeConfig> client("hc", &Calibration::adjuster_callback, NULL);
    if (error <= 0.0) {
        config.direction = 0.0;
        client.setConfiguration(config);
    }

}


    Calibration::Calibration() {
        listener = n.subscribe("/error", 100, &Calibration::callback, this);
        ros::spin();
    }





    int main(int argc, char ** argv) {
        ros::init(argc, argv, "adjuster");
        Calibration cal();
        return 0;
    }

I got the following error.

/opt/ros/kinetic/include/dynamic_reconfigure/client.h: In instantiation of ‘dynamic_reconfigure::Client<ConfigType>::Client(const string&, boost::function<void(const ConfigType&)>, boost::function<void(const dynamic_reconfigure::ConfigDescription_<std::allocator<void> >&)>) [with ConfigType = hc::HcNodeConfig; std::__cxx11::string = std::__cxx11::basic_string<char>]’:
/home/david-dev/workspace/lidar/src/calibration/src/online/calibration.cpp:11:100:   required from here
/opt/ros/kinetic/include/dynamic_reconfigure/client.h:332:19: warning: ‘dynamic_reconfigure::Client<hc::HcNodeConfig>::nh_’ will be initialized after [-Wreorder]
   ros::NodeHandle nh_;
                   ^
/opt/ros/kinetic/include/dynamic_reconfigure/client.h:326:8: warning:   ‘bool dynamic_reconfigure::Client<hc::HcNodeConfig>::received_configuration_’ [-Wreorder]
   bool received_configuration_;
        ^
In file included from /home/david-dev/workspace/lidar/src/calibration/src/online/calibration.h:5:0,
                 from /home/david-dev/workspace/lidar/src/calibration/src/online/calibration.cpp:1:
/opt/ros/kinetic/include/dynamic_reconfigure/client.h:68:3: warning:   when initialized here [-Wreorder]
   Client(
   ^
In file included from /usr/include/boost/function/detail/maybe_include.hpp:18:0,
                 from /usr/include/boost/function/detail/function_iterate.hpp:14,
                 from /usr/include/boost/preprocessor/iteration/detail/iter/forward1.hpp:52,
                 from /usr/include/boost/function.hpp:64,
                 from /opt/ros/kinetic/include/ros/forwards.h:40,
                 from /opt/ros/kinetic/include/ros/common.h:37,
                 from /opt/ros/kinetic/include/ros/ros.h:43,
                 from /home/david-dev/workspace/lidar/src/calibration/src/online/calibration.h:1,
                 from /home/david-dev/workspace/lidar/src/calibration/src/online/calibration.cpp:1:
/usr/include/boost/function/function_template.hpp: In instantiation of ‘static ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2022-07-12 22:46:47 -0600

RyanChen.YLC gravatar image

updated 2022-07-12 22:49:51 -0600

I've met the similar problem before, this perhaps relates to "setting callback functions".

I tried following 2 methods,

  1. not to add "&" for callback function and make it static member function.
  2. use boost::bind, it may be like dynamic_reconfigure_client_->setDescriptionCallback(boost::bind(&NameSpace::setDescriptionCallback, this, _1));

both solved the problem.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2022-07-11 17:06:18 -0600

Seen: 135 times

Last updated: Jul 12 '22