#include <planning_component.h>
Classes | |
struct | MultiPipelinePlanRequestParameters |
Planner parameters provided with the MotionPlanRequest. More... | |
struct | PlanRequestParameters |
Planner parameters provided with the MotionPlanRequest. More... | |
class | PlanSolutions |
Public Types | |
using | MoveItErrorCode = moveit::core::MoveItErrorCode |
typedef std::function< planning_interface::MotionPlanResponse(std::vector< planning_interface::MotionPlanResponse > const &solutions)> | SolutionCallbackFunction |
A solution callback function type for the parallel planning API of planning component. More... | |
typedef std::function< bool(PlanSolutions const &solutions, MultiPipelinePlanRequestParameters const &plan_request_parameters)> | StoppingCriterionFunction |
A stopping criterion callback function for the parallel planning API of planning component. More... | |
Public Member Functions | |
bool | execute (bool blocking=true) |
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::MotionPlanResponse const & | getLastMotionPlanResponse () |
Return the last plan solution. 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... | |
const std::string & | getPlanningGroupName () const |
Get the name of the planning group. More... | |
moveit::core::RobotStatePtr | getStartState () |
Get the considered start state if defined, otherwise get the current state. More... | |
PlanningComponent & | operator= (const PlanningComponent &)=delete |
PlanningComponent & | operator= (PlanningComponent &&other)=delete |
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 MultiPipelinePlanRequestParameters ¶meters, const SolutionCallbackFunction &solution_selection_callback=&getShortestSolution, const StoppingCriterionFunction &stopping_criterion_callback=StoppingCriterionFunction()) |
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 PlanRequestParameters ¶meters, const bool store_solution=true) |
Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters. More... | |
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... | |
PlanningComponent (const std::string &group_name, const MoveItCppPtr &moveit_cpp) | |
PlanningComponent (const std::string &group_name, const ros::NodeHandle &nh) | |
Constructor. More... | |
PlanningComponent (PlanningComponent &&other)=default | |
bool | setGoal (const geometry_msgs::PoseStamped &goal_pose, const std::string &link_name) |
Set the goal constraints generated from target pose and robot link. More... | |
bool | setGoal (const moveit::core::RobotState &goal_state) |
Set the goal constraints generated from a target state. More... | |
bool | setGoal (const std::string &named_target) |
Set the goal constraints generated from a named target state. More... | |
bool | setGoal (const std::vector< moveit_msgs::Constraints > &goal_constraints) |
Set the goal constraints used for planning. More... | |
bool | setPathConstraints (const moveit_msgs::Constraints &path_constraints) |
Set the path constraints used for planning. 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 | setTrajectoryConstraints (const moveit_msgs::TrajectoryConstraints &trajectory_constraints) |
Set the trajectory constraints generated from a moveit msg Constraints. 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... | |
~PlanningComponent () | |
Destructor. More... | |
Private Member Functions | |
void | clearContents () |
Reset all member variables. More... | |
Private Attributes | |
moveit::core::RobotStatePtr | considered_start_state_ |
std::vector< moveit_msgs::Constraints > | current_goal_constraints_ |
moveit_msgs::Constraints | current_path_constraints_ |
moveit_msgs::TrajectoryConstraints | current_trajectory_constraints_ |
const std::string | group_name_ |
const moveit::core::JointModelGroup * | joint_model_group_ |
planning_interface::MotionPlanResponse | last_plan_solution_ |
MoveItCppPtr | moveit_cpp_ |
ros::NodeHandle | nh_ |
PlanRequestParameters | plan_request_parameters_ |
moveit_msgs::WorkspaceParameters | workspace_parameters_ |
bool | workspace_parameters_set_ = false |
Definition at line 87 of file planning_component.h.
Definition at line 90 of file planning_component.h.
typedef std::function<planning_interface::MotionPlanResponse( std::vector<planning_interface::MotionPlanResponse> const& solutions)> moveit_cpp::PlanningComponent::SolutionCallbackFunction |
A solution callback function type for the parallel planning API of planning component.
Definition at line 171 of file planning_component.h.
typedef std::function<bool(PlanSolutions const& solutions, MultiPipelinePlanRequestParameters const& plan_request_parameters)> moveit_cpp::PlanningComponent::StoppingCriterionFunction |
A stopping criterion callback function for the parallel planning API of planning component.
Definition at line 175 of file planning_component.h.
moveit_cpp::PlanningComponent::PlanningComponent | ( | const std::string & | group_name, |
const ros::NodeHandle & | nh | ||
) |
Constructor.
Definition at line 103 of file planning_component.cpp.
moveit_cpp::PlanningComponent::PlanningComponent | ( | const std::string & | group_name, |
const MoveItCppPtr & | moveit_cpp | ||
) |
Definition at line 82 of file planning_component.cpp.
|
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.
|
default |
moveit_cpp::PlanningComponent::~PlanningComponent | ( | ) |
Destructor.
Definition at line 108 of file planning_component.cpp.
|
private |
Reset all member variables.
Definition at line 484 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::execute | ( | bool | blocking = true | ) |
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 427 of file planning_component.cpp.
planning_interface::MotionPlanResponse const & moveit_cpp::PlanningComponent::getLastMotionPlanResponse | ( | ) |
Return the last plan solution.
Definition at line 446 of file planning_component.cpp.
const std::vector< std::string > moveit_cpp::PlanningComponent::getNamedTargetStates | ( | ) |
Get the names of the named robot states available as targets.
Definition at line 114 of file planning_component.cpp.
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 370 of file planning_component.cpp.
const std::string & moveit_cpp::PlanningComponent::getPlanningGroupName | ( | ) | const |
Get the name of the planning group.
Definition at line 129 of file planning_component.cpp.
moveit::core::RobotStatePtr moveit_cpp::PlanningComponent::getStartState | ( | ) |
Get the considered start state if defined, otherwise get the current state.
Definition at line 340 of file planning_component.cpp.
|
delete |
|
delete |
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 329 of file planning_component.cpp.
planning_interface::MotionPlanResponse moveit_cpp::PlanningComponent::plan | ( | const MultiPipelinePlanRequestParameters & | parameters, |
const SolutionCallbackFunction & | solution_selection_callback = &getShortestSolution , |
||
const StoppingCriterionFunction & | stopping_criterion_callback = StoppingCriterionFunction() |
||
) |
Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters.
Definition at line 260 of file planning_component.cpp.
planning_interface::MotionPlanResponse moveit_cpp::PlanningComponent::plan | ( | const PlanRequestParameters & | parameters, |
const bool | store_solution = true |
||
) |
Run a plan from start or current state to fulfill the last goal constraints provided by setGoal() using the provided PlanRequestParameters.
Definition at line 146 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setGoal | ( | const geometry_msgs::PoseStamped & | goal_pose, |
const std::string & | link_name | ||
) |
Set the goal constraints generated from target pose and robot link.
Definition at line 408 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setGoal | ( | const moveit::core::RobotState & | goal_state | ) |
Set the goal constraints generated from a target state.
Definition at line 402 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setGoal | ( | const std::string & | named_target | ) |
Set the goal constraints generated from a named target state.
Definition at line 414 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setGoal | ( | const std::vector< moveit_msgs::Constraints > & | goal_constraints | ) |
Set the goal constraints used for planning.
Definition at line 396 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setPathConstraints | ( | const moveit_msgs::Constraints & | path_constraints | ) |
Set the path constraints used for planning.
Definition at line 134 of file planning_component.cpp.
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 334 of file planning_component.cpp.
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 352 of file planning_component.cpp.
void moveit_cpp::PlanningComponent::setStartStateToCurrentState | ( | ) |
Set the start state for planning to be the current state of the robot.
Definition at line 365 of file planning_component.cpp.
bool moveit_cpp::PlanningComponent::setTrajectoryConstraints | ( | const moveit_msgs::TrajectoryConstraints & | trajectory_constraints | ) |
Set the trajectory constraints generated from a moveit msg Constraints.
Definition at line 140 of file planning_component.cpp.
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 378 of file planning_component.cpp.
void moveit_cpp::PlanningComponent::unsetWorkspace | ( | ) |
Remove the workspace bounding box from planning.
Definition at line 391 of file planning_component.cpp.
|
private |
Definition at line 270 of file planning_component.h.
|
private |
Definition at line 271 of file planning_component.h.
|
private |
Definition at line 273 of file planning_component.h.
|
private |
Definition at line 272 of file planning_component.h.
|
private |
Definition at line 264 of file planning_component.h.
|
private |
Definition at line 266 of file planning_component.h.
|
private |
Definition at line 277 of file planning_component.h.
|
private |
Definition at line 263 of file planning_component.h.
|
private |
Definition at line 262 of file planning_component.h.
|
private |
Definition at line 274 of file planning_component.h.
|
private |
Definition at line 275 of file planning_component.h.
|
private |
Definition at line 276 of file planning_component.h.