#include <trajectory_pt.h>
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 | cloneAndSetTiming (const TimingConstraint &tm) const |
| Makes a clone of the underlying trajectory point and returns a polymorphic handle to it with new timing. | |
| virtual TrajectoryPtPtr | copy () const =0 |
| Makes a copy of the underlying trajectory point and returns a polymorphic handle to it. | |
| virtual TrajectoryPtPtr | copyAndSetTiming (const TimingConstraint &tm) const |
| Makes a copy of the underlying trajectory point, mutates the timing, and returns a polymorphic handle to it. | |
| const TimingConstraint & | getTiming () 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. | |
Definition at line 67 of file trajectory_pt.h.
Definition at line 70 of file trajectory_pt.h.
| descartes_core::TrajectoryPt::TrajectoryPt | ( | const TimingConstraint & | timing | ) | [inline] |
Definition at line 72 of file trajectory_pt.h.
| virtual descartes_core::TrajectoryPt::~TrajectoryPt | ( | ) | [inline, virtual] |
Definition at line 76 of file trajectory_pt.h.
| virtual TrajectoryPtPtr descartes_core::TrajectoryPt::clone | ( | ) | const [inline, virtual] |
Makes a clone of the underlying trajectory point and returns a polymorphic handle to it.
Definition at line 195 of file trajectory_pt.h.
| virtual TrajectoryPtPtr descartes_core::TrajectoryPt::cloneAndSetTiming | ( | const TimingConstraint & | tm | ) | const [inline, virtual] |
Makes a clone of the underlying trajectory point and returns a polymorphic handle to it with new timing.
| tm | The new timing value for the copied point |
Definition at line 207 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.
| virtual TrajectoryPtPtr descartes_core::TrajectoryPt::copyAndSetTiming | ( | const TimingConstraint & | tm | ) | const [inline, virtual] |
Makes a copy of the underlying trajectory point, mutates the timing, and returns a polymorphic handle to it.
| tm | The new timing value for the copied point |
Definition at line 184 of file trajectory_pt.h.
| virtual void descartes_core::TrajectoryPt::getCartesianPoses | ( | const RobotModel & | kinematics, |
| EigenSTL::vector_Affine3d & | poses | ||
| ) | const [pure virtual] |
Get "all" Cartesian poses that satisfy this point.
| kinematics | Kinematics object used to calculate pose |
| poses | Note: 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).
| seed_state | Joint_position seed. |
| kinematics | Kinematics object used to calculate pose |
| pose | If successful, affine pose of this state. |
| 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.
| seed_state | Joint_position seed. |
| model | Robot mode object used to calculate pose |
| joint_pose | Solution (if function successful). |
| ID descartes_core::TrajectoryPt::getID | ( | ) | const [inline] |
Get ID associated with this point.
Definition at line 158 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.
| model | Robot model object used to calculate pose |
| joint_poses | vector 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).
| seed_state | Joint_position seed. |
| kinematics | Kinematics object used to calculate pose |
| pose | If successful, affine pose of this state. |
| 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.
| seed_state | Joint_position seed. |
| model | Robot model object used to calculate pose |
| seed_state | RobotState used kinematic calculations and joint position seed. |
| const TimingConstraint& descartes_core::TrajectoryPt::getTiming | ( | ) | const [inline] |
Definition at line 214 of file trajectory_pt.h.
| virtual bool descartes_core::TrajectoryPt::isValid | ( | const RobotModel & | model | ) | const [pure virtual] |
Check if state satisfies trajectory point requirements.
| model | Robot 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.
| discretization | Vector of discretization values. |
| void descartes_core::TrajectoryPt::setID | ( | const ID & | id | ) | [inline] |
Set ID for this point.
| id | Number to set id_ to. |
Definition at line 166 of file trajectory_pt.h.
| void descartes_core::TrajectoryPt::setTiming | ( | const TimingConstraint & | timing | ) | [inline] |
Definition at line 219 of file trajectory_pt.h.
ID descartes_core::TrajectoryPt::id_ [protected] |
ID associated with this pt. Generally refers back to a process path defined elsewhere.
Definition at line 225 of file trajectory_pt.h.
Information specifying acceptable timing from this point to the next.
Definition at line 226 of file trajectory_pt.h.