LL_HL_comm.h
Go to the documentation of this file.
00001 #ifndef LL_HL_COMM_
00002 #define LL_HL_COMM_
00003 
00004 //system flags
00005 #define SF_PAGE_BIT1                            0x01
00006 #define SF_PAGE_BIT2                            0x02
00007 #define SF_SSP_ACK                                      0x04
00008 #define SF_GPS_NEW                                      0x08
00009 #define SF_HL_CONTROL_ENABLED           0x10
00010 #define SF_DIRECT_MOTOR_CONTROL         0x20
00011 #define SF_WAYPOINT_MODE                        0x40
00012 
00013 //ctrl_flags
00014 //scientific control
00015 #define HL_CTRL_PITCH                   0x01
00016 #define HL_CTRL_ROLL                    0x02
00017 #define HL_CTRL_YAW                     0x04
00018 #define HL_CTRL_THRUST                  0x08
00019 #define HL_CTRL_HEIGHT_ENABLED  0x10
00020 #define HL_CTRL_GPS_ENABLED             0x20
00021 //direct motor control
00022 #define HL_CTRL_MOTORS_ONOFF_BY_RC      0x01
00023 
00024 
00025 void LL_write_ctrl_data(char);
00026 int HL2LL_write_cycle(void);
00027 inline void SSP_rx_handler_HL(unsigned char);
00028 inline void SSP_data_distribution_HL(void);
00029 
00030 struct LL_ATTITUDE_DATA
00031 {
00032         unsigned short system_flags;    //GPS data acknowledge, etc.
00033 
00034         short angle_pitch;      //angles [deg*100]
00035         short angle_roll;
00036         unsigned short angle_yaw;
00037 
00038         short angvel_pitch;     //angular velocities; bias-free [0.015°/s]
00039         short angvel_roll;
00040         short angvel_yaw;
00041 
00042                                 //<-- 14 bytes @ 1kHz
00043                                 //--> 3x 26 bytes @ 333 Hz
00044                                 //=> total = 40 bytes @ 1 kHz
00045 //-----------------------------PAGE0
00046         unsigned char RC_data[10];      //8 channels @ 10 bit
00047 
00048         int latitude_best_estimate;     //GPS data fused with all other sensors
00049         int longitude_best_estimate;
00050         short acc_x;            //accelerations [mg]
00051         short acc_y;
00052         short acc_z;
00053 
00054         short dummy_333Hz_1;
00055 //-----------------------------PAGE1
00056         unsigned char motor_data[16];   //speed 0..7, PWM 0..7
00057 
00058         short speed_x_best_estimate;
00059         short speed_y_best_estimate;
00060         int height;             //height [mm]
00061         short dheight;          //differentiated height[mm/s]
00062 //------------------------------PAGE2
00063         short mag_x;
00064         short mag_y;
00065         short mag_z;
00066 
00067         short cam_angle_pitch;
00068         short cam_angle_roll;
00069         short cam_status;
00070 
00071         short battery_voltage1;
00072         short battery_voltage2;
00073         short flightMode;
00074         short flight_time;
00075         short cpu_load;
00076         short status;
00077         short status2;
00078 
00079 };
00080 
00081 extern struct LL_ATTITUDE_DATA LL_1khz_attitude_data;
00082 
00083 struct LL_CONTROL_INPUT
00084 {
00085         unsigned short system_flags;
00086                                                         //bit 0: page_select
00087                                                         //bit 1: reserved (page_select)
00088                                                         //bit 2: SSP_ack
00089                                                         //bit 3: GPS new
00090                                                         //bit 4: HL controller enabled
00091                                                         //bit 5: 0 -> "scientific" commands
00092                                                         //       1 -> direct motor commands
00093                                                         //bit 6: waypoint mode
00094 
00095         unsigned short ctrl_flags;
00096                                                         //bit 0..3:
00097                                                         // pitch, roll, yaw, height enable bits
00098                                                         //bit 4: height control enabled
00099                                                         //bit 5: yaw_control enabled
00100 
00101         short pitch, roll, yaw, thrust;                 //"scientific interface"
00102         unsigned char direct_motor_control[8];          //direct motor commands: pitch, roll, yaw, throttle, 4xDNC
00103                                                         //or motor 0..7 (Falcon)
00104 
00105                                                         //<-- 20 bytes @ 1kHz
00106                                                         //--> 2x18 bytes @ 500 Hz
00107                                                         //=> total = 38 bytes @ 1kHz
00108 
00109         int latitude;                                   //data received from GPS-unit
00110         int longitude;
00111         int height;
00112         short speed_x;
00113         short speed_y;
00114         short status;
00115 //-----------------------------
00116 
00117         unsigned short hor_accuracy;
00118         unsigned short vert_accuracy;
00119         unsigned short speed_accuracy;
00120         unsigned short numSV;
00121         unsigned short heading;
00122         short battery_voltage_1, battery_voltage_2;     //battery voltage read by HL-ADC [mV]
00123         short dummy_500Hz_2;
00124         short dummy_500Hz_3;
00125 };
00126 
00127 extern struct LL_CONTROL_INPUT LL_1khz_control_input;
00128 
00129 
00130 
00131 #endif /*LL_HL_COMM_*/


ccny_asctec_firmware
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:32