42 #include <moveit_msgs/msg/constraints.hpp>
46 using namespace std::chrono_literals;
50 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"local_planner_component");
51 const auto JOIN_THREAD_TIMEOUT = std::chrono::seconds(1);
54 constexpr
float PROGRESS_THRESHOLD = 0.995;
58 : node_{ std::make_shared<
rclcpp::Node>(
"local_planner_component",
options) }
61 local_planner_feedback_ = std::make_shared<moveit_msgs::action::LocalPlanner::Feedback>();
65 throw std::runtime_error(
"Failed to initialize local planner component");
80 RCLCPP_ERROR(LOGGER,
"When publishing a std_msgs/Float64MultiArray, you must select positions OR velocities. "
81 "Enabling both or none is not possible!");
87 planning_scene_monitor_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
88 node_,
"robot_description", tf_buffer_,
"local_planner/planning_scene_monitor");
89 if (!planning_scene_monitor_->getPlanningScene())
91 RCLCPP_ERROR(LOGGER,
"Unable to configure planning scene monitor");
103 trajectory_operator_loader_ = std::make_unique<pluginlib::ClassLoader<TrajectoryOperatorInterface>>(
104 "moveit_hybrid_planning",
"moveit::hybrid_planning::TrajectoryOperatorInterface");
106 catch (pluginlib::PluginlibException& ex)
108 RCLCPP_ERROR(LOGGER,
"Exception while creating trajectory operator plugin loader: '%s'", ex.what());
113 trajectory_operator_instance_ =
115 if (!trajectory_operator_instance_->initialize(node_, planning_scene_monitor_->getRobotModel(),
117 throw std::runtime_error(
"Unable to initialize trajectory operator plugin");
120 catch (pluginlib::PluginlibException& ex)
122 RCLCPP_ERROR(LOGGER,
"Exception while loading trajectory operator '%s': '%s'",
130 local_constraint_solver_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<LocalConstraintSolverInterface>>(
131 "moveit_hybrid_planning",
"moveit::hybrid_planning::LocalConstraintSolverInterface");
133 catch (pluginlib::PluginlibException& ex)
135 RCLCPP_ERROR(LOGGER,
"Exception while creating constraint solver plugin loader '%s'", ex.what());
140 local_constraint_solver_instance_ =
142 if (!local_constraint_solver_instance_->initialize(node_, planning_scene_monitor_, config_.
group_name))
143 throw std::runtime_error(
"Unable to initialize constraint solver plugin");
146 catch (pluginlib::PluginlibException& ex)
148 RCLCPP_ERROR(LOGGER,
"Exception while loading constraint solver '%s': '%s'",
154 cb_group_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
155 local_planning_request_server_ = rclcpp_action::create_server<moveit_msgs::action::LocalPlanner>(
158 [
this](
const rclcpp_action::GoalUUID& ,
159 const std::shared_ptr<const moveit_msgs::action::LocalPlanner::Goal>& ) {
160 RCLCPP_INFO(LOGGER,
"Received local planning goal request");
162 if (long_callback_thread_.joinable())
165 auto future = std::async(std::launch::async, &std::thread::join, &long_callback_thread_);
166 if (future.wait_for(JOIN_THREAD_TIMEOUT) == std::future_status::timeout)
168 RCLCPP_WARN(LOGGER,
"Another goal was running. Rejecting the new hybrid planning goal.");
169 return rclcpp_action::GoalResponse::REJECT;
172 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
175 [
this](
const std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>>& ) {
176 RCLCPP_INFO(LOGGER,
"Received request to cancel local planning goal");
178 if (long_callback_thread_.joinable())
180 long_callback_thread_.join();
182 return rclcpp_action::CancelResponse::ACCEPT;
185 [
this](std::shared_ptr<rclcpp_action::ServerGoalHandle<moveit_msgs::action::LocalPlanner>> goal_handle) {
186 local_planning_goal_handle_ = std::move(goal_handle);
188 if (long_callback_thread_.joinable())
190 long_callback_thread_.join();
194 auto local_planner_timer = [&]() {
196 node_->create_wall_timer(1s / config_.local_planning_frequency, [
this]() {
return executeIteration(); });
198 long_callback_thread_ = std::thread(local_planner_timer);
200 rcl_action_server_get_default_options(), cb_group_);
203 global_solution_subscriber_ = node_->create_subscription<moveit_msgs::msg::MotionPlanResponse>(
204 config_.global_solution_topic, rclcpp::SystemDefaultsQoS(),
205 [
this](
const moveit_msgs::msg::MotionPlanResponse::ConstSharedPtr& msg) {
210 new_trajectory.setRobotTrajectoryMsg(start_state, msg->trajectory);
211 *local_planner_feedback_ = trajectory_operator_instance_->addTrajectorySegment(new_trajectory);
215 if (!local_planner_feedback_->feedback.empty())
217 local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
225 RCLCPP_INFO(LOGGER,
"Using '%s' as local solution topic type", config_.local_solution_topic_type.c_str());
226 if (config_.local_solution_topic_type ==
"trajectory_msgs/JointTrajectory")
228 local_trajectory_publisher_ =
229 node_->create_publisher<trajectory_msgs::msg::JointTrajectory>(config_.local_solution_topic, 1);
231 else if (config_.local_solution_topic_type ==
"std_msgs/Float64MultiArray")
233 local_solution_publisher_ =
234 node_->create_publisher<std_msgs::msg::Float64MultiArray>(config_.local_solution_topic, 1);
236 else if (config_.local_solution_topic_type ==
"CUSTOM")
245 void LocalPlannerComponent::executeIteration()
247 auto result = std::make_shared<moveit_msgs::action::LocalPlanner::Result>();
253 case LocalPlannerState::AWAIT_GLOBAL_TRAJECTORY:
257 case LocalPlannerState::ABORT:
259 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
260 result->error_message =
"Local planner is in an aborted state. Resetting.";
261 local_planning_goal_handle_->abort(result);
266 case LocalPlannerState::LOCAL_PLANNING_ACTIVE:
268 planning_scene_monitor_->updateSceneWithCurrentState();
273 return ls->getCurrentState();
277 if (trajectory_operator_instance_->getTrajectoryProgress(current_robot_state) > PROGRESS_THRESHOLD)
279 local_planning_goal_handle_->succeed(result);
287 *local_planner_feedback_ =
288 trajectory_operator_instance_->getLocalTrajectory(current_robot_state, local_trajectory);
292 if (!local_planner_feedback_->feedback.empty())
294 local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
295 RCLCPP_ERROR(LOGGER,
"Local planner somehow failed");
301 trajectory_msgs::msg::JointTrajectory local_solution;
305 *local_planner_feedback_ = local_constraint_solver_instance_->solve(
306 local_trajectory, local_planning_goal_handle_->get_goal(), local_solution);
309 if (!local_planner_feedback_->feedback.empty())
311 local_planning_goal_handle_->publish_feedback(local_planner_feedback_);
319 if (config_.local_solution_topic_type ==
"trajectory_msgs/JointTrajectory")
321 local_trajectory_publisher_->publish(local_solution);
323 else if (config_.local_solution_topic_type ==
"std_msgs/Float64MultiArray")
326 auto joints = std::make_unique<std_msgs::msg::Float64MultiArray>();
327 if (!local_solution.points.empty())
329 if (config_.publish_joint_positions)
331 joints->data = local_solution.points[0].positions;
333 else if (config_.publish_joint_velocities)
335 joints->data = local_solution.points[0].velocities;
338 local_solution_publisher_->publish(std::move(joints));
340 else if (config_.local_solution_topic_type ==
"CUSTOM")
348 result->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
349 result->error_message =
"Unexpected failure.";
350 local_planning_goal_handle_->abort(result);
351 RCLCPP_ERROR(LOGGER,
"Local planner somehow failed");
358 void LocalPlannerComponent::reset()
360 local_constraint_solver_instance_->reset();
361 trajectory_operator_instance_->reset();
363 state_ = LocalPlannerState::AWAIT_GLOBAL_TRAJECTORY;
368 #include <rclcpp_components/register_node_macro.hpp>
Representation of a robot's state. This includes position, velocity, acceleration and effort.
LocalPlannerComponent(const rclcpp::NodeOptions &options)
Constructor.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
@ AWAIT_GLOBAL_TRAJECTORY
const rclcpp::Logger LOGGER
std::string joint_states_topic
void load(const rclcpp::Node::SharedPtr &node)
std::string collision_object_topic
std::string local_planning_action_name
std::string local_constraint_solver_plugin_name
std::string monitored_planning_scene_topic
std::string local_solution_topic_type
std::string trajectory_operator_plugin_name
bool publish_joint_velocities
bool publish_joint_positions