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