hand_commander_test.cpp
Go to the documentation of this file.
00001 
00002 // We are testing this
00003 #include "sr_hand/hand_commander.hpp"
00004 
00005 // ROS
00006 #include "ros/ros.h"
00007 
00008 // Gtest
00009 #include <gtest/gtest.h>
00010 
00011 using namespace shadowrobot;
00012 
00013 TEST(HandCommander, constructor)
00014 {
00015     HandCommander handcmd = HandCommander();
00016     EXPECT_TRUE(true);
00017 }
00018 
00019 TEST(HandCommander, topic_state)
00020 {
00021     HandCommander handcmd = HandCommander();
00022 
00023     std::string topic = handcmd.get_controller_state_topic("ffj3");
00024     EXPECT_EQ("/sh_ffj3_mixed_position_velocity_controller/state", topic);
00025 
00026     topic = handcmd.get_controller_state_topic("ffj0");
00027     EXPECT_EQ("/sh_ffj0_mixed_position_velocity_controller/state", topic);
00028 
00029     topic = handcmd.get_controller_state_topic("unknown joint");
00030     EXPECT_EQ("", topic);
00031 }
00032 
00033 TEST(HandCommander, min_max)
00034 {
00035     HandCommander handcmd = HandCommander();
00036 
00037     std::pair<double, double> min_max = handcmd.get_min_max("FFJ3");
00038     EXPECT_DOUBLE_EQ(min_max.first, 0.0);
00039     EXPECT_DOUBLE_EQ(min_max.second, 1.57079632679);
00040 
00041     //also works for lower case
00042     min_max = handcmd.get_min_max("ffj3");
00043     EXPECT_DOUBLE_EQ(min_max.first, 0.0);
00044     EXPECT_DOUBLE_EQ(min_max.second, 1.57079632679);
00045 
00046     //j0 should be 0, 180
00047     min_max = handcmd.get_min_max("ffj0");
00048     EXPECT_DOUBLE_EQ(min_max.first, 0.0);
00049     EXPECT_DOUBLE_EQ(min_max.second, 3.14159265358);
00050 
00051     //returns 0, 0 if joint not found
00052     min_max = handcmd.get_min_max("unknown joint");
00053     EXPECT_DOUBLE_EQ(min_max.first, 0.0);
00054     EXPECT_DOUBLE_EQ(min_max.second, 0.0);
00055 
00056     //Check that we can get the min and max for each joint
00057     std::vector<std::string> all_joints = handcmd.get_all_joints();
00058     for( size_t i=0; i < all_joints.size(); ++i)
00059     {
00060        min_max = handcmd.get_min_max(all_joints[i]);
00061        EXPECT_TRUE(min_max.first != min_max.second); //min = max if joint not found
00062     }
00063 }
00064 
00065 TEST(HandCommander, all_joints)
00066 {
00067     HandCommander handcmd = HandCommander();
00068 
00069     EXPECT_EQ(handcmd.get_all_joints().size(), 20);
00070 }
00071 
00072 int main(int argc, char **argv)
00073 {
00074     testing::InitGoogleTest(&argc, argv);
00075     ros::init(argc, argv, "hand_commander_test");
00076     ros::NodeHandle nh; // init the node
00077 
00078     //sleep until gazebo is ready
00079     sleep(10.0);
00080 
00081     return RUN_ALL_TESTS();
00082 }


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:44:02