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

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

#include <cart_trajectory_pt.h>

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

List of all members.

Public Member Functions

 CartTrajectoryPt (const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Default cartesian trajectory point constructor. All frames initialized to Identity.
 CartTrajectoryPt (const descartes_core::Frame &wobj_base, const TolerancedFrame &wobj_pt, const descartes_core::Frame &tool_base, const TolerancedFrame &tool_pt, double pos_increment, double orient_increment, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Full constructor of cartesian trajectory point.
 CartTrajectoryPt (const TolerancedFrame &wobj_pt, double pos_increment, double orient_increment, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Partial constructor of cartesian trajectory point (all frames not specified by parameters are initialized to Identity). This constructor should be utilized to specify the robot tip (toleranced) point relative to the robot base.
 CartTrajectoryPt (const descartes_core::Frame &wobj_pt, const descartes_core::TimingConstraint &timing=descartes_core::TimingConstraint())
 Partial constructor of cartesian trajectory point (all frames not specified by parameters are initialized to Identity). This constructor should be utilized to specify the robot tip (NOT toleranced) point relative to the robot base.
virtual
descartes_core::TrajectoryPtPtr 
copy () const
virtual bool isValid (const descartes_core::RobotModel &model) const
virtual bool setDiscretization (const std::vector< double > &discretization)
 Set discretization. Cartesian points can have position and angular discretization.
void setTool (const descartes_core::Frame &base, const TolerancedFrame &pt)
void setWobj (const descartes_core::Frame &base, const TolerancedFrame &pt)
virtual ~CartTrajectoryPt ()
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 Member Functions

bool computeCartesianPoses (EigenSTL::vector_Affine3d &poses) const

Protected Attributes

double orient_increment_
 Sampling discretization in angular orientation.
double pos_increment_
 Sampling discretization in cartesian directions.
descartes_core::Frame tool_base_
 Fixed transform from wrist/tool_plate to tool base.
TolerancedFrame tool_pt_
 Underconstrained transform from tool_base to effective pt on tool.
descartes_core::Frame wobj_base_
 Fixed transform from WCS to base of object.
TolerancedFrame wobj_pt_
 Underconstrained transform from object base to goal point on object.

Detailed Description

Cartesian Trajectory Point used to describe a Cartesian goal for a robot trajectory.

Background: For a general robotic process, TOOL pose can be variable (e.g. robot holding workpiece) or fixed (e.g. robot holding MIG torch). Similarly, the WORKOBJECT pose can be variable (e.g. robot riveting a workpiece) or fixed (e.g. stationary grinder that robot moves a tool against).

For a CartTrajectoryPt, TOOL pose is described by fixed transform from wrist to TOOL_BASE, and variable transform from TOOL_BASE to TOOL_PT. This allows the tolerances on tool pose to be easily expressed in a local tool frame. Similarly, WOBJ is located relative to world coordinate system, and is described by fixed transform from world to WOBJ_BASE, and variable transform from WOBJ_BASE to specific point on part (WOBJ_PT). Variable transforms of both TOOL and WOBJ have tolerances on both position and orientation. Optionally, additional constraints can be placed on position and orientation that can limit, but not expand, existing tolerances.

The get*Pose methods of CartTrajectoryPt try to set joint positions of a robot such that tool_pt_ is coincident with wobj_pt_.

Definition at line 203 of file cart_trajectory_pt.h.


Constructor & Destructor Documentation

Default cartesian trajectory point constructor. All frames initialized to Identity.

Definition at line 155 of file src/cart_trajectory_pt.cpp.

descartes_trajectory::CartTrajectoryPt::CartTrajectoryPt ( const descartes_core::Frame wobj_base,
const TolerancedFrame wobj_pt,
const descartes_core::Frame tool_base,
const TolerancedFrame tool_pt,
double  pos_increment,
double  orient_increment,
const descartes_core::TimingConstraint timing = descartes_core::TimingConstraint() 
)

Full constructor of cartesian trajectory point.

Parameters:
wobj_baseFixed transform from WCS to base of object
wobj_ptUnderconstrained transform from object base to goal point on object.
tool_baseFixed transform from wrist/tool_plate to tool base
tool_ptUnderconstrained transform from tool_base to effective pt on tool.
pos_incrementPosition increment used for sampling
pos_incrementOrientation increment used for sampling

Definition at line 165 of file src/cart_trajectory_pt.cpp.

descartes_trajectory::CartTrajectoryPt::CartTrajectoryPt ( const TolerancedFrame wobj_pt,
double  pos_increment,
double  orient_increment,
const descartes_core::TimingConstraint timing = descartes_core::TimingConstraint() 
)

Partial constructor of cartesian trajectory point (all frames not specified by parameters are initialized to Identity). This constructor should be utilized to specify the robot tip (toleranced) point relative to the robot base.

Parameters:
wobj_ptUnderconstrained transform from object base to goal point on object.
pos_incrementPosition increment used for sampling
pos_incrementOrientation increment used for sampling

Definition at line 178 of file src/cart_trajectory_pt.cpp.

Partial constructor of cartesian trajectory point (all frames not specified by parameters are initialized to Identity). This constructor should be utilized to specify the robot tip (NOT toleranced) point relative to the robot base.

Parameters:
wobj_ptUnderconstrained transform from object base to goal point on object.

Definition at line 190 of file src/cart_trajectory_pt.cpp.

Definition at line 249 of file cart_trajectory_pt.h.


Member Function Documentation

Definition at line 214 of file src/cart_trajectory_pt.cpp.

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

Implements descartes_core::TrajectoryPt.

Reimplemented in descartes_trajectory::AxialSymmetricPt.

Definition at line 294 of file cart_trajectory_pt.h.

Implements descartes_core::TrajectoryPt.

Definition at line 237 of file src/cart_trajectory_pt.cpp.

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

Implements descartes_core::TrajectoryPt.

Definition at line 200 of file src/cart_trajectory_pt.cpp.

bool descartes_trajectory::CartTrajectoryPt::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 270 of file src/cart_trajectory_pt.cpp.

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

Implements descartes_core::TrajectoryPt.

Definition at line 387 of file src/cart_trajectory_pt.cpp.

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

Implements descartes_core::TrajectoryPt.

Definition at line 206 of file src/cart_trajectory_pt.cpp.

bool descartes_trajectory::CartTrajectoryPt::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 378 of file src/cart_trajectory_pt.cpp.

Implements descartes_core::TrajectoryPt.

Definition at line 421 of file src/cart_trajectory_pt.cpp.

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

Set discretization. Cartesian points can have position and angular discretization.

Parameters:
discretizationVector of discretization values. Must be length 2 or 6 (position/orientation or separate xyzrpy).
Returns:
True if vector is valid length/values. TODO what are valid values?

Implements descartes_core::TrajectoryPt.

Definition at line 429 of file src/cart_trajectory_pt.cpp.

Definition at line 300 of file cart_trajectory_pt.h.

Definition at line 307 of file cart_trajectory_pt.h.


Member Data Documentation

Definition at line 206 of file cart_trajectory_pt.h.

Sampling discretization in angular orientation.

Definition at line 325 of file cart_trajectory_pt.h.

Sampling discretization in cartesian directions.

Definition at line 324 of file cart_trajectory_pt.h.

Fixed transform from wrist/tool_plate to tool base.

Definition at line 319 of file cart_trajectory_pt.h.

Underconstrained transform from tool_base to effective pt on tool.

Definition at line 320 of file cart_trajectory_pt.h.

Fixed transform from WCS to base of object.

Definition at line 321 of file cart_trajectory_pt.h.

Underconstrained transform from object base to goal point on object.

Definition at line 322 of file cart_trajectory_pt.h.


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


descartes_trajectory
Author(s): Jorge Nicho
autogenerated on Wed Aug 26 2015 11:21:27