CartesianGeneratorPos Class Reference

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>

List of all members.

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.

Detailed Description

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.


Constructor & Destructor Documentation

CartesianGeneratorPos ( std::string  name  ) 

Member Data Documentation

RTT::Command<bool(KDL::Frame,double)> _moveTo [protected]

Command to generate the motion.

Command stops when the movement is finished.

Parameters:
frame the desired frame
time the minimum time duration of the movement.
Returns:
false if a previous motion is still going on, true otherwise

Definition at line 96 of file CartesianGeneratorPos.hpp.

Referenced by CartesianGeneratorPos::CartesianGeneratorPos().


The documentation for this class was generated from the following files:
Generated on Thu Dec 23 15:05:29 2010 for OrocosComponentLibrary by  doxygen 1.6.3