#include <mav_common/comm_packets.h>#include <mav_common/comm.h>#include <mav_common/comm_types.h>#include "sdk.h"#include "main.h"#include "system.h"#include "LL_HL_comm.h"#include "uart.h"#include "time.h"#include "irq.h"#include "LPC214x.h"#include "gpsmath.h"
Go to the source code of this file.
| #define MAX_TOGGLE_CMD_TIME 2000000 |
| int checkTxPeriod | ( | uint16_t | period, |
| uint16_t | phase | ||
| ) | [inline] |
| void feedbackBeep | ( | void | ) | [inline] |
| unsigned short isSerialEnabled | ( | void | ) | [inline] |
| void processEngageDisengageTimeouts | ( | void | ) | [inline] |
| void processFlightActionRequests | ( | void | ) | [inline] |
| void processLandingThrust | ( | void | ) | [inline] |
| void processMotorCommands | ( | void | ) | [inline] |
| void processMotorStateChanges | ( | void | ) | [inline] |
| void processSendData | ( | void | ) | [inline] |
| 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.
| void sendCtrlDebugData | ( | void | ) | [inline] |
| void sendFlightStateData | ( | void | ) | [inline] |
| void sendImuData | ( | void | ) | [inline] |
| void sendMavPoseData | ( | void | ) | [inline] |
| void sendRcData | ( | void | ) | [inline] |
| void sendStatusData | ( | void | ) | [inline] |
| void synchronizeTime | ( | void | ) | [inline] |
| void writeCommand | ( | short | pitch, |
| short | roll, | ||
| short | yaw, | ||
| short | thrust, | ||
| short | ctrl, | ||
| short | enable | ||
| ) | [inline] |
| float g_cpu_load_sum = 0.0 |
| MAV_CTRL_CFG_PKT g_ctrl_cfg_pkt |
| MAV_CTRL_DEBUG_PKT g_ctrl_debug_pkt |
| MAV_CTRL_INPUT_PKT g_ctrl_input_pkt |
| MAV_DES_POSE_PKT g_des_pose_pkt |
| MAV_DES_VEL_PKT g_des_vel_pkt |
| MAV_DUMMY_PKT g_dummy_pkt |
| MAV_FLIGHT_ACTION_PKT g_flight_action_pkt |
| MAV_FLIGHT_STATE_PKT g_flight_state_pkt |
| uint8_t g_kf_x_enabled |
| uint8_t g_kf_y_enabled |
| uint8_t g_kf_yaw_enabled |
| uint8_t g_kf_z_enabled |
| MAV_HEIGHT_PKT g_mav_height_pkt |
| MAV_KF_CFG_PKT g_mav_kf_cfg_pkt |
| MAV_POSE2D_PKT g_mav_pose2D_pkt |
| short g_motors_running |
| MAV_PID_CFG_PKT g_pid_cfg_pkt |
| MAV_POSE_PKT g_pose_pkt |
| MAV_RCDATA_PKT g_rcdata_pkt |
| unsigned int g_sdk_loops |
| MAV_STATUS_PKT g_status_pkt |
| volatile int64_t g_timestamp = 0 |
| MAV_TIMESYNC_PKT g_timesync_pkt |
| int64_t g_toggle_motors_start_time |
| MAV_TX_FREQ_CFG_PKT g_tx_freq_cfg_pkt |
| struct RO_RC_DATA RO_RC_Data |
| int64_t time_correction = 0 |
| int64_t timeOffset = 0 |
| struct WO_CTRL_INPUT WO_CTRL_Input |
| struct WO_SDK_STRUCT WO_SDK |