Skip to content

Commit

Permalink
Reduced pedantry, redundancy.
Browse files Browse the repository at this point in the history
  • Loading branch information
tappan-at-git authored and bmagyar committed Jul 4, 2017
1 parent fe9a904 commit 12b0b34
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 15 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
///////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2014, PAL Robotics S.L.
// Copyright (C) 2015, Locus Robotics Corp.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -53,12 +53,6 @@ TEST_F(DiffDriveControllerTest, testOdomTopic)
ros::Duration(0.1).sleep();
}

// zero everything before test
geometry_msgs::Twist cmd_vel;
cmd_vel.linear.x = 0.0;
cmd_vel.angular.z = 0.0;
publish(cmd_vel);
ros::Duration(0.1).sleep();
// get an odom message
nav_msgs::Odometry odom_msg = getLastOdom();
// check its frame_id
Expand Down
1 change: 0 additions & 1 deletion diff_drive_controller/test/diff_drive_odom_frame.test
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
<rosparam>
diffbot_controller:
odom_frame_id: new_odom
enable_odom_tf: True
</rosparam>

<!-- Controller test -->
Expand Down
8 changes: 1 addition & 7 deletions diff_drive_controller/test/diff_drive_odom_frame_test.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
///////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2014, PAL Robotics S.L.
// Copyright (C) 2015, Locus Robotics Corp.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -67,12 +67,6 @@ TEST_F(DiffDriveControllerTest, testOdomTopic)
ros::Duration(0.1).sleep();
}

// zero everything before test
geometry_msgs::Twist cmd_vel;
cmd_vel.linear.x = 0.0;
cmd_vel.angular.z = 0.0;
publish(cmd_vel);
ros::Duration(0.1).sleep();
// get an odom message
nav_msgs::Odometry odom_msg = getLastOdom();
// check its frame_id
Expand Down

0 comments on commit 12b0b34

Please sign in to comment.