play_motion_helpers_test.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00029 
00030 #include <gtest/gtest.h>
00031 
00032 #include <ros/ros.h>
00033 #include <ros/time.h>
00034 
00035 #include "play_motion/play_motion_helpers.h"
00036 
00037 TEST(PlayMotionHelpersTest, getMotions)
00038 {
00039   play_motion::MotionNames motion_names;
00040   ros::NodeHandle nh("play_motion");
00041   play_motion::getMotionIds(nh, motion_names);
00042   EXPECT_EQ(4, motion_names.size());
00043   EXPECT_NE(motion_names.end(), std::find(motion_names.begin(), motion_names.end(), "arms_t"));
00044   EXPECT_NE(motion_names.end(), std::find(motion_names.begin(), motion_names.end(), "bow"));
00045   EXPECT_NE(motion_names.end(), std::find(motion_names.begin(), motion_names.end(), "five_joint_motion"));
00046   EXPECT_NE(motion_names.end(), std::find(motion_names.begin(), motion_names.end(), "three_point_motion"));
00047 }
00048 
00049 TEST(PlayMotionHelpersTest, getMotionJoints)
00050 {
00051   ros::NodeHandle nh("play_motion");
00052   play_motion::JointNames names;
00053   play_motion::getMotionJoints(nh, "bow", names);
00054   EXPECT_EQ(18, names.size());
00055   play_motion::getMotionJoints(nh, "five_joint_motion", names);
00056   EXPECT_EQ(5, names.size());
00057 }
00058 
00059 
00060 TEST(PlayMotionHelpersTest, getMotionPoints)
00061 {
00062   ros::NodeHandle nh("play_motion");
00063   play_motion::Trajectory traj;
00064   play_motion::getMotionPoints(nh, "arms_t", traj);
00065   EXPECT_EQ(1, traj.size());
00066   traj.clear();
00067   play_motion::getMotionPoints(nh, "three_point_motion", traj);
00068   EXPECT_EQ(3, traj.size());
00069 }
00070 
00071 TEST(PlayMotionHelpersTest, getMotionDuration)
00072 {
00073   ros::NodeHandle nh("play_motion");
00074   ros::Duration d = play_motion::getMotionDuration(nh, "arms_t");
00075   EXPECT_NEAR(0.0, d.toSec(), 0.01);
00076   d = play_motion::getMotionDuration(nh, "bow");
00077   EXPECT_NEAR(6.5, d.toSec(), 0.01);
00078 }
00079 
00080 TEST(PlayMotionHelpersTest, isAlreadyThere)
00081 {
00082   ros::NodeHandle nh("play_motion");
00083 
00084   play_motion::JointNames sourceJoints;
00085   play_motion::Trajectory sourceTraj;
00086   play_motion::getMotionJoints(nh, "bow", sourceJoints);
00087   play_motion::getMotionPoints(nh, "bow", sourceTraj);
00088 
00089 
00091   EXPECT_TRUE(play_motion::isAlreadyThere(sourceJoints, sourceTraj[0],
00092               sourceJoints, sourceTraj[0]));
00093 
00095   EXPECT_FALSE(play_motion::isAlreadyThere(sourceJoints, sourceTraj[0],
00096                sourceJoints, sourceTraj[1]));
00097 
00099   EXPECT_TRUE(play_motion::isAlreadyThere(sourceJoints, sourceTraj[0],
00100               sourceJoints, sourceTraj[1], M_2_PI));
00101 
00102   play_motion::JointNames differentJoints;
00103   play_motion::getMotionJoints(nh, "bow", differentJoints);
00104   differentJoints[0] = "made_up_joint";
00106   EXPECT_FALSE(play_motion::isAlreadyThere(differentJoints, sourceTraj[0],
00107                sourceJoints, sourceTraj[0]));
00108 
00109 
00110   differentJoints.clear();
00111   EXPECT_THROW(play_motion::isAlreadyThere(differentJoints, sourceTraj[0],
00112                sourceJoints, sourceTraj[0]), ros::Exception);
00113 }
00114 
00115 TEST(PlayMotionHelpersTest, getMotionOk)
00116 {
00117   ros::NodeHandle nh("play_motion");
00118   play_motion::MotionInfo info;
00119   play_motion::getMotion(nh, "arms_t", info);
00120   EXPECT_EQ("arms_t", info.id);
00121   EXPECT_EQ("Arms T", info.name);
00122   EXPECT_EQ("posture", info.usage);
00123   EXPECT_EQ("Both arms set straight pointing sideways at 45 degrees.", info.description);
00124 }
00125 
00126 TEST(PlayMotionHelpersTest, getMotionKo)
00127 {
00128   ros::NodeHandle nh("play_motion");
00129   play_motion::MotionInfo info;
00130   EXPECT_THROW(play_motion::getMotion(nh, "",          info), ros::Exception);
00131   EXPECT_THROW(play_motion::getMotion(nh, "bad_name",  info), ros::Exception);
00132   EXPECT_THROW(play_motion::getMotion(nh, "~bad_name", info), ros::Exception);
00133 }
00134 
00135 int main(int argc, char** argv)
00136 {
00137   testing::InitGoogleTest(&argc, argv);
00138   ros::init(argc, argv, "play_motion_helpers_test");
00139 
00140   int ret = RUN_ALL_TESTS();
00141   return ret;
00142 }
00143 


play_motion
Author(s): Paul Mathieu
autogenerated on Wed Aug 26 2015 15:29:25