Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <door_msgs/Door.h>
00041 #include <ros/node.h>
00042 #include <gtest/gtest.h>
00043 #include <door_handle_detector/door_functions.h>
00044 #include "pr2_doors_actions/executive_functions.h"
00045
00046 using namespace ros;
00047 using namespace std;
00048 using namespace door_handle_detector;
00049
00050
00051
00052
00053 int g_argc;
00054 char** g_argv;
00055
00056 class TestEKF : public testing::Test
00057 {
00058 public:
00059 door_msgs::Door my_door_1, my_door_2;
00060
00061 protected:
00063 TestEKF()
00064 {
00065 my_door_1.frame_p1.x = 1.0;
00066 my_door_1.frame_p1.y = -0.5;
00067 my_door_1.frame_p2.x = 1.0;
00068 my_door_1.frame_p2.y = 0.5;
00069 my_door_1.door_p1.x = 1.0;
00070 my_door_1.door_p1.y = -0.5;
00071 my_door_1.door_p2.x = 1.0;
00072 my_door_1.door_p2.y = 0.5;
00073 my_door_1.normal.x = 1.0;
00074 my_door_1.normal.y = 0.0;
00075 my_door_1.normal.z = 0.0;
00076 my_door_1.rot_dir = door_msgs::Door::ROT_DIR_COUNTERCLOCKWISE;
00077 my_door_1.hinge = door_msgs::Door::HINGE_P2;
00078 my_door_1.header.frame_id = "base_footprint";
00079
00080 my_door_2.frame_p1.x = -0.198;
00081 my_door_2.frame_p1.y = -1.08;
00082 my_door_2.frame_p2.x = 0.76;
00083 my_door_2.frame_p2.y = -0.82;
00084 my_door_2.door_p1.x = -0.08;
00085 my_door_2.door_p1.y = -1.12;
00086 my_door_2.door_p2.x = 0.70;
00087 my_door_2.door_p2.y = -0.87;
00088 my_door_2.normal.x = 0.29;
00089 my_door_2.normal.y = -0.95;
00090 my_door_2.normal.z = 0.0;
00091 my_door_2.rot_dir = door_msgs::Door::ROT_DIR_COUNTERCLOCKWISE;
00092 my_door_2.hinge = door_msgs::Door::HINGE_P2;
00093 my_door_2.header.frame_id = "base_footprint";
00094 }
00095
00096
00098 ~TestEKF()
00099 {}
00100 };
00101
00102
00103
00104
00105 TEST_F(TestEKF, test)
00106 {
00107 tf::Stamped<tf::Pose> pose;
00108
00109 pose = getRobotPose(my_door_2, 0.6);
00110 cout << "pose = " << pose.getOrigin()[0] << ", " <<pose.getOrigin()[1] << ", " <<pose.getOrigin()[2] << endl;
00111
00112 pose = getGripperPose(my_door_2, M_PI/4.0, 0.4);
00113 cout << "door = " << my_door_2 << endl;
00114 cout << "pose = " << pose.getOrigin()[0] << ", " <<pose.getOrigin()[1] << ", " <<pose.getOrigin()[2] << endl;
00115
00116 pose = getRobotPose(my_door_1, 0.7);
00117 ASSERT_TRUE(pose.getOrigin()[0] == 0.3);
00118 ASSERT_TRUE(pose.getOrigin()[1] == 0.0);
00119 ASSERT_TRUE(pose.getOrigin()[2] == 0.0);
00120 SUCCEED();
00121 }
00122
00123
00124
00125
00126 int main(int argc, char** argv)
00127 {
00128 testing::InitGoogleTest(&argc, argv);
00129 g_argc = argc;
00130 g_argv = argv;
00131 return RUN_ALL_TESTS();
00132 }