Public Member Functions | |
void | clear () override |
Clear the data structures used by the planner. More... | |
void | setTrajectory (robot_trajectory::RobotTrajectoryPtr trajectory) |
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... | |
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 | 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... | |
Public Member Functions inherited from planning_interface::PlanningContext | |
const std::string & | getGroupName () const |
Get the name of the group this planning context is for. More... | |
const MotionPlanRequest & | getMotionPlanRequest () const |
Get the motion plan request associated to this planning context. 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... | |
PlanningContext (const std::string &name, const std::string &group) | |
Construct a planning context named name for the group group. More... | |
void | setMotionPlanRequest (const MotionPlanRequest &request) |
Set the planning request for this context. More... | |
void | setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene) |
Set the planning scene for this context. More... | |
virtual | ~PlanningContext () |
Private Attributes | |
robot_trajectory::RobotTrajectoryPtr | m_trajectory |
Additional Inherited Members | |
Protected Attributes inherited from planning_interface::PlanningContext | |
std::string | group_ |
The group (as in the SRDF) this planning context is for. More... | |
std::string | name_ |
The name of this planning context. 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 105 of file test_planning_request_adapter_chain.cpp.
|
inlineoverridevirtual |
Clear the data structures used by the planner.
Implements planning_interface::PlanningContext.
Definition at line 138 of file test_planning_request_adapter_chain.cpp.
|
inline |
Definition at line 110 of file test_planning_request_adapter_chain.cpp.
|
inlineoverridevirtual |
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 124 of file test_planning_request_adapter_chain.cpp.
|
inlineoverridevirtual |
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 115 of file test_planning_request_adapter_chain.cpp.
|
inlineoverridevirtual |
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 133 of file test_planning_request_adapter_chain.cpp.
|
private |
Definition at line 143 of file test_planning_request_adapter_chain.cpp.