test_convert.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <gtest/gtest.h>
00031 
00032 #include <geometry_msgs/PoseStamped.h>
00033 #include <geometry_msgs/Vector3.h>
00034 #include <nav_msgs/Path.h>
00035 #include <trajectory_tracker_msgs/PathWithVelocity.h>
00036 
00037 #include <trajectory_tracker_msgs/converter.h>
00038 
00039 namespace
00040 {
00041 nav_msgs::Path generatePath()
00042 {
00043   nav_msgs::Path path;
00044   path.header.frame_id = "frame-name";
00045   path.header.stamp = ros::Time(1234.5);
00046   path.poses.resize(2);
00047   path.poses[0].pose.orientation.w = 1.0;
00048   path.poses[0].pose.position.x = 2.0;
00049   path.poses[0].pose.position.y = 3.0;
00050   path.poses[1].pose.orientation.z = 4.0;
00051   path.poses[1].pose.position.x = 5.0;
00052   path.poses[1].pose.position.y = 6.0;
00053   return path;
00054 }
00055 
00056 geometry_msgs::Vector3 generateVector3(
00057     const double x,
00058     const double y,
00059     const double z)
00060 {
00061   geometry_msgs::Vector3 vec;
00062   vec.x = x;
00063   vec.y = y;
00064   vec.z = z;
00065   return vec;
00066 }
00067 }  // namespace
00068 
00069 TEST(Converter, ToPathWithVelocityScalar)
00070 {
00071   const nav_msgs::Path in = generatePath();
00072   const trajectory_tracker_msgs::PathWithVelocity out =
00073       trajectory_tracker_msgs::toPathWithVelocity(in, 1.23);
00074 
00075   ASSERT_EQ(in.header.frame_id, out.header.frame_id);
00076   ASSERT_EQ(in.header.stamp, out.header.stamp);
00077   for (size_t i = 0; i < in.poses.size(); ++i)
00078   {
00079     ASSERT_EQ(out.poses[i].header.frame_id, in.poses[i].header.frame_id);
00080     ASSERT_EQ(out.poses[i].header.stamp, in.poses[i].header.stamp);
00081     ASSERT_EQ(out.poses[i].pose.position.x, in.poses[i].pose.position.x);
00082     ASSERT_EQ(out.poses[i].pose.position.y, in.poses[i].pose.position.y);
00083     ASSERT_EQ(out.poses[i].pose.position.z, in.poses[i].pose.position.z);
00084     ASSERT_EQ(out.poses[i].pose.orientation.x, in.poses[i].pose.orientation.x);
00085     ASSERT_EQ(out.poses[i].pose.orientation.y, in.poses[i].pose.orientation.y);
00086     ASSERT_EQ(out.poses[i].pose.orientation.z, in.poses[i].pose.orientation.z);
00087     ASSERT_EQ(out.poses[i].pose.orientation.w, in.poses[i].pose.orientation.w);
00088     ASSERT_EQ(out.poses[i].linear_velocity.x, 1.23);
00089     ASSERT_EQ(out.poses[i].linear_velocity.y, 0.0);
00090     ASSERT_EQ(out.poses[i].linear_velocity.z, 0.0);
00091   }
00092 }
00093 
00094 TEST(Converter, ToPathWithVelocityVector)
00095 {
00096   const nav_msgs::Path in = generatePath();
00097   const geometry_msgs::Vector3 vel = generateVector3(1.23, 0.12, 0.23);
00098   const trajectory_tracker_msgs::PathWithVelocity out =
00099       trajectory_tracker_msgs::toPathWithVelocity(in, vel);
00100 
00101   ASSERT_EQ(in.header.frame_id, out.header.frame_id);
00102   ASSERT_EQ(in.header.stamp, out.header.stamp);
00103   for (size_t i = 0; i < in.poses.size(); ++i)
00104   {
00105     ASSERT_EQ(out.poses[i].header.frame_id, in.poses[i].header.frame_id);
00106     ASSERT_EQ(out.poses[i].header.stamp, in.poses[i].header.stamp);
00107     ASSERT_EQ(out.poses[i].pose.position.x, in.poses[i].pose.position.x);
00108     ASSERT_EQ(out.poses[i].pose.position.y, in.poses[i].pose.position.y);
00109     ASSERT_EQ(out.poses[i].pose.position.z, in.poses[i].pose.position.z);
00110     ASSERT_EQ(out.poses[i].pose.orientation.x, in.poses[i].pose.orientation.x);
00111     ASSERT_EQ(out.poses[i].pose.orientation.y, in.poses[i].pose.orientation.y);
00112     ASSERT_EQ(out.poses[i].pose.orientation.z, in.poses[i].pose.orientation.z);
00113     ASSERT_EQ(out.poses[i].pose.orientation.w, in.poses[i].pose.orientation.w);
00114     ASSERT_EQ(out.poses[i].linear_velocity.x, vel.x);
00115     ASSERT_EQ(out.poses[i].linear_velocity.y, vel.y);
00116     ASSERT_EQ(out.poses[i].linear_velocity.z, vel.z);
00117   }
00118 }
00119 
00120 int main(int argc, char** argv)
00121 {
00122   testing::InitGoogleTest(&argc, argv);
00123 
00124   return RUN_ALL_TESTS();
00125 }


trajectory_tracker_msgs
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 19:51:43