Skip to content

Commit

Permalink
[diff_drive] The test is also always true when evaluating cmd_vel_out
Browse files Browse the repository at this point in the history
  • Loading branch information
Vincent Rousseau committed Dec 7, 2017
1 parent a10ecdf commit 4722964
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 2 deletions.
6 changes: 6 additions & 0 deletions diff_drive_controller/test/diff_drive_controller_nan.test
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,18 @@
<!-- Load common test stuff -->
<include file="$(find diff_drive_controller)/test/diff_drive_common.launch" />

<rosparam>
diffbot_controller:
publish_cmd: True
</rosparam>

<!-- Controller test -->
<test test-name="diff_drive_nan_test"
pkg="diff_drive_controller"
type="diff_drive_nan_test"
time-limit="80.0">
<remap from="cmd_vel" to="diffbot_controller/cmd_vel" />
<remap from="odom" to="diffbot_controller/odom" />
<remap from="cmd_vel_out" to="diffbot_controller/cmd_vel_out" />
</test>
</launch>
8 changes: 6 additions & 2 deletions diff_drive_controller/test/diff_drive_nan_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,8 @@ TEST_F(DiffDriveControllerTest, testNaNCmd)
cmd_vel.linear.x = NAN;
cmd_vel.angular.z = 0.0;
publish(cmd_vel);
nav_msgs::Odometry odom = getLastOdom();
ROS_INFO_STREAM("odom.twist.twist.linear.x "<<odom.twist.twist.linear.x);
geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
ROS_INFO_STREAM("cmd_vel_out.twist.linear.x "<<odom_msg.twist.linear.x);
ros::Duration(0.1).sleep();
}

Expand All @@ -109,6 +109,10 @@ TEST_F(DiffDriveControllerTest, testNaNCmd)
EXPECT_EQ(odom.twist.twist.linear.x, 0.0);
EXPECT_EQ(odom.pose.pose.position.x, 0.0);
EXPECT_EQ(odom.pose.pose.position.y, 0.0);

geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();

EXPECT_EQ(fabs(odom_msg.twist.linear.x), 0);
}

int main(int argc, char** argv)
Expand Down

0 comments on commit 4722964

Please # to comment.