trajectory_tracker_test.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2020, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef TRAJECTORY_TRACKER_TEST_H
31 #define TRAJECTORY_TRACKER_TEST_H
32 
33 #include <algorithm>
34 #include <iostream>
35 #include <list>
36 #include <memory>
37 #include <string>
38 #include <vector>
39 
40 #include <boost/thread.hpp>
41 
42 #include <Eigen/Core>
43 #include <Eigen/Geometry>
44 
45 #include <ros/ros.h>
46 
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>
54 #include <tf2/utils.h>
55 
56 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
57 #include <trajectory_tracker_msgs/PathWithVelocity.h>
58 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
59 
60 #include <gtest/gtest.h>
61 
62 class TrajectoryTrackerTest : public ::testing::Test
63 {
64 private:
75 
78 
79  std::list<nav_msgs::Odometry> odom_buffer_;
80 
81 protected:
82  std_msgs::Header last_path_header_;
83  double error_lin_;
85  double error_ang_;
86  using ParamType = trajectory_tracker::TrajectoryTrackerConfig;
87  std::unique_ptr<dynamic_reconfigure::Client<ParamType>> dynamic_reconfigure_client_;
88 
89  double getYaw() const
90  {
91  return tf2::getYaw(pose_.getRotation());
92  }
93  Eigen::Vector2d getPos() const
94  {
95  return Eigen::Vector2d(pose_.getOrigin().getX(), pose_.getOrigin().getY());
96  }
97 
98 private:
99  void cbStatus(const trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr& msg)
100  {
101  status_ = msg;
102  }
103  void cbCmdVel(const geometry_msgs::Twist::ConstPtr& msg)
104  {
105  const ros::Time now = ros::Time::now();
106  if (cmd_vel_time_ == ros::Time(0))
107  cmd_vel_time_ = now;
108  const float dt = std::min((now - cmd_vel_time_).toSec(), 0.1);
109  const tf2::Transform pose_diff(tf2::Quaternion(tf2::Vector3(0, 0, 1), msg->angular.z * dt),
110  tf2::Vector3(msg->linear.x * dt, 0, 0));
111  pose_ *= pose_diff;
112  cmd_vel_time_ = now;
113  cmd_vel_ = msg;
114  ++cmd_vel_count_;
115  }
116 
117 public:
119  trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr status_;
120  geometry_msgs::Twist::ConstPtr cmd_vel_;
122 
124  : nh_("")
125  , pnh_("~")
126  {
128  "cmd_vel", 1, &TrajectoryTrackerTest::cbCmdVel, this);
130  "trajectory_tracker/status", 1, &TrajectoryTrackerTest::cbStatus, this);
131  pub_path_ = nh_.advertise<nav_msgs::Path>("path", 1, true);
132  pub_path_vel_ = nh_.advertise<trajectory_tracker_msgs::PathWithVelocity>("path_velocity", 1, true);
133  pub_odom_ = nh_.advertise<nav_msgs::Odometry>("odom", 10, true);
134 
135  double delay;
136  pnh_.param("odom_delay", delay, 0.0);
137  delay_ = ros::Duration(delay);
138  pnh_.param("error_lin", error_lin_, 0.01);
139  pnh_.param("error_large_lin", error_large_lin_, 0.1);
140  pnh_.param("error_ang", error_ang_, 0.01);
141 
142  dynamic_reconfigure_client_.reset(new dynamic_reconfigure::Client<ParamType>("/trajectory_tracker"));
143 
144  ros::Rate wait(10);
145  for (size_t i = 0; i < 100; ++i)
146  {
147  wait.sleep();
148  ros::spinOnce();
149  if (pub_path_.getNumSubscribers() > 0)
150  break;
151  }
152  }
153  void initState(const tf2::Transform& pose)
154  {
155  // Wait trajectory_tracker node
156  ros::Rate rate(10);
157  const auto start = ros::WallTime::now();
158  while (ros::ok())
159  {
160  nav_msgs::Path path;
161  path.header.frame_id = "odom";
162  path.header.stamp = ros::Time::now();
163  pub_path_.publish(path);
164 
165  pose_ = pose;
167 
168  rate.sleep();
169  ros::spinOnce();
170  if (status_ &&
171  status_->status != trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING)
172  break;
173  ASSERT_LT(ros::WallTime::now(), start + ros::WallDuration(10.0))
174  << "trajectory_tracker status timeout, status: "
175  << (status_ ? std::to_string(static_cast<int>(status_->status)) : "none");
176  }
177  ros::Duration(0.5).sleep();
178  }
179  void initState(const Eigen::Vector2d& pos, const float yaw)
180  {
181  initState(tf2::Transform(tf2::Quaternion(tf2::Vector3(0, 0, 1), yaw),
182  tf2::Vector3(pos.x(), pos.y(), 0)));
183  }
184  void waitUntilStart(const std::function<void()> func = nullptr)
185  {
186  ros::Rate rate(50);
187  const auto start = ros::WallTime::now();
188  while (ros::ok())
189  {
190  if (func)
191  func();
192 
194  rate.sleep();
195  ros::spinOnce();
196  if (status_ &&
197  status_->status == trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING)
198  break;
199  ASSERT_LT(ros::WallTime::now(), start + ros::WallDuration(10.0))
200  << "trajectory_tracker status timeout, status: "
201  << (status_ ? std::to_string(static_cast<int>(status_->status)) : "none");
202  }
204  cmd_vel_count_ = 0;
205  }
206  void publishPath(const std::vector<Eigen::Vector3d>& poses)
207  {
208  nav_msgs::Path path;
209  path.header.frame_id = "odom";
210  path.header.stamp = ros::Time::now();
211 
212  for (const Eigen::Vector3d& p : poses)
213  {
214  const Eigen::Quaterniond q(Eigen::AngleAxisd(p[2], Eigen::Vector3d(0, 0, 1)));
215 
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();
224 
225  path.poses.push_back(pose);
226  }
227  pub_path_.publish(path);
228  last_path_header_ = path.header;
229  }
230  void publishPathVelocity(const std::vector<Eigen::Vector4d>& poses)
231  {
232  trajectory_tracker_msgs::PathWithVelocity path;
233  path.header.frame_id = "odom";
234  path.header.stamp = ros::Time::now();
235 
236  for (const Eigen::Vector4d& p : poses)
237  {
238  const Eigen::Quaterniond q(Eigen::AngleAxisd(p[2], Eigen::Vector3d(0, 0, 1)));
239 
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];
249 
250  path.poses.push_back(pose);
251  }
252  // needs sleep to prevent that the empty path from initState arrives later.
253  ros::Duration(0.5).sleep();
254  pub_path_vel_.publish(path);
255  last_path_header_ = path.header;
256  }
258  {
259  const ros::Time now = ros::Time::now();
260 
261  nav_msgs::Odometry odom;
262  odom.header.frame_id = "odom";
263  odom.header.stamp = now;
264  odom.child_frame_id = "base_link";
265  tf2::toMsg(pose_, odom.pose.pose);
266  if (cmd_vel_)
267  {
268  odom.twist.twist.linear = cmd_vel_->linear;
269  odom.twist.twist.angular = cmd_vel_->angular;
270  }
271  publishTransform(odom);
272  }
273 
274  void publishTransform(const nav_msgs::Odometry& odom)
275  {
276  odom_buffer_.push_back(odom);
277 
278  const ros::Time pub_time = odom.header.stamp - delay_;
279 
280  while (odom_buffer_.size() > 0)
281  {
282  nav_msgs::Odometry odom = odom_buffer_.front();
283  if (odom.header.stamp > pub_time)
284  break;
285 
286  odom_buffer_.pop_front();
287 
288  if (odom.header.stamp != trans_stamp_last_)
289  {
290  geometry_msgs::TransformStamped trans;
291  trans.header = odom.header;
292  trans.header.stamp += ros::Duration(0.1);
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;
300 
301  tfb_.sendTransform(trans);
302  pub_odom_.publish(odom);
303  }
304  trans_stamp_last_ = odom.header.stamp;
305  }
306  }
307 
308  double getCmdVelFrameRate() const
309  {
311  }
312 
313  bool getConfig(ParamType& config) const
314  {
315  const ros::WallTime time_limit = ros::WallTime::now() + ros::WallDuration(10.0);
316  while (time_limit > ros::WallTime::now())
317  {
318  if (dynamic_reconfigure_client_->getCurrentConfiguration(config, ros::Duration(0.1)))
319  {
320  return true;
321  }
322  ros::spinOnce();
323  }
324  return false;
325  }
326 
327  bool setConfig(const ParamType& config)
328  {
329  // Wait until parameter server becomes ready
330  ParamType dummy;
331  if (!getConfig(dummy))
332  {
333  return false;
334  }
335  return dynamic_reconfigure_client_->setConfiguration(config);
336  }
337 };
338 
339 namespace trajectory_tracker_msgs
340 {
341 std::ostream& operator<<(std::ostream& os, const TrajectoryTrackerStatus::ConstPtr& msg)
342 {
343  if (!msg)
344  {
345  os << "nullptr";
346  }
347  else
348  {
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;
354  }
355  return os;
356 }
357 } // namespace trajectory_tracker_msgs
358 
359 #endif // TRAJECTORY_TRACKER_TEST_H
TrajectoryTrackerTest::TrajectoryTrackerTest
TrajectoryTrackerTest()
Definition: trajectory_tracker_test.h:123
trajectory_tracker_msgs::operator<<
std::ostream & operator<<(std::ostream &os, const TrajectoryTrackerStatus::ConstPtr &msg)
Definition: trajectory_tracker_test.h:341
TrajectoryTrackerTest::sub_status_
ros::Subscriber sub_status_
Definition: trajectory_tracker_test.h:68
ros::Publisher
TrajectoryTrackerTest::publishTransform
void publishTransform(const nav_msgs::Odometry &odom)
Definition: trajectory_tracker_test.h:274
TrajectoryTrackerTest::ParamType
trajectory_tracker::TrajectoryTrackerConfig ParamType
Definition: trajectory_tracker_test.h:86
TrajectoryTrackerTest::getYaw
double getYaw() const
Definition: trajectory_tracker_test.h:89
tf2::getYaw
double getYaw(const A &a)
utils.h
ros.h
TrajectoryTrackerTest::initState
void initState(const Eigen::Vector2d &pos, const float yaw)
Definition: trajectory_tracker_test.h:179
TrajectoryTrackerTest::cmd_vel_count_
int cmd_vel_count_
Definition: trajectory_tracker_test.h:77
TrajectoryTrackerTest::publishPathVelocity
void publishPathVelocity(const std::vector< Eigen::Vector4d > &poses)
Definition: trajectory_tracker_test.h:230
TrajectoryTrackerTest::publishTransform
void publishTransform()
Definition: trajectory_tracker_test.h:257
ros::spinOnce
ROSCPP_DECL void spinOnce()
TrajectoryTrackerTest::initial_cmd_vel_time_
ros::Time initial_cmd_vel_time_
Definition: trajectory_tracker_test.h:76
tf2::Transform::getOrigin
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
wait
void wait(int seconds)
TrajectoryTrackerTest::setConfig
bool setConfig(const ParamType &config)
Definition: trajectory_tracker_test.h:327
TrajectoryTrackerTest::cbStatus
void cbStatus(const trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr &msg)
Definition: trajectory_tracker_test.h:99
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
TrajectoryTrackerTest::pub_odom_
ros::Publisher pub_odom_
Definition: trajectory_tracker_test.h:71
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
transform_broadcaster.h
TrajectoryTrackerTest::dynamic_reconfigure_client_
std::unique_ptr< dynamic_reconfigure::Client< ParamType > > dynamic_reconfigure_client_
Definition: trajectory_tracker_test.h:87
TrajectoryTrackerTest::status_
trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr status_
Definition: trajectory_tracker_test.h:119
TrajectoryTrackerTest::cmd_vel_time_
ros::Time cmd_vel_time_
Definition: trajectory_tracker_test.h:73
TrajectoryTrackerTest::cbCmdVel
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
Definition: trajectory_tracker_test.h:103
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
TrajectoryTrackerTest::getCmdVelFrameRate
double getCmdVelFrameRate() const
Definition: trajectory_tracker_test.h:308
TrajectoryTrackerTest::error_lin_
double error_lin_
Definition: trajectory_tracker_test.h:83
TrajectoryTrackerTest::pub_path_vel_
ros::Publisher pub_path_vel_
Definition: trajectory_tracker_test.h:70
TrajectoryTrackerTest::error_ang_
double error_ang_
Definition: trajectory_tracker_test.h:85
ros::WallTime::now
static WallTime now()
TrajectoryTrackerTest::initState
void initState(const tf2::Transform &pose)
Definition: trajectory_tracker_test.h:153
TrajectoryTrackerTest::sub_cmd_vel_
ros::Subscriber sub_cmd_vel_
Definition: trajectory_tracker_test.h:67
tf2::Transform
tf2::Transform::getRotation
Quaternion getRotation() const
TrajectoryTrackerTest::trans_stamp_last_
ros::Time trans_stamp_last_
Definition: trajectory_tracker_test.h:74
TrajectoryTrackerTest::delay_
ros::Duration delay_
Definition: trajectory_tracker_test.h:121
TrajectoryTrackerTest::nh_
ros::NodeHandle nh_
Definition: trajectory_tracker_test.h:65
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::WallTime
ros::Rate::sleep
bool sleep()
TrajectoryTrackerTest::tfb_
tf2_ros::TransformBroadcaster tfb_
Definition: trajectory_tracker_test.h:72
TrajectoryTrackerTest::error_large_lin_
double error_large_lin_
Definition: trajectory_tracker_test.h:84
start
ROSCPP_DECL void start()
TrajectoryTrackerTest::pnh_
ros::NodeHandle pnh_
Definition: trajectory_tracker_test.h:66
ros::Time
TrajectoryTrackerTest::getConfig
bool getConfig(ParamType &config) const
Definition: trajectory_tracker_test.h:313
TrajectoryTrackerTest::last_path_header_
std_msgs::Header last_path_header_
Definition: trajectory_tracker_test.h:82
tf2_ros::TransformBroadcaster
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
ros::Rate
ros::Duration::sleep
bool sleep() const
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
TrajectoryTrackerTest::pub_path_
ros::Publisher pub_path_
Definition: trajectory_tracker_test.h:69
ros::WallDuration
TrajectoryTrackerTest
Definition: trajectory_tracker_test.h:62
TrajectoryTrackerTest::odom_buffer_
std::list< nav_msgs::Odometry > odom_buffer_
Definition: trajectory_tracker_test.h:79
TrajectoryTrackerTest::waitUntilStart
void waitUntilStart(const std::function< void()> func=nullptr)
Definition: trajectory_tracker_test.h:184
TrajectoryTrackerTest::pose_
tf2::Transform pose_
Definition: trajectory_tracker_test.h:118
ros::Duration
trajectory_tracker_msgs
TrajectoryTrackerTest::getPos
Eigen::Vector2d getPos() const
Definition: trajectory_tracker_test.h:93
ros::NodeHandle
ros::Subscriber
TrajectoryTrackerTest::publishPath
void publishPath(const std::vector< Eigen::Vector3d > &poses)
Definition: trajectory_tracker_test.h:206
ros::Time::now
static Time now()
TrajectoryTrackerTest::cmd_vel_
geometry_msgs::Twist::ConstPtr cmd_vel_
Definition: trajectory_tracker_test.h:120


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Wed Mar 19 2025 02:14:15