Public Member Functions | Private Attributes
constrained_ik::JointInterpolationPlanner Class Reference

Joint interpolation planner for moveit. More...

#include <joint_interpolation_planner.h>

Inheritance diagram for constrained_ik::JointInterpolationPlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void clear () override
 Clear planner data.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW JointInterpolationPlanner (const std::string &name, const std::string &group)
 JointInterpolationPlanner Constructor.
 JointInterpolationPlanner (const JointInterpolationPlanner &other)
 JointInterpolationPlanner Copy Constructor.
bool solve (planning_interface::MotionPlanResponse &res) override
 Generate a joint interpolated trajectory.
bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 Generate a joint interpolated trajectory.
bool terminate () override
 Terminate the active planner solve.

Private Attributes

boost::atomic< bool > terminate_

Detailed Description

Joint interpolation planner for moveit.

This class is used to represent a joint interpolated path planner for moveit. This planner does not have the inherent ability to avoid collision. It does check if the path created is collision free before it returns a trajectory. If a collision is found it returns an empty trajectory and moveit error.

Definition at line 51 of file joint_interpolation_planner.h.


Constructor & Destructor Documentation

EIGEN_MAKE_ALIGNED_OPERATOR_NEW constrained_ik::JointInterpolationPlanner::JointInterpolationPlanner ( const std::string &  name,
const std::string &  group 
) [inline]

JointInterpolationPlanner Constructor.

Parameters:
nameof planner
groupof the planner

Definition at line 61 of file joint_interpolation_planner.h.

JointInterpolationPlanner Copy Constructor.

Parameters:
otherjoint interpolation planner

Definition at line 67 of file joint_interpolation_planner.h.


Member Function Documentation

Generate a joint interpolated trajectory.

Parameters:
resplanner response
Returns:

Implements constrained_ik::CLIKPlanningContext.

Definition at line 55 of file joint_interpolation_planner.cpp.

Generate a joint interpolated trajectory.

Parameters:
resplanner detailed response
Returns:

Implements constrained_ik::CLIKPlanningContext.

Definition at line 41 of file joint_interpolation_planner.cpp.

bool constrained_ik::JointInterpolationPlanner::terminate ( ) [inline, override, virtual]

Terminate the active planner solve.

Returns:
True if successfully terminated, otherwise false

Implements constrained_ik::CLIKPlanningContext.

Definition at line 76 of file joint_interpolation_planner.h.


Member Data Documentation

Termination flag

Definition at line 97 of file joint_interpolation_planner.h.


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


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Sat Jun 8 2019 19:23:46