Go to the documentation of this file.00001
00031 #ifndef MOTORMESSAGE_H
00032 #define MOTORMESSAGE_H
00033
00034 #include <stdint.h>
00035 #include <vector>
00036
00037 class MotorMessage{
00038
00039 public:
00040
00041 MotorMessage() {};
00042 ~MotorMessage() {};
00043
00044
00045 enum MessageTypes {
00046 TYPE_READ = 0xAA,
00047 TYPE_WRITE = 0xBB,
00048 TYPE_RESPONSE = 0xCC
00049 };
00050
00051
00052 enum Registers {
00053 REG_STOP_START = 0x00,
00054 REG_BRAKE_STOP = 0x01,
00055 REG_CRUISE_STOP = 0x02,
00056
00057 REG_LEFT_PWM = 0x03,
00058 REG_RIGHT_PWM = 0x04,
00059
00060
00061
00062 REG_LEFT_SPEED_SET = 0x07,
00063 REG_RIGHT_SPEED_SET = 0x08,
00064
00065 REG_LEFT_RAMP = 0x09,
00066 REG_RIGHT_RAMP = 0x0A,
00067
00068 REG_LEFT_ODOM = 0x0B,
00069 REG_RIGHT_ODOM = 0x0C,
00070
00071 REG_DEADMAN = 0x0D,
00072
00073 REG_LEFT_CURRENT = 0x0E,
00074 REG_RIGHT_CURRENT = 0x0F,
00075
00076 REG_ERROR_COUNT = 0x10,
00077 REG_5V_MAIN_ERROR = 0x11,
00078 REG_5V_AUX_ERROR = 0x12,
00079 REG_12V_MAIN_ERROR = 0x13,
00080 REG_12V_AUX_ERROR = 0x14,
00081 REG_5V_MAIN_OL = 0x15,
00082 REG_5V_AUX_OL = 0x16,
00083 REG_12V_MAIN_OL = 0x17,
00084 REG_12V_AUX_OL = 0x18,
00085 REG_LEFT_MOTOR_ERROR = 0x19,
00086 REG_RIGHT_MOTOR_ERROR = 0x1A,
00087
00088 REG_PARAM_P = 0x1B,
00089 REG_PARAM_I = 0x1C,
00090 REG_PARAM_D = 0x1D,
00091 REG_PARAM_C = 0x1E,
00092
00093 REG_LED_1 = 0x1F,
00094 REG_LED_2 = 0x20,
00095
00096 REG_HARDWARE_VERSION = 0x21,
00097 REG_FIRMWARE_VERSION = 0x22,
00098
00099 REG_BATTERY_VOLTAGE = 0x23,
00100 REG_5V_MAIN_CURRENT = 0x24,
00101 REG_12V_MAIN_CURRENT = 0x25,
00102 REG_5V_AUX_CURRENT = 0x26,
00103 REG_12V_AUX_CURRENT = 0x27,
00104
00105 REG_LEFT_SPEED_MEASURED = 0x28,
00106 REG_RIGHT_SPEED_MEASURED = 0x29
00107 };
00108
00109 void setType(MotorMessage::MessageTypes type);
00110 MotorMessage::MessageTypes getType() const;
00111
00112 void setRegister(MotorMessage::Registers reg);
00113 MotorMessage::Registers getRegister() const;
00114
00115 void setData(int32_t data);
00116 int32_t getData() const;
00117
00118 std::vector<uint8_t> serialize() const;
00119 int deserialize(const std::vector<uint8_t> &serialized);
00120
00121
00122 private:
00123 uint8_t type;
00124 uint8_t register_addr;
00125 uint8_t data[4];
00126
00127 const static uint8_t delimeter = 0x7E;
00128 const static uint8_t protocol_version = 0x02;
00129
00130 const static uint8_t valid_types[];
00131 const static uint8_t valid_registers[];
00132
00133 static int verifyType(uint8_t t);
00134 static int verifyRegister(uint8_t r);
00135
00136 static uint8_t generateChecksum(const std::vector<uint8_t> &data);
00137
00138 };
00139
00140 #endif