00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include "CartesianControllerPos.hpp"
00023 #include <assert.h>
00024 #include <ocl/ComponentLoader.hpp>
00025
00026 ORO_CREATE_COMPONENT_TYPE();
00027 ORO_LIST_COMPONENT_TYPE( OCL::CartesianControllerPos );
00028
00029 namespace OCL
00030 {
00031
00032 using namespace RTT;
00033 using namespace KDL;
00034 using namespace std;
00035
00036
00037 CartesianControllerPos::CartesianControllerPos(string name)
00038 : TaskContext(name,PreOperational),
00039 _gain_local(6,0.0),
00040 _position_meas("CartesianSensorPosition"),
00041 _position_desi("CartesianDesiredPosition"),
00042 _velocity_out("CartesianOutputVelocity"),
00043 _controller_gain("K", "Proportional Gain",vector<double>(6,0.0))
00044 {
00045
00046
00047
00048 this->ports()->addPort(&_position_meas);
00049 this->ports()->addPort(&_position_desi);
00050 this->ports()->addPort(&_velocity_out);
00051
00052
00053 this->properties()->addProperty(&_controller_gain);
00054
00055 }
00056
00057 CartesianControllerPos::~CartesianControllerPos(){};
00058
00059 bool CartesianControllerPos::configureHook()
00060 {
00061
00062
00063
00064 if(_controller_gain.value().size()!=6)
00065 return false;
00066
00067 _gain_local=_controller_gain.value();
00068 return true;
00069 }
00070
00071 bool CartesianControllerPos::startHook()
00072 {
00073 return true;
00074 }
00075
00076 void CartesianControllerPos::updateHook()
00077 {
00078
00079 _position_meas_local = _position_meas.Get();
00080 _position_desi_local = _position_desi.Get();
00081
00082 _velocity_out_local = diff(_position_meas_local, _position_desi_local);
00083
00084 for(unsigned int i=0; i<6; i++)
00085 _velocity_out_local(i) *= _gain_local[i];
00086
00087 _velocity_out.Set(_velocity_out_local);
00088 }
00089
00090 void CartesianControllerPos::stopHook()
00091 {
00092 }
00093
00094 void CartesianControllerPos::cleanupHook()
00095 {
00096 }
00097
00098 }