Skip to content

Commit 3c4f5d7

Browse files
committed
Reduced pedantry, redundancy.
1 parent e451b87 commit 3c4f5d7

File tree

3 files changed

+2
-15
lines changed

3 files changed

+2
-15
lines changed

diff_drive_controller/test/diff_drive_default_odom_frame_test.cpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
///////////////////////////////////////////////////////////////////////////////
2-
// Copyright (C) 2014, PAL Robotics S.L.
2+
// Copyright (C) 2015, Locus Robotics Corp.
33
//
44
// Redistribution and use in source and binary forms, with or without
55
// modification, are permitted provided that the following conditions are met:
@@ -53,12 +53,6 @@ TEST_F(DiffDriveControllerTest, testOdomTopic)
5353
ros::Duration(0.1).sleep();
5454
}
5555

56-
// zero everything before test
57-
geometry_msgs::Twist cmd_vel;
58-
cmd_vel.linear.x = 0.0;
59-
cmd_vel.angular.z = 0.0;
60-
publish(cmd_vel);
61-
ros::Duration(0.1).sleep();
6256
// get an odom message
6357
nav_msgs::Odometry odom_msg = getLastOdom();
6458
// check its frame_id

diff_drive_controller/test/diff_drive_odom_frame.test

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
<rosparam>
77
diffbot_controller:
88
odom_frame_id: new_odom
9-
enable_odom_tf: True
109
</rosparam>
1110

1211
<!-- Controller test -->

diff_drive_controller/test/diff_drive_odom_frame_test.cpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
///////////////////////////////////////////////////////////////////////////////
2-
// Copyright (C) 2014, PAL Robotics S.L.
2+
// Copyright (C) 2015, Locus Robotics Corp.
33
//
44
// Redistribution and use in source and binary forms, with or without
55
// modification, are permitted provided that the following conditions are met:
@@ -67,12 +67,6 @@ TEST_F(DiffDriveControllerTest, testOdomTopic)
6767
ros::Duration(0.1).sleep();
6868
}
6969

70-
// zero everything before test
71-
geometry_msgs::Twist cmd_vel;
72-
cmd_vel.linear.x = 0.0;
73-
cmd_vel.angular.z = 0.0;
74-
publish(cmd_vel);
75-
ros::Duration(0.1).sleep();
7670
// get an odom message
7771
nav_msgs::Odometry odom_msg = getLastOdom();
7872
// check its frame_id

0 commit comments

Comments
 (0)