33 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
35 #include <dynamic_reconfigure/client.h>
40 void runTest(
const double goal_tolerance_lin_vel,
const double goal_tolerance_ang_vel,
41 const double linear_vel,
const double rotation_vel,
const int32_t expected_status)
45 std::vector<Eigen::Vector3d> poses;
46 for (
double x = 0.0; x < 0.5; x += 0.01)
47 poses.push_back(Eigen::Vector3d(x, 0.0, 0.0));
48 poses.push_back(Eigen::Vector3d(0.5, 0.0, 0.0));
53 param.goal_tolerance_lin_vel = goal_tolerance_lin_vel;
54 param.goal_tolerance_ang_vel = goal_tolerance_ang_vel;
57 nav_msgs::Odometry odom;
58 odom.header.frame_id =
"odom";
59 odom.child_frame_id =
"base_link";
60 odom.pose.pose.position.x = 0.5;
61 odom.pose.pose.position.y = 0.0;
62 odom.pose.pose.position.z = 0.0;
63 odom.pose.pose.orientation.x = 0.0;
64 odom.pose.pose.orientation.y = 0.0;
65 odom.pose.pose.orientation.z = 0.0;
66 odom.pose.pose.orientation.w = 1.0;
67 odom.twist.twist.linear.x = linear_vel;
68 odom.twist.twist.linear.y = 0.0;
69 odom.twist.twist.linear.z = 0.0;
70 odom.twist.twist.angular.x = 0.0;
71 odom.twist.twist.angular.y = 0.0;
72 odom.twist.twist.angular.z = rotation_vel;
88 FAIL() <<
"Expected status: " << expected_status <<
" Actual status: " <<
status_->status;
94 SCOPED_TRACE(
"NoVelocityToleranceWithRemainingLinearVel");
95 runTest(0.0, 0.0, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
100 SCOPED_TRACE(
"NoVelocityToleranceWithRemainingAngularVel");
101 runTest(0.0, 0.0, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
106 SCOPED_TRACE(
"LinearVelocityToleranceWithRemainingLinearVel");
107 runTest(0.05, 0.0, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
112 SCOPED_TRACE(
"LinearVelocityToleranceWithRemainingAngularVel");
113 runTest(0.05, 0.0, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
118 SCOPED_TRACE(
"AngularrVelocityToleranceWithRemainingLinearVel");
119 runTest(0.0, 0.05, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
124 SCOPED_TRACE(
"AngularrVelocityToleranceWithRemainingAngularVel");
125 runTest(0.0, 0.05, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
128 int main(
int argc,
char** argv)
130 testing::InitGoogleTest(&argc, argv);
131 ros::init(argc, argv,
"test_trajectory_tracker_overshoot");
133 return RUN_ALL_TESTS();