mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
2c6e096a3b
git-svn-id: https://arducopter.googlecode.com/svn/trunk@286 f9c3cf11-9bcb-44bc-f272-b75c42450872
43 lines
826 B
C++
Executable File
43 lines
826 B
C++
Executable File
#ifndef AP_GPS_IMU_h
|
|
#define AP_GPS_IMU_h
|
|
|
|
#include "AP_GPS.h"
|
|
#define MAXPAYLOAD 32
|
|
|
|
class AP_GPS_IMU : public AP_GPS
|
|
{
|
|
public:
|
|
// Methods
|
|
AP_GPS_IMU();
|
|
void init();
|
|
void update();
|
|
|
|
// Properties
|
|
long roll_sensor; // how much we're turning in deg * 100
|
|
long pitch_sensor; // our angle of attack in deg * 100
|
|
int airspeed;
|
|
float imu_health;
|
|
uint8_t imu_ok;
|
|
|
|
private:
|
|
// Packet checksums
|
|
uint8_t ck_a;
|
|
uint8_t ck_b;
|
|
uint8_t GPS_ck_a;
|
|
uint8_t GPS_ck_b;
|
|
|
|
uint8_t step;
|
|
uint8_t msg_class;
|
|
uint8_t message_num;
|
|
uint8_t payload_length;
|
|
uint8_t payload_counter;
|
|
uint8_t buffer[MAXPAYLOAD];
|
|
|
|
void join_data();
|
|
void join_data_xplane();
|
|
void GPS_join_data();
|
|
void checksum(unsigned char data);
|
|
long join_4_bytes(unsigned char Buffer[]);
|
|
};
|
|
|
|
#endif |