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

#include <stomp_moveit_planning_context.hpp>

Inheritance diagram for stomp_moveit::StompPlanningContext:
Inheritance graph
[legend]
Collaboration diagram for stomp_moveit::StompPlanningContext:
Collaboration graph
[legend]

Public Member Functions

 StompPlanningContext (const std::string &name, const std::string &group_name, const stomp_moveit::Params &params)
 
void 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...
 
void 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 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...
 
void clear () override
 Clear the data structures used by the planner. More...
 
void setPathPublisher (const std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray >> &path_publisher)
 
std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray > > getPathPublisher ()
 
- 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 MotionPlanRequestgetMotionPlanRequest () 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...
 

Detailed Description

Definition at line 54 of file stomp_moveit_planning_context.hpp.

Constructor & Destructor Documentation

◆ StompPlanningContext()

stomp_moveit::StompPlanningContext::StompPlanningContext ( const std::string &  name,
const std::string &  group_name,
const stomp_moveit::Params &  params 
)

Definition at line 209 of file stomp_moveit_planning_context.cpp.

Member Function Documentation

◆ clear()

void stomp_moveit::StompPlanningContext::clear ( )
overridevirtual

Clear the data structures used by the planner.

Implements planning_interface::PlanningContext.

Definition at line 300 of file stomp_moveit_planning_context.cpp.

◆ getPathPublisher()

std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray > > stomp_moveit::StompPlanningContext::getPathPublisher ( )

Definition at line 310 of file stomp_moveit_planning_context.cpp.

Here is the caller graph for this function:

◆ setPathPublisher()

void stomp_moveit::StompPlanningContext::setPathPublisher ( const std::shared_ptr< rclcpp::Publisher< visualization_msgs::msg::MarkerArray >> &  path_publisher)

Definition at line 304 of file stomp_moveit_planning_context.cpp.

◆ solve() [1/2]

void stomp_moveit::StompPlanningContext::solve ( planning_interface::MotionPlanDetailedResponse res)
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 280 of file stomp_moveit_planning_context.cpp.

Here is the call graph for this function:

◆ solve() [2/2]

void stomp_moveit::StompPlanningContext::solve ( planning_interface::MotionPlanResponse res)
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 215 of file stomp_moveit_planning_context.cpp.

Here is the call graph for this function:

◆ terminate()

bool stomp_moveit::StompPlanningContext::terminate ( )
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 288 of file stomp_moveit_planning_context.cpp.


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