motor.cpp
Go to the documentation of this file.
00001 #include "phidgets_api/motor.h"
00002 
00003 #include <cassert>
00004 
00005 // Get and return the value name of type type (I varient is indexed)
00006 #define GAR(type, name)      type x; int ret = CPhidgetMotorControl_get ## name (motor_handle_, &x); assert(ret == EPHIDGET_OK); return x;
00007 #define GAR_I(type, name, i) type x; int ret = CPhidgetMotorControl_get ## name (motor_handle_, i, &x); assert(ret == EPHIDGET_OK); return x;
00008 
00009 // Set the value name to x (I varient is indexed)
00010 #define SET(name, x)      int ret = CPhidgetMotorControl_set ## name (motor_handle_, x); assert(ret == EPHIDGET_OK);
00011 #define SET_I(name, x, i) int ret = CPhidgetMotorControl_set ## name (motor_handle_, i, x); assert(ret == EPHIDGET_OK);
00012 
00013 namespace phidgets
00014 {
00015 
00016 MotorController::MotorController():
00017   Phidget(),
00018   motor_handle_(0)
00019 {
00020   // create the handle
00021   CPhidgetMotorControl_create(&motor_handle_);
00022 
00023   // pass handle to base class
00024   Phidget::init((CPhidgetHandle)motor_handle_);
00025 
00026   // register base class callbacks
00027   Phidget::registerHandlers();
00028 
00029   // register motor data callbacks
00030   CPhidgetMotorControl_set_OnVelocityChange_Handler(motor_handle_, VelocityChangeHandler, this);
00031   CPhidgetMotorControl_set_OnCurrentChange_Handler(motor_handle_, CurrentChangeHandler, this);
00032   CPhidgetMotorControl_set_OnInputChange_Handler(motor_handle_, InputChangeHandler, this);
00033   CPhidgetMotorControl_set_OnEncoderPositionChange_Handler(motor_handle_, EncoderPositionChangeHandler, this);
00034   CPhidgetMotorControl_set_OnEncoderPositionUpdate_Handler(motor_handle_, EncoderPositionUpdateHandler, this);
00035   CPhidgetMotorControl_set_OnBackEMFUpdate_Handler(motor_handle_, BackEMFUpdateHandler, this);
00036   CPhidgetMotorControl_set_OnSensorUpdate_Handler(motor_handle_, SensorUpdateHandler, this);
00037   CPhidgetMotorControl_set_OnCurrentUpdate_Handler(motor_handle_, CurrentUpdateHandler, this);
00038 }
00039 
00040 int MotorController::getMotorCount()
00041 {
00042   GAR(int, MotorCount);
00043 }
00044 
00045 double MotorController::getVelocity(int index)
00046 {
00047   GAR_I(double, Velocity, index);
00048 }
00049 
00050 void MotorController::setVelocity(int index, double velocity)
00051 {
00052   SET_I(Velocity, velocity, index);
00053 }
00054 
00055 double MotorController::getAcceleration(int index)
00056 {
00057   GAR_I(double, Acceleration, index);
00058 }
00059 
00060 void MotorController::setAcceleration(int index, double acceleration)
00061 {
00062   SET_I(Acceleration, acceleration, index);
00063 }
00064 
00065 double MotorController::getAccelerationMax(int index)
00066 {
00067   GAR_I(double, AccelerationMax, index);
00068 }
00069 
00070 double MotorController::getAccelerationMin(int index)
00071 {
00072   GAR_I(double, AccelerationMin, index);
00073 }
00074 
00075 double MotorController::getCurrent(int index)
00076 {
00077   GAR_I(double, Current, index);
00078 }
00079 
00080 int MotorController::getInputCount()
00081 {
00082   GAR(int, InputCount);
00083 }
00084 
00085 bool MotorController::getInputState(int index)
00086 {
00087   int state;
00088   int ret = CPhidgetMotorControl_getInputState(motor_handle_, index, &state);
00089 
00090   assert(ret == EPHIDGET_OK);
00091 
00092   return state == PTRUE;
00093 }
00094 
00095 int MotorController::getEncoderCount()
00096 {
00097   GAR(int, EncoderCount);
00098 }
00099 
00100 int MotorController::getEncoderPosition(int index)
00101 {
00102   GAR_I(int, EncoderPosition, index);
00103 }
00104 
00105 void MotorController::setEncoderPosition(int index, int position)
00106 {
00107   SET_I(EncoderPosition, position, index);
00108 }
00109 
00110 int MotorController::getBackEMFSensingState(int index)
00111 {
00112   GAR_I(int, BackEMFSensingState, index);
00113 }
00114 
00115 void MotorController::setBackEMFSensingState(int index, int bEMFState)
00116 {
00117   SET_I(BackEMFSensingState, bEMFState, index);
00118 }
00119 
00120 double MotorController::getBackEMF(int index)
00121 {
00122   GAR_I(double, BackEMF, index);
00123 }
00124 
00125 double MotorController::getSupplyVoltage()
00126 {
00127   GAR(double, SupplyVoltage);
00128 }
00129 
00130 double MotorController::getBraking(int index)
00131 {
00132   GAR_I(double, Braking, index);
00133 }
00134 
00135 void MotorController::setBraking(int index, double braking)
00136 {
00137   SET_I(Braking, braking, index);
00138 }
00139 
00140 int MotorController::getSensorCount()
00141 {
00142   GAR(int, SensorCount);
00143 }
00144 
00145 int MotorController::getSensorValue(int index)
00146 {
00147   GAR_I(int, SensorValue, index);
00148 }
00149 
00150 int MotorController::getSensorRawValue(int index)
00151 {
00152   GAR_I(int, SensorRawValue, index);
00153 }
00154 
00155 int MotorController::getRatiometric()
00156 {
00157   GAR(int, Ratiometric);
00158 }
00159 
00160 void MotorController::setRatiometric(int ratiometric)
00161 {
00162   SET(Ratiometric, ratiometric);
00163 }
00164 
00165 int MotorController::VelocityChangeHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity)
00166 {
00167   ((MotorController*)userPtr)->velocityChangeHandler(index, velocity);
00168 }
00169 
00170 int MotorController::CurrentChangeHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current)
00171 {
00172   ((MotorController*)userPtr)->currentChangeHandler(index, current);
00173 }
00174 
00175 int MotorController::InputChangeHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState)
00176 {
00177   ((MotorController*)userPtr)->inputChangeHandler(index, inputState);
00178 }
00179 
00180 int MotorController::EncoderPositionChangeHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, int time, int positionChange)
00181 {
00182   ((MotorController*)userPtr)->encoderPositionChangeHandler(index, time, positionChange);
00183 }
00184 
00185 int MotorController::EncoderPositionUpdateHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, int positionChange)
00186 {
00187   ((MotorController*)userPtr)->encoderPositionUpdateHandler(index, positionChange);
00188 }
00189 
00190 int MotorController::BackEMFUpdateHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, double voltage)
00191 {
00192   ((MotorController*)userPtr)->backEMFUpdateHandler(index, voltage);
00193 }
00194 
00195 int MotorController::SensorUpdateHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, int sensorValue)
00196 {
00197   ((MotorController*)userPtr)->sensorUpdateHandler(index, sensorValue);
00198 }
00199 
00200 int MotorController::CurrentUpdateHandler(CPhidgetMotorControlHandle phid, void *userPtr, int index, double current)
00201 {
00202   ((MotorController*)userPtr)->currentUpdateHandler(index, current);
00203 }
00204 
00205 void MotorController::velocityChangeHandler(int index, double velocity)
00206 {
00207   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00208 }
00209 
00210 void MotorController::currentChangeHandler(int index, double current)
00211 {
00212   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00213 }
00214 
00215 void MotorController::inputChangeHandler(int index, int inputState)
00216 {
00217   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00218 }
00219 
00220 void MotorController::encoderPositionChangeHandler(int index, int time, int positionChange)
00221 {
00222   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00223 }
00224 
00225 void MotorController::encoderPositionUpdateHandler(int index, int positionChange)
00226 {
00227   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00228 }
00229 
00230 void MotorController::backEMFUpdateHandler(int index, double voltage)
00231 {
00232   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00233 }
00234 
00235 void MotorController::sensorUpdateHandler(int index, int sensorValue)
00236 {
00237   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00238 }
00239 
00240 void MotorController::currentUpdateHandler(int index, double current)
00241 {
00242   // This method can be overridden in a concrete subclass (e.g., ROS wrapper)
00243 }
00244 
00245 } //namespace phidgets


phidgets_api
Author(s): Tully Foote, Ivan Dryanovski
autogenerated on Wed Aug 16 2017 02:50:15