CartesianControllerVel Class Reference

This class implements a TaskContext that controlls the end-effector frame of a robot. More...

#include <CartesianControllerVel.hpp>

List of all members.

Public Member Functions

 CartesianControllerVel (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::ReadDataPort< KDL::Frame > _position_meas
 DataPort containing the measured frame, shared with OCL::CartesianSensor.
RTT::DataPort< KDL::Twist > _velocity_desi
 DataPort containing the desired twist, represented in the base frame with end-effector reference point, shared with OCL::CartesianGeneratorPos.
RTT::WriteDataPort< KDL::Twist > _velocity_out
 DataPort containing the output twist, represented in the base frame with end-effector reference point, shared with OCL::CartesianEffectorVel.
RTT::Property< std::vector
< double > > 
_controller_gain
 Vector with the control gain value for each dof.

Detailed Description

This class implements a TaskContext that controlls the end-effector frame of a robot.

It uses a simple position-feedback and velocity-feedforward to calculate an output twist. twist_out = K_gain * ( frame_desired - frame_measured) + twist_desired.

Definition at line 46 of file CartesianControllerVel.hpp.


Constructor & Destructor Documentation

CartesianControllerVel ( std::string  name  ) 

Constructor of the class.

Parameters:
name name of the TaskContext

Definition at line 35 of file CartesianControllerVel.cpp.

References CartesianControllerVel::_controller_gain, CartesianControllerVel::_position_meas, CartesianControllerVel::_velocity_desi, and CartesianControllerVel::_velocity_out.


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