#include <local_constraint_solver_interface.h>
Class LocalConstraintSolverInterface - Base class for a local constrain solver.
Definition at line 59 of file local_constraint_solver_interface.h.
◆ LocalConstraintSolverInterface() [1/3]
moveit::hybrid_planning::LocalConstraintSolverInterface::LocalConstraintSolverInterface |
( |
| ) |
|
|
default |
◆ LocalConstraintSolverInterface() [2/3]
◆ LocalConstraintSolverInterface() [3/3]
◆ ~LocalConstraintSolverInterface()
virtual moveit::hybrid_planning::LocalConstraintSolverInterface::~LocalConstraintSolverInterface |
( |
| ) |
|
|
virtualdefault |
◆ 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 |
◆ operator=() [1/2]
◆ operator=() [2/2]
◆ reset()
virtual bool moveit::hybrid_planning::LocalConstraintSolverInterface::reset |
( |
| ) |
|
|
pure virtual |
◆ 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_trajectory | The local trajectory to pursue |
local_goal | Local goal constraints |
local_solution | solution 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: