00001
00046 #ifndef CLEARPATH_MESSAGE_CMD_H
00047 #define CLEARPATH_MESSAGE_CMD_H
00048
00049 #include "husky_base/horizon_legacy/Message.h"
00050
00051 namespace clearpath
00052 {
00053
00054 class CmdMessage : public Message
00055 {
00056 private:
00057 static long total_destroyed;
00058 static long total_sent;
00059
00060 public:
00061 CmdMessage() : Message()
00062 {
00063 }
00064
00065 CmdMessage(const CmdMessage &other) : Message(other)
00066 {
00067 }
00068
00069 virtual ~CmdMessage();
00070 };
00071
00072 class CmdProcessorReset : public CmdMessage
00073 {
00074 public:
00075 CmdProcessorReset();
00076
00077 CmdProcessorReset(const CmdProcessorReset &other);
00078 };
00079
00080 class CmdRestoreSettings : public CmdMessage
00081 {
00082 public:
00083 enum restoreFlags
00084 {
00085 USER_SETTINGS = 0x1,
00086 FACTORY_SETTINGS = 0x2
00087 };
00088 public:
00089 CmdRestoreSettings(enum restoreFlags flags);
00090
00091 CmdRestoreSettings(const CmdRestoreSettings &other);
00092 };
00093
00094 class CmdStoreSettings : public CmdMessage
00095 {
00096 public:
00097 CmdStoreSettings();
00098
00099 CmdStoreSettings(const CmdStoreSettings &other);
00100 };
00101
00102 class SetAckermannOutput : public CmdMessage
00103 {
00104 public:
00105 enum payloadOffsets
00106 {
00107 STEERING = 0,
00108 THROTTLE = 2,
00109 BRAKE = 4,
00110 PAYLOAD_LEN = 6
00111 };
00112
00113 public:
00114 SetAckermannOutput(double steering, double throt, double brake);
00115
00116 SetAckermannOutput(const SetAckermannOutput &other);
00117 };
00118
00119 class SetDifferentialControl : public CmdMessage
00120 {
00121 public:
00122 enum payloadOffsets
00123 {
00124 LEFT_P = 0,
00125 LEFT_I = 2,
00126 LEFT_D = 4,
00127 LEFT_FEEDFWD = 6,
00128 LEFT_STIC = 8,
00129 LEFT_INT_LIM = 10,
00130 RIGHT_P = 12,
00131 RIGHT_I = 14,
00132 RIGHT_D = 16,
00133 RIGHT_FEEDFWD = 18,
00134 RIGHT_STIC = 20,
00135 RIGHT_INT_LIM = 22,
00136 PAYLOAD_LEN = 24
00137 };
00138
00139 public:
00140 SetDifferentialControl(double p,
00141 double i,
00142 double d,
00143 double feedfwd,
00144 double stic,
00145 double int_lim);
00146
00147 SetDifferentialControl(double left_p,
00148 double left_i,
00149 double left_d,
00150 double left_feedfwd,
00151 double left_stic,
00152 double left_int_lim,
00153 double right_p,
00154 double right_i,
00155 double right_d,
00156 double right_feedfwd,
00157 double right_stic,
00158 double right_int_lim);
00159
00160 SetDifferentialControl(const SetDifferentialControl &other);
00161 };
00162
00163 class SetDifferentialOutput : public CmdMessage
00164 {
00165 public:
00166 enum payloadOffsets
00167 {
00168 LEFT = 0,
00169 RIGHT = 2,
00170 PAYLOAD_LEN = 4
00171 };
00172
00173 public:
00174 SetDifferentialOutput(double left, double right);
00175
00176 SetDifferentialOutput(const SetDifferentialOutput &other);
00177 };
00178
00179 class SetDifferentialSpeed : public CmdMessage
00180 {
00181 public:
00182 enum payloadOffsets
00183 {
00184 LEFT_SPEED = 0,
00185 RIGHT_SPEED = 2,
00186 LEFT_ACCEL = 4,
00187 RIGHT_ACCEL = 6,
00188 PAYLOAD_LEN = 8
00189 };
00190
00191 public:
00192 SetDifferentialSpeed(double left_spd, double right_speed, double left_accel, double right_accel);
00193
00194 SetDifferentialSpeed(const SetDifferentialSpeed &other);
00195 };
00196
00197 class SetGear : public CmdMessage
00198 {
00199 public:
00200 SetGear(uint8_t gear);
00201
00202 SetGear(const SetGear &other);
00203 };
00204
00205 class SetMaxAccel : public CmdMessage
00206 {
00207 public:
00208 enum payloadOffsets
00209 {
00210 MAX_FWD = 0,
00211 MAX_REV = 2,
00212 PAYLOAD_LEN = 4
00213 };
00214
00215 public:
00216 SetMaxAccel(double max_fwd, double max_rev);
00217
00218 SetMaxAccel(const SetMaxAccel &other);
00219 };
00220
00221 class SetMaxSpeed : public CmdMessage
00222 {
00223 public:
00224 enum payloadOffsets
00225 {
00226 MAX_FWD = 0,
00227 MAX_REV = 2,
00228 PAYLOAD_LEN = 4
00229 };
00230
00231 public:
00232 SetMaxSpeed(double max_fwd, double max_rev);
00233
00234 SetMaxSpeed(const SetMaxSpeed &other);
00235 };
00236
00237 class SetPlatformName : public CmdMessage
00238 {
00239 public:
00240 SetPlatformName(const char *name);
00241
00242 SetPlatformName(const SetPlatformName &other);
00243 };
00244
00245 class SetPlatformTime : public CmdMessage
00246 {
00247 public:
00248 SetPlatformTime(uint32_t time);
00249
00250 SetPlatformTime(const SetPlatformTime &other);
00251 };
00252
00253 class SetSafetySystem : public CmdMessage
00254 {
00255 public:
00256 SetSafetySystem(uint16_t flags);
00257
00258 SetSafetySystem(const SetSafetySystem &other);
00259 };
00260
00261 class SetTurn : public CmdMessage
00262 {
00263 public:
00264 enum payloadOffsets
00265 {
00266 TRANSLATIONAL = 0,
00267 TURN_RADIUS = 2,
00268 TRANS_ACCEL = 4,
00269 PAYLOAD_LEN = 6
00270 };
00271
00272 public:
00273 SetTurn(double trans, double rad, double accel);
00274
00275 SetTurn(const SetTurn &other);
00276 };
00277
00278 class SetVelocity : public CmdMessage
00279 {
00280 public:
00281 enum payloadOffsets
00282 {
00283 TRANSLATIONAL = 0,
00284 ROTATIONAL = 2,
00285 TRANS_ACCEL = 4,
00286 PAYLOAD_LEN = 6
00287 };
00288
00289 public:
00290 SetVelocity(double trans, double rot, double accel);
00291
00292 SetVelocity(const SetVelocity &other);
00293 };
00294
00295 };
00296
00297 #endif // CLEARPATH_MESSAGE_CMD_H
00298