Skip to content

Commit 45ba7b2

Browse files
committed
Fixing some tests with Ignition::msgs::Pose.
1 parent 7fef104 commit 45ba7b2

File tree

2 files changed

+19
-10
lines changed

2 files changed

+19
-10
lines changed

test/publishers/ros1_publisher.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ int main(int argc, char ** argv)
8484

8585
// geometry_msgs::TransformStamped.
8686
ros::Publisher transform_stamped_pub =
87-
n.advertise<geometry_msgs::TransformStamped>("transform_stampted", 1000);
87+
n.advertise<geometry_msgs::TransformStamped>("transform_stamped", 1000);
8888
geometry_msgs::TransformStamped transform_stamped_msg;
8989
ros1_ign_bridge::testing::createTestMsg(transform_stamped_msg);
9090

test/test_utils.h

Lines changed: 18 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -539,15 +539,24 @@ namespace testing
539539
/// \param[in] _msg The message to compare.
540540
void compareTestMsg(const ignition::msgs::Pose &_msg)
541541
{
542-
compareTestMsg(_msg.header());
543-
544-
ignition::msgs::Pose expected_msg;
545-
createTestMsg(expected_msg);
546-
// child_frame_id
547-
EXPECT_EQ(expected_msg.header().data(2).key(), _msg.header().data(2).key());
548-
EXPECT_EQ(1, _msg.header().data(2).value_size());
549-
EXPECT_EQ(expected_msg.header().data(2).value(0),
550-
_msg.header().data(2).value(0));
542+
if (_msg.header().data_size() > 0)
543+
{
544+
compareTestMsg(_msg.header());
545+
546+
ignition::msgs::Pose expected_msg;
547+
createTestMsg(expected_msg);
548+
549+
if (_msg.header().data_size() > 2)
550+
{
551+
// child_frame_id
552+
ASSERT_EQ(3, expected_msg.header().data_size());
553+
ASSERT_EQ(3, _msg.header().data_size());
554+
EXPECT_EQ(expected_msg.header().data(2).key(), _msg.header().data(2).key());
555+
EXPECT_EQ(1, _msg.header().data(2).value_size());
556+
EXPECT_EQ(expected_msg.header().data(2).value(0),
557+
_msg.header().data(2).value(0));
558+
}
559+
}
551560

552561
compareTestMsg(_msg.position());
553562
compareTestMsg(_msg.orientation());

0 commit comments

Comments
 (0)