Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00024
00025 #include <ros/ros.h>
00026 #include <ros/console.h>
00027 #include <string>
00028
00029 #include <dynamic_reconfigure/BoolParameter.h>
00030 #include <dynamic_reconfigure/IntParameter.h>
00031 #include <dynamic_reconfigure/Reconfigure.h>
00032 #include <dynamic_reconfigure/Config.h>
00033
00034
00035
00039 class ChangeRonexConfigurationExample
00040 {
00041 public:
00042 ChangeRonexConfigurationExample()
00043 {
00044 }
00045
00046 ~ChangeRonexConfigurationExample()
00047 {
00048 }
00049
00054 void configureRonex(std::string path)
00055 {
00056 dynamic_reconfigure::ReconfigureRequest srv_req;
00057 dynamic_reconfigure::ReconfigureResponse srv_resp;
00058 dynamic_reconfigure::BoolParameter bool_param;
00059 dynamic_reconfigure::IntParameter int_param;
00060 dynamic_reconfigure::Config conf;
00061
00062 bool_param.name = "input_mode_0";
00063 bool_param.value = false;
00064 conf.bools.push_back(bool_param);
00065
00066 bool_param.name = "input_mode_1";
00067 bool_param.value = false;
00068 conf.bools.push_back(bool_param);
00069
00070 int_param.name = "pwm_period_0";
00071 int_param.value = 200;
00072 conf.ints.push_back(int_param);
00073
00074 int_param.name = "pwm_clock_divider";
00075 int_param.value = 3000;
00076 conf.ints.push_back(int_param);
00077
00078 srv_req.config = conf;
00079
00080 ros::service::call(path + "/set_parameters", srv_req, srv_resp);
00081 }
00082 };
00083
00084
00085
00086 int main(int argc, char **argv)
00087 {
00088
00089 ros::init(argc, argv, "change_ronex_configuration_cpp");
00090
00091
00092 ChangeRonexConfigurationExample example;
00093
00094
00095 std::string ronex_id = "test_ronex";
00096 std::string ronex_path = "/ronex/general_io/" + ronex_id + "/";
00097
00098
00099 example.configureRonex(ronex_path);
00100
00101 return 0;
00102 }
00103
00104