|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
PlanningContext for obtaining PTP trajectories. More...
#include <planning_context_ptp.hpp>


Public Member Functions | |
| PlanningContextPTP (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, const pilz_industrial_motion_planner::LimitsContainer &limits) | |
Public Member Functions inherited from pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP > | |
| PlanningContextBase (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, const pilz_industrial_motion_planner::LimitsContainer &limits) | |
| ~PlanningContextBase () override | |
| void | solve (planning_interface::MotionPlanResponse &res) override |
| Calculates a trajectory for the request this context is currently set for. | |
| void | solve (planning_interface::MotionPlanDetailedResponse &res) override |
| Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function just delegates to the common response however here the same trajectory is stored with the descriptions "plan", "simplify", "interpolate". | |
| bool | terminate () override |
| Will terminate solve() | |
| void | clear () override |
| Clear the data structures used by the planner. | |
Public Member Functions inherited from planning_interface::PlanningContext | |
| PlanningContext (const std::string &name, const std::string &group) | |
| Construct a planning context named name for the group group. | |
| virtual | ~PlanningContext () |
| const std::string & | getGroupName () const |
| Get the name of the group this planning context is for. | |
| const std::string & | getName () const |
| Get the name of this planning context. | |
| const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
| Get the planning scene associated to this planning context. | |
| const MotionPlanRequest & | getMotionPlanRequest () const |
| Get the motion plan request associated to this planning context. | |
| void | setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene) |
| Set the planning scene for this context. | |
| void | setMotionPlanRequest (const MotionPlanRequest &request) |
| Set the planning request for this context. | |
Additional Inherited Members | |
Public Attributes inherited from pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP > | |
| std::atomic_bool | terminated_ |
| Flag if terminated. | |
| moveit::core::RobotModelConstPtr | model_ |
| The robot model. | |
| pilz_industrial_motion_planner::LimitsContainer | limits_ |
| Joint limits to be used during planning. | |
Protected Attributes inherited from pilz_industrial_motion_planner::PlanningContextBase< TrajectoryGeneratorPTP > | |
| TrajectoryGeneratorPTP | generator_ |
Protected Attributes inherited from planning_interface::PlanningContext | |
| std::string | name_ |
| The name of this planning context. | |
| std::string | group_ |
| The group (as in the SRDF) this planning context is for. | |
| planning_scene::PlanningSceneConstPtr | planning_scene_ |
| The planning scene for this context. | |
| MotionPlanRequest | request_ |
| The planning request for this context. | |
PlanningContext for obtaining PTP trajectories.
Definition at line 57 of file planning_context_ptp.hpp.
|
inline |
Definition at line 60 of file planning_context_ptp.hpp.