moveit2
The MoveIt Motion Planning Framework for ROS 2.
local_planner_component.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, 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: Sebastian Jahr
36  Description: A local planner component node that is customizable through plugins that implement the local planning
37  problem solver algorithm and the trajectory matching and blending.
38  */
39 
40 #pragma once
41 
42 #include <rclcpp/rclcpp.hpp>
43 #include <rclcpp_action/rclcpp_action.hpp>
44 
45 #include <pluginlib/class_loader.hpp>
46 
47 #include <moveit_msgs/action/local_planner.hpp>
48 #include <moveit_msgs/msg/motion_plan_response.hpp>
49 #include <moveit_msgs/msg/robot_trajectory.hpp>
50 
51 #include <std_msgs/msg/float64.hpp>
52 #include <std_msgs/msg/float64_multi_array.hpp>
53 
54 #include <trajectory_msgs/msg/joint_trajectory.hpp>
55 
60 
61 #include <tf2_ros/buffer.h>
62 #include <tf2_ros/transform_listener.h>
63 
64 // Forward declaration of parameter class allows users to implement custom parameters
66 {
68 }
70 {
73 enum class LocalPlannerState : int8_t
74 {
75  ABORT = -1,
76  ERROR = 0,
77  UNCONFIGURED = 1,
80 };
81 
86 {
87 public:
89  LocalPlannerComponent(const rclcpp::NodeOptions& options);
90 
93  {
94  // Join the thread used for long-running callbacks
95  if (long_callback_thread_.joinable())
96  {
97  long_callback_thread_.join();
98  }
99  }
100 
107  bool initialize();
108 
112  void executeIteration();
113 
114  // This function is required to make this class a valid NodeClass
115  // see https://docs.ros2.org/foxy/api/rclcpp_components/register__node__macro_8hpp.html
116  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() // NOLINT
117  {
118  return node_->get_node_base_interface(); // NOLINT
119  }
120 
121 private:
123  void reset();
124 
125  std::shared_ptr<rclcpp::Node> node_;
126 
127  // Planner configuration
128  std::shared_ptr<local_planner_parameters::Params> config_;
129 
130  // Current planner state. Must be thread-safe
131  std::atomic<LocalPlannerState> state_;
132 
133  // Timer to periodically call executeIteration()
134  rclcpp::TimerBase::SharedPtr timer_;
135 
136  // Latest action goal handle
137  std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>> local_planning_goal_handle_;
138 
139  // Local planner feedback
140  std::shared_ptr<moveit_msgs::action::LocalPlanner::Feedback> local_planner_feedback_;
141 
142  // Planning scene monitor to get the current planning scene
143  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
144 
145  // TF
146  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
147  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
148 
149  // Global solution listener
150  rclcpp::Subscription<moveit_msgs::msg::MotionPlanResponse>::SharedPtr global_solution_subscriber_;
151 
152  // Local planning request action server
153  rclcpp_action::Server<moveit_msgs::action::LocalPlanner>::SharedPtr local_planning_request_server_;
154 
155  // Local solution publisher
156  rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr local_trajectory_publisher_;
157  rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr local_solution_publisher_;
158 
159  // Local constraint solver plugin loader
160  std::unique_ptr<pluginlib::ClassLoader<LocalConstraintSolverInterface>> local_constraint_solver_plugin_loader_;
161 
162  // Local constrain solver instance to compute a local solution each iteration
163  std::shared_ptr<LocalConstraintSolverInterface> local_constraint_solver_instance_;
164 
165  // Trajectory operator plugin
166  std::unique_ptr<pluginlib::ClassLoader<TrajectoryOperatorInterface>> trajectory_operator_loader_;
167 
168  // Trajectory_operator instance handle trajectory matching and blending
169  std::shared_ptr<TrajectoryOperatorInterface> trajectory_operator_instance_;
170 
171  // This thread is used for long-running callbacks. It's a member so they do not go out of scope.
172  std::thread long_callback_thread_;
173 
174  // A unique callback group, to avoid mixing callbacks with other action servers
175  rclcpp::CallbackGroup::SharedPtr cb_group_;
176 };
177 } // namespace moveit::hybrid_planning
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
LocalPlannerComponent(const rclcpp::NodeOptions &options)
Constructor.