moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
moveit_cpp_test.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2019, PickNik Inc.
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 PickNik Inc. 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
35/* Author: Jafar Abdi
36 Desc: Test the MoveItCpp and PlanningComponent interfaces
37*/
38
39// ROS
40#include <rclcpp/rclcpp.hpp>
41
42// Testing
43#include <gtest/gtest.h>
44
45// Main class
48// Msgs
49#include <geometry_msgs/PointStamped.h>
50
51namespace moveit
52{
53namespace planning_interface
54{
55class MoveItCppTest : public ::testing::Test
56{
57public:
58 void SetUp() override
59 {
60 rclcpp::NodeOptions node_options;
61 // This enables loading arbitrary parameters
62 // However, best practice would be to declare parameters in the corresponding classes
63 // and provide descriptions about expected use
64 // TODO(henningkayser): remove once all parameters are declared inside the components
65 node_options.automatically_declare_parameters_from_overrides(true);
66 node_ = rclcpp::Node::make_shared("/moveit_cpp_test");
67 moveit_cpp_ptr = std::make_unique<MoveItCpp>(node_);
68 planning_component_ptr = std::make_unique<PlanningComponent>(PLANNING_GROUP, moveit_cpp_ptr);
69 robot_model_ptr = moveit_cpp_ptr->getRobotModel();
70 jmg_ptr = robot_model_ptr->getJointModelGroup(PLANNING_GROUP);
71
72 target_pose1.header.frame_id = "panda_link0";
73 target_pose1.pose.orientation.w = 1.0;
74 target_pose1.pose.position.x = 0.28;
75 target_pose1.pose.position.y = -0.2;
76 target_pose1.pose.position.z = 0.5;
77
78 start_pose.orientation.w = 1.0;
79 start_pose.position.x = 0.55;
80 start_pose.position.y = 0.0;
81 start_pose.position.z = 0.6;
82
83 target_pose2.orientation.w = 1.0;
84 target_pose2.position.x = 0.55;
85 target_pose2.position.y = -0.05;
86 target_pose2.position.z = 0.8;
87 }
88
89protected:
90 rclcpp::Node node_;
91 MoveItCppPtr moveit_cpp_ptr;
92 PlanningComponentPtr planning_component_ptr;
93 moveit::core::RobotModelConstPtr robot_model_ptr;
95 const std::string PLANNING_GROUP = "panda_arm";
96 geometry_msgs::PoseStamped target_pose1;
97 geometry_msgs::Pose target_pose2;
98 geometry_msgs::Pose start_pose;
99};
100
101// Test the current and the initial state of the Panda robot
102TEST_F(MoveItCppTest, GetCurrentStateTest)
103{
104 ros::Duration(1.0).sleep(); // Otherwise joint_states will result in an invalid robot state
105 auto robot_model = moveit_cpp_ptr->getRobotModel();
106 auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
107 EXPECT_TRUE(moveit_cpp_ptr->getCurrentState(robot_state, 0.0));
108 // Make sure the Panda robot is in "ready" state which is loaded from yaml
109 std::vector<double> joints_vals;
110 robot_state->copyJointGroupPositions(PLANNING_GROUP, joints_vals);
111 EXPECT_NEAR(joints_vals[0], 0.0, 0.001); // panda_joint1
112 EXPECT_NEAR(joints_vals[1], -0.785, 0.001); // panda_joint2
113 EXPECT_NEAR(joints_vals[2], 0.0, 0.001); // panda_joint3
114 EXPECT_NEAR(joints_vals[3], -2.356, 0.001); // panda_joint4
115 EXPECT_NEAR(joints_vals[4], 0.0, 0.001); // panda_joint5
116 EXPECT_NEAR(joints_vals[5], 1.571, 0.001); // panda_joint6
117 EXPECT_NEAR(joints_vals[6], 0.785, 0.001); // panda_joint7
118}
119
120// Test the name of the planning group used by PlanningComponent for the Panda robot
121TEST_F(MoveItCppTest, NameOfPlanningGroupTest)
122{
123 EXPECT_STREQ(planning_component_ptr->getPlanningGroupName().c_str(), "panda_arm");
124}
125
126// Test setting the start state of the plan to the current state of the robot
127TEST_F(MoveItCppTest, TestSetStartStateToCurrentState)
128{
129 planning_component_ptr->setStartStateToCurrentState();
130 planning_component_ptr->setGoal(target_pose1, "panda_link8");
131
132 ASSERT_TRUE(static_cast<bool>(planning_component_ptr->plan()));
133 // TODO(JafarAbdi) adding testing to the soln state
134}
135
136// Test setting the goal using geometry_msgs::PoseStamped and a robot's link name
137TEST_F(MoveItCppTest, TestSetGoalFromPoseStamped)
138{
139 planning_component_ptr->setGoal(target_pose1, "panda_link8");
140
141 ASSERT_TRUE(static_cast<bool>(planning_component_ptr->plan()));
142}
143
144// Test setting the plan start state using moveit::core::RobotState
145TEST_F(MoveItCppTest, TestSetStartStateFromRobotState)
146{
147 auto start_state = *(moveit_cpp_ptr->getCurrentState());
148 start_state.setFromIK(jmg_ptr, start_pose);
149
150 planning_component_ptr->setStartState(start_state);
151 planning_component_ptr->setGoal(target_pose1, "panda_link8");
152
153 ASSERT_TRUE(static_cast<bool>(planning_component_ptr->plan()));
154}
155
156// Test setting the goal of the plan using a moveit::core::RobotState
157TEST_F(MoveItCppTest, TestSetGoalFromRobotState)
158{
159 auto target_state = *(moveit_cpp_ptr->getCurrentState());
160
161 target_state.setFromIK(jmg_ptr, target_pose2);
162
163 planning_component_ptr->setGoal(target_state);
164
165 ASSERT_TRUE(static_cast<bool>(planning_component_ptr->plan()));
166}
167} // namespace planning_interface
168} // namespace moveit
169
170int main(int argc, char** argv)
171{
172 testing::InitGoogleTest(&argc, argv);
173 ros::init(argc, argv, "moveit_cpp_test");
174
175 ros::AsyncSpinner spinner(4);
176 spinner.start();
177
178 int result = RUN_ALL_TESTS();
179
180 return result;
181}
moveit::core::RobotModelConstPtr robot_model_ptr
const moveit::core::JointModelGroup * jmg_ptr
int main(int argc, char **argv)
TEST_F(MoveItCppTest, GetCurrentStateTest)
Main namespace for MoveIt.
Definition exceptions.h:43
This namespace includes the base class for MoveIt planners.