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 } HLI_IMU;
00128
00130 typedef struct
00131 __attribute__((packed))
00132 {
00134
00136 int64_t timestamp;
00137
00139 int32_t latitude;
00140 int32_t longitude;
00141
00143 uint32_t height;
00144
00146 int32_t pressure_height;
00147
00149 int32_t speedX;
00150 int32_t speedY;
00151
00153 uint16_t heading;
00154
00156 uint32_t horizontalAccuracy;
00157 uint32_t verticalAccuracy;
00158 uint32_t speedAccuracy;
00159
00161
00167 int32_t status;
00168
00170 uint32_t numSatellites;
00171 }HLI_GPS;
00172
00174 typedef struct
00175 __attribute__((packed))
00176 {
00178 int64_t timestamp;
00179
00181 int16_t battery_voltage;
00182
00183 uint16_t state_estimation;
00184 uint16_t position_control;
00185 uint16_t flight_mode;
00186
00188 uint16_t flight_time;
00189
00191 uint16_t cpu_load;
00192
00193 int32_t debug1;
00194 int32_t debug2;
00195
00197
00203 int8_t motors;
00204
00206 uint32_t rx_packets;
00207
00209 uint32_t rx_packets_good;
00210
00212 int8_t have_SSDK_parameters;
00213
00214 int64_t timesync_offset;
00215
00216 } HLI_STATUS;
00217
00218 #define HLI_NUMBER_RC_CHANNELS 8
00219
00220 typedef struct
00221 __attribute__((packed))
00222 {
00224 int64_t timestamp;
00225
00226 uint16_t channel[HLI_NUMBER_RC_CHANNELS];
00237 }HLI_RCDATA;
00238
00240 typedef struct
00241 __attribute__((packed))
00242 {
00244 int16_t x;
00246 int16_t y;
00248 int16_t yaw;
00250 int16_t z;
00251 } HLI_CMD_LL;
00252
00253 typedef struct
00254 __attribute__((packed))
00255 {
00257 uint8_t motors;
00258 } HLI_MOTORS;
00259
00260 typedef struct
00261 __attribute__((packed))
00262 {
00263 uint32_t state;
00264 uint32_t baudrate;
00265 } HLI_BAUDRATE;
00266
00268 typedef struct EXT_POSITION HLI_EXT_POSITION;
00269
00271 typedef struct EXT_POSITION_CMD HLI_CMD_HL;
00272
00274
00284 typedef struct
00285 __attribute__((packed))
00286 {
00287 int64_t tc1;
00288 int64_t ts1;
00289 } HLI_TIMESYNC;
00290
00291 #define HLI_EKF_STATE_SIZE 16
00292 #define HLI_EKF_STATE_CURRENT_STATE 1
00293 #define HLI_EKF_STATE_INITIALIZATION 2
00294 #define HLI_EKF_STATE_STATE_CORRECTION 3
00295
00296 typedef struct
00297 __attribute__((packed))
00298 {
00299 int64_t timestamp;
00300
00302 int16_t acc_x;
00303 int16_t acc_y;
00304 int16_t acc_z;
00305
00307 int16_t ang_vel_roll;
00308 int16_t ang_vel_pitch;
00309 int16_t ang_vel_yaw;
00310
00312 float state[HLI_EKF_STATE_SIZE];
00313
00314 uint32_t flag;
00315 }HLI_EKF_STATE;
00316
00318 typedef struct
00319 __attribute__((packed))
00320 {
00321 uint16_t imu;
00322 uint16_t rcdata;
00323 uint16_t ssdk_debug;
00324 uint16_t gps;
00325 uint16_t ekf_state;
00326 uint16_t mag;
00327 }HLI_SUBSCRIPTION;
00328
00330 typedef struct
00331 __attribute__((packed))
00332 {
00333 uint16_t mode_state_estimation;
00334 uint16_t mode_position_control;
00335 uint16_t position_control_axis_enable;
00336 uint16_t battery_warning_voltage;
00337 }HLI_CONFIG;
00338
00340 typedef struct
00341 __attribute__((packed))
00342 {
00343 uint8_t have_parameters;
00344 }HLI_SSDK_STATUS;
00345
00347 typedef struct
00348 __attribute__((packed))
00349 {
00350 uint8_t ack_packet;
00351 }HLI_ACK;
00352
00354 typedef struct
00355 __attribute__((packed))
00356 {
00357 int64_t timestamp;
00358
00359 int16_t x;
00360 int16_t y;
00361 int16_t z;
00362 }HLI_MAG;
00363
00364 #endif