moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::hybrid_planning::LocalConstraintSolverInterface Class Referenceabstract

#include <local_constraint_solver_interface.h>

Inheritance diagram for moveit::hybrid_planning::LocalConstraintSolverInterface:
Inheritance graph
[legend]

Public Member Functions

 LocalConstraintSolverInterface ()=default
 
 LocalConstraintSolverInterface (const LocalConstraintSolverInterface &)=default
 
 LocalConstraintSolverInterface (LocalConstraintSolverInterface &&)=default
 
LocalConstraintSolverInterfaceoperator= (const LocalConstraintSolverInterface &)=default
 
LocalConstraintSolverInterfaceoperator= (LocalConstraintSolverInterface &&)=default
 
virtual ~LocalConstraintSolverInterface ()=default
 
virtual bool initialize (const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const std::string &group_name)=0
 
virtual moveit_msgs::action::LocalPlanner::Feedback solve (const robot_trajectory::RobotTrajectory &local_trajectory, const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal > local_goal, trajectory_msgs::msg::JointTrajectory &local_solution)=0
 
virtual bool reset ()=0
 

Detailed Description

Class LocalConstraintSolverInterface - Base class for a local constrain solver.

Definition at line 59 of file local_constraint_solver_interface.h.

Constructor & Destructor Documentation

◆ LocalConstraintSolverInterface() [1/3]

moveit::hybrid_planning::LocalConstraintSolverInterface::LocalConstraintSolverInterface ( )
default

◆ LocalConstraintSolverInterface() [2/3]

moveit::hybrid_planning::LocalConstraintSolverInterface::LocalConstraintSolverInterface ( const LocalConstraintSolverInterface )
default

◆ LocalConstraintSolverInterface() [3/3]

moveit::hybrid_planning::LocalConstraintSolverInterface::LocalConstraintSolverInterface ( LocalConstraintSolverInterface &&  )
default

◆ ~LocalConstraintSolverInterface()

virtual moveit::hybrid_planning::LocalConstraintSolverInterface::~LocalConstraintSolverInterface ( )
virtualdefault

Member Function Documentation

◆ initialize()

virtual bool moveit::hybrid_planning::LocalConstraintSolverInterface::initialize ( const rclcpp::Node::SharedPtr &  node,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor,
const std::string &  group_name 
)
pure virtual

Initialize local constraint solver

Returns
True if initialization was successful

Implemented in moveit::hybrid_planning::ForwardTrajectory.

◆ operator=() [1/2]

LocalConstraintSolverInterface& moveit::hybrid_planning::LocalConstraintSolverInterface::operator= ( const LocalConstraintSolverInterface )
default

◆ operator=() [2/2]

LocalConstraintSolverInterface& moveit::hybrid_planning::LocalConstraintSolverInterface::operator= ( LocalConstraintSolverInterface &&  )
default

◆ reset()

virtual bool moveit::hybrid_planning::LocalConstraintSolverInterface::reset ( )
pure virtual

Reset local constraint solver to some user-defined initial state

Returns
True if reset was successful

Implemented in moveit::hybrid_planning::ForwardTrajectory.

◆ solve()

virtual moveit_msgs::action::LocalPlanner::Feedback moveit::hybrid_planning::LocalConstraintSolverInterface::solve ( const robot_trajectory::RobotTrajectory local_trajectory,
const std::shared_ptr< const moveit_msgs::action::LocalPlanner::Goal >  local_goal,
trajectory_msgs::msg::JointTrajectory &  local_solution 
)
pure virtual

Solve local planning problem for the current iteration

Parameters
local_trajectoryThe local trajectory to pursue
local_goalLocal goal constraints
local_solutionsolution plan in joint space
Returns
Feedback event from the current solver call i.e. "Collision detected"

Implemented in moveit::hybrid_planning::ForwardTrajectory.


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