Skip to content

Commit

Permalink
Fixing some tests with Ignition::msgs::Pose.
Browse files Browse the repository at this point in the history
  • Loading branch information
caguero committed Mar 20, 2019
1 parent 7fef104 commit 45ba7b2
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 10 deletions.
2 changes: 1 addition & 1 deletion test/publishers/ros1_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ int main(int argc, char ** argv)

// geometry_msgs::TransformStamped.
ros::Publisher transform_stamped_pub =
n.advertise<geometry_msgs::TransformStamped>("transform_stampted", 1000);
n.advertise<geometry_msgs::TransformStamped>("transform_stamped", 1000);
geometry_msgs::TransformStamped transform_stamped_msg;
ros1_ign_bridge::testing::createTestMsg(transform_stamped_msg);

Expand Down
27 changes: 18 additions & 9 deletions test/test_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -539,15 +539,24 @@ namespace testing
/// \param[in] _msg The message to compare.
void compareTestMsg(const ignition::msgs::Pose &_msg)
{
compareTestMsg(_msg.header());

ignition::msgs::Pose expected_msg;
createTestMsg(expected_msg);
// child_frame_id
EXPECT_EQ(expected_msg.header().data(2).key(), _msg.header().data(2).key());
EXPECT_EQ(1, _msg.header().data(2).value_size());
EXPECT_EQ(expected_msg.header().data(2).value(0),
_msg.header().data(2).value(0));
if (_msg.header().data_size() > 0)
{
compareTestMsg(_msg.header());

ignition::msgs::Pose expected_msg;
createTestMsg(expected_msg);

if (_msg.header().data_size() > 2)
{
// child_frame_id
ASSERT_EQ(3, expected_msg.header().data_size());
ASSERT_EQ(3, _msg.header().data_size());
EXPECT_EQ(expected_msg.header().data(2).key(), _msg.header().data(2).key());
EXPECT_EQ(1, _msg.header().data(2).value_size());
EXPECT_EQ(expected_msg.header().data(2).value(0),
_msg.header().data(2).value(0));
}
}

compareTestMsg(_msg.position());
compareTestMsg(_msg.orientation());
Expand Down

0 comments on commit 45ba7b2

Please sign in to comment.