Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef __HL_INTERFACE__
00034 #define __HL_INTERFACE__
00035
00036 #include "extPositionCtrl.h"
00037 #include "HL_SSDK.h"
00038 #include <inttypes.h>
00039
00040
00041
00042 #define HLI_PACKET_ID_IMU 0x01 ///< imu packet
00043 #define HLI_PACKET_ID_STATUS 0x02 ///< status packet
00044 #define HLI_PACKET_ID_GPS 0x03 ///< gps
00045 #define HLI_PACKET_ID_RC 0x04 ///< rc data
00046 #define HLI_PACKET_ID_SSDK_DEBUG 0x05 ///< debug data from datafusion/position controller
00047 #define HLI_PACKET_ID_CONTROL_LL 0x06 ///< this is for commands that get forwarded to the LL processor i.e. acceleration/attitude and gps velocities
00048 #define HLI_PACKET_ID_CONTROL_HL 0x07 ///< commands for control by the HL
00049 #define HLI_PACKET_ID_POSITION_UPDATE 0x08 ///< (absolute) position update from external reference
00050 #define HLI_PACKET_ID_MOTORS 0x09 ///< motor on/off commands
00051 #define HLI_PACKET_ID_BAUDRATE 0x0a ///< set baudrate
00052 #define HLI_PACKET_ID_SSDK_PARAMETERS 0x0b ///< set params for matlab onboard controller
00053 #define HLI_PACKET_ID_TIMESYNC 0x0c ///< timesync packet indentifier
00054 #define HLI_PACKET_ID_CONTROL_ENABLE 0x0d ///< packet to enable single axis for control
00055 #define HLI_PACKET_ID_EKF_STATE 0x0e ///< packet to exchange the state of the position/attitude ekf
00056 #define HLI_PACKET_ID_SUBSCRIPTION 0x0f ///< packet to define the periods the packets are sent with
00057 #define HLI_PACKET_ID_SSDK_STATUS 0x10 ///< SSDK status packet
00058 #define HLI_PACKET_ID_ACK 0x11 ///< Acknowledge packet
00059 #define HLI_PACKET_ID_CONFIG 0x12 ///< Acknowledge packet
00060 #define HLI_PACKET_ID_MAG 0x13 ///< Magnetic compass data packet
00061
00062
00063
00064 #define HLI_FLIGHTMODE_ACC 0x01
00065 #define HLI_FLIGHTMODE_HEIGHT 0x03
00066 #define HLI_FLIGHTMODE_GPS 0x07
00067 #define HLI_SERIALINTERFACE_ENABLED_BIT 0x20
00068 #define HLI_SERIALINTERFACE_ACTIVE_BIT 0x40
00069 #define HLI_PITCH_BIT 0x01
00070 #define HLI_ROLL_BIT 0x02
00071 #define HLI_YAW_BIT 0x04
00072 #define HLI_THRUST_BIT 0x08
00073 #define HLI_HEIGHT_BIT 0x10
00074 #define HLI_GPS_BIT 0x20
00075
00076
00077 #define HLI_COMMUNICATION_TIMEOUT 3
00078 #define HLI_DEFAULT_BAUDRATE 57600
00079 #define HLI_DEFAULT_PERIOD_IMU 20
00080 #define HLI_DEFAULT_PERIOD_GPS 200
00081 #define HLI_DEFAULT_PERIOD_SSDK_DEBUG 200
00082 #define HLI_DEFAULT_PERIOD_RCDATA 100
00083 #define HLI_DEFAULT_PERIOD_EKF_STATE 0
00084
00085
00086 #define HLI_MODE_STATE_ESTIMATION_OFF 0x01 ///< switches state estimation on the HL off
00087 #define HLI_MODE_STATE_ESTIMATION_HL_SSDK 0x02 ///< state estimation is performed on the HL in the SSDK based on positions that are sent to it
00088 #define HLI_MODE_STATE_ESTIMATION_HL_EKF 0x04 ///< state estimation is performed on the HL based on the state prediction of an EKF
00089 #define HLI_MODE_STATE_ESTIMATION_EXT 0x08 ///< state estimation is performed externally, e.g. on the host computer
00090 #define HLI_MODE_POSCTRL_OFF 0x10 ///< position control switched off
00091 #define HLI_MODE_POSCTRL_LL 0x20 ///< position control in performed on the LL controller. This just works if GPS is available
00092 #define HLI_MODE_POSCTRL_HL 0x40 ///< use position controller on the HL based on state estimation on the HL or external state estimation
00093
00094
00095 #define HLI_COMM_ACK 0x01 ///< defines that a packet has to be acknowledged when received
00096
00098 typedef struct
00099 __attribute__((packed))
00100 {
00101
00103 int64_t timestamp;
00104
00106 int16_t acc_x;
00107 int16_t acc_y;
00108 int16_t acc_z;
00109
00111 int16_t ang_vel_roll;
00112 int16_t ang_vel_pitch;
00113 int16_t ang_vel_yaw;
00114
00116 int16_t ang_roll;
00117 int16_t ang_pitch;
00118
00120 uint16_t ang_yaw;
00121
00123 int32_t height;
00124
00126 int16_t differential_height;
00127
00129 uint8_t motors[6];
00130 } HLI_IMU;
00131
00133 typedef struct
00134 __attribute__((packed))
00135 {
00137
00139 int64_t timestamp;
00140
00142 int32_t latitude;
00143 int32_t longitude;
00144
00146 uint32_t height;
00147
00149 int32_t pressure_height;
00150
00152 int32_t speedX;
00153 int32_t speedY;
00154
00156 uint16_t heading;
00157
00159 uint32_t horizontalAccuracy;
00160 uint32_t verticalAccuracy;
00161 uint32_t speedAccuracy;
00162
00164
00170 int32_t status;
00171
00173 uint32_t numSatellites;
00174 }HLI_GPS;
00175
00177 typedef struct
00178 __attribute__((packed))
00179 {
00181 int64_t timestamp;
00182
00184 int16_t battery_voltage;
00185
00186 uint16_t state_estimation;
00187 uint16_t position_control;
00188 uint16_t flight_mode;
00189
00191 uint16_t flight_time;
00192
00194 uint16_t cpu_load;
00195
00196 int32_t debug1;
00197 int32_t debug2;
00198
00200
00206 int8_t motors;
00207
00209 uint32_t rx_packets;
00210
00212 uint32_t rx_packets_good;
00213
00215 int8_t have_SSDK_parameters;
00216
00217 int64_t timesync_offset;
00218
00219 } HLI_STATUS;
00220
00221 #define HLI_NUMBER_RC_CHANNELS 8
00222
00223 typedef struct
00224 __attribute__((packed))
00225 {
00227 int64_t timestamp;
00228
00229 uint16_t channel[HLI_NUMBER_RC_CHANNELS];
00240 }HLI_RCDATA;
00241
00243 typedef struct
00244 __attribute__((packed))
00245 {
00247 int16_t x;
00249 int16_t y;
00251 int16_t yaw;
00253 int16_t z;
00254 } HLI_CMD_LL;
00255
00256 typedef struct
00257 __attribute__((packed))
00258 {
00260 uint8_t motors;
00261 } HLI_MOTORS;
00262
00263 typedef struct
00264 __attribute__((packed))
00265 {
00266 uint32_t state;
00267 uint32_t baudrate;
00268 } HLI_BAUDRATE;
00269
00271 typedef struct EXT_POSITION HLI_EXT_POSITION;
00272
00274 typedef struct EXT_POSITION_CMD HLI_CMD_HL;
00275
00277
00287 typedef struct
00288 __attribute__((packed))
00289 {
00290 int64_t tc1;
00291 int64_t ts1;
00292 } HLI_TIMESYNC;
00293
00294 #define HLI_EKF_STATE_SIZE 16
00295 #define HLI_EKF_STATE_CURRENT_STATE 1
00296 #define HLI_EKF_STATE_INITIALIZATION 2
00297 #define HLI_EKF_STATE_STATE_CORRECTION 3
00298
00299 typedef struct
00300 __attribute__((packed))
00301 {
00302 int64_t timestamp;
00303
00305 int16_t acc_x;
00306 int16_t acc_y;
00307 int16_t acc_z;
00308
00310 int16_t ang_vel_roll;
00311 int16_t ang_vel_pitch;
00312 int16_t ang_vel_yaw;
00313
00315 float state[HLI_EKF_STATE_SIZE];
00316
00317 uint32_t flag;
00318 }HLI_EKF_STATE;
00319
00321 typedef struct
00322 __attribute__((packed))
00323 {
00324 uint16_t imu;
00325 uint16_t rcdata;
00326 uint16_t ssdk_debug;
00327 uint16_t gps;
00328 uint16_t ekf_state;
00329 uint16_t mag;
00330 }HLI_SUBSCRIPTION;
00331
00333 typedef struct
00334 __attribute__((packed))
00335 {
00336 uint16_t mode_state_estimation;
00337 uint16_t mode_position_control;
00338 uint16_t position_control_axis_enable;
00339 uint16_t battery_warning_voltage;
00340 }HLI_CONFIG;
00341
00343 typedef struct
00344 __attribute__((packed))
00345 {
00346 uint8_t have_parameters;
00347 }HLI_SSDK_STATUS;
00348
00350 typedef struct
00351 __attribute__((packed))
00352 {
00353 uint8_t ack_packet;
00354 }HLI_ACK;
00355
00357 typedef struct
00358 __attribute__((packed))
00359 {
00360 int64_t timestamp;
00361
00362 int16_t x;
00363 int16_t y;
00364 int16_t z;
00365 }HLI_MAG;
00366
00367
00368 #endif