41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42 #include <geometry_msgs/msg/quaternion_stamped.hpp>
46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros_planning_interface.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);
63 robot_model_ = planning_scene_monitor_->getRobotModel();
66 const std::string error =
"Unable to construct robot model. Please make sure all needed information is on the "
68 RCLCPP_FATAL_STREAM(LOGGER, error);
69 throw std::runtime_error(error);
72 bool load_planning_pipelines =
true;
73 if (load_planning_pipelines && !loadPlanningPipelines(
options.planning_pipeline_options))
75 const std::string error =
"Failed to load planning pipelines from parameter server";
76 RCLCPP_FATAL_STREAM(LOGGER, error);
77 throw std::runtime_error(error);
80 trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
81 node_, robot_model_, planning_scene_monitor_->getStateMonitor());
83 RCLCPP_DEBUG(LOGGER,
"MoveItCpp running");
88 RCLCPP_INFO(LOGGER,
"Deleting MoveItCpp");
92 bool MoveItCpp::loadPlanningSceneMonitor(
const PlanningSceneMonitorOptions&
options)
94 planning_scene_monitor_ =
95 std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_,
options.robot_description,
options.name);
97 RCLCPP_DEBUG(LOGGER,
"Configuring Planning Scene Monitor");
98 if (planning_scene_monitor_->getPlanningScene())
101 RCLCPP_INFO(LOGGER,
"Listening to '%s' for joint states",
options.joint_state_topic.c_str());
103 planning_scene_monitor_->startStateMonitor(
options.joint_state_topic,
options.attached_collision_object_topic);
106 options.monitored_planning_scene_topic);
108 planning_scene_monitor_->startSceneMonitor(
options.publish_planning_scene_topic);
110 planning_scene_monitor_->startWorldGeometryMonitor();
114 RCLCPP_ERROR(LOGGER,
"Planning scene not configured");
119 if (
options.wait_for_initial_state_timeout > 0.0)
121 return planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(),
122 options.wait_for_initial_state_timeout);
128 bool MoveItCpp::loadPlanningPipelines(
const PlanningPipelineOptions&
options)
132 for (
const auto& planning_pipeline_name :
options.pipeline_names)
134 if (planning_pipelines_.count(planning_pipeline_name) > 0)
136 RCLCPP_WARN(LOGGER,
"Skipping duplicate entry for planning pipeline '%s'.", planning_pipeline_name.c_str());
139 RCLCPP_INFO(LOGGER,
"Loading planning pipeline '%s'", planning_pipeline_name.c_str());
140 planning_pipeline::PlanningPipelinePtr pipeline;
141 pipeline = std::make_shared<planning_pipeline::PlanningPipeline>(robot_model_, node_, planning_pipeline_name,
144 if (!pipeline->getPlannerManager())
146 RCLCPP_ERROR(LOGGER,
"Failed to initialize planning pipeline '%s'.", planning_pipeline_name.c_str());
150 planning_pipelines_[planning_pipeline_name] = pipeline;
153 if (planning_pipelines_.empty())
155 RCLCPP_ERROR(LOGGER,
"Failed to load any planning pipelines.");
160 std::vector<std::string> group_names = robot_model_->getJointModelGroupNames();
161 for (
const auto& pipeline_entry : planning_pipelines_)
163 for (
const auto& group_name : group_names)
165 const auto& pipeline = pipeline_entry.second;
166 for (
const auto& planner_configuration : pipeline->getPlannerManager()->getPlannerConfigurations())
168 if (planner_configuration.second.group == group_name)
170 groups_pipelines_map_[group_name].insert(pipeline_entry.first);
191 if (wait_seconds > 0.0 && !planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(), wait_seconds))
193 RCLCPP_ERROR(LOGGER,
"Did not receive robot state");
198 current_state = std::make_shared<moveit::core::RobotState>(
scene->getCurrentState());
205 moveit::core::RobotStatePtr current_state;
207 return current_state;
212 return planning_pipelines_;
217 if (group_name.empty() || groups_pipelines_map_.count(group_name) == 0)
219 RCLCPP_ERROR(LOGGER,
"No planning pipelines loaded for group '%s'. Check planning pipeline and controller setup.",
224 return groups_pipelines_map_.at(group_name);
229 return planning_scene_monitor_;
234 return planning_scene_monitor_;
239 return trajectory_execution_manager_;
244 return trajectory_execution_manager_;
253 RCLCPP_ERROR(LOGGER,
"Robot trajectory is undefined");
258 if (!trajectory_execution_manager_->ensureActiveControllersForGroup(group_name))
260 RCLCPP_ERROR(LOGGER,
"Execution failed! No active controllers configured for group '%s'", group_name.c_str());
265 moveit_msgs::msg::RobotTrajectory robot_trajectory_msg;
269 trajectory_execution_manager_->push(robot_trajectory_msg);
270 trajectory_execution_manager_->execute();
271 return trajectory_execution_manager_->waitForExecution();
273 trajectory_execution_manager_->pushAndExecute(robot_trajectory_msg);
279 return planning_scene_monitor_->getTFClient();
282 void MoveItCpp::clearContents()
284 planning_scene_monitor_.reset();
285 robot_model_.reset();
286 planning_pipelines_.clear();
const std::shared_ptr< tf2_ros::Buffer > & getTFBuffer() const
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
moveit_controller_manager::ExecutionStatus execute(const std::string &group_name, const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking=true)
Execute a trajectory on the planning group specified by group_name using the trajectory execution man...
std::set< std::string > getPlanningPipelineNames(const std::string &group_name="") const
Get the names of all loaded planning pipelines. Specify group_name to filter the results by planning ...
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines() const
Get all loaded planning pipeline instances mapped to their reference names.
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
Get the stored instance of the trajectory execution manager.
const planning_scene_monitor::PlanningSceneMonitorPtr & 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, const std::shared_ptr< tf2_ros::Buffer > &)
Constructor.
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.
constexpr char PLANNING_PLUGIN_PARAM[]
const rclcpp::Logger LOGGER
The reported execution status.
Parameter container for initializing MoveItCpp.