30 #ifndef TRAJECTORY_TRACKER_TEST_H
31 #define TRAJECTORY_TRACKER_TEST_H
40 #include <boost/thread.hpp>
43 #include <Eigen/Geometry>
47 #include <dynamic_reconfigure/client.h>
48 #include <geometry_msgs/Twist.h>
49 #include <nav_msgs/Odometry.h>
50 #include <nav_msgs/Path.h>
51 #include <rosgraph_msgs/Clock.h>
56 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
57 #include <trajectory_tracker_msgs/PathWithVelocity.h>
58 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
60 #include <gtest/gtest.h>
86 using ParamType = trajectory_tracker::TrajectoryTrackerConfig;
99 void cbStatus(
const trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr& msg)
103 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
108 const float dt = std::min((now -
cmd_vel_time_).toSec(), 0.1);
110 tf2::Vector3(msg->linear.x * dt, 0, 0));
119 trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr
status_;
145 for (
size_t i = 0; i < 100; ++i)
161 path.header.frame_id =
"odom";
171 status_->status != trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING)
174 <<
"trajectory_tracker status timeout, status: "
175 << (
status_ ? std::to_string(
static_cast<int>(
status_->status)) :
"none");
179 void initState(
const Eigen::Vector2d& pos,
const float yaw)
182 tf2::Vector3(pos.x(), pos.y(), 0)));
197 status_->status == trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING)
200 <<
"trajectory_tracker status timeout, status: "
201 << (
status_ ? std::to_string(
static_cast<int>(
status_->status)) :
"none");
209 path.header.frame_id =
"odom";
212 for (
const Eigen::Vector3d& p : poses)
214 const Eigen::Quaterniond q(Eigen::AngleAxisd(p[2], Eigen::Vector3d(0, 0, 1)));
216 geometry_msgs::PoseStamped pose;
217 pose.header.frame_id = path.header.frame_id;
218 pose.pose.position.x = p[0];
219 pose.pose.position.y = p[1];
220 pose.pose.orientation.x = q.x();
221 pose.pose.orientation.y = q.y();
222 pose.pose.orientation.z = q.z();
223 pose.pose.orientation.w = q.w();
225 path.poses.push_back(pose);
232 trajectory_tracker_msgs::PathWithVelocity path;
233 path.header.frame_id =
"odom";
236 for (
const Eigen::Vector4d& p : poses)
238 const Eigen::Quaterniond q(Eigen::AngleAxisd(p[2], Eigen::Vector3d(0, 0, 1)));
240 trajectory_tracker_msgs::PoseStampedWithVelocity pose;
241 pose.header.frame_id = path.header.frame_id;
242 pose.pose.position.x = p[0];
243 pose.pose.position.y = p[1];
244 pose.pose.orientation.x = q.x();
245 pose.pose.orientation.y = q.y();
246 pose.pose.orientation.z = q.z();
247 pose.pose.orientation.w = q.w();
248 pose.linear_velocity.x = p[3];
250 path.poses.push_back(pose);
261 nav_msgs::Odometry odom;
262 odom.header.frame_id =
"odom";
263 odom.header.stamp = now;
264 odom.child_frame_id =
"base_link";
268 odom.twist.twist.linear =
cmd_vel_->linear;
269 odom.twist.twist.angular =
cmd_vel_->angular;
283 if (odom.header.stamp > pub_time)
290 geometry_msgs::TransformStamped trans;
291 trans.header = odom.header;
293 trans.child_frame_id = odom.child_frame_id;
294 trans.transform.translation.x = odom.pose.pose.position.x;
295 trans.transform.translation.y = odom.pose.pose.position.y;
296 trans.transform.rotation.x = odom.pose.pose.orientation.x;
297 trans.transform.rotation.y = odom.pose.pose.orientation.y;
298 trans.transform.rotation.z = odom.pose.pose.orientation.z;
299 trans.transform.rotation.w = odom.pose.pose.orientation.w;
341 std::ostream&
operator<<(std::ostream& os,
const TrajectoryTrackerStatus::ConstPtr& msg)
349 os <<
" header: " << msg->header.stamp <<
" " << msg->header.frame_id << std::endl
350 <<
" distance_remains: " << msg->distance_remains << std::endl
351 <<
" angle_remains: " << msg->angle_remains << std::endl
352 <<
" status: " << msg->status << std::endl
353 <<
" path_header: " << msg->path_header.stamp <<
" " << msg->header.frame_id;
359 #endif // TRAJECTORY_TRACKER_TEST_H