dd_client.cpp
Go to the documentation of this file.
1 //
2 // Created by Noam Dori on 01/07/18.
3 //
4 #include <ros/ros.h>
5 #include <gtest/gtest.h>
7 #include <ddynamic_reconfigure/TutorialParams.h>
8 #include <dynamic_reconfigure/Reconfigure.h>
9 
10 using namespace ros;
11 namespace ddynamic_reconfigure {
12 
16  TEST(DDFullScaleTest, doTest) { // NOLINT(cert-err58-cpp,modernize-use-equals-delete)
17  // ROS init stage
18  NodeHandle nh;
19 
20  ServiceClient dynamics = nh.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");
21  int new_int = 2, new_enum = 2;
22  double new_double = 0.2;
23  string new_string = "2";
24  bool new_bool = false;
25 
26  dynamic_reconfigure::Reconfigure srv;
27 
28  dynamic_reconfigure::IntParameter int_param;
29  int_param.name = "int_param";
30  int_param.value = new_int;
31  srv.request.config.ints.push_back(int_param);
32 
33  dynamic_reconfigure::DoubleParameter double_param;
34  double_param.name = "double_param";
35  double_param.value = new_double;
36  srv.request.config.doubles.push_back(double_param);
37 
38  dynamic_reconfigure::BoolParameter bool_param;
39  bool_param.name = "bool_param";
40  bool_param.value = (unsigned char)new_bool;
41  srv.request.config.bools.push_back(bool_param);
42 
43  dynamic_reconfigure::StrParameter str_param;
44  str_param.name = "str_param";
45  str_param.value = new_string;
46  srv.request.config.strs.push_back(str_param);
47 
48  dynamic_reconfigure::IntParameter enum_param;
49  enum_param.name = "enum_param";
50  enum_param.value = new_enum;
51  srv.request.config.ints.push_back(enum_param);
52 
53  ASSERT_TRUE(dynamics.call(srv));
54 
55  ServiceClient client = nh.serviceClient<ddynamic_reconfigure::TutorialParams>("get_params");
56  ddynamic_reconfigure::TutorialParams params;
57  ASSERT_TRUE(client.call(params));
58 
59  ASSERT_EQ(new_int,params.response.int_param);
60  ASSERT_EQ(new_double,params.response.double_param);
61  ASSERT_EQ(new_string,params.response.str_param);
62  ASSERT_EQ(new_bool,params.response.bool_param);
63  ASSERT_EQ(new_enum,params.response.enum_param);
64  }
65 }
66 
67 
68 int main(int argc, char** argv) {
69  init(argc, argv, "dd_client");
70  testing::InitGoogleTest(&argc, argv);
71 
72  srand((unsigned int)random());
73 
74  return RUN_ALL_TESTS();
75 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
Definition: dd_client.cpp:68
TEST(DDFullScaleTest, doTest)
A ROS client making sure the server sends the new information.
Definition: dd_client.cpp:16


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Thu May 16 2019 02:46:37