This class implements a TaskContext that controlls the end-effector frame of a robot. More...
#include <CartesianControllerPosVel.hpp>
Public Member Functions | |
CartesianControllerPosVel (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::ReadDataPort< KDL::Frame > | _position_desi |
DataPort containing the desired frame, shared with OCL::CartesianGeneratorPos. | |
RTT::ReadDataPort< 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. |
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 45 of file CartesianControllerPosVel.hpp.
CartesianControllerPosVel | ( | std::string | name | ) |
Constructor of the class.
name | name of the TaskContext |
Definition at line 34 of file CartesianControllerPosVel.cpp.
References CartesianControllerPosVel::_controller_gain, CartesianControllerPosVel::_position_desi, CartesianControllerPosVel::_position_meas, CartesianControllerPosVel::_velocity_desi, and CartesianControllerPosVel::_velocity_out.