|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <chomp_planning_context.h>


Public Member Functions | |
| bool | solve (planning_interface::MotionPlanResponse &res) override |
| Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that. More... | |
| bool | solve (planning_interface::MotionPlanDetailedResponse &res) override |
| Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that. More... | |
| void | clear () override |
| Clear the data structures used by the planner. More... | |
| bool | terminate () override |
| If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true). More... | |
| CHOMPPlanningContext (const std::string &name, const std::string &group, const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node) | |
| ~CHOMPPlanningContext () override=default | |
| void | initialize () |
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. More... | |
| virtual | ~PlanningContext () |
| const std::string & | getGroupName () const |
| Get the name of the group this planning context is for. More... | |
| const std::string & | getName () const |
| Get the name of this planning context. More... | |
| const planning_scene::PlanningSceneConstPtr & | getPlanningScene () const |
| Get the planning scene associated to this planning context. More... | |
| const MotionPlanRequest & | getMotionPlanRequest () const |
| Get the motion plan request associated to this planning context. More... | |
| void | setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene) |
| Set the planning scene for this context. More... | |
| void | setMotionPlanRequest (const MotionPlanRequest &request) |
| Set the planning request for this context. More... | |
Additional Inherited Members | |
Protected Attributes inherited from planning_interface::PlanningContext | |
| std::string | name_ |
| The name of this planning context. More... | |
| std::string | group_ |
| The group (as in the SRDF) this planning context is for. More... | |
| planning_scene::PlanningSceneConstPtr | planning_scene_ |
| The planning scene for this context. More... | |
| MotionPlanRequest | request_ |
| The planning request for this context. More... | |
Definition at line 48 of file chomp_planning_context.h.
| chomp_interface::CHOMPPlanningContext::CHOMPPlanningContext | ( | const std::string & | name, |
| const std::string & | group, | ||
| const moveit::core::RobotModelConstPtr & | model, | ||
| const rclcpp::Node::SharedPtr & | node | ||
| ) |
Definition at line 42 of file chomp_planning_context.cpp.
|
overridedefault |
|
overridevirtual |
Clear the data structures used by the planner.
Implements planning_interface::PlanningContext.
Definition at line 77 of file chomp_planning_context.cpp.
| void chomp_interface::CHOMPPlanningContext::initialize | ( | ) |
|
overridevirtual |
Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that.
Implements planning_interface::PlanningContext.
Definition at line 50 of file chomp_planning_context.cpp.
|
overridevirtual |
Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that.
Implements planning_interface::PlanningContext.
Definition at line 55 of file chomp_planning_context.cpp.
|
overridevirtual |
If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true).
Implements planning_interface::PlanningContext.
Definition at line 71 of file chomp_planning_context.cpp.