This class implements a TaskContext that creates a path in Cartesian space between the current cartesian position and a new desired cartesian position. More...
#include <CartesianGeneratorPos.hpp>
Public Member Functions | |
CartesianGeneratorPos (std::string name) | |
Constructor of the class. | |
virtual bool | configureHook () |
virtual bool | startHook () |
virtual void | updateHook () |
virtual void | stopHook () |
virtual void | cleanupHook () |
Protected Attributes | |
RTT::Command< bool(KDL::Frame, double)> | _moveTo |
Command to generate the motion. | |
RTT::Method< void(void)> | _reset_position |
Method that resets the generators desired frame tho the current measured frame and the desired twist to zero. | |
RTT::ReadDataPort< KDL::Frame > | _position_meas |
Dataport containing the current measured end-effector frame, shared with OCL::CartesianSensor. | |
RTT::WriteDataPort< KDL::Frame > | _position_desi |
Dataport containing the current desired end-effector frame, shared with OCL::CartesianControllerPos, OCL::CartesianControllerPosVel. | |
RTT::WriteDataPort< KDL::Twist > | _velocity_desi |
Dataport containing the current desired end-effector twist, shared with OCL::CartesianControllerPosVel, OCL::CartesianControllerVel. | |
RTT::Property< std::vector < double > > | _maximum_velocity |
Property containing a vector with the maximum velocity of each dof. | |
RTT::Property< std::vector < double > > | _maximum_acceleration |
Property containing a vector with the maximum acceleration of each dof. |
This class implements a TaskContext that creates a path in Cartesian space between the current cartesian position and a new desired cartesian position.
It uses trapezoidal velocity-profiles for every dof using a maximum velocity and a maximum acceleration. It generates frame and twist setpoints which can be used by OCL::CartesianControllerPos, OCL::CartesianControllerPosVel or OCL::CartesianControllerVel.
Definition at line 52 of file CartesianGeneratorPos.hpp.
CartesianGeneratorPos | ( | std::string | name | ) |
Constructor of the class.
name | name of the TaskContext |
Definition at line 34 of file CartesianGeneratorPos.cpp.
References CartesianGeneratorPos::_maximum_acceleration, CartesianGeneratorPos::_maximum_velocity, CartesianGeneratorPos::_moveTo, CartesianGeneratorPos::_position_desi, CartesianGeneratorPos::_position_meas, CartesianGeneratorPos::_reset_position, and CartesianGeneratorPos::_velocity_desi.
RTT::Command<bool(KDL::Frame,double)> _moveTo [protected] |
Command to generate the motion.
Command stops when the movement is finished.
frame | the desired frame | |
time | the minimum time duration of the movement. |
Definition at line 96 of file CartesianGeneratorPos.hpp.
Referenced by CartesianGeneratorPos::CartesianGeneratorPos().