moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group_ompl_constraints_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, 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: Boston Cleek
36  Desc: move group interface ompl constrained planning capabilities for planning and execution
37 */
38 
39 // Testing
40 #include <gtest/gtest.h>
41 
42 // ROS
43 #include <rclcpp/rclcpp.hpp>
44 #include <tf2/LinearMath/Quaternion.h>
45 #include <tf2_eigen/tf2_eigen.hpp>
46 
47 // MoveIt
51 #include <moveit_msgs/msg/constraints.hpp>
52 
53 // accuracy tested for position and orientation
54 static const double EPSILON = 1e-2;
55 
56 static const std::string PLANNING_GROUP = "panda_arm";
57 static const double PLANNING_TIME_S = 60.0;
58 static const double MAX_VELOCITY_SCALE = 1.0;
59 static const double MAX_ACCELERATION_SCALE = 1.0;
60 static const double PLANNING_ATTEMPTS = 5.0;
61 static const double GOAL_TOLERANCE = 1e-5;
62 
63 class ConstrainedPlanningTestFixture : public ::testing::Test
64 {
65 public:
66  void SetUp() override
67  {
68  move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(node_, PLANNING_GROUP);
69  move_group_->setPlanningTime(PLANNING_TIME_S);
70  move_group_->setNumPlanningAttempts(PLANNING_ATTEMPTS);
71  move_group_->setGoalTolerance(GOAL_TOLERANCE);
72  move_group_->setMaxVelocityScalingFactor(MAX_VELOCITY_SCALE);
73  move_group_->setMaxAccelerationScalingFactor(MAX_ACCELERATION_SCALE);
74 
75  ref_link_ = move_group_->getPoseReferenceFrame();
76  ee_link_ = move_group_->getEndEffectorLink();
77 
78  executor_->add_node(node_);
79  executor_thread_ = std::thread([this]() { this->executor_->spin(); });
80  }
81 
83  : node_(std::make_shared<rclcpp::Node>("ompl_constrained_planning_testing"))
84  , executor_(std::make_shared<rclcpp::executors::SingleThreadedExecutor>())
85  {
86  }
87 
88  void TearDown() override
89  {
90  executor_->cancel();
91  if (executor_thread_.joinable())
92  {
93  executor_thread_.join();
94  }
95  }
96 
97  void planAndMove(const geometry_msgs::msg::PoseStamped& pose_goal_stamped,
98  const moveit_msgs::msg::Constraints& path_constraint)
99  {
100  SCOPED_TRACE("planAndMove");
101 
102  ASSERT_TRUE(move_group_->setPoseTarget(pose_goal_stamped));
103  move_group_->setPathConstraints(path_constraint);
104 
106  ASSERT_EQ(move_group_->plan(plan), moveit::core::MoveItErrorCode::SUCCESS);
107  ASSERT_EQ(move_group_->move(), moveit::core::MoveItErrorCode::SUCCESS);
108  }
109 
110  void testPose(const geometry_msgs::msg::PoseStamped& pose_goal_stamped)
111  {
112  SCOPED_TRACE("testPose");
113 
114  const geometry_msgs::msg::PoseStamped actual_pose_stamped = move_group_->getCurrentPose();
115  Eigen::Isometry3d goal_pose, actual_pose;
116 
117  tf2::fromMsg(pose_goal_stamped.pose, goal_pose);
118  tf2::fromMsg(actual_pose_stamped.pose, actual_pose);
119 
120  std::stringstream ss;
121  ss << "expected: \n" << goal_pose.matrix() << "\nactual: \n" << actual_pose.matrix();
122  EXPECT_TRUE(actual_pose.isApprox(goal_pose, EPSILON)) << ss.str();
123  }
124 
125 protected:
126  rclcpp::Node::SharedPtr node_;
127  rclcpp::Executor::SharedPtr executor_;
128  std::thread executor_thread_;
129  moveit::planning_interface::MoveGroupInterfacePtr move_group_;
130  std::string ref_link_, ee_link_;
131  // mutable std::mutex latest_state_mutex_;
132 };
133 
135 {
136  SCOPED_TRACE("PositionConstraint");
137 
138  // Start
139  move_group_->setStartStateToCurrentState();
140  const geometry_msgs::msg::PoseStamped eef_pose = move_group_->getCurrentPose();
141 
142  // Create a goal
143  geometry_msgs::msg::PoseStamped pose_goal = eef_pose;
144  pose_goal.pose.position.y += 0.3;
145  pose_goal.pose.position.z -= 0.3;
146 
147  // Box position constraint
148  moveit_msgs::msg::PositionConstraint position_constraint;
149  position_constraint.header.frame_id = ref_link_;
150  position_constraint.link_name = ee_link_;
151  position_constraint.weight = 1.0;
152 
153  shape_msgs::msg::SolidPrimitive cbox;
154  cbox.type = shape_msgs::msg::SolidPrimitive::BOX;
155  cbox.dimensions = { 0.1, 0.4, 0.4 };
156  position_constraint.constraint_region.primitives.emplace_back(cbox);
157 
158  geometry_msgs::msg::Pose cbox_pose;
159  cbox_pose.position.x = eef_pose.pose.position.x;
160  cbox_pose.position.y = 0.15;
161  cbox_pose.position.z = 0.45;
162  cbox_pose.orientation.w = 1.0;
163  position_constraint.constraint_region.primitive_poses.emplace_back(cbox_pose);
164 
165  // Create path constraint
166  moveit_msgs::msg::Constraints path_constraint;
167  path_constraint.name = "position constraint";
168  path_constraint.position_constraints.emplace_back(position_constraint);
169 
170  planAndMove(pose_goal, path_constraint);
171 
172  testPose(pose_goal);
173 }
174 
175 int main(int argc, char** argv)
176 {
177  rclcpp::init(argc, argv);
178  ::testing::InitGoogleTest(&argc, argv);
179 
180  int ret = RUN_ALL_TESTS();
181  rclcpp::shutdown();
182  return ret;
183 }
moveit::planning_interface::MoveGroupInterfacePtr move_group_
void testPose(const geometry_msgs::msg::PoseStamped &pose_goal_stamped)
void planAndMove(const geometry_msgs::msg::PoseStamped &pose_goal_stamped, const moveit_msgs::msg::Constraints &path_constraint)
constexpr double PLANNING_TIME_S
constexpr double MAX_ACCELERATION_SCALE
constexpr double GOAL_TOLERANCE
constexpr double MAX_VELOCITY_SCALE
int main(int argc, char **argv)
TEST_F(ConstrainedPlanningTestFixture, PositionConstraint)
Definition: plan.py:1
The representation of a motion plan (as ROS messasges)