Go to the documentation of this file.
58 struct PlanningSceneMonitorOptions
62 std::string ns =
"planning_scene_monitor_options/";
63 nh.
param<std::string>(ns +
"name",
name,
"planning_scene_monitor");
85 struct PlanningPipelineOptions
89 std::string ns =
"planning_pipelines/";
136 bool getCurrentState(moveit::core::RobotStatePtr& current_state,
double wait_seconds);
140 moveit::core::RobotStatePtr
getCurrentState(
double wait_seconds = 0.0);
143 const std::map<std::string, planning_pipeline::PlanningPipelinePtr>&
getPlanningPipelines()
const;
149 std::shared_ptr<const tf2_ros::Buffer>
getTFBuffer()
const;
159 bool blocking =
true);
166 std::shared_ptr<tf2_ros::TransformListener>
tf_listener_;
std::string publish_planning_scene_topic
planning_scene_monitor::PlanningSceneMonitorConstPtr getPlanningSceneMonitor() const
Get the stored instance of the planning scene monitor.
bool 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...
Parameter container for initializing MoveItCpp.
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
Options(const ros::NodeHandle &nh)
std::string joint_state_topic
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
MoveItCpp(const ros::NodeHandle &nh, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer={})
Constructor.
bool getParam(const std::string &key, bool &b) const
bool terminatePlanningPipeline(std::string const &pipeline_name)
Utility to terminate a given planning pipeline.
std::string monitored_planning_scene_topic
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
MoveItCpp & operator=(const MoveItCpp &)=delete
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
std::string robot_description
std::vector< std::string > pipeline_names
Specification of options to use when constructing the MoveItCpp class.
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst()
std::shared_ptr< const tf2_ros::Buffer > getTFBuffer() const
void load(const ros::NodeHandle &nh)
bool getCurrentState(moveit::core::RobotStatePtr ¤t_state, double wait_seconds)
Get the current state queried from the current state monitor.
MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp)
std::string attached_collision_object_topic
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst()
struct contains the the variables used for loading the planning pipeline
double wait_for_initial_state_timeout
const ros::NodeHandle & getNodeHandle() const
Get the ROS node handle of this instance operates on.
ros::NodeHandle node_handle_
trajectory_execution_manager::TrajectoryExecutionManagerConstPtr getTrajectoryExecutionManager() const
Get the stored instance of the trajectory execution manager.
PlanningPipelineOptions planning_pipeline_options
std::map< std::string, std::set< std::string > > groups_algorithms_map_
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines() const
Get all loaded planning pipeline instances mapped to their reference names.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
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.
bool loadPlanningSceneMonitor(const PlanningSceneMonitorOptions &options)
Initialize and setup the planning scene monitor.
static const std::string MONITORED_PLANNING_SCENE_TOPIC
T param(const std::string ¶m_name, const T &default_val) const
void load(const ros::NodeHandle &nh)
std::string parent_namespace
PlanningSceneMonitorOptions planning_scene_monitor_options
bool loadPlanningPipelines(const PlanningPipelineOptions &options)
Initialize and setup the planning pipelines.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
moveit_cpp::MoveItCpp MoveItCpp
MOVEIT_CLASS_FORWARD(MoveItCpp)
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:18