#include <motor.h>
Public Member Functions | |
double | getAcceleration (int index) |
double | getAccelerationMax (int index) |
double | getAccelerationMin (int index) |
double | getBackEMF (int index) |
int | getBackEMFSensingState (int index) |
double | getBraking (int index) |
double | getCurrent (int index) |
int | getEncoderCount () |
int | getEncoderPosition (int index) |
int | getInputCount () |
bool | getInputState (int index) |
int | getMotorCount () |
int | getRatiometric () |
int | getSensorCount () |
int | getSensorRawValue (int index) |
int | getSensorValue (int index) |
double | getSupplyVoltage () |
double | getVelocity (int index) |
MotorController () | |
void | setAcceleration (int index, double acceleration) |
void | setBackEMFSensingState (int index, int bEMFState) |
void | setBraking (int index, double braking) |
void | setEncoderPosition (int index, int position) |
void | setRatiometric (int ratiometric) |
void | setVelocity (int index, double velocity) |
Protected Member Functions | |
virtual void | backEMFUpdateHandler (int index, double voltage) |
virtual void | currentChangeHandler (int index, double current) |
virtual void | currentUpdateHandler (int index, double current) |
virtual void | encoderPositionChangeHandler (int index, int time, int positionChange) |
virtual void | encoderPositionUpdateHandler (int index, int positionChange) |
virtual void | inputChangeHandler (int index, int inputState) |
virtual void | sensorUpdateHandler (int index, int sensorValue) |
virtual void | velocityChangeHandler (int index, double velocity) |
Protected Attributes | |
CPhidgetMotorControlHandle | motor_handle_ |
Static Private Member Functions | |
static int | BackEMFUpdateHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, double voltage) |
static int | CurrentChangeHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, double current) |
static int | CurrentUpdateHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, double current) |
static int | EncoderPositionChangeHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, int time, int positionChange) |
static int | EncoderPositionUpdateHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, int positionChange) |
static int | InputChangeHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, int inputState) |
static int | SensorUpdateHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, int sensorValue) |
static int | VelocityChangeHandler (CPhidgetMotorControlHandle phid, void *userPtr, int index, double velocity) |
void phidgets::MotorController::backEMFUpdateHandler | ( | int | index, |
double | voltage | ||
) | [protected, virtual] |
int phidgets::MotorController::BackEMFUpdateHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
double | voltage | ||
) | [static, private] |
void phidgets::MotorController::currentChangeHandler | ( | int | index, |
double | current | ||
) | [protected, virtual] |
int phidgets::MotorController::CurrentChangeHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
double | current | ||
) | [static, private] |
void phidgets::MotorController::currentUpdateHandler | ( | int | index, |
double | current | ||
) | [protected, virtual] |
int phidgets::MotorController::CurrentUpdateHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
double | current | ||
) | [static, private] |
void phidgets::MotorController::encoderPositionChangeHandler | ( | int | index, |
int | time, | ||
int | positionChange | ||
) | [protected, virtual] |
int phidgets::MotorController::EncoderPositionChangeHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
int | time, | ||
int | positionChange | ||
) | [static, private] |
void phidgets::MotorController::encoderPositionUpdateHandler | ( | int | index, |
int | positionChange | ||
) | [protected, virtual] |
int phidgets::MotorController::EncoderPositionUpdateHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
int | positionChange | ||
) | [static, private] |
double phidgets::MotorController::getAcceleration | ( | int | index | ) |
double phidgets::MotorController::getAccelerationMax | ( | int | index | ) |
double phidgets::MotorController::getAccelerationMin | ( | int | index | ) |
double phidgets::MotorController::getBackEMF | ( | int | index | ) |
int phidgets::MotorController::getBackEMFSensingState | ( | int | index | ) |
double phidgets::MotorController::getBraking | ( | int | index | ) |
double phidgets::MotorController::getCurrent | ( | int | index | ) |
int phidgets::MotorController::getEncoderPosition | ( | int | index | ) |
bool phidgets::MotorController::getInputState | ( | int | index | ) |
int phidgets::MotorController::getSensorRawValue | ( | int | index | ) |
int phidgets::MotorController::getSensorValue | ( | int | index | ) |
double phidgets::MotorController::getSupplyVoltage | ( | ) |
double phidgets::MotorController::getVelocity | ( | int | index | ) |
void phidgets::MotorController::inputChangeHandler | ( | int | index, |
int | inputState | ||
) | [protected, virtual] |
int phidgets::MotorController::InputChangeHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
int | inputState | ||
) | [static, private] |
void phidgets::MotorController::sensorUpdateHandler | ( | int | index, |
int | sensorValue | ||
) | [protected, virtual] |
int phidgets::MotorController::SensorUpdateHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
int | sensorValue | ||
) | [static, private] |
void phidgets::MotorController::setAcceleration | ( | int | index, |
double | acceleration | ||
) |
void phidgets::MotorController::setBackEMFSensingState | ( | int | index, |
int | bEMFState | ||
) |
void phidgets::MotorController::setBraking | ( | int | index, |
double | braking | ||
) |
void phidgets::MotorController::setEncoderPosition | ( | int | index, |
int | position | ||
) |
void phidgets::MotorController::setRatiometric | ( | int | ratiometric | ) |
void phidgets::MotorController::setVelocity | ( | int | index, |
double | velocity | ||
) |
void phidgets::MotorController::velocityChangeHandler | ( | int | index, |
double | velocity | ||
) | [protected, virtual] |
int phidgets::MotorController::VelocityChangeHandler | ( | CPhidgetMotorControlHandle | phid, |
void * | userPtr, | ||
int | index, | ||
double | velocity | ||
) | [static, private] |
CPhidgetMotorControlHandle phidgets::MotorController::motor_handle_ [protected] |