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

Cartesian path planner for moveit. More...

#include <cartesian_planner.h>

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

List of all members.

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW CartesianPlanner (const std::string &name, const std::string &group)
 CartesianPlanner Constructor.
 CartesianPlanner (const CartesianPlanner &other)
 CartesianPlanner Copy Constructor.
void clear () override
 Clear planner data.
bool initializeSolver ()
 This will initialize the solver if it has not all ready.
void resetSolverConfiguration ()
 Reset the planners IK solver configuration to it default settings.
void setSolverConfiguration (const ConstrainedIKConfiguration &config)
 Set the planners IK solver configuration.
bool solve (planning_interface::MotionPlanResponse &res) override
 Inverse Kinematic Solve.
bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 Inverse Kinematic Solve.
bool terminate () override
 Terminate the active planner solve.

Private Member Functions

std::vector< Eigen::Affine3d,
Eigen::aligned_allocator
< Eigen::Affine3d > > 
interpolateCartesian (const Eigen::Affine3d &start, const Eigen::Affine3d &stop, double ds, double dt) const
 Preform position and orientation interpolation between start and stop.

Private Attributes

boost::mutex mutex_
std::string robot_description_
robot_model::RobotModelConstPtr robot_model_
boost::shared_ptr< Constrained_IKsolver_
boost::atomic< bool > terminate_

Detailed Description

Cartesian path planner for moveit.

This class is used to represent a cartesian path planner for moveit. It finds a straight line path between the start and goal position. 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 52 of file cartesian_planner.h.


Constructor & Destructor Documentation

constrained_ik::CartesianPlanner::CartesianPlanner ( const std::string &  name,
const std::string &  group 
)

CartesianPlanner Constructor.

Parameters:
nameof planner
groupof the planner

Definition at line 41 of file cartesian_planner.cpp.

CartesianPlanner Copy Constructor.

Parameters:
othercartesian planner

Definition at line 68 of file cartesian_planner.h.


Member Function Documentation

This will initialize the solver if it has not all ready.

Returns:
True if successful, otherwise false

Definition at line 51 of file cartesian_planner.cpp.

std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > constrained_ik::CartesianPlanner::interpolateCartesian ( const Eigen::Affine3d &  start,
const Eigen::Affine3d &  stop,
double  ds,
double  dt 
) const [private]

Preform position and orientation interpolation between start and stop.

Parameters:
startbegining pose of trajectory
stopend pose of trajectory
dsmax cartesian translation interpolation step
dtmax cartesian orientation interpolation step
Returns:
std::vector<Eigen::Affine3d>

Definition at line 243 of file cartesian_planner.cpp.

Set the planners IK solver configuration.

Parameters:
configConstrained IK solver configuration

Definition at line 64 of file cartesian_planner.cpp.

Inverse Kinematic Solve.

Parameters:
resplanner response
Returns:

Implements constrained_ik::CLIKPlanningContext.

Definition at line 88 of file cartesian_planner.cpp.

Inverse Kinematic Solve.

Parameters:
resplanner detailed response
Returns:

Implements constrained_ik::CLIKPlanningContext.

Definition at line 74 of file cartesian_planner.cpp.

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

Terminate the active planner solve.

Returns:
True if successfully terminated, otherwise false

Implements constrained_ik::CLIKPlanningContext.

Definition at line 80 of file cartesian_planner.h.


Member Data Documentation

Mutex

Definition at line 131 of file cartesian_planner.h.

robot description value from ros param server

Definition at line 128 of file cartesian_planner.h.

robot_model::RobotModelConstPtr constrained_ik::CartesianPlanner::robot_model_ [private]

Robot model object

Definition at line 129 of file cartesian_planner.h.

Constrained IK Solver

Definition at line 130 of file cartesian_planner.h.

boost::atomic<bool> constrained_ik::CartesianPlanner::terminate_ [private]

Termination flag

Definition at line 127 of file cartesian_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:45