#include <ElmoCtrl.h>
Public Types | |
enum | { POS_CTRL, VEL_CTRL } |
Public Member Functions | |
ElmoCtrl () | |
int | evalCanBuffer () |
CANPeakSysUSB * | GetCanCtrl () |
int | getGearPosVelRadS (double *pdAngleGearRad, double *pdVelGearRadS) |
double | getJointVelocity () |
int | GetMotionCtrlType () |
bool | Home () |
bool | Init (ElmoCtrlParams *params, bool home=true) |
double | MoveJointSpace (double PosRad) |
bool | RecoverAfterEmergencyStop () |
int | setGearPosVelRadS (double dPosRad, double dVelRadS) |
void | setMaxVelocity (float radpersec) |
bool | SetMotionCtrlType (int type) |
bool | Stop () |
~ElmoCtrl () | |
Public Attributes | |
CanDriveHarmonica * | m_Joint |
joint mutexes | |
enum ElmoCtrl:: { ... } | MOTION_CTRL_TYPE |
Private Member Functions | |
bool | sendNetStartCanOpen (CanItf *canCtrl) |
Private Attributes | |
CanOpenAddress | m_CanAddress |
int | m_CanBaseAddress |
CANPeakSysUSB * | m_CanCtrl |
CanMsg | m_CanMsgRec |
int | m_EncIncrPerRevMot |
double | m_GearRatio |
int | m_HomingDigIn |
int | m_HomingDir |
double | m_JointOffset |
DriveParam * | m_JointParams |
double | m_LowerLimit |
double | m_MaxVel |
int | m_MotionCtrlType |
int | m_MotorDirection |
pthread_mutex_t | m_Mutex |
joint mutexes | |
ElmoCtrlParams * | m_Params |
joint velocity mutexes | |
double | m_UpperLimit |
Definition at line 171 of file ElmoCtrl.h.
anonymous enum |
Definition at line 224 of file ElmoCtrl.h.
ElmoCtrl::ElmoCtrl | ( | ) |
Definition at line 77 of file ElmoCtrl.cpp.
ElmoCtrl::~ElmoCtrl | ( | ) |
Definition at line 87 of file ElmoCtrl.cpp.
int ElmoCtrl::evalCanBuffer | ( | ) |
Triggers evaluation of the can-buffer.
Definition at line 127 of file ElmoCtrl.cpp.
CANPeakSysUSB* ElmoCtrl::GetCanCtrl | ( | ) | [inline] |
Definition at line 230 of file ElmoCtrl.h.
int ElmoCtrl::getGearPosVelRadS | ( | double * | pdAngleGearRad, | |
double * | pdVelGearRadS | |||
) |
Gets the position and velocity.
pdAngleGearRad | joint-position in radian | |
pdVelGearRadS | joint-velocity in radian per second |
Definition at line 415 of file ElmoCtrl.cpp.
double ElmoCtrl::getJointVelocity | ( | ) |
int ElmoCtrl::GetMotionCtrlType | ( | ) |
Definition at line 410 of file ElmoCtrl.cpp.
bool ElmoCtrl::Home | ( | ) |
Definition at line 97 of file ElmoCtrl.cpp.
bool ElmoCtrl::Init | ( | ElmoCtrlParams * | params, | |
bool | home = true | |||
) |
Definition at line 163 of file ElmoCtrl.cpp.
double ElmoCtrl::MoveJointSpace | ( | double | PosRad | ) |
bool ElmoCtrl::RecoverAfterEmergencyStop | ( | ) |
Definition at line 147 of file ElmoCtrl.cpp.
bool ElmoCtrl::sendNetStartCanOpen | ( | CanItf * | canCtrl | ) | [private] |
Definition at line 61 of file ElmoCtrl.cpp.
int ElmoCtrl::setGearPosVelRadS | ( | double | dPosRad, | |
double | dVelRadS | |||
) |
Sets required position and veolocity. Use this function only in position mode.
Definition at line 430 of file ElmoCtrl.cpp.
void ElmoCtrl::setMaxVelocity | ( | float | radpersec | ) | [inline] |
Definition at line 191 of file ElmoCtrl.h.
bool ElmoCtrl::SetMotionCtrlType | ( | int | type | ) |
Definition at line 385 of file ElmoCtrl.cpp.
bool ElmoCtrl::Stop | ( | ) |
Definition at line 454 of file ElmoCtrl.cpp.
CanOpenAddress ElmoCtrl::m_CanAddress [private] |
Definition at line 246 of file ElmoCtrl.h.
int ElmoCtrl::m_CanBaseAddress [private] |
Definition at line 245 of file ElmoCtrl.h.
CANPeakSysUSB* ElmoCtrl::m_CanCtrl [private] |
Definition at line 248 of file ElmoCtrl.h.
CanMsg ElmoCtrl::m_CanMsgRec [private] |
Definition at line 275 of file ElmoCtrl.h.
int ElmoCtrl::m_EncIncrPerRevMot [private] |
Definition at line 254 of file ElmoCtrl.h.
double ElmoCtrl::m_GearRatio [private] |
Definition at line 256 of file ElmoCtrl.h.
int ElmoCtrl::m_HomingDigIn [private] |
Definition at line 253 of file ElmoCtrl.h.
int ElmoCtrl::m_HomingDir [private] |
Definition at line 252 of file ElmoCtrl.h.
CanDriveHarmonica* ElmoCtrl::m_Joint |
joint mutexes
Definition at line 235 of file ElmoCtrl.h.
double ElmoCtrl::m_JointOffset [private] |
Definition at line 260 of file ElmoCtrl.h.
DriveParam* ElmoCtrl::m_JointParams [private] |
Definition at line 243 of file ElmoCtrl.h.
double ElmoCtrl::m_LowerLimit [private] |
Definition at line 259 of file ElmoCtrl.h.
double ElmoCtrl::m_MaxVel [private] |
Definition at line 251 of file ElmoCtrl.h.
int ElmoCtrl::m_MotionCtrlType [private] |
Definition at line 241 of file ElmoCtrl.h.
int ElmoCtrl::m_MotorDirection [private] |
Definition at line 255 of file ElmoCtrl.h.
pthread_mutex_t ElmoCtrl::m_Mutex [private] |
joint mutexes
Definition at line 267 of file ElmoCtrl.h.
ElmoCtrlParams* ElmoCtrl::m_Params [private] |
joint velocity mutexes
Thread IDs for PowerCube connection threads Arguments for Powercube connection Threads
Definition at line 274 of file ElmoCtrl.h.
double ElmoCtrl::m_UpperLimit [private] |
Definition at line 258 of file ElmoCtrl.h.
enum { ... } ElmoCtrl::MOTION_CTRL_TYPE |