$search

sdk.h File Reference

#include <inttypes.h>
#include "pid.h"
#include "uart.h"
#include "hardware.h"
#include "kalman.h"
#include "comm_util_LL.h"
Include dependency graph for sdk.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  MAV_CTRL_CMD
struct  MAV_DES_POSE
struct  MAV_POSE_SI
struct  RO_ALL_DATA
struct  RO_RC_DATA
struct  WAYPOINT
struct  WO_CTRL_INPUT
struct  WO_DIRECT_INDIVIDUAL_MOTOR_CONTROL
struct  WO_DIRECT_MOTOR_CONTROL
struct  WO_SDK_STRUCT

Defines

#define CMD_MAX_PERIOD   100
#define LAND_THRUST_DECREASE_PERIOD   1
#define LAND_THRUST_DECREASE_STEP   0.01
#define WP_CMD_ABORT   0x06
#define WP_CMD_GOHOME   0x04
#define WP_CMD_LAND   0x03
#define WP_CMD_LAUNCH   0x02
#define WP_CMD_SETHOME   0x05
#define WP_CMD_SINGLE_WP   0x01
#define WP_NAVSTAT_20M   0x04
#define WP_NAVSTAT_PILOT_ABORT   0x08
#define WP_NAVSTAT_REACHED_POS   0x01
#define WP_NAVSTAT_REACHED_POS_TIME   0x02
#define WPPROP_ABSCOORDS   0x01
#define WPPROP_AUTOMATICGOTO   0x10
#define WPPROP_HEIGHTENABLED   0x02
#define WPPROP_YAWENABLED   0x04

Functions

int checkTxPeriod (uint16_t period, uint16_t phase)
 gets called every sdk loops. Currently, only checks for packets from the PC and starts autobaud in case there wwas no communication in the last 10 s
void estop (void)
void feedbackBeep (void)
unsigned short isSerialEnabled (void)
void processEngageDisengageTimeouts (void)
void processFlightActionRequests (void)
void processKF (void)
void processLandingThrust (void)
void processMotorCommands (void)
void processMotorStateChanges (void)
void processSendData (void)
void SDK_mainloop (void)
void sdkInit (void)
void sendCtrlDebugData (void)
void sendFlightStateData (void)
void sendImuData (void)
void sendMavPoseData (void)
void sendRcData (void)
void sendStatusData (void)
void synchronizeTime (void)
 adjusts HLP time to host PC time
void writeCommand (short pitch, short roll, short yaw, short thrust, short ctrl, short enable)

Variables

struct RO_ALL_DATA RO_ALL_Data
struct RO_RC_DATA RO_RC_Data
struct WO_CTRL_INPUT WO_CTRL_Input
struct
WO_DIRECT_INDIVIDUAL_MOTOR_CONTROL 
WO_Direct_Individual_Motor_Control
struct WO_DIRECT_MOTOR_CONTROL WO_Direct_Motor_Control
struct WO_SDK_STRUCT WO_SDK
unsigned char wpCtrlAckTrigger
unsigned short wpCtrlDistToWp
unsigned short wpCtrlNavStatus
unsigned char wpCtrlWpCmd
unsigned char wpCtrlWpCmdUpdated
struct WAYPOINT wpToLL

Define Documentation

#define CMD_MAX_PERIOD   100

Definition at line 43 of file sdk.h.

#define LAND_THRUST_DECREASE_PERIOD   1

Definition at line 46 of file sdk.h.

#define LAND_THRUST_DECREASE_STEP   0.01

Definition at line 45 of file sdk.h.

#define WP_CMD_ABORT   0x06

Definition at line 385 of file sdk.h.

#define WP_CMD_GOHOME   0x04

Definition at line 383 of file sdk.h.

#define WP_CMD_LAND   0x03

Definition at line 382 of file sdk.h.

#define WP_CMD_LAUNCH   0x02

Definition at line 381 of file sdk.h.

#define WP_CMD_SETHOME   0x05

Definition at line 384 of file sdk.h.

#define WP_CMD_SINGLE_WP   0x01

Definition at line 380 of file sdk.h.

#define WP_NAVSTAT_20M   0x04

Definition at line 394 of file sdk.h.

#define WP_NAVSTAT_PILOT_ABORT   0x08

Definition at line 395 of file sdk.h.

#define WP_NAVSTAT_REACHED_POS   0x01

Definition at line 392 of file sdk.h.

#define WP_NAVSTAT_REACHED_POS_TIME   0x02

Definition at line 393 of file sdk.h.

#define WPPROP_ABSCOORDS   0x01

Definition at line 374 of file sdk.h.

#define WPPROP_AUTOMATICGOTO   0x10

Definition at line 377 of file sdk.h.

#define WPPROP_HEIGHTENABLED   0x02

Definition at line 375 of file sdk.h.

#define WPPROP_YAWENABLED   0x04

Definition at line 376 of file sdk.h.


Function Documentation

int checkTxPeriod ( uint16_t  period,
uint16_t  phase 
) [inline]

gets called every sdk loops. Currently, only checks for packets from the PC and starts autobaud in case there wwas no communication in the last 10 s

checks if a packet has to be sent

Definition at line 401 of file sdk.c.

void estop ( void   )  [inline]
void feedbackBeep ( void   )  [inline]

Definition at line 495 of file sdk.c.

unsigned short isSerialEnabled ( void   )  [inline]

Definition at line 328 of file sdk.c.

void processEngageDisengageTimeouts ( void   )  [inline]

Definition at line 595 of file sdk.c.

void processFlightActionRequests ( void   )  [inline]

Definition at line 544 of file sdk.c.

void processKF ( void   )  [inline]

Definition at line 409 of file sdk.c.

void processLandingThrust ( void   )  [inline]

Definition at line 607 of file sdk.c.

void processMotorCommands ( void   )  [inline]

Definition at line 635 of file sdk.c.

void processMotorStateChanges ( void   )  [inline]

Definition at line 523 of file sdk.c.

void processSendData ( void   )  [inline]

Definition at line 679 of file sdk.c.

void SDK_mainloop ( void   ) 

SDK_mainloop(void) is triggered @ 1kHz.

WO_(Write Only) data is written to the LL processor after execution of this function.

RO_(Read Only) data is updated before entering this function and can be read to obtain information for supervision or control

WO_ and RO_ structs are defined in sdk.h

The struct LL_1khz_attitude_data (defined in LL_HL_comm.h) can be used to read all sensor data, results of the data fusion and R/C inputs transmitted from the LL-processor. This struct is automatically updated at 1 kHz.

Definition at line 178 of file sdk.c.

void sdkInit ( void   ) 

Definition at line 120 of file sdk.c.

void sendCtrlDebugData ( void   )  [inline]

Definition at line 305 of file sdk.c.

void sendFlightStateData ( void   )  [inline]

Definition at line 287 of file sdk.c.

void sendImuData ( void   )  [inline]

Definition at line 276 of file sdk.c.

void sendMavPoseData ( void   )  [inline]

Definition at line 271 of file sdk.c.

void sendRcData ( void   )  [inline]

Definition at line 292 of file sdk.c.

void sendStatusData ( void   )  [inline]

Definition at line 300 of file sdk.c.

void synchronizeTime ( void   )  [inline]

adjusts HLP time to host PC time

Definition at line 333 of file sdk.c.

void writeCommand ( short  pitch,
short  roll,
short  yaw,
short  thrust,
short  ctrl,
short  enable 
) [inline]

Definition at line 261 of file sdk.c.


Variable Documentation

Definition at line 244 of file sdk.h.

Definition at line 49 of file sdk.c.

Definition at line 48 of file sdk.c.

Definition at line 299 of file sdk.h.

Definition at line 50 of file sdk.c.

Definition at line 47 of file sdk.c.

unsigned char wpCtrlAckTrigger

Definition at line 48 of file LL_HL_comm.c.

unsigned short wpCtrlDistToWp

Definition at line 51 of file LL_HL_comm.c.

unsigned short wpCtrlNavStatus

Definition at line 50 of file LL_HL_comm.c.

unsigned char wpCtrlWpCmd

Definition at line 45 of file LL_HL_comm.c.

unsigned char wpCtrlWpCmdUpdated

Definition at line 46 of file LL_HL_comm.c.

struct WAYPOINT wpToLL

Definition at line 53 of file LL_HL_comm.c.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Mar 5 11:33:42 2013