42 #include <rclcpp/rclcpp.hpp>
48 #include <tf2_ros/buffer.h>
60 void load(
const rclcpp::Node::SharedPtr& node)
62 const std::string ns =
"planning_scene_monitor_options";
63 node->get_parameter_or(ns +
".name",
name, std::string(
"planning_scene_monitor"));
64 node->get_parameter_or(ns +
".robot_description",
robot_description, std::string(
"robot_description"));
87 void load(
const rclcpp::Node::SharedPtr& node)
89 const std::string ns =
"planning_pipelines.";
111 [[deprecated(
"Passing tf2_ros::Buffer to MoveItCpp's constructor is deprecated")]]
MoveItCpp(
112 const rclcpp::Node::SharedPtr& node,
const std::shared_ptr<tf2_ros::Buffer>& )
116 MoveItCpp(
const rclcpp::Node::SharedPtr& node);
117 [[deprecated(
"Passing tf2_ros::Buffer to MoveItCpp's constructor is deprecated")]]
MoveItCpp(
118 const rclcpp::Node::SharedPtr& node,
const Options&
options,
const std::shared_ptr<tf2_ros::Buffer>& )
142 const rclcpp::Node::SharedPtr&
getNode()
const;
146 bool getCurrentState(moveit::core::RobotStatePtr& current_state,
double wait_seconds);
150 moveit::core::RobotStatePtr
getCurrentState(
double wait_seconds = 0.0);
153 const std::map<std::string, planning_pipeline::PlanningPipelinePtr>&
getPlanningPipelines()
const;
163 const std::shared_ptr<tf2_ros::Buffer>&
getTFBuffer()
const;
173 bool blocking =
true);
177 rclcpp::Node::SharedPtr node_;
178 moveit::core::RobotModelConstPtr robot_model_;
179 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
182 std::map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
183 std::map<std::string, std::set<std::string>> groups_pipelines_map_;
184 std::map<std::string, std::set<std::string>> groups_algorithms_map_;
187 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
190 void clearContents();
MoveItCpp(MoveItCpp &&other)=default
const std::shared_ptr< tf2_ros::Buffer > & getTFBuffer() const
MoveItCpp & operator=(MoveItCpp &&other)=default
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...
MoveItCpp & operator=(const MoveItCpp &)=delete
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.
MoveItCpp(const rclcpp::Node::SharedPtr &node, const Options &options, const std::shared_ptr< tf2_ros::Buffer > &)
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 MoveItCpp &)=delete
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy....
MoveItCpp(const rclcpp::Node::SharedPtr &node, const std::shared_ptr< tf2_ros::Buffer > &)
Constructor.
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst()
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
static const std::string MONITORED_PLANNING_SCENE_TOPIC
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
moveit_cpp::MoveItCpp MoveItCpp
MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp)
MOVEIT_CLASS_FORWARD(MoveItCpp)
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
The reported execution status.
Parameter container for initializing MoveItCpp.
PlanningPipelineOptions planning_pipeline_options
Options(const rclcpp::Node::SharedPtr &node)
PlanningSceneMonitorOptions planning_scene_monitor_options
struct contains the the variables used for loading the planning pipeline
void load(const rclcpp::Node::SharedPtr &node)
std::vector< std::string > pipeline_names
std::string parent_namespace
Specification of options to use when constructing the MoveItCpp class.
void load(const rclcpp::Node::SharedPtr &node)
std::string robot_description
std::string publish_planning_scene_topic
std::string joint_state_topic
std::string monitored_planning_scene_topic
std::string attached_collision_object_topic
double wait_for_initial_state_timeout