30 #include <gtest/gtest.h> 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> 41 nav_msgs::Path generatePath()
44 path.header.frame_id =
"frame-name";
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;
56 geometry_msgs::Vector3 generateVector3(
61 geometry_msgs::Vector3 vec;
69 TEST(Converter, ToPathWithVelocityScalar)
71 const nav_msgs::Path in = generatePath();
72 const trajectory_tracker_msgs::PathWithVelocity out =
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)
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);
94 TEST(Converter, ToPathWithVelocityVector)
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 =
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)
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);
120 int main(
int argc,
char** argv)
122 testing::InitGoogleTest(&argc, argv);
124 return RUN_ALL_TESTS();
int main(int argc, char **argv)
TEST(Converter, ToPathWithVelocityScalar)
PathWithVelocity toPathWithVelocity(const nav_msgs::Path &src, const double vel)