2 #include <gmock/gmock.h> 4 #include <dynamic_reconfigure/Reconfigure.h> 8 using ::testing::Exactly;
17 MockClass() : double_param_(0.0), int_param_(0), bool_param_(false)
20 MOCK_METHOD0(userCallback,
void());
22 MOCK_METHOD1(strCallback,
void(std::string));
24 MOCK_METHOD1(doubleCallback,
void(
double));
26 MOCK_METHOD1(intCallback,
void(
int));
28 MOCK_METHOD1(boolCallback,
void(
bool));
39 void cfgCb(
const dynamic_reconfigure::ConfigConstPtr& msg)
47 while (!cfg_msg_.get() &&
ros::ok())
67 dynamic_reconfigure::Reconfigure srv;
68 dynamic_reconfigure::IntParameter int_param;
69 int_param.name =
"int_param";
70 int_param.value = 1234;
72 srv.request.config.ints.push_back(int_param);
92 dynamic_reconfigure::Reconfigure srv;
93 dynamic_reconfigure::IntParameter int_param;
94 int_param.name =
"int_param";
95 int_param.value = 1234;
97 srv.request.config.ints.push_back(int_param);
103 auto config = std::async([&nh, &srv]() {
112 srv.request.config.ints.back().value = 3214;
113 config = std::async([&nh, &srv]() {
119 EXPECT_EQ(mock.
int_param_, srv.request.config.ints.back().value);
137 EXPECT_CALL(mock, userCallback()).Times(Exactly(1));
139 dynamic_reconfigure::Reconfigure srv;
140 dynamic_reconfigure::IntParameter int_param;
141 int_param.name =
"int_param";
142 int_param.value = -1234;
143 srv.request.config.ints.push_back(int_param);
145 dynamic_reconfigure::BoolParameter bool_param;
146 bool_param.name =
"bool_param";
147 bool_param.value =
true;
148 srv.request.config.bools.push_back(bool_param);
150 dynamic_reconfigure::DoubleParameter double_param;
151 double_param.name =
"double_param";
152 double_param.value = 42.4242;
153 srv.request.config.doubles.push_back(double_param);
170 boost::bind(&MockClass::intCallback, &mock, _1));
172 boost::bind(&MockClass::doubleCallback, &mock, _1));
174 boost::bind(&MockClass::boolCallback, &mock, _1));
176 boost::bind(&MockClass::strCallback, &mock, _1));
181 dynamic_reconfigure::Reconfigure srv;
182 dynamic_reconfigure::IntParameter int_param;
183 int_param.name =
"int_param";
184 int_param.value = -1234;
186 dynamic_reconfigure::DoubleParameter double_param;
187 double_param.name =
"double_param";
188 double_param.value = 42.4242;
190 dynamic_reconfigure::StrParameter str_param;
191 str_param.name =
"str_param";
192 str_param.value =
"hello";
194 EXPECT_CALL(mock, intCallback(int_param.value)).Times(Exactly(2));
195 EXPECT_CALL(mock, doubleCallback(double_param.value)).Times(Exactly(1));
196 EXPECT_CALL(mock, boolCallback(_)).Times(Exactly(0));
197 EXPECT_CALL(mock, strCallback(
"hello")).Times(Exactly(1));
199 srv.request.config.ints.push_back(int_param);
203 srv.request.config.doubles.push_back(double_param);
204 srv.request.config.strs.push_back(str_param);
215 boost::bind(&MockClass::intCallback, &mock, _1));
217 boost::bind(&MockClass::doubleCallback, &mock, _1));
219 boost::bind(&MockClass::boolCallback, &mock, _1));
221 boost::bind(&MockClass::strCallback, &mock, _1));
226 dynamic_reconfigure::Reconfigure srv;
227 dynamic_reconfigure::IntParameter int_param;
228 int_param.name =
"int_param";
229 int_param.value = -1234;
231 dynamic_reconfigure::DoubleParameter double_param;
232 double_param.name =
"double_param";
233 double_param.value = 42.4242;
235 dynamic_reconfigure::StrParameter str_param;
236 str_param.name =
"str_param";
237 str_param.value =
"hello";
239 EXPECT_CALL(mock, intCallback(int_param.value)).Times(Exactly(2));
240 EXPECT_CALL(mock, doubleCallback(double_param.value)).Times(Exactly(1));
241 EXPECT_CALL(mock, boolCallback(_)).Times(Exactly(0));
242 EXPECT_CALL(mock, strCallback(
"hello")).Times(Exactly(1));
244 srv.request.config.ints.push_back(int_param);
248 srv.request.config.doubles.push_back(double_param);
249 srv.request.config.strs.push_back(str_param);
261 double double_param = 1.0;
262 std::string str_param =
"";
263 std::string second_str_param =
"";
264 bool bool_param =
false;
273 "/foo/parameter_updates", 1, boost::bind(&DDynamicReconfigureTest::cfgCb,
this, _1));
277 ASSERT_EQ(1, cfg_msg_->ints.size());
278 ASSERT_EQ(
"int_param", cfg_msg_->ints[0].name);
279 ASSERT_EQ(int_param, cfg_msg_->ints[0].value);
280 ASSERT_EQ(1, cfg_msg_->doubles.size());
281 ASSERT_EQ(
"double_param", cfg_msg_->doubles[0].name);
282 ASSERT_EQ(double_param, cfg_msg_->doubles[0].value);
283 ASSERT_EQ(2, cfg_msg_->strs.size());
284 ASSERT_EQ(
"str_param", cfg_msg_->strs[0].name);
285 ASSERT_EQ(str_param, cfg_msg_->strs[0].value);
287 ASSERT_EQ(
"second_str_param", cfg_msg_->strs[1].name);
288 ASSERT_EQ(second_str_param, cfg_msg_->strs[1].value);
289 ASSERT_EQ(1, cfg_msg_->bools.size());
290 ASSERT_EQ(
"bool_param", cfg_msg_->bools[0].name);
291 ASSERT_EQ(bool_param, cfg_msg_->bools[0].value);
295 str_param =
"changed";
299 ASSERT_EQ(1, cfg_msg_->ints.size());
300 ASSERT_EQ(
"int_param", cfg_msg_->ints[0].name);
301 ASSERT_EQ(int_param, cfg_msg_->ints[0].value);
302 ASSERT_EQ(1, cfg_msg_->doubles.size());
303 ASSERT_EQ(
"double_param", cfg_msg_->doubles[0].name);
304 ASSERT_EQ(double_param, cfg_msg_->doubles[0].value);
305 ASSERT_EQ(2, cfg_msg_->strs.size());
306 ASSERT_EQ(
"str_param", cfg_msg_->strs[0].name);
307 ASSERT_EQ(str_param, cfg_msg_->strs[0].value);
309 ASSERT_EQ(
"second_str_param", cfg_msg_->strs[1].name);
310 ASSERT_EQ(second_str_param, cfg_msg_->strs[1].value);
311 ASSERT_EQ(1, cfg_msg_->bools.size());
312 ASSERT_EQ(
"bool_param", cfg_msg_->bools[0].name);
313 ASSERT_EQ(bool_param, cfg_msg_->bools[0].value);
318 int main(
int argc,
char** argv)
320 testing::InitGoogleTest(&argc, argv);
321 ros::init(argc, argv,
"ddynamic_reconfigure_test");
324 ::testing::InitGoogleMock(&argc, argv);
326 return RUN_ALL_TESTS();
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TEST_F(DDynamicReconfigureTest, threadTest)
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)
const std::string & getNamespace() const