renamer_test.cpp
Go to the documentation of this file.
1 #include "config.h"
2 #include <gtest/gtest.h>
3 
4 #include <sensor_msgs/JointState.h>
6 
7 using namespace ros::message_traits;
8 using namespace RosIntrospection;
9 
10 /*
11 TEST(Renamer, DeserializeJointStateAndRename)
12 {
13  std::vector<SubstitutionRule> rules;
14  rules.push_back( SubstitutionRule("position.#", "name.#", "@/pos") );
15  rules.push_back( SubstitutionRule("velocity.#", "name.#", "@/vel") );
16  rules.push_back( SubstitutionRule("effort.#", "name.#", "@/eff") );
17 
18  ROSTypeList type_map = buildROSTypeMapFromDefinition(
19  DataType<sensor_msgs::JointState >::value(),
20  Definition<sensor_msgs::JointState >::value() );
21 
22  sensor_msgs::JointState joint_state;
23 
24  joint_state.header.seq = 2016;
25  joint_state.header.stamp.sec = 1234;
26  joint_state.header.stamp.nsec = 567*1000*1000;
27  joint_state.header.frame_id = "pippo";
28 
29  joint_state.name.resize( 3 );
30  joint_state.position.resize( 3 );
31  joint_state.velocity.resize( 3 );
32  joint_state.effort.resize( 3 );
33 
34  std::string names[3];
35  names[0] = ("hola");
36  names[1] = ("ciao");
37  names[2] = ("bye");
38 
39  for (int i=0; i<3; i++)
40  {
41  joint_state.name[i] = names[i];
42  joint_state.position[i]= 11+i;
43  joint_state.velocity[i]= 21+i;
44  joint_state.effort[i]= 31+i;
45  }
46 
47  std::vector<uint8_t> buffer(64*1024);
48  ros::serialization::OStream stream(buffer.data(), buffer.size());
49  ros::serialization::Serializer<sensor_msgs::JointState>::write(stream, joint_state);
50 
51  ROSType main_type( DataType<sensor_msgs::JointState >::value() );
52 
53  FlatMessage flat_container;
54 
55  buildRosFlatType(type_map, main_type, "JointState", buffer.data(), &flat_container);
56  applyNameTransform( rules, &flat_container );
57 
58  if(VERBOSE_TEST){
59  for(auto&it: renamed_value) {
60  std::cout << it.first << " >> " << it.second << std::endl;
61  }
62  }
63 
64  int i = 0;
65 
66  EXPECT_EQ( renamed_value[i].first , SString("JointState/hola/pos"));
67  EXPECT_EQ( renamed_value[i++].second, 11 );
68 
69  EXPECT_EQ( renamed_value[i].first , SString("JointState/ciao/pos"));
70  EXPECT_EQ( renamed_value[i++].second, 12 );
71 
72  EXPECT_EQ( renamed_value[i].first , SString("JointState/bye/pos"));
73  EXPECT_EQ( renamed_value[i++].second, 13 );
74 
75  EXPECT_EQ( renamed_value[i].first , SString("JointState/hola/vel"));
76  EXPECT_EQ( renamed_value[i++].second, 21 );
77 
78  EXPECT_EQ( renamed_value[i].first , SString("JointState/ciao/vel"));
79  EXPECT_EQ( renamed_value[i++].second, 22 );
80 
81  EXPECT_EQ( renamed_value[i].first , SString("JointState/bye/vel"));
82  EXPECT_EQ( renamed_value[i++].second, 23 );
83 
84  EXPECT_EQ( renamed_value[i].first , SString("JointState/hola/eff"));
85  EXPECT_EQ( renamed_value[i++].second, 31 );
86 
87  EXPECT_EQ( renamed_value[i].first , SString("JointState/ciao/eff"));
88  EXPECT_EQ( renamed_value[i++].second, 32 );
89 
90  EXPECT_EQ( renamed_value[i].first , SString("JointState/bye/eff"));
91  EXPECT_EQ( renamed_value[i++].second, 33 );
92 
93  EXPECT_EQ( renamed_value[i].first , SString("JointState/header/seq"));
94  EXPECT_EQ( renamed_value[i++].second, 2016 );
95 
96  EXPECT_EQ( renamed_value[i].first , SString("JointState/header/stamp"));
97  EXPECT_EQ( renamed_value[i++].second, 1234.567 );
98 
99 }
100 */
101 
102 TEST(Renamer2, DeserializeJointStateAndRename)
103 {
105 
106  std::vector<SubstitutionRule> rules;
107  rules.push_back( SubstitutionRule("position.#", "name.#", "@/pos") );
108  rules.push_back( SubstitutionRule("velocity.#", "name.#", "@/vel") );
109  rules.push_back( SubstitutionRule("effort.#", "name.#", "@/eff") );
110 
112 
114  "JointState", main_type,
116 
117  parser.registerRenamingRules( main_type, rules);
118 
119  sensor_msgs::JointState joint_state;
120 
121  joint_state.header.seq = 2016;
122  joint_state.header.stamp.sec = 1234;
123  joint_state.header.stamp.nsec = 567*1000*1000;
124  joint_state.header.frame_id = "pippo";
125 
126  joint_state.name.resize( 3 );
127  joint_state.position.resize( 3 );
128  joint_state.velocity.resize( 3 );
129  joint_state.effort.resize( 3 );
130 
131  std::string names[3];
132  names[0] = ("hola");
133  names[1] = ("ciao");
134  names[2] = ("bye");
135 
136  for (int i=0; i<3; i++)
137  {
138  joint_state.name[i] = names[i];
139  joint_state.position[i]= 11+i;
140  joint_state.velocity[i]= 21+i;
141  joint_state.effort[i]= 31+i;
142  }
143 
144  std::vector<uint8_t> buffer( ros::serialization::serializationLength(joint_state) );
145  ros::serialization::OStream stream(buffer.data(), buffer.size());
147 
149  RenamedValues renamed_value;
150 
151  parser.deserializeIntoFlatContainer("JointState", absl::Span<uint8_t>(buffer), &flat_container,100);
152  parser.applyNameTransform("JointState", flat_container, &renamed_value);
153 
154  if(VERBOSE_TEST)
155  {
156  std::cout << "----------------\n";
157  for(auto&it: flat_container.value) {
158  std::cout << it.first.toStdString() << " >> " << it.second.convert<double>() << std::endl;
159  }
160  std::cout << "----------------\n";
161  for(auto&it: renamed_value) {
162  std::cout << it.first << " >> " << it.second.convert<double>() << std::endl;
163  }
164  std::cout << "----------------\n";
165  }
166 
167  int i = 0;
168 
169  EXPECT_EQ( renamed_value[i].first , ("JointState/header/seq"));
170  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 2016 );
171 
172  EXPECT_EQ( renamed_value[i].first , ("JointState/header/stamp"));
173  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 1234.567 );
174 
175  EXPECT_EQ( renamed_value[i].first , ("JointState/hola/pos"));
176  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 11 );
177 
178  EXPECT_EQ( renamed_value[i].first , ("JointState/ciao/pos"));
179  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 12 );
180 
181  EXPECT_EQ( renamed_value[i].first , ("JointState/bye/pos"));
182  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 13 );
183 
184  EXPECT_EQ( renamed_value[i].first , ("JointState/hola/vel"));
185  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 21 );
186 
187  EXPECT_EQ( renamed_value[i].first , ("JointState/ciao/vel"));
188  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 22 );
189 
190  EXPECT_EQ( renamed_value[i].first , ("JointState/bye/vel"));
191  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 23 );
192 
193  EXPECT_EQ( renamed_value[i].first , ("JointState/hola/eff"));
194  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 31 );
195 
196  EXPECT_EQ( renamed_value[i].first , ("JointState/ciao/eff"));
197  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 32 );
198 
199  EXPECT_EQ( renamed_value[i].first , ("JointState/bye/eff"));
200  EXPECT_EQ( renamed_value[i++].second.convert<double>(), 33 );
201 
202 }
203 
EXPECT_EQ(flat_container.value[index].first.toStdString(),("imu/header/seq"))
static void write(Stream &stream, typename boost::call_traits< T >::param_type t)
RosIntrospection::Parser parser
void applyNameTransform(const std::string &msg_identifier, const FlatMessage &container, RenamedValues *renamed_value)
std::vector< std::pair< StringTreeLeaf, Variant > > value
#define VERBOSE_TEST
Definition: config.h:4
bool deserializeIntoFlatContainer(const std::string &msg_identifier, absl::Span< uint8_t > buffer, FlatMessage *flat_container_output, const uint32_t max_array_size) const
FlatMessage flat_container
uint32_t serializationLength(const T &t)
std::vector< std::pair< std::string, Variant > > RenamedValues
TEST(Renamer2, DeserializeJointStateAndRename)
ros::serialization::OStream stream(buffer.data(), buffer.size())
int i
std::vector< uint8_t > buffer(ros::serialization::serializationLength(imu))
void registerRenamingRules(const ROSType &type, const std::vector< SubstitutionRule > &rules)
void registerMessageDefinition(const std::string &message_identifier, const ROSType &main_type, const std::string &definition)


type_introspection_tests
Author(s): Davide Faconti
autogenerated on Fri Apr 13 2018 02:21:58