Interface class for the servomotor controller. More...
#include <epos_driver.hpp>
Public Member Functions | |
eposdriver (ros::NodeHandle parameters) | |
Configuration of the node. | |
int | Main () |
The main loop handling all the functionalities of the driver. | |
int | Off () |
turn off the servomotor | |
int | On () |
setup the servomotor | |
~eposdriver () | |
Private Member Functions | |
int | EposError () |
This function displays the error status. | |
int | EposState () |
This function displays the statueof epos. | |
bool | MoveCycle (epos_driver::MoveCycle::Request &req, epos_driver::MoveCycle::Response &res) |
This is a handler to a service for a cyclic move. | |
bool | MoveTo (epos_driver::MoveTo::Request &req, epos_driver::MoveTo::Response &res) |
This is a handler to a service for a single move. | |
unsigned int | Radps2rpm (double radps) |
Converts radians to rotations. | |
Private Attributes | |
unsigned int | accel |
acceleration of the motor [rpm/s] | |
unsigned int | deccel |
deceleration of the motor [rpm/s] | |
double | highLimit |
the top limit of the cyclic motion of sensor | |
double | lowLimit |
the bottom limit of the cyclic motion of sensor | |
unsigned int | maxVelocity |
maximum velocity of the motor [rpm] | |
unsigned int | moduleCount |
number of controlled modules | |
int | motorState |
Motor on=1 off=0. | |
bool | moveDown |
flag for direction of movement to low_limit | |
bool | moveSingle |
flag for single movement | |
bool | moveUp |
flag for direction of movement to high_limit | |
std::string | myFrameId |
name of my coordination frame | |
ros::NodeHandle | nodeHandler |
node handler | |
double | pAccelRadpss |
accelaeration ot the motor [rad/s^s] (prameter handeler) | |
int | pAccelRpmps |
acceleration of the motor [rpm/s] (prameter handeler) | |
std::string | parentFrameId |
name of my parent coordination frame | |
double | pDeccelRadpss |
decelleration ot the motor [rad/s^s] (prameter handeler) | |
int | pDeccelRpmps |
deceleration of the motor [rpm/s] (prameter handeler) | |
double | pMaxVelocityRadps |
maximum velocity of the motor [rad/s] (prameter handeler) | |
int | pMaxVelocityRpm |
maximum velocity of the motor [rpm] (prameter handeler) | |
std::string | port |
path to the epos device | |
double | sensorPoseX |
x position of the wrist | |
double | sensorPoseY |
y position of the wrist | |
double | sensorPoseZ |
z position of the wrist | |
ros::Publisher | statePublisher |
state publisher of EPOS servomotor | |
bool | synchronize |
keps the information if pose can be synchornized or not | |
int | timeShift |
time which we need to shif to get proper time stamp of postion | |
double | topicFrequency |
frequency at which the topic with state is published | |
int | tresholdTicks |
treshold for changing the direction of mobement | |
bool | useRadps |
true if you want to use radians per second false if you want to use rpm | |
bool | useTrapezoidal |
true if you want to use trapezoidal profile false for sinusoidal |
Interface class for the servomotor controller.
This class impelents iterface for the epos servomotor controller. It is based on libray epos.h.
Definition at line 40 of file epos_driver.hpp.
eposdriver::eposdriver | ( | ros::NodeHandle | parameters | ) |
Configuration of the node.
In the constructor we set all the initial parmaeters and we also start the node itself however we do not start the communication with the servomotor.
[in] | param | thorugh this NodeHandle there are passed argumnets to the node. |
Definition at line 19 of file epos_driver.cpp.
eposdriver::~eposdriver | ( | ) | [inline] |
Definition at line 45 of file epos_driver.hpp.
int eposdriver::EposError | ( | ) | [private] |
This function displays the error status.
This function displays error of epos driver in more ROS friendly way. It is just a rewritten function checkEPOSerror().
Definition at line 345 of file epos_driver.cpp.
int eposdriver::EposState | ( | ) | [private] |
This function displays the statueof epos.
This function displays state of epos driver in more ROS friendly way. It is just a rewritten function printEPOSstate().
Definition at line 402 of file epos_driver.cpp.
int eposdriver::Main | ( | ) |
The main loop handling all the functionalities of the driver.
This function handles all the functionalities of the node. All the topics are published and all services are advertised inside of this function.
Definition at line 205 of file epos_driver.cpp.
bool eposdriver::MoveCycle | ( | epos_driver::MoveCycle::Request & | req, |
epos_driver::MoveCycle::Response & | res | ||
) | [private] |
This is a handler to a service for a cyclic move.
This is a handler for for the servie MoveTo. It accepts the input in radians. This service moves the sensor only once to given position.
Definition at line 449 of file epos_driver.cpp.
bool eposdriver::MoveTo | ( | epos_driver::MoveTo::Request & | req, |
epos_driver::MoveTo::Response & | res | ||
) | [private] |
This is a handler to a service for a single move.
This is a handler for for the servie MoveTo. It accepts the input in radians. This service moves the sensor only once to given position.
Definition at line 432 of file epos_driver.cpp.
int eposdriver::Off | ( | ) |
turn off the servomotor
This function closes communication with the epos servomotor.
Definition at line 182 of file epos_driver.cpp.
int eposdriver::On | ( | ) |
setup the servomotor
In this function take place all the necessarry setup of the driver. It opens and configure serial port.
This function is based on MainSetup from ALL4-e-Ham.
Definition at line 65 of file epos_driver.cpp.
unsigned int eposdriver::Radps2rpm | ( | double | radps | ) | [private] |
Converts radians to rotations.
This function is used to convert the units of rotation speed. It is based on code from ALL-4-eHAM
[in] | radps | input in radians |
Definition at line 327 of file epos_driver.cpp.
unsigned int eposdriver::accel [private] |
acceleration of the motor [rpm/s]
Definition at line 67 of file epos_driver.hpp.
unsigned int eposdriver::deccel [private] |
deceleration of the motor [rpm/s]
Definition at line 68 of file epos_driver.hpp.
double eposdriver::highLimit [private] |
the top limit of the cyclic motion of sensor
Definition at line 74 of file epos_driver.hpp.
double eposdriver::lowLimit [private] |
the bottom limit of the cyclic motion of sensor
Definition at line 75 of file epos_driver.hpp.
unsigned int eposdriver::maxVelocity [private] |
maximum velocity of the motor [rpm]
Definition at line 66 of file epos_driver.hpp.
unsigned int eposdriver::moduleCount [private] |
number of controlled modules
Definition at line 71 of file epos_driver.hpp.
int eposdriver::motorState [private] |
Motor on=1 off=0.
Definition at line 69 of file epos_driver.hpp.
bool eposdriver::moveDown [private] |
flag for direction of movement to low_limit
Definition at line 76 of file epos_driver.hpp.
bool eposdriver::moveSingle [private] |
flag for single movement
Definition at line 78 of file epos_driver.hpp.
bool eposdriver::moveUp [private] |
flag for direction of movement to high_limit
Definition at line 77 of file epos_driver.hpp.
std::string eposdriver::myFrameId [private] |
name of my coordination frame
Definition at line 79 of file epos_driver.hpp.
ros::NodeHandle eposdriver::nodeHandler [private] |
node handler
Definition at line 54 of file epos_driver.hpp.
double eposdriver::pAccelRadpss [private] |
accelaeration ot the motor [rad/s^s] (prameter handeler)
Definition at line 60 of file epos_driver.hpp.
int eposdriver::pAccelRpmps [private] |
acceleration of the motor [rpm/s] (prameter handeler)
Definition at line 63 of file epos_driver.hpp.
std::string eposdriver::parentFrameId [private] |
name of my parent coordination frame
Definition at line 80 of file epos_driver.hpp.
double eposdriver::pDeccelRadpss [private] |
decelleration ot the motor [rad/s^s] (prameter handeler)
Definition at line 61 of file epos_driver.hpp.
int eposdriver::pDeccelRpmps [private] |
deceleration of the motor [rpm/s] (prameter handeler)
Definition at line 64 of file epos_driver.hpp.
double eposdriver::pMaxVelocityRadps [private] |
maximum velocity of the motor [rad/s] (prameter handeler)
Definition at line 59 of file epos_driver.hpp.
int eposdriver::pMaxVelocityRpm [private] |
maximum velocity of the motor [rpm] (prameter handeler)
Definition at line 62 of file epos_driver.hpp.
std::string eposdriver::port [private] |
path to the epos device
Definition at line 56 of file epos_driver.hpp.
double eposdriver::sensorPoseX [private] |
x position of the wrist
Definition at line 81 of file epos_driver.hpp.
double eposdriver::sensorPoseY [private] |
y position of the wrist
Definition at line 82 of file epos_driver.hpp.
double eposdriver::sensorPoseZ [private] |
z position of the wrist
Definition at line 83 of file epos_driver.hpp.
ros::Publisher eposdriver::statePublisher [private] |
state publisher of EPOS servomotor
Definition at line 55 of file epos_driver.hpp.
bool eposdriver::synchronize [private] |
keps the information if pose can be synchornized or not
Definition at line 57 of file epos_driver.hpp.
int eposdriver::timeShift [private] |
time which we need to shif to get proper time stamp of postion
Definition at line 85 of file epos_driver.hpp.
double eposdriver::topicFrequency [private] |
frequency at which the topic with state is published
Definition at line 73 of file epos_driver.hpp.
int eposdriver::tresholdTicks [private] |
treshold for changing the direction of mobement
Definition at line 84 of file epos_driver.hpp.
bool eposdriver::useRadps [private] |
true if you want to use radians per second false if you want to use rpm
Definition at line 58 of file epos_driver.hpp.
bool eposdriver::useTrapezoidal [private] |
true if you want to use trapezoidal profile false for sinusoidal
Definition at line 65 of file epos_driver.hpp.