Subversion Repositories NaviCtrl

Rev

Rev 789 | Blame | Compare with Previous | Last modification | View Log | RSS feed

#ifndef _UART1_H
#define _UART1_H

#define UART_FLIGHTCTRL 0
#define UART_MK3MAG     1
#define UART_MKGPS      2

#include "ubx.h"
#include "waypoints.h"

#define NC_ERROR0_SPI_RX                                0x01
#define NC_ERROR0_COMPASS_RX                    0x02
#define NC_ERROR0_FC_INCOMPATIBLE               0x04
#define NC_ERROR0_COMPASS_INCOMPATIBLE  0x08
#define NC_ERROR0_GPS_RX                                0x10
#define NC_ERROR0_COMPASS_VALUE                 0x20

#define DISABLE_FC_UART GPIO_WriteBit(GPIO3, GPIO_Pin_7, Bit_SET);
#define  ENABLE_FC_UART GPIO_WriteBit(GPIO3, GPIO_Pin_7, Bit_RESET);

typedef struct
{
        u8 SWMajor;
        u8 SWMinor;
        u8 ProtoMajor;
        u8 LabelTextCRC;
        u8 SWPatch;
    u8 HardwareError[2];
    u8 HWMajor;
    u8 BL_Firmware;  
    u8 Flags;
} __attribute__((packed)) UART_VersionInfo_t;

extern UART_VersionInfo_t UART_VersionInfo;

//VersionInfo.Flags
#define NC_VERSION_FLAG_MK3MAG_PRESENT      0x01
#define NC_VERSION_FLAG_GPS_PRESENT             0x02

typedef struct
{
        s16 AngleNick;  // in 0.1 deg
        s16 AngleRoll;   // in 0.1 deg
        s16 Heading;    // in 0.1 deg
    u8 StickNick;
    u8 StickRoll;
    u8 StickYaw;
    u8 StickGas;
        s16 Altimeter_5cm; // in 5cm -> devide by 20 to get meters & multiply with 5 to get cm
        u8 reserve[2];
} __attribute__((packed)) Data3D_t;

extern Data3D_t Data3D;


extern const u8 ANALOG_LABEL[32][16];

#define AMPEL_FC                0x01
#define AMPEL_BL                0x02
#define AMPEL_NC                0x04
#define AMPEL_COMPASS   0x08

typedef struct
{
        u8 StatusGreen;
        u8 StatusRed;
        u16 Analog[32];    // Debugwerte
} __attribute__((packed)) DebugOut_t;

extern DebugOut_t DebugOut;

/*
typedef struct
{
        u8      Digital[2];
        u8      RemoteButtons;
        s8      Nick;
        s8      Roll;
        s8      Yaw;
        u8      Gas;
        s8      Height;
        u8      free;
        u8      Frame;
        u8      Config;
} __attribute__((packed)) ExternControl_t;
*/


#define EC_VALID                        0x01 // only valid if this is 1
#define EC_GAS_ADD                      0x02 // if 1 -> use the GAS Value not as MAX
#define EC_USE_SWITCH           0x20 // if 1 -> use the Switches for further control
#define EC_IGNORE_RC_STICK      0x40 // direct control (do nor add to RC-Stick)
#define EC_IGNORE_RC_LOST       0x80 // if 1 -> for Flying without RC-Control

// defines for ExternalControl.Switches -> control GPS Modes etc. if(Config & EC_USE_SWITCH)
#define EC2_PH                          0x01 // GPS-Mode: PH
#define EC2_CH                          0x02 // GPS-Mode: CH
#define EC2_CAREFREE            0x10 //
#define EC2_ALTITUDE            0x20 //
#define EC2_AUTOSTART           0x40 //
#define EC2_AUTOLAND            0x80 //

typedef struct
{
 signed char Nick;
 signed char Roll;
 signed char Gier;
 signed char Gas;
 unsigned char Frame; // will return a confirm frame with this value
 unsigned char Config;
 unsigned char Switches;
 unsigned char Free1; // these two don't need capacity in the ASCII data string
 unsigned char Free2;
} __attribute__((packed)) ExternControl_t;
extern ExternControl_t ExternControl;
extern u8 NewExternalControlFrame; // flag that sends the Frame to FC

#define SERIAL_POTI_START 17
#define WP_EVENT_PPM_IN   29
#define PPM_IN_OFF        30
#define PPM_IN_MAX        31
#define PPM_IN_MID        32
typedef struct
{
 signed char   Ch[12];
} __attribute__((packed)) SerialChannel_t;
extern SerialChannel_t SerialChannel;
extern u8 NewSerialChannelFrame; // flag that sends the Frame to FC

typedef struct
{
        s16 Nick;
        s16 Roll;
        s16 Compass;                                    // angle between north and head of the MK
} __attribute__((packed)) Attitude_t;


typedef struct
{
        u16 Distance_dm;                                        // distance to target in dm
        s16 Bearing;                                    // course to target in deg
} __attribute__((packed)) GPS_PosDev_t;

#define NAVIDATA_VERSION 5

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ old protocol
//+ start abbo communication with: 'O' + Interval [10ms]
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
typedef struct   // 84 Bytes    (note: this is the old protocol)
{
        u8 Version;                                             // version of the data structure = 5
        GPS_Pos_t CurrentPosition;              // see gpspos.h for details
        GPS_Pos_t TargetPosition;
        GPS_PosDev_t TargetPositionDeviation;
        GPS_Pos_t HomePosition;
        GPS_PosDev_t HomePositionDeviation;
        u8  WaypointIndex;                              // index of current waypoints running from 0 to WaypointNumber-1
        u8  WaypointNumber;                             // number of stored waypoints
        u8  SatsInUse;                                  // number of satellites used for position solution
        s16 Altimeter_5cm;                              // hight according to air pressure
        s16 Variometer;                                 // climb(+) and sink(-) rate
        u16 FlyingTime;                                 // in seconds
        u8  UBat;                                               // Battery Voltage in 0.1 Volts
        u16 GroundSpeed;                                // speed over ground in cm/s (2D)
        s16 Heading;                                    // current flight direction in ° as angle to north
        s16     CompassHeading;                         // current compass value in °
        s8  AngleNick;                                  // current Nick angle in 1°
        s8  AngleRoll;                                  // current Rick angle in 1°
        u8  RC_Quality;                                 // RC_Quality
        u8  FCStatusFlags;                              // Flags from FC see main.c FC_STATUS_xxx
        u8  NCFlags;                                    // Flags from NC see main.h NC_FLAG_xxx
        u8  Errorcode;                                  // 0 --> okay
        u8  WP_OperatingRadius;                 // current WP operation radius around the Home Position in m
        s16 TopSpeed;                                   // velocity in vertical direction in cm/s
        u8  TargetHoldTime;                             // time in s to stay at the given target, counts down to 0 if target has been reached
        u8  FCStatusFlags2;                             // StatusFlags2 (since version 5 added)
        s16 SetpointAltitude;                   // setpoint for altitude
        u8  Gas;                                                // current gas (thrust)
        u16 Current;                                    // actual current in 0.1A steps
        u16 UsedCapacity;                               // used capacity in mAh
        u8 reserve1;                                    // to fit into 84 bytes (must be divisible by 3)
        u8 reserve2;                                    // to fit into 84 bytes (must be divisible by 3)
} __attribute__((packed)) NaviData_t;
extern NaviData_t NaviData;

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ New protocol
//+ start abbo communication with: 'O' + Interval 1byte [10ms] + MaxBytesPerSecond (2Bytes)
//+ i.e. 'O'+10+1024
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

typedef struct // Index:10 (15 Bytes need 27 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        u8 CamCtrlChar;                 // Status from a connected CamCtrl unit: 'R' = REC  'c' = Ready  '!' = Error  ...etc
u8 reserve1;                     
} __attribute__((packed)) NaviData_Tiny_t;
extern NaviData_Tiny_t NaviData_Tiny;

#define START_PAYLOAD_DATA  13  //

typedef struct  // Index:11 (24 Bytes need 39 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        u8 OSDStatusFlags2;             // see main.h for definitions OSD_FLAG2_xxx
        u8  NCFlags;                    // Flags from NC
u8 ReserveFlags;
        u8  Errorcode;                  // 0 --> okay  see http://wiki.mikrokopter.de/ErrorCodes
        u8 SpeakHoTT;                   // voice output SPEAK_xxx (see spi_slave.h)
        u8 VarioCharacter;              // display as ascii character ('+' = 'climb' etc)
        u8 GPS_ModeCharacter;   // display as ascii character ('H' = 'Home' etc)
        u8 BL_MinOfMaxPWM;              // status byte of the BL-Ctrls
} __attribute__((packed)) NaviData_Flags_t;
extern NaviData_Flags_t NaviData_Flags;

typedef struct  // Index:12  (27 Bytes need 43 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        s32 TargetLongitude;    //
        s32 TargetLatitude;             //
        s16 TargetAltitude;     // hight according to air pressure
        u8  RC_Quality;                 // RC_Quality
} __attribute__((packed)) NaviData_Target_t;
extern NaviData_Target_t NaviData_Target;

typedef struct  // Index:13  (30 Bytes need 47 ASCII-characters)
{                                          
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        s32 HomeLongitude;              //
        s32 HomeLatitude;               //
        s16 HomeAltitude;               // hight according to air pressure
        u16 WP_OperatingRadius; // current WP operation radius around the Home Position in m
        u8 LipoCellCount;
        u8 DescendRange;                // in [10m]
        u8 ManualFlyingRange;   // in [10m]
u8 reserve1;
u8 reserve2;
} __attribute__((packed)) NaviData_Home_t;
extern NaviData_Home_t NaviData_Home;

typedef struct   // Index:14    (24 Bytes need 39 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        u16 FlyingTime;                 // in seconds
        u16 DistanceToHome;             // [10cm] (100 = 10m)
        u8  HeadingToHome;              // in 2° (100 = 200°)
        u16 DistanceToTarget;   // [10cm] (100 = 10m)  
        u8  HeadingToTarget;    // in 2° (100 = 200°)
        s8  AngleNick;                  // current Nick angle in 1°
        s8  AngleRoll;                  // current Rick angle in 1°
        u8  SatsInUse;                  // number of satellites used for position solution
} __attribute__((packed)) NaviData_Deviation_t;
extern NaviData_Deviation_t NaviData_Deviation;

typedef struct // Index:15 (18 Bytes need 31 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8  GroundSpeed;                // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        u8  WaypointIndex;              // index of current waypoints running from 0 to WaypointNumber-1
        u8  WaypointNumber;             // number of stored waypoints
        u8  TargetHoldTime;             // time in s to stay at the given target, counts down to 0 if target has been reached
        u8 WP_Eventchannel;             // the current value of the event channel
u8 reserve;
} __attribute__((packed)) NaviData_WP_t;
extern NaviData_WP_t NaviData_WP;

typedef struct // Index:16  (27 Bytes need 43 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        u16 UBat;                               // Battery Voltage in 0.1 Volts
        u16 Current;                    // actual current in 0.1A steps
        u16 UsedCapacity;               // used capacity in mAh
        s8  Variometer;                 // climb(+) and sink(-) rate
        u8  Heading;                    // Current moving direction in 2° (100 = 200°)
        u8      CompassHeading;         // current compass value in 2°
        u8  Gas;                                // current gas (thrust)
        u16 ShutterCounter;             // counts every time a Out1 was activated
        s16 SetpointAltitude;   // setpoint for altitude
} __attribute__((packed)) NaviData_Volatile_t;
extern NaviData_Volatile_t NaviData_Volatile;


typedef struct  // Index:17  (21 Bytes need 35 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 ActualLongitude;    //
        s32 ActualLatitude;             //
        s16 Altimeter_5cm;              // hight -> devide by 20 to get meters & multiply with 5 to get cm
        u8 GroundSpeed;                 // speed over ground in 10cm/s (2D) (255 = 91km/h)
        u8 OSDStatusFlags;              // see main.h for definitions OSD_FLAG_xxx
        s32 Longitude;                  // Failsafe-Position
        s32 Latitude;                   // Failsafe-Position
} __attribute__((packed)) NaviData_FS_Pos_t;
extern NaviData_FS_Pos_t NaviData_Failsafe;

typedef struct // Index:18  (9 Bytes need 19 ASCII-characters)
{
        u8 Index;                               // Index to identify this data set
        s32 Longitude;                  // Trigger Position
        s32 Latitude;                   // Trigger Position
} __attribute__((packed)) NaviData_Out_t;
extern NaviData_Out_t NaviData_Out1Trigger;


extern UART_TypeDef *DebugUART;
extern volatile u8 SerialLinkOkay;
extern Buffer_t UART1_tx_buffer;
extern Buffer_t UART1_rx_buffer;
extern u16 UART1_BaudrateFallbackTimeout;

void UART1_Init(void);
void UART1_Transmit(void);
void UART1_TransmitTxData(void);
void UART1_ProcessRxData(void);

s16  UART1_Putchar(char c);
void UART1_PutString(u8 *s);
extern u8 text[]; // globally used text buffer
extern u8 UART1_Request_SendFollowMe;
extern u8 LastTransmittedFCStatusFlags2;
extern u8 UART1_Request_ReadPoint;
extern WPL_Store_t WPL_Store;
extern u8 CalculateDebugLableCrc(void);
extern u8 NaviData_Flags_SpeakHoTT_Processed;

extern void UART1_Configure(u32 baudrate);

typedef struct
{
        u8 User[128];
        u8 eMail[128];
        u8 Feature[128];
        u8 Expire[11];
        u8 License[16];
} __attribute__((packed)) LicenseS_t;
extern u8 *LicensePtr;

extern u32 NMEA_Interval;// in ms
#define LICENSE_SIZE            480
#define LICENSE_SIZE_TEXT       411

#endif //_UART1_H