Go to the documentation of this file.00001
00024 #ifndef PUMA_MOTOR_DRIVER_DRIVER_H
00025 #define PUMA_MOTOR_DRIVER_DRIVER_H
00026
00027 #include <stdint.h>
00028 #include <string>
00029
00030 #include "puma_motor_driver/can_proto.h"
00031 #include "puma_motor_msgs/Status.h"
00032
00033 namespace puma_motor_driver
00034 {
00035
00036 class Gateway;
00037 class Message;
00038
00039 class Driver
00040 {
00041 public:
00042 Driver(Gateway& gateway, uint8_t device_number, std::string device_name);
00043
00044 void processMessage(const Message& received_msg);
00045
00051 void requestStatusMessages();
00052
00058 void requestFeedbackMessages();
00063 void requestFeedbackDutyCycle();
00068 void requestFeedbackCurrent();
00073 void requestFeedbackPosition();
00078 void requestFeedbackSpeed();
00082 void requestFeedbackPowerState();
00087 void requestFeedbackSetpoint();
00092 void clearStatusCache();
00098 void commandDutyCycle(float cmd);
00104 void commandSpeed(double cmd);
00105
00106
00107
00108
00114 void setEncoderCPR(uint16_t encoder_cpr);
00120 void setGearRatio(float gear_ratio);
00126 void setMode(uint8_t mode);
00136 void setMode(uint8_t mode, double p, double i, double d);
00144 void setGains(double p, double i, double d);
00145
00151 uint8_t lastFault();
00157 uint8_t lastPower();
00163 uint8_t lastMode();
00169 float lastDutyCycle();
00175 float lastBusVoltage();
00181 float lastCurrent();
00187 float lastOutVoltage();
00193 float lastTemperature();
00199 float lastAnalogInput();
00205 double lastPosition();
00211 double lastSpeed();
00218 double lastSetpoint();
00219
00224 void configureParams();
00229 void verifyParams();
00235 bool isConfigured();
00236 void resetConfiguration();
00240 void updateGains();
00250 uint8_t posEncoderRef();
00256 uint8_t spdEncoderRef();
00262 uint16_t encoderCounts();
00263
00270 double getP();
00277 double getI();
00284 double getD();
00291 uint8_t* getRawP();
00298 uint8_t* getRawI();
00305 uint8_t* getRawD();
00312 float statusDutyCycleGet();
00319 double statusSpeedGet();
00326 float statusCurrentGet();
00333 double statusPositionGet();
00334
00337 Driver operator=(const Driver& rhs)
00338 {
00339 return Driver(gateway_, device_number_, device_name_);
00340 }
00341
00342 std::string deviceName() { return device_name_; }
00343
00344 uint8_t deviceNumber() { return device_number_; }
00345
00346
00347 struct StatusField
00348 {
00349 uint8_t data[4];
00350 bool received;
00351
00352 float interpretFixed8x8()
00353 {
00354 return *(reinterpret_cast<int16_t*>(data)) / static_cast<float>(1<<8);
00355 }
00356
00357 double interpretFixed16x16()
00358 {
00359 return *(reinterpret_cast<int32_t*>(data)) / static_cast<double>(1<<16);
00360 }
00361 };
00362
00363
00364 private:
00365 Gateway& gateway_;
00366 uint8_t device_number_;
00367 std::string device_name_;
00368
00369 bool configured_;
00370 uint8_t state_;
00371
00372 uint8_t control_mode_;
00373 double gain_p_;
00374 double gain_i_;
00375 double gain_d_;
00376 uint16_t encoder_cpr_;
00377 float gear_ratio_;
00378
00382 void sendUint8(uint32_t id, uint8_t value);
00383 void sendUint16(uint32_t id, uint16_t value);
00384 void sendFixed8x8(uint32_t id, float value);
00385 void sendFixed16x16(uint32_t id, double value);
00386
00393 bool verifyRaw16x16(uint8_t* received, double expected);
00394
00401 bool verifyRaw8x8(uint8_t* received, float expected);
00402
00403 StatusField status_fields_[12];
00404
00405 StatusField* statusFieldForMessage(const Message& msg);
00406 };
00407
00408 }
00409
00410 #endif // PUMA_MOTOR_DRIVER_DRIVER_H