moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_basic_integration.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, 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: Andy Zelenak
36 Desc: Launch hybrid planning and test basic functionality
37*/
38
39#include <gtest/gtest.h>
43#include <rclcpp/rclcpp.hpp>
44#include <rclcpp_action/rclcpp_action.hpp>
45#include <tf2_ros/buffer.h>
46
47#include <moveit_msgs/action/hybrid_planner.hpp>
48#include <moveit_msgs/msg/display_robot_state.hpp>
49#include <moveit_msgs/msg/motion_plan_response.hpp>
50
52{
53using namespace std::chrono_literals;
54
55class HybridPlanningFixture : public ::testing::Test
56{
57public:
58 HybridPlanningFixture() : node_(std::make_shared<rclcpp::Node>("hybrid_planning_testing"))
59 {
60 action_successful_ = false;
61 action_aborted_ = false;
62 action_complete_ = false;
63
64 executor_.add_node(node_);
65
66 hp_action_client_ = rclcpp_action::create_client<moveit_msgs::action::HybridPlanner>(node_, "run_hybrid_planning");
67
68 // Add new collision object as soon as global trajectory is available.
69 global_solution_subscriber_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
70 "global_trajectory", rclcpp::SystemDefaultsQoS(),
71 [](const moveit_msgs::msg::MotionPlanResponse::SharedPtr /* unused */) {});
72
73 RCLCPP_INFO(node_->get_logger(), "Initialize Planning Scene Monitor");
74 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
75
76 planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, "robot_description",
77 "planning_scene_monitor");
78 if (!planning_scene_monitor_->getPlanningScene())
79 {
80 RCLCPP_ERROR(node_->get_logger(), "The planning scene was not retrieved!");
81 std::exit(EXIT_FAILURE);
82 }
83 else
84 {
85 planning_scene_monitor_->startStateMonitor();
86 planning_scene_monitor_->setPlanningScenePublishingFrequency(100);
88 "/planning_scene");
89 planning_scene_monitor_->startSceneMonitor();
90 }
91
92 if (!planning_scene_monitor_->waitForCurrentRobotState(node_->now(), 5))
93 {
94 RCLCPP_ERROR(node_->get_logger(), "Timeout when waiting for /joint_states updates. Is the robot running?");
95 std::exit(EXIT_FAILURE);
96 }
97
98 if (!hp_action_client_->wait_for_action_server(20s))
99 {
100 RCLCPP_ERROR(node_->get_logger(), "Hybrid planning action server not available after waiting");
101 std::exit(EXIT_FAILURE);
102 }
103
104 // Setup motion planning goal taken from motion_planning_api tutorial
105 const std::string planning_group = "panda_arm";
107 const moveit::core::RobotModelPtr& robot_model = robot_model_loader.getModel();
108
109 // Create a RobotState and JointModelGroup
110 const auto robot_state = std::make_shared<moveit::core::RobotState>(robot_model);
111 const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(planning_group);
112
113 // Configure a valid robot state
114 robot_state->setToDefaultValues(joint_model_group, "ready");
115 robot_state->update();
116 // Lock the planning scene as briefly as possible
117 {
119 locked_planning_scene->setCurrentState(*robot_state);
120 }
121
122 const moveit::core::RobotState goal_state([robot_model, joint_model_group]() {
123 moveit::core::RobotState goal_state(robot_model);
124 std::vector<double> joint_values = { 0.0, 0.0, 0.0, 0.0, 0.0, 1.571, 0.785 };
125 goal_state.setJointGroupPositions(joint_model_group, joint_values);
126 return goal_state;
127 }());
128
129 // Create desired motion goal
130 const moveit_msgs::msg::MotionPlanRequest goal_motion_request(
131 [robot_state, planning_group, goal_state, joint_model_group]() {
132 moveit_msgs::msg::MotionPlanRequest goal_motion_request;
133 moveit::core::robotStateToRobotStateMsg(*robot_state, goal_motion_request.start_state);
134 goal_motion_request.group_name = planning_group;
135 goal_motion_request.num_planning_attempts = 10;
136 goal_motion_request.max_velocity_scaling_factor = 0.1;
137 goal_motion_request.max_acceleration_scaling_factor = 0.1;
138 goal_motion_request.allowed_planning_time = 2.0;
139 goal_motion_request.planner_id = "ompl";
140 goal_motion_request.pipeline_id = "ompl";
141 goal_motion_request.goal_constraints.resize(1);
142 goal_motion_request.goal_constraints[0] =
143 kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group);
144 return goal_motion_request;
145 }());
146
147 // Create Hybrid Planning action request
148 moveit_msgs::msg::MotionSequenceItem sequence_item;
149 sequence_item.req = goal_motion_request;
150 sequence_item.blend_radius = 0.0; // Single goal
151
152 moveit_msgs::msg::MotionSequenceRequest sequence_request;
153 sequence_request.items.push_back(sequence_item);
154
155 goal_action_request_ = moveit_msgs::action::HybridPlanner::Goal();
156 goal_action_request_.planning_group = planning_group;
157 goal_action_request_.motion_sequence = sequence_request;
158
159 send_goal_options_ = rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SendGoalOptions();
160 send_goal_options_.result_callback =
161 [this](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::WrappedResult& result) {
162 switch (result.code)
163 {
164 case rclcpp_action::ResultCode::SUCCEEDED:
165 action_successful_ = true;
166 RCLCPP_INFO(node_->get_logger(), "Hybrid planning goal succeeded");
167 break;
168 case rclcpp_action::ResultCode::ABORTED:
169 action_aborted_ = true;
170 RCLCPP_ERROR(node_->get_logger(), "Hybrid planning goal was aborted");
171 break;
172 case rclcpp_action::ResultCode::CANCELED:
173 RCLCPP_ERROR(node_->get_logger(), "Hybrid planning goal was canceled");
174 break;
175 default:
176 RCLCPP_ERROR(node_->get_logger(), "Unknown hybrid planning result code");
177 break;
178 }
179 action_complete_ = true;
180 return;
181 };
182 send_goal_options_.feedback_callback =
183 [this](rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::SharedPtr /*unused*/,
184 const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Feedback> feedback) {
185 RCLCPP_INFO(node_->get_logger(), "%s", feedback->feedback.c_str());
186 };
187 }
188
189 rclcpp::executors::MultiThreadedExecutor executor_;
190
191protected:
192 rclcpp::Node::SharedPtr node_;
193 rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SharedPtr hp_action_client_;
194 rclcpp::Subscription<moveit_msgs::msg::MotionPlanResponse>::SharedPtr global_solution_subscriber_;
195 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
196 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
197 std::atomic_bool action_successful_;
198 std::atomic_bool action_complete_;
199 std::atomic_bool action_aborted_;
200
201 // Action request
202 moveit_msgs::action::HybridPlanner::Goal goal_action_request_;
203 rclcpp_action::Client<moveit_msgs::action::HybridPlanner>::SendGoalOptions send_goal_options_;
204}; // class HybridPlanningFixture
205
206// Make a hybrid planning request and verify it completes
208{
209 std::thread run_thread([this]() {
210 // Send the goal
211 auto goal_handle_future = hp_action_client_->async_send_goal(goal_action_request_, send_goal_options_);
212 });
213
214 rclcpp::Rate rate(10);
215 while (!action_complete_)
216 {
217 executor_.spin_once();
218 rate.sleep();
219 }
220 run_thread.join();
221 ASSERT_TRUE(action_successful_);
222}
223
224// Make a hybrid planning request then abort it
225// TODO(sjahr): Fix and re-enable
226/*TEST_F(HybridPlanningFixture, ActionAbortion)
227{
228 std::thread run_thread([this]() {
229 // Send the goal
230 auto goal_handle_future = hp_action_client_->async_send_goal(goal_action_request_, send_goal_options_);
231
232 // Cancel the goal
233 hp_action_client_->async_cancel_all_goals();
234 });
235
236 rclcpp::Rate rate(10);
237 while (!action_complete_)
238 {
239 executor_.spin_once();
240 rate.sleep();
241 }
242 run_thread.join();
243 ASSERT_FALSE(action_successful_);
244 ASSERT_TRUE(action_aborted_);
245}*/
246} // namespace moveit_hybrid_planning
247
248int main(int argc, char** argv)
249{
250 rclcpp::init(argc, argv);
251 ::testing::InitGoogleTest(&argc, argv);
252
253 int ret = RUN_ALL_TESTS();
254 rclcpp::shutdown();
255 return ret;
256}
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rclcpp_action::Client< moveit_msgs::action::HybridPlanner >::SendGoalOptions send_goal_options_
rclcpp::Subscription< moveit_msgs::msg::MotionPlanResponse >::SharedPtr global_solution_subscriber_
rclcpp::executors::MultiThreadedExecutor executor_
moveit_msgs::action::HybridPlanner::Goal goal_action_request_
rclcpp_action::Client< moveit_msgs::action::HybridPlanner >::SharedPtr hp_action_client_
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition utils.cpp:152
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
TEST_F(HybridPlanningFixture, ActionCompletion)
int main(int argc, char **argv)