#include <ForceTrajectory.h>
Public Member Functions | |
ForceTrajectory () | |
virtual void | getPose (double time, KDL::JntArrayAcc &pose) |
getPose get pose at a particular time | |
void | printFrame (std::string name, KDL::Frame frame) |
void | setCartesianHybCntrl (boost::shared_ptr< Cartesian_HybCntrl > forceController_in) |
virtual | ~ForceTrajectory () |
Protected Attributes | |
boost::shared_ptr < Cartesian_HybCntrl > | forceController |
double | lastTime |
std::string | logCategory |
Definition at line 7 of file ForceTrajectory.h.
Definition at line 3 of file ForceTrajectory.cpp.
virtual ForceTrajectory::~ForceTrajectory | ( | ) | [inline, virtual] |
Definition at line 11 of file ForceTrajectory.h.
void ForceTrajectory::getPose | ( | double | time, |
KDL::JntArrayAcc & | pose | ||
) | [virtual] |
getPose get pose at a particular time
time | time along trajectory (0 - getDuration()) |
stepPose | pose corresponding to the time |
each step in a joint trajectory contains the position, velocity, and acceleration
Reimplemented from TreeIkTrajectory.
Definition at line 9 of file ForceTrajectory.cpp.
void ForceTrajectory::printFrame | ( | std::string | name, |
KDL::Frame | frame | ||
) |
Definition at line 91 of file ForceTrajectory.cpp.
void ForceTrajectory::setCartesianHybCntrl | ( | boost::shared_ptr< Cartesian_HybCntrl > | forceController_in | ) | [inline] |
Definition at line 13 of file ForceTrajectory.h.
boost::shared_ptr<Cartesian_HybCntrl> ForceTrajectory::forceController [protected] |
Definition at line 28 of file ForceTrajectory.h.
double ForceTrajectory::lastTime [protected] |
Reimplemented from TreeIkTrajectory.
Definition at line 29 of file ForceTrajectory.h.
std::string ForceTrajectory::logCategory [protected] |
Definition at line 30 of file ForceTrajectory.h.