HBstructs.h

Go to the documentation of this file.
00001 // ----------------------------------------------------------------------------
00002 //
00003 // $Id$
00004 //
00005 // Copyright 2008, 2009, 2010, 2011, 2012  Antonio Franchi and Paolo Stegagno
00006 //
00007 // This file is part of MIP.
00008 //
00009 // MIP is free software: you can redistribute it and/or modify
00010 // it under the terms of the GNU General Public License as published by
00011 // the Free Software Foundation, either version 3 of the License, or
00012 // (at your option) any later version.
00013 //
00014 // MIP is distributed in the hope that it will be useful,
00015 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00016 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00017 // GNU General Public License for more details.
00018 //
00019 // You should have received a copy of the GNU General Public License
00020 // along with MIP. If not, see <http://www.gnu.org/licenses/>.
00021 //
00022 // Contact info: antonio.franchi@tuebingen.mpg.de stegagno@diag.uniroma1.it
00023 //
00024 // ----------------------------------------------------------------------------
00025 
00026 #ifndef HB_STRUCTS__
00027 #define HB_STRUCTS__
00028 
00029 // Packet descriptors (received from Hb)
00030 #define PD_IMURAWDATA  0x01
00031 #define PD_LLSTATUS   0x02
00032 #define PD_IMUCALCDATA  0x03
00033 #define PD_HLSTATUS   0x04
00034 
00035 #define PD_CTRLOUT   0x11
00036 #define PD_FLIGHTPARAMS  0x12
00037 #define PD_CTRLCOMMANDS  0x13
00038 #define PD_CTRLINTERNAL  0x14
00039 #define PD_RCDATA        0x15
00040 #define PD_CTRLSTATUS  0x16
00041 
00042 #define PD_WAYPOINT   0x20
00043 #define PD_CURRENTWAY  0x21
00044 #define PD_NMEADATA   0x22
00045 #define PD_GPSDATA   0x23
00046 
00047 #define NUM_OF_STRUCTS  24
00048 
00049 /* <<---- START - LABROB ---->> */
00050 #define PD_LABROB_POSE_IN     0x25
00051 #define PD_LABROB_FDATA       0x26
00052 #define PD_LABROB_CTRL_IN     0x27
00053 #define PD_LABROB_CTRL_FL     0x28
00054 #define PD_LABROB_CTRL_GAINS  0x29
00055 #define PD_LABROB_FLTR_GAINS  0x31
00056 #define PD_LABROB_MESSAGE     0x32
00057 /* <<----  END  - LABROB ---->> */
00058 
00059 
00060 
00061 // Define macros bit codes for datatypes
00062 #define DT_LL_status    (unsigned short)0x0001
00063 #define DT_IMU_RawData   (unsigned short)0x0002
00064 #define DT_IMU_CalcData   (unsigned short)0x0004
00065 #define DT_RC_Data     (unsigned short)0x0008
00066 #define DT_CTRL_Out     (unsigned short)0x0010
00067 #define DT_GPS_Data     (unsigned short)0x0080
00068 #define DT_current_way    (unsigned short)0x0100
00069 #define DT_GPS_Data_Advanced  (unsigned short)0x0200
00070 #define DT_CAM_Data     (unsigned short)0x0800
00071 // TODO check the size of all datatypes
00072 #define DATATYPE_SIZE 2
00073 
00074 
00076  //system flags
00077  #define SF_PAGE_BIT1     0x01
00078  #define SF_PAGE_BIT2     0x02
00079  #define SF_SSP_ACK     0x04
00080  #define SF_GPS_NEW     0x08
00081  #define SF_HL_CONTROL_ENABLED  0x10
00082  #define SF_DIRECT_MOTOR_CONTROL  0x20
00083  #define SF_WAYPOINT_MODE   0x40
00084 
00085 
00086   // TODO: check those values
00087 
00088   //ctrl_flags
00089  //scientific control
00090  #define HL_CTRL_PITCH    0x01
00091  #define HL_CTRL_ROLL     0x02
00092  #define HL_CTRL_YAW      0x04
00093  #define HL_CTRL_THRUST    0x08
00094  #define HL_CTRL_HEIGHT_ENABLED 0x10
00095  #define HL_CTRL_GPS_ENABLED  0x20
00096 
00097  //direct motor control
00098  #define HL_CTRL_MOTORS_ONOFF_BY_RC 0x01
00099 
00101 
00102 // define the maximum of data size
00103 // TODO check the true max
00104 #define MAX_DATA_SIZE 100
00105 
00107  struct IMU_CALCDATA {
00108  /*  angles derived by integration of gyro_outputs,
00109   drift compensated by data fusion; 1000 = 1 degree
00110   -90000..+90000 pitch(nick) and roll,
00111   0..360000 yaw;
00112  */
00113   int angle_nick;
00114   int angle_roll;
00115   int angle_yaw;
00116  
00117  //angular velocities, raw values [16 bit], bias free, in 0.0154 �/s (=> 64.8 = 1 �/s)
00118   int angvel_nick;
00119   int angvel_roll;
00120   int angvel_yaw;
00121  
00122  //acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g
00123   short acc_x_calib;
00124   short acc_y_calib;
00125   short acc_z_calib;
00126  
00127  //horizontal / vertical accelerations: -10000..+10000 = -1g..+1g
00128   short acc_x;
00129   short acc_y;
00130   short acc_z;
00131  
00132  //reference angles derived by accelerations only: -90000..+90000; 1000 = 1 degree
00133   int acc_angle_nick;
00134   int acc_angle_roll;
00135  
00136  //total acceleration measured (10000 = 1g)
00137   int acc_absolute_value;
00138  
00139  // magnetic field sensors output, offset free and scaled; units not determined,
00140  //  as only the direction of the field vector is taken into account
00141   int Hx;
00142   int Hy;
00143   int Hz;
00144  
00145  //compass reading: angle reference for angle_yaw: 0..360000; 1000 = 1 degree
00146   int mag_heading;
00147  
00148  //pseudo speed measurements: integrated accelerations, pulled towards zero; units unknown; used for short-term position stabilization
00149   int speed_x;
00150   int speed_y;
00151   int speed_z;
00152  
00153  //height in mm (after data fusion)
00154   int height;
00155  
00156  //diff. height in mm/s (after data fusion)
00157   int dheight;
00158  
00159  //diff. height measured by the pressure sensor [mm/s]
00160   int dheight_reference;
00161  
00162  //height measured by the pressure sensor [mm]
00163   int height_reference;
00164  };
00165 
00166  struct IMU_RAWDATA {
00167 
00168  //pressure sensor 24-bit value, not scaled but bias free
00169   int pressure;
00170 
00171  //16-bit gyro readings; 32768 = 2.5V
00172   short gyro_x;
00173   short gyro_y;
00174   short gyro_z;
00175  
00176  //10-bit magnetic field sensor readings
00177   short mag_x;
00178   short mag_y;
00179   short mag_z;
00180  
00181  //16-bit accelerometer readings
00182   short acc_x;
00183   short acc_y;
00184   short acc_z;
00185  
00186  //16-bit temperature measurement using yaw-gyro internal sensor
00187   unsigned short temp_gyro;
00188  
00189  //16-bit temperature measurement using ADC internal sensor
00190   unsigned int temp_ADC;
00191  };
00192 
00193 
00194  struct SYSTEM_PERMANENT_DATA {
00195   unsigned int total_uptime;
00196   unsigned int total_flighttime;
00197   unsigned int onoff_cycles;
00198   unsigned int number_of_flights;
00199   unsigned int chksum;
00200  };
00201 
00202 
00205  struct LL_ATTITUDE_DATA {
00206   unsigned short system_flags; //GPS data acknowledge, etc.
00207   short angle_pitch; //angles [deg*100]
00208   short angle_roll;
00209   unsigned short angle_yaw;
00210   short angvel_pitch; //angular velocities; bias-free [0.015°/s]
00211   short angvel_roll;
00212   short angvel_yaw;
00213      //<-- 14 bytes @ 1kHz
00214      //--> 3x 26 bytes @ 333 Hz
00215      //=> total = 40 bytes @ 1 kHz
00216  //-----------------------------PAGE0
00217   unsigned char RC_data[10]; //8 channels @ 10 bit
00218   int latitude_best_estimate; //GPS data fused with all other sensors
00219   int longitude_best_estimate;
00220   short acc_x;  //accelerations [mg]
00221   short acc_y;
00222   short acc_z;
00223   short dummy_333Hz_1;
00224 
00225  //-----------------------------PAGE1
00226   unsigned char motor_data[16]; //speed 0..7, PWM 0..7
00227   short speed_x_best_estimate;
00228   short speed_y_best_estimate;
00229   int height;  //height [mm]
00230   short dheight;  //differentiated height[mm/s]
00231 
00232  //------------------------------PAGE2
00233   short mag_x;
00234   short mag_y;
00235   short mag_z;
00236   short cam_angle_pitch;
00237   short cam_angle_roll;
00238   short cam_status;
00239   short battery_voltage1;
00240   short battery_voltage2;
00241   short flightMode;
00242   short flight_time;
00243   short cpu_load;
00244   short status;
00245   short status2;
00246  };
00247 
00249  struct GPS_DATA { 
00250  //latitude/longitude in deg * 10^7
00251   int latitude;
00252   int longitude;
00253 
00254  //GPS height in mm 
00255   int height;
00256 
00257  //speed in x (E/W) and y(N/S) in mm/s 
00258   int speed_x;
00259   int speed_y;
00260 
00261  //GPS heading in deg * 1000
00262   int heading; 
00263 
00264  //accuracy estimates in mm and mm/s
00265   unsigned int horizontal_accuracy;
00266   unsigned int vertical_accuracy;
00267   unsigned int speed_accuracy;
00268  
00269  //number of satellite vehicles used in NAV solution
00270   unsigned int numSV;
00271 
00272  // GPS status information; Bit7...Bit3: 0 Bit 2: longitude direction Bit1: latitude direction Bit 0: GPS lock
00273   int status;   
00274 
00275  };
00276 
00277 struct GPS_DATA_ADVANCED {
00278  //latitude/longitude in deg * 10ˆ7
00279   int latitude;
00280   int longitude;
00281 
00282  //GPS height in mm
00283   int height;
00284 
00285  //speed in x (E/W) and y(N/S) in mm/s
00286   int speed_x;
00287   int speed_y;
00288 
00289  //GPS heading in deg * 1000
00290   int heading;
00291 
00292  //accuracy estimates in mm and mm/s
00293   unsigned int horizontal_accuracy;
00294   unsigned int vertical_accuracy;
00295   unsigned int speed_accuracy;
00296 
00297  //number of satellite vehicles used in NAV solution
00298   unsigned int numSV;
00299 
00300  //GPS status information; 0x03 = valid GPS fix
00301   int status;
00302 
00303  //coordinates of current origin in deg * 10ˆ7
00304   int latitude_best_estimate;
00305   int longitude_best_estimate;
00306 
00307  //velocities in X (E/W) and Y (N/S) after data fusion
00308   int speed_x_best_estimate;
00309   int speed_y_best_estimate;
00310 };
00311 
00312 
00313 struct LABROB_FLIGHT_DATA {
00314  unsigned short int time[2];  // Time vector: sec,msec (till 9 hours)
00315 
00316  int height;      // Barometer height in mm
00317  short dheight;     // Barometer differential height in mm/s
00318  short sonar_height;    // Sonar height in mm
00319  short sonar_dheight;   // Sonar differential height in mm/s
00320 // short sonar_proj;    // Sonar height (projected) in mm
00322 // short height_reference;   // Thrust control
00323  short thrust_control;   // Thrust control
00324 
00325  // Added to verify the height controller (to be removed)
00326 // short Hk;
00327 // short h_reference;
00328 // int integral;
00329 
00330  short angle_pitch;    // attitude data: angles [deg*100] (from LL_ATTITUDE_DATA)
00331  short angle_roll;
00332  unsigned short angle_yaw;
00333 
00334  short angvel_pitch;    // angular velocities; bias-free [0.015°/s] (from LL_ATTITUDE_DATA)
00335  short angvel_roll;
00336  short angvel_yaw;
00337 
00338 // short acc_x;     // acceleration measurements: mm/s^2
00339 // short acc_y;
00340 // short acc_z;
00341 
00342  // flags char, maintains flags for control, measurements update etc.
00343  // bit 0: whether the vehicle is remote controlled or not
00344  // bit 1: whether sonar data is updated or not
00345  // bit 2: whether the height control is active or not
00346  // bit 3:
00347  // bit 4:
00348  // bit 5:
00349  short flags;
00350 };
00351 extern struct LABROB_FLIGHT_DATA Labrob_Fdata;
00352   
00353   
00354   // Remote control, received from serial link
00355 struct LABROB_CTRL_INPUT {
00356   short pitch;  //Pitch input: -2047..+2047 (0=neutral)
00357   short roll;   //Roll input: -2047..+2047  (0=neutral)
00358   short yaw;    //(=R/C Stick input) -2047..+2047 (0=neutral)
00359   short thrust; //Collective: 0..4095 = 0..100%
00360   short height_ref; // Reference for height control in mm
00361   short ctrl;       /*control byte:
00362               bit 0: pitch control enabled
00363               bit 1: roll control enabled
00364               bit 2: yaw control enabled
00365               bit 3: thrust control enabled
00366               bit 4: Height control enabled
00367               bit 5: GPS position control enabled
00368               */
00369   short chksum;
00370 };
00371 
00372 // Control flags: send/receive enables, controller enables
00373 struct LABROB_CTRL_FLAGS {
00374   short send;
00375   // maintains flags for packets selection
00376   // bit 0: LABROB_FLIGHT_DATA
00377   // bit 1: LABROB_CTRL_INPUT
00378   // bit 2: LABROB_CONTROL_FLAGS
00379   // bit 3: CONTROLLERS_GAINS
00380   // bit 4: FILTERS_GAINS
00381   // bit 5:
00382 
00383   short controllers;
00384   // maintains flags for controller selection
00385   // bit 0: HEIGHT_CONTROL_PID (PID control)
00386   // bit 1: HEIGHT_CONTROL_2 ()
00387   // bit 2: POSITION_CONTROL
00388   // bit 3:
00389   // bit 4:
00390   // bit 5:
00391 
00392   short flight_data_delay;  // flight data   delay in ms : min 1 (= 1000 Hz) : base 20 (= 50  Hz)
00393   short ctrl_input_delay;  // control input  delay in ms : min 1 (= 1000 Hz) : base 20 (= 50  Hz)
00394   short ctrl_flags_delay;  // control flags  delay in ms : min 1 (= 1000 Hz) : base 20 (= 50  Hz)
00395   short height_control_delay; // height control delay in ms : min 1 (= 1000 Hz) : base 5 (= 200  Hz)
00396   short chksum;
00397 };
00398 extern struct LABROB_CTRL_FLAGS Labrob_Ctrl_Flags;
00399 
00400 // Control gains, used to change controllers
00401 struct LABROB_CONTROLLERS_GAINS {
00402   short height_pid[3];     // [0] = proportional; [1] = integral; [2] = derivative
00403   short chksum;
00404 };
00405 
00406 // Control gains, used to change controllers
00407 struct LABROB_FILTERS_GAINS {
00408   double sonar_height_filter[2];
00409   short chksum;
00410 };
00411 
00412 // Pose packet, for further purpose
00413 struct LABROB_POSE_INPUT {
00414   short pos_x, pos_y, pos_z;
00415   short ori_x, ori_y, ori_z;
00416   unsigned short int time[2];   // Time vector: sec,msec (till 9 hours)
00417   short chksum;
00418 };
00419  
00420 #endif
00421 
00422 

Generated on Mon Feb 20 07:01:07 2017 for MIP by  doxygen 1.5.6