2 #include <gtest/gtest.h> 4 #include <sensor_msgs/JointState.h> 102 TEST(Renamer2, DeserializeJointStateAndRename)
106 std::vector<SubstitutionRule> rules;
114 "JointState", main_type,
119 sensor_msgs::JointState joint_state;
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";
126 joint_state.name.resize( 3 );
127 joint_state.position.resize( 3 );
128 joint_state.velocity.resize( 3 );
129 joint_state.effort.resize( 3 );
131 std::string names[3];
136 for (
int i=0;
i<3;
i++)
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;
156 std::cout <<
"----------------\n";
157 for(
auto&it: flat_container.
value) {
158 std::cout << it.first.toStdString() <<
" >> " << it.second.convert<
double>() << std::endl;
160 std::cout <<
"----------------\n";
161 for(
auto&it: renamed_value) {
162 std::cout << it.first <<
" >> " << it.second.convert<
double>() << std::endl;
164 std::cout <<
"----------------\n";
169 EXPECT_EQ( renamed_value[i].first , (
"JointState/header/seq"));
170 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 2016 );
172 EXPECT_EQ( renamed_value[i].first , (
"JointState/header/stamp"));
173 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 1234.567 );
175 EXPECT_EQ( renamed_value[i].first , (
"JointState/hola/pos"));
176 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 11 );
178 EXPECT_EQ( renamed_value[i].first , (
"JointState/ciao/pos"));
179 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 12 );
181 EXPECT_EQ( renamed_value[i].first , (
"JointState/bye/pos"));
182 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 13 );
184 EXPECT_EQ( renamed_value[i].first , (
"JointState/hola/vel"));
185 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 21 );
187 EXPECT_EQ( renamed_value[i].first , (
"JointState/ciao/vel"));
188 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 22 );
190 EXPECT_EQ( renamed_value[i].first , (
"JointState/bye/vel"));
191 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 23 );
193 EXPECT_EQ( renamed_value[i].first , (
"JointState/hola/eff"));
194 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 31 );
196 EXPECT_EQ( renamed_value[i].first , (
"JointState/ciao/eff"));
197 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 32 );
199 EXPECT_EQ( renamed_value[i].first , (
"JointState/bye/eff"));
200 EXPECT_EQ( renamed_value[i++].second.convert<
double>(), 33 );
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
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())
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)