moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
chomp_moveit_test_rrbot.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 <gtest/gtest.h>
40#include <ros/ros.h>
41
42class CHOMPMoveitTest : public ::testing::Test
43{
44public:
47
48public:
50 {
51 }
52};
53
54// TEST CASES
55TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
56{
57 move_group_.setStartState(*(move_group_.getCurrentState()));
58 move_group_.setJointValueTarget(std::vector<double>({ 1.0, 1.0 }));
59
60 moveit::core::MoveItErrorCode error_code = move_group_.plan(my_plan_);
61 EXPECT_GT(my_plan_.trajectory.joint_trajectory.points.size(), 0u);
62 EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::SUCCESS);
63}
64
65TEST_F(CHOMPMoveitTest, jointSpaceBadGoal)
66{
67 move_group_.setStartState(*(move_group_.getCurrentState()));
68 // joint2 is limited to [-PI/2, PI/2]
69 move_group_.setJointValueTarget(std::vector<double>({ 100.0, 2 * M_PI / 3.0 }));
70
71 moveit::core::MoveItErrorCode error_code = move_group_.plan(my_plan_);
72 EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_ROBOT_STATE);
73}
74
75TEST_F(CHOMPMoveitTest, cartesianGoal)
76{
77 move_group_.setStartState(*(move_group_.getCurrentState()));
78 geometry_msgs::Pose target_pose1;
79 target_pose1.orientation.w = 1.0;
80 target_pose1.position.x = 10000.;
81 target_pose1.position.y = 10000.;
82 target_pose1.position.z = 10000.;
83 move_group_.setPoseTarget(target_pose1);
84
85 moveit::core::MoveItErrorCode error_code = move_group_.plan(my_plan_);
86 // CHOMP doesn't support Cartesian-space goals at the moment
87 EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS);
88}
89
90TEST_F(CHOMPMoveitTest, noStartState)
91{
92 move_group_.setJointValueTarget(std::vector<double>({ 0.2, 0.2 }));
93
94 moveit::core::MoveItErrorCode error_code = move_group_.plan(my_plan_);
95 EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::SUCCESS);
96}
97
98TEST_F(CHOMPMoveitTest, collisionAtEndOfPath)
99{
100 move_group_.setStartState(*(move_group_.getCurrentState()));
101 move_group_.setJointValueTarget(std::vector<double>({ M_PI / 2.0, 0 }));
102
103 moveit::core::MoveItErrorCode error_code = move_group_.plan(my_plan_);
104 EXPECT_EQ(error_code.val, moveit::core::MoveItErrorCode::INVALID_MOTION_PLAN);
105}
106
107int main(int argc, char** argv)
108{
109 testing::InitGoogleTest(&argc, argv);
110 ros::init(argc, argv, "chomp_moveit_test_rrbot");
111
112 ros::AsyncSpinner spinner(1);
113 spinner.start();
114 int ret = RUN_ALL_TESTS();
115 spinner.stop();
116 ros::shutdown();
117 return ret;
118}
int main(int argc, char **argv)
TEST_F(CHOMPMoveitTest, jointSpaceGoodGoal)
moveit::planning_interface::MoveGroupInterface::Plan my_plan_
moveit::planning_interface::MoveGroupInterface move_group_
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Client class to conveniently use the ROS interfaces provided by the move_group node.
void setStartState(const moveit_msgs::msg::RobotState &start_state)
If a different start state should be considered instead of the current state of the robot,...
The representation of a motion plan (as ROS messages)