33 #include <dynamic_reconfigure/server.h>
44 dynamic_reconfigure::ReconfigureRequest srv_req;
45 dynamic_reconfigure::ReconfigureResponse srv_resp;
48 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
50 EXPECT_EQ(1, srv_resp.config.bools.size());
52 if (!srv_resp.config.bools.empty())
54 EXPECT_EQ(
"enable_odom_tf", srv_resp.config.bools[0].name);
56 EXPECT_EQ(
false, srv_resp.config.bools[0].value);
59 EXPECT_EQ(4, srv_resp.config.doubles.size());
61 if (srv_resp.config.doubles.size() >= 4)
63 EXPECT_EQ(
"left_wheel_radius_multiplier", srv_resp.config.doubles[0].name);
64 EXPECT_EQ(1, srv_resp.config.doubles[0].value);
66 EXPECT_EQ(
"right_wheel_radius_multiplier", srv_resp.config.doubles[1].name);
67 EXPECT_EQ(1, srv_resp.config.doubles[1].value);
69 EXPECT_EQ(
"wheel_separation_multiplier", srv_resp.config.doubles[2].name);
70 EXPECT_EQ(1, srv_resp.config.doubles[2].value);
72 EXPECT_EQ(
"publish_rate", srv_resp.config.doubles[3].name);
73 EXPECT_EQ(50, srv_resp.config.doubles[3].value);
76 dynamic_reconfigure::DoubleParameter double_param;
77 double_param.name =
"left_wheel_radius_multiplier";
78 double_param.value = 0.95;
80 srv_req.config.doubles.push_back(double_param);
82 double_param.name =
"right_wheel_radius_multiplier";
83 double_param.value = 0.95;
85 srv_req.config.doubles.push_back(double_param);
87 double_param.name =
"wheel_separation_multiplier";
88 double_param.value = 0.95;
90 srv_req.config.doubles.push_back(double_param);
92 double_param.name =
"publish_rate";
93 double_param.value = 150;
95 srv_req.config.doubles.push_back(double_param);
97 dynamic_reconfigure::BoolParameter bool_param;
98 bool_param.name =
"enable_odom_tf";
99 bool_param.value =
false;
101 srv_req.config.bools.push_back(bool_param);
104 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
106 EXPECT_EQ(1, srv_resp.config.bools.size());
108 if (!srv_resp.config.bools.empty())
110 EXPECT_EQ(
"enable_odom_tf", srv_resp.config.bools[0].name);
111 EXPECT_EQ(
false, srv_resp.config.bools[0].value);
114 EXPECT_EQ(4, srv_resp.config.doubles.size());
116 if (srv_resp.config.doubles.size() >= 4)
118 EXPECT_EQ(
"left_wheel_radius_multiplier", srv_resp.config.doubles[0].name);
119 EXPECT_EQ(0.95, srv_resp.config.doubles[0].value);
121 EXPECT_EQ(
"right_wheel_radius_multiplier", srv_resp.config.doubles[1].name);
122 EXPECT_EQ(0.95, srv_resp.config.doubles[1].value);
124 EXPECT_EQ(
"wheel_separation_multiplier", srv_resp.config.doubles[2].name);
125 EXPECT_EQ(0.95, srv_resp.config.doubles[2].value);
127 EXPECT_EQ(
"publish_rate", srv_resp.config.doubles[3].name);
128 EXPECT_EQ(150, srv_resp.config.doubles[3].value);
136 while(!isControllerAlive() &&
ros::ok())
141 FAIL() <<
"Something went wrong while executing test";
149 dynamic_reconfigure::ReconfigureRequest srv_req;
150 dynamic_reconfigure::ReconfigureResponse srv_resp;
152 dynamic_reconfigure::BoolParameter bool_param;
153 bool_param.name =
"enable_odom_tf";
154 bool_param.value =
true;
156 srv_req.config.bools.push_back(bool_param);
158 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
165 int main(
int argc,
char** argv)
167 testing::InitGoogleTest(&argc, argv);
168 ros::init(argc, argv,
"diff_drive_dyn_reconf_test");
172 int ret = RUN_ALL_TESTS();