Public Member Functions | Public Attributes | Protected Attributes
descartes_trajectory::JointTrajectoryPt Class Reference

Joint Trajectory Point used to describe a joint goal for a robot trajectory. More...

#include <joint_trajectory_pt.h>

Inheritance diagram for descartes_trajectory::JointTrajectoryPt:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual
descartes_core::TrajectoryPtPtr 
copy () const
virtual bool isValid (const descartes_core::RobotModel &model) const
 JointTrajectoryPt (const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 All frames initialized to Identity, joint values left empty.
 JointTrajectoryPt (const std::vector< TolerancedJointValue > &joints, const descartes_core::Frame &tool, const descartes_core::Frame &wobj, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Full joint trajectory point constructor.
 JointTrajectoryPt (const std::vector< TolerancedJointValue > &joints, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Full joint trajectory point constructor.
 JointTrajectoryPt (const std::vector< double > &joints, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Full joint trajectory point constructor.
const std::vector< double > & lower () const
const std::vector< double > & nominal () const
virtual bool setDiscretization (const std::vector< double > &discretization)
 Set discretization. Each joint can have a different discretization.
void setJoints (const std::vector< TolerancedJointValue > &joints)
void setTool (const descartes_core::Frame &tool)
void setWobj (const descartes_core::Frame &wobj)
const std::vector< double > & upper () const
virtual ~JointTrajectoryPt ()
Getters for Cartesian pose(s)
virtual bool getClosestCartPose (const std::vector< double > &seed_state, const descartes_core::RobotModel &model, Eigen::Affine3d &pose) const
virtual bool getNominalCartPose (const std::vector< double > &seed_state, const descartes_core::RobotModel &model, Eigen::Affine3d &pose) const
virtual void getCartesianPoses (const descartes_core::RobotModel &model, EigenSTL::vector_Affine3d &poses) const
Getters for joint pose(s)
virtual bool getClosestJointPose (const std::vector< double > &seed_state, const descartes_core::RobotModel &model, std::vector< double > &joint_pose) const
virtual bool getNominalJointPose (const std::vector< double > &seed_state, const descartes_core::RobotModel &model, std::vector< double > &joint_pose) const
virtual void getJointPoses (const descartes_core::RobotModel &model, std::vector< std::vector< double > > &joint_poses) const

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Protected Attributes

std::vector< double > discretization_
 How finely to discretize each joint.
std::vector< double > lower_
std::vector< double > nominal_
std::vector< double > upper_
JointTrajectoryPt transforms. Used in get*CartPose() methods and for interpolation.
descartes_core::Frame tool_
 Transform from robot wrist to active tool pt.
descartes_core::Frame wobj_
 Transform from world to active workobject pt.

Detailed Description

Joint Trajectory Point used to describe a joint goal for a robot trajectory.

Background: The TOOL is something held by the robot. It is located relative to robot wrist/tool plate. The WOBJ is something that exists in the world/global environment that is not held by robot.

For a JointTrajectoryPt, the transform from wrist to tool, and base to workobject, are defined by fixed frames. These transforms are important when calculating interpolation. The joint position is specified as a nominal with upper/lower tolerances.

The get*Pose() methods of JointTrajectoryPt try to set joint positions of a robot such that tool_ is coincident with wobj_.

Definition at line 67 of file joint_trajectory_pt.h.


Constructor & Destructor Documentation

All frames initialized to Identity, joint values left empty.

Definition at line 52 of file src/joint_trajectory_pt.cpp.

Full joint trajectory point constructor.

Parameters:
jointsFixed joint position with tolerance
toolTransform from robot wrist to active tool pt.
wobjTransform from world to active workobject pt.

Definition at line 57 of file src/joint_trajectory_pt.cpp.

Full joint trajectory point constructor.

Parameters:
jointsFixed joint position with tolerance

Definition at line 64 of file src/joint_trajectory_pt.cpp.

Full joint trajectory point constructor.

Parameters:
jointsFixed joint position

Definition at line 71 of file src/joint_trajectory_pt.cpp.

Definition at line 102 of file joint_trajectory_pt.h.


Member Function Documentation

virtual descartes_core::TrajectoryPtPtr descartes_trajectory::JointTrajectoryPt::copy ( ) const [inline, virtual]

Implements descartes_core::TrajectoryPt.

Definition at line 147 of file joint_trajectory_pt.h.

Implements descartes_core::TrajectoryPt.

Definition at line 93 of file src/joint_trajectory_pt.cpp.

bool descartes_trajectory::JointTrajectoryPt::getClosestCartPose ( const std::vector< double > &  seed_state,
const descartes_core::RobotModel model,
Eigen::Affine3d &  pose 
) const [virtual]

Implements descartes_core::TrajectoryPt.

Definition at line 81 of file src/joint_trajectory_pt.cpp.

bool descartes_trajectory::JointTrajectoryPt::getClosestJointPose ( const std::vector< double > &  seed_state,
const descartes_core::RobotModel model,
std::vector< double > &  joint_pose 
) const [virtual]

Implements descartes_core::TrajectoryPt.

Definition at line 98 of file src/joint_trajectory_pt.cpp.

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

Implements descartes_core::TrajectoryPt.

Definition at line 118 of file src/joint_trajectory_pt.cpp.

bool descartes_trajectory::JointTrajectoryPt::getNominalCartPose ( const std::vector< double > &  seed_state,
const descartes_core::RobotModel model,
Eigen::Affine3d &  pose 
) const [virtual]

Implements descartes_core::TrajectoryPt.

Definition at line 87 of file src/joint_trajectory_pt.cpp.

bool descartes_trajectory::JointTrajectoryPt::getNominalJointPose ( const std::vector< double > &  seed_state,
const descartes_core::RobotModel model,
std::vector< double > &  joint_pose 
) const [virtual]

Implements descartes_core::TrajectoryPt.

Definition at line 111 of file src/joint_trajectory_pt.cpp.

Implements descartes_core::TrajectoryPt.

Definition at line 125 of file src/joint_trajectory_pt.cpp.

const std::vector<double>& descartes_trajectory::JointTrajectoryPt::lower ( ) const [inline]

Definition at line 175 of file joint_trajectory_pt.h.

const std::vector<double>& descartes_trajectory::JointTrajectoryPt::nominal ( ) const [inline]

Definition at line 165 of file joint_trajectory_pt.h.

bool descartes_trajectory::JointTrajectoryPt::setDiscretization ( const std::vector< double > &  discretization) [virtual]

Set discretization. Each joint can have a different discretization.

Parameters:
discretizationVector of discretization values. If length=1, set all elements of discretization_ are set to value.
Returns:
True if vector is length 1 or length(joint_position_) and value[ii] are within 0-range(joint_position[ii]).

Implements descartes_core::TrajectoryPt.

Definition at line 130 of file src/joint_trajectory_pt.cpp.

Definition at line 159 of file src/joint_trajectory_pt.cpp.

Definition at line 154 of file joint_trajectory_pt.h.

Definition at line 159 of file joint_trajectory_pt.h.

const std::vector<double>& descartes_trajectory::JointTrajectoryPt::upper ( ) const [inline]

Definition at line 170 of file joint_trajectory_pt.h.


Member Data Documentation

How finely to discretize each joint.

Definition at line 184 of file joint_trajectory_pt.h.

Definition at line 70 of file joint_trajectory_pt.h.

std::vector<double> descartes_trajectory::JointTrajectoryPt::lower_ [protected]

Definition at line 182 of file joint_trajectory_pt.h.

std::vector<double> descartes_trajectory::JointTrajectoryPt::nominal_ [protected]

Definition at line 181 of file joint_trajectory_pt.h.

Transform from robot wrist to active tool pt.

Definition at line 189 of file joint_trajectory_pt.h.

std::vector<double> descartes_trajectory::JointTrajectoryPt::upper_ [protected]

Definition at line 183 of file joint_trajectory_pt.h.

Transform from world to active workobject pt.

Definition at line 190 of file joint_trajectory_pt.h.


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


descartes_trajectory
Author(s): Jorge Nicho
autogenerated on Thu Jun 6 2019 21:36:04