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
00043 ChangeRonexConfigurationExample()
00044 {
00045 }
00046
00047 ~ChangeRonexConfigurationExample()
00048 {
00049 }
00050
00055 void configureRonex(std::string path)
00056 {
00057 dynamic_reconfigure::ReconfigureRequest srv_req;
00058 dynamic_reconfigure::ReconfigureResponse srv_resp;
00059 dynamic_reconfigure::BoolParameter bool_param;
00060 dynamic_reconfigure::IntParameter int_param;
00061 dynamic_reconfigure::Config conf;
00062
00063 bool_param.name = "input_mode_0";
00064 bool_param.value = false;
00065 conf.bools.push_back(bool_param);
00066
00067 bool_param.name = "input_mode_1";
00068 bool_param.value = false;
00069 conf.bools.push_back(bool_param);
00070
00071 int_param.name = "pwm_period_0";
00072 int_param.value = 200;
00073 conf.ints.push_back(int_param);
00074
00075 int_param.name = "pwm_clock_divider";
00076 int_param.value = 3000;
00077 conf.ints.push_back(int_param);
00078
00079 srv_req.config = conf;
00080
00081 ros::service::call(path + "/set_parameters", srv_req, srv_resp);
00082 }
00083
00084 };
00085
00086
00087
00088 int main(int argc, char **argv)
00089 {
00090
00091 ros::init(argc, argv, "change_ronex_configuration_cpp");
00092
00093
00094 ChangeRonexConfigurationExample example;
00095
00096
00097 std::string ronex_id = "test_ronex";
00098 std::string ronex_path = "/ronex/general_io/" + ronex_id + "/";
00099
00100
00101 example.configureRonex(ronex_path);
00102
00103 return 0;
00104 }
00105
00106