33 #include <dynamic_reconfigure/server.h> 39 while(!isControllerAlive() &&
ros::ok())
44 FAIL() <<
"Something went wrong while executing test";
49 dynamic_reconfigure::ReconfigureRequest srv_req;
50 dynamic_reconfigure::ReconfigureResponse srv_resp;
53 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
55 EXPECT_EQ(1, srv_resp.config.bools.size());
57 if (!srv_resp.config.bools.empty())
59 EXPECT_EQ(
"enable_odom_tf", srv_resp.config.bools[0].name);
61 EXPECT_EQ(
false, srv_resp.config.bools[0].value);
64 EXPECT_EQ(4, srv_resp.config.doubles.size());
66 if (srv_resp.config.doubles.size() >= 4)
68 EXPECT_EQ(
"left_wheel_radius_multiplier", srv_resp.config.doubles[0].name);
69 EXPECT_EQ(1, srv_resp.config.doubles[0].value);
71 EXPECT_EQ(
"right_wheel_radius_multiplier", srv_resp.config.doubles[1].name);
72 EXPECT_EQ(1, srv_resp.config.doubles[1].value);
74 EXPECT_EQ(
"wheel_separation_multiplier", srv_resp.config.doubles[2].name);
75 EXPECT_EQ(1, srv_resp.config.doubles[2].value);
77 EXPECT_EQ(
"publish_rate", srv_resp.config.doubles[3].name);
78 EXPECT_EQ(50, srv_resp.config.doubles[3].value);
81 dynamic_reconfigure::DoubleParameter double_param;
82 double_param.name =
"left_wheel_radius_multiplier";
83 double_param.value = 0.95;
85 srv_req.config.doubles.push_back(double_param);
87 double_param.name =
"right_wheel_radius_multiplier";
88 double_param.value = 0.95;
90 srv_req.config.doubles.push_back(double_param);
92 double_param.name =
"wheel_separation_multiplier";
93 double_param.value = 0.95;
95 srv_req.config.doubles.push_back(double_param);
97 double_param.name =
"publish_rate";
98 double_param.value = 150;
100 srv_req.config.doubles.push_back(double_param);
102 dynamic_reconfigure::BoolParameter bool_param;
103 bool_param.name =
"enable_odom_tf";
104 bool_param.value =
false;
106 srv_req.config.bools.push_back(bool_param);
109 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
111 EXPECT_EQ(1, srv_resp.config.bools.size());
113 if (!srv_resp.config.bools.empty())
115 EXPECT_EQ(
"enable_odom_tf", srv_resp.config.bools[0].name);
116 EXPECT_EQ(
false, srv_resp.config.bools[0].value);
119 EXPECT_EQ(4, srv_resp.config.doubles.size());
121 if (srv_resp.config.doubles.size() >= 4)
123 EXPECT_EQ(
"left_wheel_radius_multiplier", srv_resp.config.doubles[0].name);
124 EXPECT_EQ(0.95, srv_resp.config.doubles[0].value);
126 EXPECT_EQ(
"right_wheel_radius_multiplier", srv_resp.config.doubles[1].name);
127 EXPECT_EQ(0.95, srv_resp.config.doubles[1].value);
129 EXPECT_EQ(
"wheel_separation_multiplier", srv_resp.config.doubles[2].name);
130 EXPECT_EQ(0.95, srv_resp.config.doubles[2].value);
132 EXPECT_EQ(
"publish_rate", srv_resp.config.doubles[3].name);
133 EXPECT_EQ(150, srv_resp.config.doubles[3].value);
141 while(!isControllerAlive() &&
ros::ok())
146 FAIL() <<
"Something went wrong while executing test";
154 dynamic_reconfigure::ReconfigureRequest srv_req;
155 dynamic_reconfigure::ReconfigureResponse srv_resp;
157 dynamic_reconfigure::BoolParameter bool_param;
158 bool_param.name =
"enable_odom_tf";
159 bool_param.value =
true;
161 srv_req.config.bools.push_back(bool_param);
163 EXPECT_TRUE(
ros::service::call(
"diffbot_controller/set_parameters", srv_req, srv_resp));
170 int main(
int argc,
char** argv)
172 testing::InitGoogleTest(&argc, argv);
173 ros::init(argc, argv,
"diff_drive_dyn_reconf_test");
177 int ret = RUN_ALL_TESTS();
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
TEST_F(DiffDriveControllerTest, testDynReconfServerAlive)