test_convert.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 <gtest/gtest.h>
31 
32 #include <geometry_msgs/PoseStamped.h>
33 #include <geometry_msgs/Vector3.h>
34 #include <nav_msgs/Path.h>
35 #include <trajectory_tracker_msgs/PathWithVelocity.h>
36 
38 
39 namespace
40 {
41 nav_msgs::Path generatePath()
42 {
43  nav_msgs::Path path;
44  path.header.frame_id = "frame-name";
45  path.header.stamp = ros::Time(1234.5);
46  path.poses.resize(2);
47  path.poses[0].pose.orientation.w = 1.0;
48  path.poses[0].pose.position.x = 2.0;
49  path.poses[0].pose.position.y = 3.0;
50  path.poses[1].pose.orientation.z = 4.0;
51  path.poses[1].pose.position.x = 5.0;
52  path.poses[1].pose.position.y = 6.0;
53  return path;
54 }
55 
56 geometry_msgs::Vector3 generateVector3(
57  const double x,
58  const double y,
59  const double z)
60 {
61  geometry_msgs::Vector3 vec;
62  vec.x = x;
63  vec.y = y;
64  vec.z = z;
65  return vec;
66 }
67 } // namespace
68 
69 TEST(Converter, ToPathWithVelocityScalar)
70 {
71  const nav_msgs::Path in = generatePath();
72  const trajectory_tracker_msgs::PathWithVelocity out =
74 
75  ASSERT_EQ(in.header.frame_id, out.header.frame_id);
76  ASSERT_EQ(in.header.stamp, out.header.stamp);
77  for (size_t i = 0; i < in.poses.size(); ++i)
78  {
79  ASSERT_EQ(out.poses[i].header.frame_id, in.poses[i].header.frame_id);
80  ASSERT_EQ(out.poses[i].header.stamp, in.poses[i].header.stamp);
81  ASSERT_EQ(out.poses[i].pose.position.x, in.poses[i].pose.position.x);
82  ASSERT_EQ(out.poses[i].pose.position.y, in.poses[i].pose.position.y);
83  ASSERT_EQ(out.poses[i].pose.position.z, in.poses[i].pose.position.z);
84  ASSERT_EQ(out.poses[i].pose.orientation.x, in.poses[i].pose.orientation.x);
85  ASSERT_EQ(out.poses[i].pose.orientation.y, in.poses[i].pose.orientation.y);
86  ASSERT_EQ(out.poses[i].pose.orientation.z, in.poses[i].pose.orientation.z);
87  ASSERT_EQ(out.poses[i].pose.orientation.w, in.poses[i].pose.orientation.w);
88  ASSERT_EQ(out.poses[i].linear_velocity.x, 1.23);
89  ASSERT_EQ(out.poses[i].linear_velocity.y, 0.0);
90  ASSERT_EQ(out.poses[i].linear_velocity.z, 0.0);
91  }
92 }
93 
94 TEST(Converter, ToPathWithVelocityVector)
95 {
96  const nav_msgs::Path in = generatePath();
97  const geometry_msgs::Vector3 vel = generateVector3(1.23, 0.12, 0.23);
98  const trajectory_tracker_msgs::PathWithVelocity out =
100 
101  ASSERT_EQ(in.header.frame_id, out.header.frame_id);
102  ASSERT_EQ(in.header.stamp, out.header.stamp);
103  for (size_t i = 0; i < in.poses.size(); ++i)
104  {
105  ASSERT_EQ(out.poses[i].header.frame_id, in.poses[i].header.frame_id);
106  ASSERT_EQ(out.poses[i].header.stamp, in.poses[i].header.stamp);
107  ASSERT_EQ(out.poses[i].pose.position.x, in.poses[i].pose.position.x);
108  ASSERT_EQ(out.poses[i].pose.position.y, in.poses[i].pose.position.y);
109  ASSERT_EQ(out.poses[i].pose.position.z, in.poses[i].pose.position.z);
110  ASSERT_EQ(out.poses[i].pose.orientation.x, in.poses[i].pose.orientation.x);
111  ASSERT_EQ(out.poses[i].pose.orientation.y, in.poses[i].pose.orientation.y);
112  ASSERT_EQ(out.poses[i].pose.orientation.z, in.poses[i].pose.orientation.z);
113  ASSERT_EQ(out.poses[i].pose.orientation.w, in.poses[i].pose.orientation.w);
114  ASSERT_EQ(out.poses[i].linear_velocity.x, vel.x);
115  ASSERT_EQ(out.poses[i].linear_velocity.y, vel.y);
116  ASSERT_EQ(out.poses[i].linear_velocity.z, vel.z);
117  }
118 }
119 
120 int main(int argc, char** argv)
121 {
122  testing::InitGoogleTest(&argc, argv);
123 
124  return RUN_ALL_TESTS();
125 }
int main(int argc, char **argv)
TEST(Converter, ToPathWithVelocityScalar)
PathWithVelocity toPathWithVelocity(const nav_msgs::Path &src, const double vel)
Definition: converter.h:40


trajectory_tracker_msgs
Author(s): Atsushi Watanabe
autogenerated on Fri Jun 7 2019 22:01:07