chomp_moveit_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Heriot-Watt University, Edinburgh Centre for Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <ros/ros.h>
38 #include <gtest/gtest.h>
39 
40 #include <moveit/move_group_interface/move_group_interface.h>
41 #include <moveit/planning_scene_interface/planning_scene_interface.h>
42 
43 class CHOMPMoveitTest : public ::testing::Test
44 {
45 public:
46  moveit::planning_interface::MoveGroupInterface move_group_;
47  moveit::planning_interface::MoveGroupInterface::Plan my_plan_;
48 
49 public:
50  CHOMPMoveitTest() : move_group_(moveit::planning_interface::MoveGroupInterface("arm"))
51  {
52  }
53 };
54 
55 // TEST CASES
56 TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
57 {
58  move_group_.setStartState(*(move_group_.getCurrentState()));
59  move_group_.setJointValueTarget(std::vector<double>({ 1.0, 1.0 }));
60 
61  moveit::planning_interface::MoveItErrorCode error_code = move_group_.plan(my_plan_);
62  EXPECT_GT(my_plan_.trajectory_.joint_trajectory.points.size(), 0);
63  EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::SUCCESS);
64 }
65 
66 TEST_F(CHOMPMoveitTest, jointSpaceBadGoal)
67 {
68  move_group_.setStartState(*(move_group_.getCurrentState()));
69  // joint2 is limited to [-PI/2, PI/2]
70  move_group_.setJointValueTarget(std::vector<double>({ 100.0, 2 * M_PI / 3.0 }));
71 
72  moveit::planning_interface::MoveItErrorCode error_code = move_group_.plan(my_plan_);
73  EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_ROBOT_STATE);
74 }
75 
76 TEST_F(CHOMPMoveitTest, cartesianGoal)
77 {
78  move_group_.setStartState(*(move_group_.getCurrentState()));
79  geometry_msgs::Pose target_pose1;
80  target_pose1.orientation.w = 1.0;
81  target_pose1.position.x = 10000.;
82  target_pose1.position.y = 10000.;
83  target_pose1.position.z = 10000.;
84  move_group_.setPoseTarget(target_pose1);
85 
86  moveit::planning_interface::MoveItErrorCode error_code = move_group_.plan(my_plan_);
87  // CHOMP doesn't support Cartesian-space goals at the moment
88  EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS);
89 }
90 
91 TEST_F(CHOMPMoveitTest, noStartState)
92 {
93  move_group_.setJointValueTarget(std::vector<double>({ 0.2, 0.2 }));
94 
95  moveit::planning_interface::MoveItErrorCode error_code = move_group_.plan(my_plan_);
96  EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_ROBOT_STATE);
97 }
98 
99 TEST_F(CHOMPMoveitTest, collisionAtEndOfPath)
100 {
101  move_group_.setStartState(*(move_group_.getCurrentState()));
102  move_group_.setJointValueTarget(std::vector<double>({ M_PI / 2.0, 0 }));
103 
104  moveit::planning_interface::MoveItErrorCode error_code = move_group_.plan(my_plan_);
105  EXPECT_EQ(error_code.val, moveit::planning_interface::MoveItErrorCode::INVALID_MOTION_PLAN);
106 }
107 
108 int main(int argc, char** argv)
109 {
110  testing::InitGoogleTest(&argc, argv);
111  ros::init(argc, argv, "chomp_moveit_test");
112 
113  ros::AsyncSpinner spinner(1);
114  spinner.start();
115  int ret = RUN_ALL_TESTS();
116  spinner.stop();
117  ros::shutdown();
118  return ret;
119 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define M_PI
#define EXPECT_EQ(a, b)
moveit::planning_interface::MoveGroupInterface move_group_
TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
ROSCPP_DECL void shutdown()
moveit::planning_interface::MoveGroupInterface::Plan my_plan_


chomp_interface
Author(s): Gil Jones
autogenerated on Wed Jul 10 2019 04:04:17