comm_packets.h
Go to the documentation of this file.
00001 #ifndef COMM_PACKETS_H
00002 #define COMM_PACKETS_H
00003 
00004 #include <inttypes.h>
00005 
00006 #include "mav_common/comm_types.h"
00007   
00008 #define MAV_ACK_PKT_ID                          0x00
00009 #define MAV_CTRL_CFG_PKT_ID                     0x01
00010 #define MAV_PID_CFG_PKT_ID                      0x02
00011 #define MAV_KF_CFG_PKT_ID                       0x03
00012 #define MAV_DUMMY_PKT_ID                        0x04
00013 #define MAV_POSE2D_PKT_ID                       0x05
00014 #define MAV_HEIGHT_PKT_ID                       0x06
00015 #define MAV_POSE_PKT_ID                         0x07
00016 #define MAV_FLIGHT_ACTION_PKT_ID                0x08
00017 #define MAV_FLIGHT_STATE_PKT_ID                 0x09
00018 #define MAV_IMU_PKT_ID                          0x0A
00019 #define MAV_RCDATA_PKT_ID                       0x0B
00020 #define MAV_TIMESYNC_PKT_ID                     0x0C
00021 #define MAV_STATUS_PKT_ID                       0x0D
00022 #define MAV_TX_FREQ_CFG_PKT_ID                  0x0E
00023 #define MAV_CTRL_INPUT_PKT_ID                   0x0F
00024 #define MAV_DES_POSE_PKT_ID                     0x10
00025 #define MAV_DES_VEL_PKT_ID                      0x11
00026 #define MAV_CTRL_DEBUG_PKT_ID                   0x12
00027 
00028 // for testing the connection
00029 typedef struct
00030 __attribute__((packed))
00031 {
00032   uint8_t dummy;
00033 } MAV_DUMMY_PKT;
00034 
00036 typedef struct
00037 __attribute__((packed))
00038 {
00039   uint16_t imu_period;
00040   uint16_t rcdata_period;
00041   uint16_t flight_state_period;
00042   uint16_t pose_period;
00043   uint16_t status_period;
00044   uint16_t ctrl_debug_period;
00045 
00046   uint16_t imu_phase;
00047   uint16_t rcdata_phase;
00048   uint16_t flight_state_phase;
00049   uint16_t pose_phase;
00050   uint16_t status_phase;
00051   uint16_t ctrl_debug_phase;
00052 
00053 } MAV_TX_FREQ_CFG_PKT;
00054 
00056 typedef struct
00057 __attribute__((packed))
00058 {
00059   uint8_t ack_packet;
00060 } MAV_ACK_PKT;
00061 
00062 // config packet for ctrl params
00063 typedef struct
00064 __attribute__((packed))
00065 {
00066  // p, i, d, bias for x-position control
00067  Param k_p_x;
00068  Param k_i_x;
00069  Param k_d_x;
00070  Param k_d2_x;
00071  Param d_base_x;
00072  Param bias_x;
00073  Param max_i_x;
00074  Param max_err_x;
00075 
00076  // p, i, d, bias for y-position control
00077  Param k_p_y;
00078  Param k_i_y;
00079  Param k_d_y;
00080  Param k_d2_y;
00081  Param d_base_y;
00082  Param bias_y;
00083  Param max_i_y;
00084  Param max_err_y;
00085 
00086  // p, i, d, bias for x-velocity control
00087  Param k_p_vx;
00088  Param k_i_vx;
00089  Param k_d_vx;
00090  Param bias_vx;
00091  Param max_i_vx;
00092  Param max_err_vx;
00093 
00094  // p, i, d, bias for y-velocity control
00095  Param k_p_vy;
00096  Param k_i_vy;
00097  Param k_d_vy;
00098  Param bias_vy;
00099  Param max_i_vy;
00100  Param max_err_vy;
00101 
00102  // p, i, d, bias for y-velocity control
00103   Param k_p_vz;
00104   Param k_i_vz;
00105   Param k_d_vz;
00106   Param bias_vz;
00107   Param max_i_vz;
00108   Param max_err_vz;
00109 
00110  // p, i, d, bias for height control
00111  Param k_p_z;
00112  Param k_i_z;
00113  Param k_d_z;
00114  Param k_d2_z;
00115  Param bias_z;
00116  Param max_i_z;
00117  Param max_err_z;
00118 
00119  // p, i, d, bias for yaw control
00120  Param k_p_yaw;
00121  Param k_i_yaw;
00122  Param k_d_yaw;
00123  Param bias_yaw;
00124  Param max_i_yaw;
00125  Param max_err_yaw;
00126 
00127 } MAV_PID_CFG_PKT;
00128 
00129 // config packet for ctrl params
00130 typedef struct
00131 __attribute__((packed))
00132 {
00133   uint8_t ctrl_mode_roll;
00134   uint8_t ctrl_mode_pitch;
00135   uint8_t ctrl_mode_yaw_rate;
00136   uint8_t ctrl_mode_thrust;
00137 
00138   Angle       cmd_roll_limit;       // roll limit,     SI
00139   Angle       cmd_pitch_limit;      // pitch limit,    SI
00140   AngVelocity cmd_yaw_rate_limit;   // yaw rate limit, SI
00141   Thrust      cmd_thrust_limit;     // thrust limit,   %
00142 
00143   Param cmd_roll_delta_limit;       // [rad / iteration]
00144   Param cmd_pitch_delta_limit;      // [rad / iteration]
00145   Param cmd_yaw_rate_delta_limit;   // [rad/s / iteration]
00146   Param cmd_thrust_delta_limit;     // [% / iteration]
00147 
00148 } MAV_CTRL_CFG_PKT;
00149 
00150 // debug packet for the controllers
00151 typedef struct
00152 __attribute__((packed))
00153 {
00154   int16_t cmd_roll_LL;         // in LL units
00155   int16_t cmd_pitch_LL;        // in LL units
00156   int16_t cmd_yaw_rate_LL;     // in LL units
00157   int16_t cmd_thrust_LL;       // in LL units
00158 
00159   Angle cmd_roll;         // in SI units
00160   Angle cmd_pitch;        // in SI units
00161   Angle cmd_yaw_rate;     // in SI units
00162   Angle cmd_thrust;       // in SI units
00163 
00164   int16_t roll_limit;     // in LL units
00165   int16_t pitch_limit;    // in LL units
00166   int16_t yaw_rate_limit; // in LL units
00167   int16_t thrust_limit;   // in LL units
00168 
00169   int32_t error_x;
00170   int32_t error_y;
00171   int32_t error_z;
00172   int16_t error_yaw;
00173 
00174   float vel_x_bf; //velocity in the horizontal plan
00175   float vel_y_bf;
00176   float pid_error_vx_bf;
00177   float pid_error_vy_bf;
00178   float ax_bf; //acceleration in the horizontal plan
00179   float ay_bf; //acceleration in the horizontal plan
00180   float az;
00181   uint8_t ctrl_mode_roll;
00182   uint8_t ctrl_mode_pitch;
00183   uint8_t ctrl_mode_yaw_rate;
00184   uint8_t ctrl_mode_thrust;
00185 
00186   float acc_x_wf;
00187   float acc_y_wf;
00188   float acc_z_wf;
00189 
00190   float pid_x_i_term;    // in SI (%)
00191   float pid_y_i_term;    // in SI
00192   float pid_yaw_i_term;  // in SI
00193   float pid_z_i_term;    // in SI
00194 
00195   float pid_error_x_bf; // body frame x error in SI
00196   float pid_error_y_bf; // body frame y error in SI
00197 
00198 } MAV_CTRL_DEBUG_PKT;
00199 
00200 // 2d pose from laser scan matcher
00201 typedef struct
00202 __attribute__((packed))
00203 {
00204   Position  x;     // x position, SI
00205   Position  y;     // y position, SI
00206   Velocity  vx;    // x velocity, SI
00207   Velocity  vy;    // y velocity, SI
00208   Angle     yaw;   // yaw position, SI
00209 } MAV_POSE2D_PKT;
00210 
00211 // height from laser altimeter
00212 typedef struct
00213 __attribute__((packed))
00214 {
00215   Position z;      // z position, SI
00216   Velocity vz;     // z velocity, SI
00217 } MAV_HEIGHT_PKT;
00218 
00219 typedef struct
00220 __attribute__((packed))
00221 {
00222   Position x;     // x position, SI
00223   Position y;     // y position, SI
00224   Position z;     // z position, SI
00225 
00226   Velocity vx;    // x velocity, SI
00227   Velocity vy;    // y velocity, SI
00228   Velocity vz;    // y velocity, SI
00229 
00230   Angle roll;     // roll  orientation, SI
00231   Angle pitch;    // pitch orientation, SI
00232   Angle yaw;      // yaw   orientation, SI
00233 } MAV_POSE_PKT;
00234 
00235 // state action
00236 typedef struct
00237 __attribute__((packed))
00238 {
00239   uint8_t action;
00240 } MAV_FLIGHT_ACTION_PKT;
00241 
00242 // flight state
00243 typedef struct
00244 __attribute__((packed))
00245 {
00246   uint8_t state;
00247 } MAV_FLIGHT_STATE_PKT;
00248 
00249 // state action
00250 typedef struct
00251 __attribute__((packed))
00252 {
00253   int64_t timestamp;           // timestamp in us; synchronized to host pc
00254   int64_t timesync_offset;
00255 
00256   float battery_voltage;     // battery voltage [mv]
00257 
00258   //uint16_t flight_time;        // Flight time [s]
00259 
00260   float cpu_load;           // cpu load in % of the time of one sdk loop
00261 
00262   //uint32_t rx_packets;         // total received packets
00263   //uint32_t rx_packets_good;    // total received good packets
00264 } MAV_STATUS_PKT;
00265 
00266 typedef struct
00267 __attribute__((packed))
00268 {
00269  Angle roll;  // roll  orientation, SI
00270  Angle pitch; // pitch orientation, SI
00271  Angle yaw;   // yaw   orientation, SI
00272 
00273  AngVelocity roll_rate;
00274  AngVelocity pitch_rate;
00275  AngVelocity yaw_rate;
00276 
00277  Acceleration acc_x;
00278  Acceleration acc_y;
00279  Acceleration acc_z;
00280 
00281 } MAV_IMU_PKT;
00282 
00283 typedef struct
00284 __attribute__((packed))
00285 {
00286  uint8_t enable_mask;
00287 
00288  Param Q_x;
00289  Param Q_y;
00290  Param Q_z;
00291  Param Q_roll;
00292  Param Q_ptch;
00293  Param Q_yaw;
00294 
00295  Param R_x; //laser x position covariace
00296  Param R_vx;//laser x velocity covariace
00297  Param R_y;
00298  Param R_vy;
00299  Param R_z;
00300  Param R_vz;
00301  Param R_vz_p; //for pressure sensor
00302  Param R_roll;
00303  Param R_ptch;
00304  Param R_yaw;
00305 
00306 } MAV_KF_CFG_PKT;
00307 
00309 typedef struct
00310 __attribute__((packed))
00311 {
00313   int64_t timestamp;
00314 
00315   uint16_t channel[8];
00316 
00317   // channel[0]: Pitch
00318   // channel[1]: Roll
00319   // channel[2]: Thrust
00320   // channel[3]: Yaw
00321   // channel[4]: Serial interface enable/disable
00322   // channel[5]: manual / height control / GPS + height control
00323   //
00324   // range of each channel: 0..4095
00325 
00326 } MAV_RCDATA_PKT;
00327 
00329 
00339 typedef struct
00340 __attribute__((packed))
00341 {
00342   int64_t tc1;
00343   int64_t ts1;
00344 } MAV_TIMESYNC_PKT;
00345 
00346 // Used in direct control mode
00347 typedef struct
00348 __attribute__((packed))
00349 {
00350   Angle       cmd_roll;      // roll  ,    in SI
00351   Angle       cmd_pitch;     // pitch ,    in SI
00352   AngVelocity cmd_yaw_rate;  // yaw_rate,  in SI
00353   Thrust      cmd_thrust;    // thrust,    in %
00354 } MAV_CTRL_INPUT_PKT;
00355 
00356 typedef struct
00357 __attribute__((packed))
00358 {
00359   Position x;     // desired x position, in SI
00360   Position y;     // desired y position, in SI
00361   Position z;     // desired z position, in SI
00362 
00363   Angle yaw;          // desired yaw orientation, in SI
00364 } MAV_DES_POSE_PKT;
00365 
00366 typedef struct
00367 __attribute__((packed))
00368 {
00369   Velocity vx;    // desired x velocity, in SI
00370   Velocity vy;    // desired y velocity, in SI
00371   Velocity vz;
00372 
00373   AngVelocity yaw_rate;  // desired yaw rate, in SI
00374 } MAV_DES_VEL_PKT;
00375 
00376 #endif // COMM_PACKETS_H


mav_common
Author(s): Ivan Dryanovski
autogenerated on Thu Jan 2 2014 11:28:00