moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | List of all members
moveit_cpp::PlanningComponent Class Reference

#include <planning_component.h>

Classes

struct  MultiPipelinePlanRequestParameters
 Planner parameters provided with the MotionPlanRequest. More...
 
struct  PlanRequestParameters
 Planner parameters provided with the MotionPlanRequest. More...
 

Public Member Functions

 PlanningComponent (const std::string &group_name, const rclcpp::Node::SharedPtr &node)
 Constructor. More...
 
 PlanningComponent (const std::string &group_name, const MoveItCppPtr &moveit_cpp)
 
 PlanningComponent (const PlanningComponent &)=delete
 This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy. Pass by references, move it, or simply create multiple instances where required. More...
 
PlanningComponentoperator= (const PlanningComponent &)=delete
 
 PlanningComponent (PlanningComponent &&other)=delete
 
PlanningComponentoperator= (PlanningComponent &&other)=delete
 
 ~PlanningComponent ()=default
 Destructor. More...
 
const std::string & getPlanningGroupName () const
 Get the name of the planning group. More...
 
const std::vector< std::string > getNamedTargetStates ()
 Get the names of the named robot states available as targets. More...
 
std::map< std::string, double > getNamedTargetStateValues (const std::string &name)
 Get the joint values for targets specified by name. More...
 
void setWorkspace (double minx, double miny, double minz, double maxx, double maxy, double maxz)
 Specify the workspace bounding box. The box is specified in the planning frame (i.e. relative to the robot root link start position). This is useful when the planning group contains the root joint of the robot – i.e. when planning motion for the robot relative to the world. More...
 
void unsetWorkspace ()
 Remove the workspace bounding box from planning. More...
 
moveit::core::RobotStatePtr getStartState ()
 Get the considered start state if defined, otherwise get the current state. More...
 
bool setStartState (const moveit::core::RobotState &start_state)
 Set the robot state that should be considered as start state for planning. More...
 
bool setStartState (const std::string &named_state)
 Set the named robot state that should be considered as start state for planning. More...
 
void setStartStateToCurrentState ()
 Set the start state for planning to be the current state of the robot. More...
 
bool setGoal (const std::vector< moveit_msgs::msg::Constraints > &goal_constraints)
 Set the goal constraints used for planning. More...
 
bool setGoal (const moveit::core::RobotState &goal_state)
 Set the goal constraints generated from a target state. More...
 
bool setGoal (const geometry_msgs::msg::PoseStamped &goal_pose, const std::string &link_name)
 Set the goal constraints generated from target pose and robot link. More...
 
bool setGoal (const std::string &named_target)
 Set the goal constraints generated from a named target state. More...
 
bool setPathConstraints (const moveit_msgs::msg::Constraints &path_constraints)
 Set the path constraints generated from a moveit msg Constraints. More...
 
bool setTrajectoryConstraints (const moveit_msgs::msg::TrajectoryConstraints &trajectory_constraints)
 Set the trajectory constraints generated from a moveit msg Constraints. More...
 
planning_interface::MotionPlanResponse plan ()
 Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using default parameters. More...
 
planning_interface::MotionPlanResponse plan (const PlanRequestParameters &parameters, planning_scene::PlanningScenePtr planning_scene=nullptr)
 Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters. More...
 
planning_interface::MotionPlanResponse plan (const MultiPipelinePlanRequestParameters &parameters, const moveit::planning_pipeline_interfaces::SolutionSelectionFunction &solution_selection_function=&moveit::planning_pipeline_interfaces::getShortestSolution, const moveit::planning_pipeline_interfaces::StoppingCriterionFunction &stopping_criterion_callback=nullptr, planning_scene::PlanningScenePtr planning_scene=nullptr)
 Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters. This defaults to taking the full planning time (null stopping_criterion_callback) and finding the shortest solution in joint space. More...
 
bool execute (bool)
 Execute the latest computed solution trajectory computed by plan(). By default this function terminates after the execution is complete. The execution can be run in background by setting blocking to false. More...
 
::planning_interface::MotionPlanRequest getMotionPlanRequest (const PlanRequestParameters &plan_request_parameters)
 Utility function to get a MotionPlanRequest from PlanRequestParameters and the internal state of the PlanningComponent instance. More...
 
std::vector<::planning_interface::MotionPlanRequestgetMotionPlanRequestVector (const MultiPipelinePlanRequestParameters &multi_pipeline_plan_request_parameters)
 Utility function to get a Vector of MotionPlanRequest from a vector of PlanRequestParameters and the internal state of the PlanningComponent instance. More...
 

Detailed Description

Definition at line 55 of file planning_component.h.

Constructor & Destructor Documentation

◆ PlanningComponent() [1/4]

moveit_cpp::PlanningComponent::PlanningComponent ( const std::string &  group_name,
const rclcpp::Node::SharedPtr &  node 
)

Constructor.

Definition at line 65 of file planning_component.cpp.

◆ PlanningComponent() [2/4]

moveit_cpp::PlanningComponent::PlanningComponent ( const std::string &  group_name,
const MoveItCppPtr &  moveit_cpp 
)

Definition at line 50 of file planning_component.cpp.

◆ PlanningComponent() [3/4]

moveit_cpp::PlanningComponent::PlanningComponent ( const PlanningComponent )
delete

This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy. Pass by references, move it, or simply create multiple instances where required.

◆ PlanningComponent() [4/4]

moveit_cpp::PlanningComponent::PlanningComponent ( PlanningComponent &&  other)
delete

◆ ~PlanningComponent()

moveit_cpp::PlanningComponent::~PlanningComponent ( )
default

Destructor.

Member Function Documentation

◆ execute()

bool moveit_cpp::PlanningComponent::execute ( bool  )
inline

Execute the latest computed solution trajectory computed by plan(). By default this function terminates after the execution is complete. The execution can be run in background by setting blocking to false.

Definition at line 212 of file planning_component.h.

◆ getMotionPlanRequest()

planning_interface::MotionPlanRequest moveit_cpp::PlanningComponent::getMotionPlanRequest ( const PlanRequestParameters plan_request_parameters)

Utility function to get a MotionPlanRequest from PlanRequestParameters and the internal state of the PlanningComponent instance.

Definition at line 326 of file planning_component.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getMotionPlanRequestVector()

std::vector<::planning_interface::MotionPlanRequest > moveit_cpp::PlanningComponent::getMotionPlanRequestVector ( const MultiPipelinePlanRequestParameters multi_pipeline_plan_request_parameters)

Utility function to get a Vector of MotionPlanRequest from a vector of PlanRequestParameters and the internal state of the PlanningComponent instance.

Definition at line 355 of file planning_component.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getNamedTargetStates()

const std::vector< std::string > moveit_cpp::PlanningComponent::getNamedTargetStates ( )

Get the names of the named robot states available as targets.

Definition at line 77 of file planning_component.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getNamedTargetStateValues()

std::map< std::string, double > moveit_cpp::PlanningComponent::getNamedTargetStateValues ( const std::string &  name)

Get the joint values for targets specified by name.

Definition at line 268 of file planning_component.cpp.

Here is the call graph for this function:

◆ getPlanningGroupName()

const std::string & moveit_cpp::PlanningComponent::getPlanningGroupName ( ) const

Get the name of the planning group.

Definition at line 92 of file planning_component.cpp.

◆ getStartState()

moveit::core::RobotStatePtr moveit_cpp::PlanningComponent::getStartState ( )

Get the considered start state if defined, otherwise get the current state.

Definition at line 235 of file planning_component.cpp.

◆ operator=() [1/2]

PlanningComponent& moveit_cpp::PlanningComponent::operator= ( const PlanningComponent )
delete

◆ operator=() [2/2]

PlanningComponent& moveit_cpp::PlanningComponent::operator= ( PlanningComponent &&  other)
delete

◆ plan() [1/3]

planning_interface::MotionPlanResponse moveit_cpp::PlanningComponent::plan ( )

Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using default parameters.

Definition at line 214 of file planning_component.cpp.

Here is the call graph for this function:

◆ plan() [2/3]

planning_interface::MotionPlanResponse moveit_cpp::PlanningComponent::plan ( const MultiPipelinePlanRequestParameters parameters,
const moveit::planning_pipeline_interfaces::SolutionSelectionFunction solution_selection_function = &moveit::planning_pipeline_interfaces::getShortestSolution,
const moveit::planning_pipeline_interfaces::StoppingCriterionFunction stopping_criterion_callback = nullptr,
planning_scene::PlanningScenePtr  planning_scene = nullptr 
)

Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters. This defaults to taking the full planning time (null stopping_criterion_callback) and finding the shortest solution in joint space.

Definition at line 151 of file planning_component.cpp.

Here is the call graph for this function:

◆ plan() [3/3]

planning_interface::MotionPlanResponse moveit_cpp::PlanningComponent::plan ( const PlanRequestParameters parameters,
planning_scene::PlanningScenePtr  planning_scene = nullptr 
)

Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters.

Definition at line 109 of file planning_component.cpp.

Here is the call graph for this function:

◆ setGoal() [1/4]

bool moveit_cpp::PlanningComponent::setGoal ( const geometry_msgs::msg::PoseStamped &  goal_pose,
const std::string &  link_name 
)

Set the goal constraints generated from target pose and robot link.

Definition at line 306 of file planning_component.cpp.

Here is the call graph for this function:

◆ setGoal() [2/4]

bool moveit_cpp::PlanningComponent::setGoal ( const moveit::core::RobotState goal_state)

Set the goal constraints generated from a target state.

Definition at line 300 of file planning_component.cpp.

Here is the call graph for this function:

◆ setGoal() [3/4]

bool moveit_cpp::PlanningComponent::setGoal ( const std::string &  named_target)

Set the goal constraints generated from a named target state.

Definition at line 312 of file planning_component.cpp.

Here is the call graph for this function:

◆ setGoal() [4/4]

bool moveit_cpp::PlanningComponent::setGoal ( const std::vector< moveit_msgs::msg::Constraints > &  goal_constraints)

Set the goal constraints used for planning.

Definition at line 294 of file planning_component.cpp.

Here is the caller graph for this function:

◆ setPathConstraints()

bool moveit_cpp::PlanningComponent::setPathConstraints ( const moveit_msgs::msg::Constraints &  path_constraints)

Set the path constraints generated from a moveit msg Constraints.

Definition at line 97 of file planning_component.cpp.

◆ setStartState() [1/2]

bool moveit_cpp::PlanningComponent::setStartState ( const moveit::core::RobotState start_state)

Set the robot state that should be considered as start state for planning.

Definition at line 229 of file planning_component.cpp.

Here is the caller graph for this function:

◆ setStartState() [2/2]

bool moveit_cpp::PlanningComponent::setStartState ( const std::string &  named_state)

Set the named robot state that should be considered as start state for planning.

Definition at line 249 of file planning_component.cpp.

Here is the call graph for this function:

◆ setStartStateToCurrentState()

void moveit_cpp::PlanningComponent::setStartStateToCurrentState ( )

Set the start state for planning to be the current state of the robot.

Definition at line 263 of file planning_component.cpp.

◆ setTrajectoryConstraints()

bool moveit_cpp::PlanningComponent::setTrajectoryConstraints ( const moveit_msgs::msg::TrajectoryConstraints &  trajectory_constraints)

Set the trajectory constraints generated from a moveit msg Constraints.

Definition at line 103 of file planning_component.cpp.

◆ setWorkspace()

void moveit_cpp::PlanningComponent::setWorkspace ( double  minx,
double  miny,
double  minz,
double  maxx,
double  maxy,
double  maxz 
)

Specify the workspace bounding box. The box is specified in the planning frame (i.e. relative to the robot root link start position). This is useful when the planning group contains the root joint of the robot – i.e. when planning motion for the robot relative to the world.

Definition at line 276 of file planning_component.cpp.

◆ unsetWorkspace()

void moveit_cpp::PlanningComponent::unsetWorkspace ( )

Remove the workspace bounding box from planning.

Definition at line 289 of file planning_component.cpp.


The documentation for this class was generated from the following files: