42#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
43#include <geometry_msgs/msg/quaternion_stamped.hpp>
53 : node_(node), logger_(
moveit::getLogger(
"moveit.ros.moveit_cpp"))
56 if (!loadPlanningSceneMonitor(options.planning_scene_monitor_options))
58 const std::string error =
"Unable to configure planning scene monitor";
59 RCLCPP_FATAL_STREAM(logger_, error);
60 throw std::runtime_error(error);
65 const std::string error =
"Unable to construct robot model. Please make sure all needed information is on the "
67 RCLCPP_FATAL_STREAM(logger_, error);
68 throw std::runtime_error(error);
71 bool load_planning_pipelines =
true;
72 if (load_planning_pipelines && !loadPlanningPipelines(options.planning_pipeline_options))
74 const std::string error =
"Failed to load planning pipelines from parameter server";
75 RCLCPP_FATAL_STREAM(logger_, error);
76 throw std::runtime_error(error);
79 trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
80 node_,
getRobotModel(), planning_scene_monitor_->getStateMonitor());
82 RCLCPP_DEBUG(logger_,
"MoveItCpp running");
87 RCLCPP_INFO(logger_,
"Deleting MoveItCpp");
90bool MoveItCpp::loadPlanningSceneMonitor(
const PlanningSceneMonitorOptions& options)
92 planning_scene_monitor_ =
93 std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, options.robot_description, options.name);
95 RCLCPP_DEBUG(logger_,
"Configuring Planning Scene Monitor");
96 if (planning_scene_monitor_->getPlanningScene())
99 RCLCPP_INFO(logger_,
"Listening to '%s' for joint states", options.joint_state_topic.c_str());
101 planning_scene_monitor_->startStateMonitor(options.joint_state_topic, options.attached_collision_object_topic);
104 options.monitored_planning_scene_topic);
106 planning_scene_monitor_->startSceneMonitor(options.publish_planning_scene_topic);
108 planning_scene_monitor_->startWorldGeometryMonitor();
112 RCLCPP_ERROR(logger_,
"Planning scene not configured");
117 if (
options.wait_for_initial_state_timeout > 0.0)
119 return planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(),
120 options.wait_for_initial_state_timeout);
126bool MoveItCpp::loadPlanningPipelines(
const PlanningPipelineOptions& options)
129 planning_pipelines_ =
132 if (planning_pipelines_.empty())
134 RCLCPP_ERROR(logger_,
"Failed to load any planning pipelines.");
142 return planning_scene_monitor_->getRobotModel();
152 if (wait_seconds > 0.0 && !planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(), wait_seconds))
154 RCLCPP_ERROR(logger_,
"Did not receive robot state");
159 current_state = std::make_shared<moveit::core::RobotState>(scene->getCurrentState());
166 moveit::core::RobotStatePtr current_state;
168 return current_state;
173 return planning_pipelines_;
178 return planning_scene_monitor_;
183 return planning_scene_monitor_;
188 return trajectory_execution_manager_;
193 return trajectory_execution_manager_;
198 const std::vector<std::string>& )
205 const std::vector<std::string>& controllers)
209 RCLCPP_ERROR(logger_,
"Robot trajectory is undefined");
216 if (!trajectory_execution_manager_->ensureActiveControllersForGroup(group_name))
218 RCLCPP_ERROR(logger_,
"Execution failed! No active controllers configured for group '%s'", group_name.c_str());
223 moveit_msgs::msg::RobotTrajectory robot_trajectory_msg;
225 trajectory_execution_manager_->push(robot_trajectory_msg, controllers);
226 trajectory_execution_manager_->execute();
227 return trajectory_execution_manager_->waitForExecution();
241 catch (
const std::out_of_range& oor)
243 RCLCPP_ERROR(logger_,
"Cannot terminate pipeline '%s' because no pipeline with that name exists",
244 pipeline_name.c_str());
251 return planning_scene_monitor_->getTFClient();
255 return planning_scene_monitor_->getTFClient();
std::shared_ptr< const tf2_ros::Buffer > getTFBuffer() const
moveit_controller_manager::ExecutionStatus execute(const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking, const std::vector< std::string > &controllers=std::vector< std::string >())
Execute a trajectory on the planning group specified by the robot's trajectory using the trajectory e...
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines() const
Get all loaded planning pipeline instances mapped to their reference names.
planning_scene_monitor::PlanningSceneMonitorConstPtr getPlanningSceneMonitor() const
Get the stored instance of the planning scene monitor.
bool getCurrentState(moveit::core::RobotStatePtr ¤t_state, double wait_seconds)
Get the current state queried from the current state monitor.
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst()
const rclcpp::Node::SharedPtr & getNode() const
Get the ROS node this instance operates on.
MoveItCpp(const rclcpp::Node::SharedPtr &node)
Constructor.
bool terminatePlanningPipeline(const std::string &pipeline_name)
Utility to terminate the given planning pipeline.
trajectory_execution_manager::TrajectoryExecutionManagerConstPtr getTrajectoryExecutionManager() const
Get the stored instance of the trajectory execution manager.
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
@ UPDATE_SCENE
The entire scene was updated.
std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > createPlanningPipelineMap(const std::vector< std::string > &pipeline_names, const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace=std::string())
Utility function to create a map of named planning pipelines.
Main namespace for MoveIt.
The reported execution status.
Parameter container for initializing MoveItCpp.