test_trajectory_recorder.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, 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 #include <ros/ros.h>
33 #include <nav_msgs/Path.h>
34 #include <std_srvs/Empty.h>
35 
36 #include <algorithm>
37 #include <string>
38 
39 #include <gtest/gtest.h>
40 
41 TEST(TrajectoryRecorder, TfToPath)
42 {
43  ros::NodeHandle nh("");
44 
45  nav_msgs::Path::ConstPtr path;
46  int received_count = 0;
47  const boost::function<void(const nav_msgs::Path::ConstPtr&)> cb_path =
48  [&path, &received_count](const nav_msgs::Path::ConstPtr& msg) -> void
49  {
50  ++received_count;
51  path = msg;
52  };
53  ros::Subscriber sub_path = nh.subscribe("path", 1, cb_path);
55 
56  const tf2::Transform points[] =
57  {
58  tf2::Transform(tf2::Quaternion(0, 0, 0, 1), tf2::Vector3(0, 0, 0)),
59  tf2::Transform(tf2::Quaternion(0, 0, 1, 0), tf2::Vector3(2, 0, 0)),
60  tf2::Transform(tf2::Quaternion(0, 0, 0, -1), tf2::Vector3(3, 5, 0)),
61  tf2::Transform(tf2::Quaternion(0, 0, -1, 0), tf2::Vector3(-1, 5, 1))
62  };
63  const size_t len = sizeof(points) / sizeof(tf2::Transform);
64 
65  ros::Duration(1.0).sleep();
66  for (auto& p : points)
67  {
68  for (size_t i = 0; i < 3; ++i)
69  {
70  geometry_msgs::TransformStamped trans =
72  p, ros::Time::now() + ros::Duration(0.1), "map"));
73  trans.child_frame_id = "base_link";
74  tfb.sendTransform(trans);
75  ros::Duration(0.1).sleep();
76  }
77  }
78  ros::spinOnce();
79  ASSERT_TRUE(static_cast<bool>(path));
80  ASSERT_EQ(received_count, 1);
81 
82  ASSERT_EQ(path->poses.size(), len);
83  for (size_t i = 0; i < len; ++i)
84  {
85  ASSERT_EQ(path->poses[i].pose.position.x, points[i].getOrigin().x());
86  ASSERT_EQ(path->poses[i].pose.position.y, points[i].getOrigin().y());
87  ASSERT_EQ(path->poses[i].pose.position.z, points[i].getOrigin().z());
88  ASSERT_EQ(path->poses[i].pose.orientation.x, points[i].getRotation().x());
89  ASSERT_EQ(path->poses[i].pose.orientation.y, points[i].getRotation().y());
90  ASSERT_EQ(path->poses[i].pose.orientation.z, points[i].getRotation().z());
91  ASSERT_EQ(path->poses[i].pose.orientation.w, points[i].getRotation().w());
92  }
93 
94  ros::ServiceClient client = nh.serviceClient<std_srvs::Empty>("/trajectory_recorder/clear_path");
95  std_srvs::Empty empty;
96  ASSERT_TRUE(client.call(empty));
97 
98  while (received_count != 2)
99  {
100  ros::spinOnce();
101  ros::Duration(0.1).sleep();
102  }
103  ASSERT_EQ(static_cast<int>(path->poses.size()), 1);
104  ASSERT_EQ(path->poses.back().pose.position.x, points[len - 1].getOrigin().x());
105  ASSERT_EQ(path->poses.back().pose.position.y, points[len - 1].getOrigin().y());
106  ASSERT_EQ(path->poses.back().pose.position.z, points[len - 1].getOrigin().z());
107  ASSERT_EQ(path->poses.back().pose.orientation.x, points[len - 1].getRotation().x());
108  ASSERT_EQ(path->poses.back().pose.orientation.y, points[len - 1].getRotation().y());
109  ASSERT_EQ(path->poses.back().pose.orientation.z, points[len - 1].getRotation().z());
110  ASSERT_EQ(path->poses.back().pose.orientation.w, points[len - 1].getRotation().w());
111 }
112 
113 int main(int argc, char** argv)
114 {
115  testing::InitGoogleTest(&argc, argv);
116  ros::init(argc, argv, "test_trajectory_recorder");
117 
118  return RUN_ALL_TESTS();
119 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void sendTransform(const geometry_msgs::TransformStamped &transform)
B toMsg(const A &a)
int main(int argc, char **argv)
static Time now()
ROSCPP_DECL void spinOnce()
TEST(TrajectoryRecorder, TfToPath)


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:40