#include <RosMsgTreeIkTrajectoryFactory.h>
Public Member Functions | |
| virtual boost::shared_ptr < RosMsgJointTrajectory > | getTrajectory (const sensor_msgs::JointState &jointPositions, const sensor_msgs::JointState &jointVels, const sensor_msgs::JointState &prevJointVels, const r2_msgs::PoseState &poseState, const r2_msgs::PoseState &poseVels, const r2_msgs::PoseTrajectory &goalTraj) const |
| getTrajectory produces a trajectory object from the inputs | |
| RosMsgTreeIkTrajectoryFactory () | |
| void | setCartesianFactory (boost::shared_ptr< const SynchedCartesianTrajectoryFactory > factory_in) |
| void | setTreeIk (boost::shared_ptr< KdlTreeIk > treeIk_in) |
| virtual | ~RosMsgTreeIkTrajectoryFactory () |
Protected Types | |
| typedef CartesianTrajectorySequenceFactory < SynchedTrajectory > | sequenceFactoryType |
Protected Attributes | |
| boost::shared_ptr< const SynchedCartesianTrajectoryFactory > | factory |
| boost::shared_ptr < sequenceFactoryType > | sequenceFactory |
| boost::shared_ptr< KdlTreeIk > | treeIk |
Definition at line 23 of file RosMsgTreeIkTrajectoryFactory.h.
typedef CartesianTrajectorySequenceFactory<SynchedTrajectory> RosMsgTreeIkTrajectoryFactory::sequenceFactoryType [protected] |
Definition at line 60 of file RosMsgTreeIkTrajectoryFactory.h.
Definition at line 26 of file RosMsgTreeIkTrajectoryFactory.h.
| virtual RosMsgTreeIkTrajectoryFactory::~RosMsgTreeIkTrajectoryFactory | ( | ) | [inline, virtual] |
Definition at line 27 of file RosMsgTreeIkTrajectoryFactory.h.
| boost::shared_ptr< RosMsgJointTrajectory > RosMsgTreeIkTrajectoryFactory::getTrajectory | ( | const sensor_msgs::JointState & | jointPositions, |
| const sensor_msgs::JointState & | jointVels, | ||
| const sensor_msgs::JointState & | prevJointVels, | ||
| const r2_msgs::PoseState & | poseState, | ||
| const r2_msgs::PoseState & | poseVels, | ||
| const r2_msgs::PoseTrajectory & | goalTraj | ||
| ) | const [virtual] |
getTrajectory produces a trajectory object from the inputs
| jointPositions | start joint positions |
| jointVels | start joint velocities |
| prevJointVels | previous joint velocities (joint states only hold pos & vel so the prev is used to derive acc) |
| poseState | start cartesian poses |
| poseVels | starting cartesian vels |
| goalTraj | goal joint positions |
Definition at line 3 of file RosMsgTreeIkTrajectoryFactory.cpp.
| void RosMsgTreeIkTrajectoryFactory::setCartesianFactory | ( | boost::shared_ptr< const SynchedCartesianTrajectoryFactory > | factory_in | ) | [inline] |
Definition at line 29 of file RosMsgTreeIkTrajectoryFactory.h.
| void RosMsgTreeIkTrajectoryFactory::setTreeIk | ( | boost::shared_ptr< KdlTreeIk > | treeIk_in | ) | [inline] |
Definition at line 36 of file RosMsgTreeIkTrajectoryFactory.h.
boost::shared_ptr<const SynchedCartesianTrajectoryFactory> RosMsgTreeIkTrajectoryFactory::factory [protected] |
Definition at line 62 of file RosMsgTreeIkTrajectoryFactory.h.
boost::shared_ptr<sequenceFactoryType> RosMsgTreeIkTrajectoryFactory::sequenceFactory [protected] |
Definition at line 61 of file RosMsgTreeIkTrajectoryFactory.h.
boost::shared_ptr<KdlTreeIk> RosMsgTreeIkTrajectoryFactory::treeIk [protected] |
Definition at line 58 of file RosMsgTreeIkTrajectoryFactory.h.