Public Types | Public Member Functions | Protected Attributes
descartes_core::TrajectoryPt Class Reference

#include <trajectory_pt.h>

List of all members.

Public Types

typedef TrajectoryID ID

Public Member Functions

virtual TrajectoryPtPtr clone () const
 Makes a clone of the underlying trajectory point and returns a polymorphic handle to it.
virtual TrajectoryPtPtr copy () const =0
 Makes a copy of the underlying trajectory point and returns a polymorphic handle to it.
const TimingConstraintgetTiming () const
virtual bool isValid (const RobotModel &model) const =0
 Check if state satisfies trajectory point requirements.
virtual bool setDiscretization (const std::vector< double > &discretization)=0
 Set discretization. Note: derived classes interpret and use discretization differently.
void setTiming (const TimingConstraint &timing)
 TrajectoryPt (const TimingConstraint &timing)
virtual ~TrajectoryPt ()
Getters for Cartesian pose(s)

References to "closest" position are decided by norm of joint-space distance.

virtual bool getClosestCartPose (const std::vector< double > &seed_state, const RobotModel &kinematics, Eigen::Affine3d &pose) const =0
 Get single Cartesian pose associated with closest position of this point to seed_state. (Pose of TOOL point expressed in WOBJ frame).
virtual bool getNominalCartPose (const std::vector< double > &seed_state, const RobotModel &kinematics, Eigen::Affine3d &pose) const =0
 Get single Cartesian pose associated with nominal of this point. (Pose of TOOL point expressed in WOBJ frame).
virtual void getCartesianPoses (const RobotModel &kinematics, EigenSTL::vector_Affine3d &poses) const =0
 Get "all" Cartesian poses that satisfy this point.
Getters for joint pose(s)

References to "closest" position are decided by norm of joint-space distance.

virtual bool getClosestJointPose (const std::vector< double > &seed_state, const RobotModel &model, std::vector< double > &joint_pose) const =0
 Get single Joint pose closest to seed_state.
virtual bool getNominalJointPose (const std::vector< double > &seed_state, const RobotModel &model, std::vector< double > &joint_pose) const =0
 Get single Joint pose closest to seed_state.
virtual void getJointPoses (const RobotModel &model, std::vector< std::vector< double > > &joint_poses) const =0
 Get "all" joint poses that satisfy this point.
Getters/Setters for ID
ID getID () const
 Get ID associated with this point.
void setID (const ID &id)
 Set ID for this point.

Protected Attributes

ID id_
 ID associated with this pt. Generally refers back to a process path defined elsewhere.
TimingConstraint timing_
 Information specifying acceptable timing from this point to the next.

Detailed Description

Definition at line 70 of file trajectory_pt.h.


Member Typedef Documentation

Definition at line 73 of file trajectory_pt.h.


Constructor & Destructor Documentation

Definition at line 75 of file trajectory_pt.h.

virtual descartes_core::TrajectoryPt::~TrajectoryPt ( ) [inline, virtual]

Definition at line 80 of file trajectory_pt.h.


Member Function Documentation

virtual TrajectoryPtPtr descartes_core::TrajectoryPt::clone ( ) const [inline, virtual]

Makes a clone of the underlying trajectory point and returns a polymorphic handle to it.

Returns:
A clone, with the same data but a unique ID, of the underlying point type

Definition at line 187 of file trajectory_pt.h.

virtual TrajectoryPtPtr descartes_core::TrajectoryPt::copy ( ) const [pure virtual]

Makes a copy of the underlying trajectory point and returns a polymorphic handle to it.

Returns:
A copy, with the same ID, of the underlying point type
virtual void descartes_core::TrajectoryPt::getCartesianPoses ( const RobotModel kinematics,
EigenSTL::vector_Affine3d poses 
) const [pure virtual]

Get "all" Cartesian poses that satisfy this point.

Parameters:
kinematicsKinematics object used to calculate pose
posesNote: Number of poses returned may be subject to discretization used.
virtual bool descartes_core::TrajectoryPt::getClosestCartPose ( const std::vector< double > &  seed_state,
const RobotModel kinematics,
Eigen::Affine3d &  pose 
) const [pure virtual]

Get single Cartesian pose associated with closest position of this point to seed_state. (Pose of TOOL point expressed in WOBJ frame).

Parameters:
seed_stateJoint_position seed.
kinematicsKinematics object used to calculate pose
poseIf successful, affine pose of this state.
Returns:
True if calculation successful. pose untouched if return false.
virtual bool descartes_core::TrajectoryPt::getClosestJointPose ( const std::vector< double > &  seed_state,
const RobotModel model,
std::vector< double > &  joint_pose 
) const [pure virtual]

Get single Joint pose closest to seed_state.

Parameters:
seed_stateJoint_position seed.
modelRobot mode object used to calculate pose
joint_poseSolution (if function successful).
Returns:
True if calculation successful. joint_pose untouched if return is false.

Get ID associated with this point.

Definition at line 163 of file trajectory_pt.h.

virtual void descartes_core::TrajectoryPt::getJointPoses ( const RobotModel model,
std::vector< std::vector< double > > &  joint_poses 
) const [pure virtual]

Get "all" joint poses that satisfy this point.

Parameters:
modelRobot model object used to calculate pose
joint_posesvector of solutions (if function successful). Note: # of solutions may be subject to discretization used.
virtual bool descartes_core::TrajectoryPt::getNominalCartPose ( const std::vector< double > &  seed_state,
const RobotModel kinematics,
Eigen::Affine3d &  pose 
) const [pure virtual]

Get single Cartesian pose associated with nominal of this point. (Pose of TOOL point expressed in WOBJ frame).

Parameters:
seed_stateJoint_position seed.
kinematicsKinematics object used to calculate pose
poseIf successful, affine pose of this state.
Returns:
True if calculation successful. pose untouched if return false.
virtual bool descartes_core::TrajectoryPt::getNominalJointPose ( const std::vector< double > &  seed_state,
const RobotModel model,
std::vector< double > &  joint_pose 
) const [pure virtual]

Get single Joint pose closest to seed_state.

Parameters:
seed_stateJoint_position seed.
modelRobot model object used to calculate pose
seed_stateRobotState used kinematic calculations and joint position seed.
Returns:
True if calculation successful. joint_pose untouched if return is false.

Definition at line 194 of file trajectory_pt.h.

virtual bool descartes_core::TrajectoryPt::isValid ( const RobotModel model) const [pure virtual]

Check if state satisfies trajectory point requirements.

Parameters:
modelRobot model object used to determine validity
virtual bool descartes_core::TrajectoryPt::setDiscretization ( const std::vector< double > &  discretization) [pure virtual]

Set discretization. Note: derived classes interpret and use discretization differently.

Parameters:
discretizationVector of discretization values.
Returns:
True if vector is valid length/values.
void descartes_core::TrajectoryPt::setID ( const ID id) [inline]

Set ID for this point.

Parameters:
idNumber to set id_ to.

Definition at line 171 of file trajectory_pt.h.

void descartes_core::TrajectoryPt::setTiming ( const TimingConstraint timing) [inline]

Definition at line 199 of file trajectory_pt.h.


Member Data Documentation

ID associated with this pt. Generally refers back to a process path defined elsewhere.

Definition at line 205 of file trajectory_pt.h.

Information specifying acceptable timing from this point to the next.

Definition at line 206 of file trajectory_pt.h.


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


descartes_core
Author(s): Dan Solomon
autogenerated on Wed Aug 26 2015 11:21:21