30 #include <gtest/gtest.h>    34 #include <dynamic_reconfigure/IntParameter.h>    35 #include <dynamic_reconfigure/Reconfigure.h>    36 #include <dynamic_reconfigure/ConfigDescription.h>    38 #include <yaml-cpp/yaml.h>    44 void checkValues(
const dynamic_reconfigure::ReconfigureResponse& srv_resp, 
int int_value, 
double double_value, std::string string_value, 
bool bool_value)
    47   ASSERT_EQ(srv_resp.config.ints.size(), 1);
    48   for (
auto& value : srv_resp.config.ints)
    50     if (value.name == 
"test_int")
    52       ASSERT_EQ(value.value, int_value);
    59   ASSERT_EQ(srv_resp.config.strs.size(), 1);
    60   for (
auto& value : srv_resp.config.strs)
    62     if (value.name == 
"test_string")
    64       ASSERT_EQ(value.value, string_value);
    70   bool got_bool = 
false;
    71   ASSERT_EQ(srv_resp.config.bools.size(), 1);
    72   for (
auto& value : srv_resp.config.bools)
    74     if (value.name == 
"test_bool")
    76       ASSERT_EQ(value.value, bool_value);
    80   ASSERT_TRUE(got_bool);
    82   bool got_double = 
false;
    83   bool got_float = 
false;
    84   ASSERT_EQ(srv_resp.config.doubles.size(), 2);
    85   for (
auto& value : srv_resp.config.doubles)
    87     if (value.name == 
"test_double")
    89       ASSERT_DOUBLE_EQ(value.value, double_value);
    92     if (value.name == 
"test_float")
    97   ASSERT_TRUE(got_double);
    98   ASSERT_TRUE(got_float);
   108 TEST(DynamicParameters, testGetAndSetParams)
   111   dynamic_reconfigure::ReconfigureRequest srv_req;
   112   dynamic_reconfigure::ReconfigureResponse srv_resp;
   115       nh.
serviceClient<dynamic_reconfigure::Reconfigure>(
"/dynamic_parameters_test/set_parameters");
   118   result = client.
call(srv_req, srv_resp);
   123   dynamic_reconfigure::Config config = srv_resp.config;
   124   config.doubles[0].value = 1.0;
   125   config.ints[0].value = 2;
   126   config.strs[0].value = 
"test";
   127   config.bools[0].value = 
true;
   129   srv_req.config = config;
   130   result = client.
call(srv_req, srv_resp);
   139 TEST(DynamicParameters, testParamDescriptions)
   142   bool got_description = 
false;
   143   dynamic_reconfigure::ConfigDescription desc;
   146       "/dynamic_parameters_test/parameter_descriptions",
   148       [&got_description, &desc](
const dynamic_reconfigure::ConfigDescriptionConstPtr& 
msg) {
   149         got_description = 
true;
   161   ASSERT_TRUE(got_description);
   163   bool got_edit_method = 
false;
   164   ASSERT_EQ(desc.groups.size(), 1);
   165   for (
const auto& group : desc.groups)
   167     ASSERT_EQ(group.name, 
"Default");
   168     ASSERT_EQ(group.parameters.size(), 5);
   169     for (
const auto& 
param : group.parameters)
   171       if (
param.name == 
"test_int" && !
param.edit_method.empty())
   173         got_edit_method = 
true;
   174         YAML::Node node = YAML::Load(
param.edit_method);
   175         ASSERT_TRUE(node.IsMap());
   176         ASSERT_TRUE(node[
"enum_description"]);
   177         ASSERT_TRUE(node[
"enum"]);
   178         YAML::Node enums = node[
"enum"];
   179         ASSERT_EQ(enums.size(), 4);
   180         YAML::Node first = enums[0];
   181         ASSERT_EQ(first[
"srcline"].as<int>(), 0);
   182         ASSERT_EQ(first[
"description"].as<std::string>(), 
"Unknown");
   183         ASSERT_EQ(first[
"srcfile"].as<std::string>(), 
"dynamic_parameters.h");
   184         ASSERT_EQ(first[
"cconsttype"].as<std::string>(), 
"const int");
   185         ASSERT_EQ(first[
"value"].as<int>(), 1);
   186         ASSERT_EQ(first[
"ctype"].as<std::string>(), 
"int");
   187         ASSERT_EQ(first[
"type"].as<std::string>(), 
"int");
   188         ASSERT_EQ(first[
"name"].as<std::string>(), 
"First");
   190         ASSERT_EQ(first[
"srcline"].as<int>(), 0);
   191         ASSERT_EQ(first[
"description"].as<std::string>(), 
"Unknown");
   192         ASSERT_EQ(first[
"srcfile"].as<std::string>(), 
"dynamic_parameters.h");
   193         ASSERT_EQ(first[
"cconsttype"].as<std::string>(), 
"const int");
   194         ASSERT_EQ(first[
"value"].as<int>(), 2);
   195         ASSERT_EQ(first[
"ctype"].as<std::string>(), 
"int");
   196         ASSERT_EQ(first[
"type"].as<std::string>(), 
"int");
   197         ASSERT_EQ(first[
"name"].as<std::string>(), 
"Second");
   201   ASSERT_TRUE(got_edit_method);
   204 int main(
int argc, 
char **argv)
   206   ros::init(argc, argv, 
"dynamic_parameters_test");
   207   testing::InitGoogleTest(&argc, argv);
   210   int result = RUN_ALL_TESTS();
 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
TEST(DynamicParameters, testGetAndSetParams)
ROSCPP_DECL void shutdown()
void checkValues(const dynamic_reconfigure::ReconfigureResponse &srv_resp, int int_value, double double_value, std::string string_value, bool bool_value)
ROSCPP_DECL void spinOnce()