Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
#include "nps_radio_control_spektrum.h"
#include "nps_radio_control.h"
#include <glib.h>
#include <stdio.h>
#include <termios.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <string.h>
#include <errno.h>
#include <inttypes.h>
Go to the source code of this file.
Macros | |
#define | IUCLC 0 |
#define | CHANNEL_OF_FRAME(i) ((((frame_buf[2*i]<<8) + frame_buf[2*i+1])&0x03FF)-512) |
#define | SYNC_1 0x03 |
#define | SYNC_2 0x12 |
#define | STA_UNINIT 0 |
#define | STA_GOT_SYNC_1 1 |
#define | STA_GOT_SYNC_2 2 |
#define | FRAME_LEN 14 |
Functions | |
static gboolean | on_serial_data_received (GIOChannel *source, GIOCondition condition, gpointer data) |
static void | parse_data (char *buf, int len) |
static void | handle_frame (void) |
int | nps_radio_control_spektrum_init (const char *device) |
Variables | |
static int | sp_fd |
uint8_t | status = STA_UNINIT |
static uint8_t | frame_buf [FRAME_LEN] |
static uint32_t | idx = 0 |
Definition at line 20 of file nps_radio_control_spektrum.c.
#define FRAME_LEN 14 |
Definition at line 103 of file nps_radio_control_spektrum.c.
#define IUCLC 0 |
Definition at line 17 of file nps_radio_control_spektrum.c.
#define STA_GOT_SYNC_1 1 |
Definition at line 98 of file nps_radio_control_spektrum.c.
#define STA_GOT_SYNC_2 2 |
Definition at line 99 of file nps_radio_control_spektrum.c.
#define STA_UNINIT 0 |
Definition at line 97 of file nps_radio_control_spektrum.c.
#define SYNC_1 0x03 |
Definition at line 94 of file nps_radio_control_spektrum.c.
#define SYNC_2 0x12 |
Definition at line 95 of file nps_radio_control_spektrum.c.
|
static |
Definition at line 141 of file nps_radio_control_spektrum.c.
References CHANNEL_OF_FRAME, NpsRadioControl::mode, nps_radio_control, NpsRadioControl::pitch, NpsRadioControl::roll, NpsRadioControl::throttle, and NpsRadioControl::yaw.
Referenced by parse_data().
int nps_radio_control_spektrum_init | ( | const char * | device | ) |
Definition at line 31 of file nps_radio_control_spektrum.c.
References B115200, IUCLC, on_serial_data_received(), and sp_fd.
Referenced by nps_radio_control_init().
|
static |
Definition at line 74 of file nps_radio_control_spektrum.c.
References parse_data(), and TRUE.
Referenced by nps_radio_control_spektrum_init().
|
static |
Definition at line 107 of file nps_radio_control_spektrum.c.
References frame_buf, FRAME_LEN, handle_frame(), idx, STA_GOT_SYNC_1, STA_GOT_SYNC_2, STA_UNINIT, status, SYNC_1, and SYNC_2.
Referenced by on_serial_data_received().
Definition at line 104 of file nps_radio_control_spektrum.c.
Referenced by parse_data().
|
static |
Definition at line 105 of file nps_radio_control_spektrum.c.
Referenced by act_feedback_cb(), actuators_disco_set(), ahrs_switch(), attitude_ref_quat_float_idx_set_omega_p(), attitude_ref_quat_float_idx_set_omega_q(), attitude_ref_quat_float_idx_set_omega_r(), attitude_ref_quat_float_schedule(), baro_cb(), cloud_sensor_callback(), dshotTlmRec(), esc32_get_float(), find_launch_index(), image_show_points_color(), mavlink_common_message_handler(), mtostk_populate_float_array_from_buffer(), mtostk_populate_uuid_from_buffer(), osd_put_s(), parse_data(), pfc_act_feedback_cb(), pfc_actuators_value(), power_uavcan_send_power_device(), px4flow_i2c_periodic(), radio_control_get(), radio_control_set(), range_msg_callback(), rm3100_get_raw_from_buf(), rotwing_state_feedback_cb(), rpm_cb(), spi_submit(), stabilization_attitude_gain_schedule(), superbitrf_gen_dsmx_channels(), and vn200_read_message().
|
static |
Definition at line 22 of file nps_radio_control_spektrum.c.
Referenced by nps_radio_control_spektrum_init().
uint8_t status = STA_UNINIT |
Definition at line 101 of file nps_radio_control_spektrum.c.
Referenced by _vl53l5cx_poll_for_answer(), _vl53l5cx_poll_for_mcu_boot(), _vl53l5cx_send_offset_data(), _vl53l5cx_send_xtalk_data(), acInfoCalcPositionEnu_f(), acInfoCalcPositionEnu_i(), acInfoCalcPositionLla_f(), acInfoCalcPositionLla_i(), acInfoCalcPositionUtm_f(), acInfoCalcPositionUtm_i(), acInfoCalcVelocityEnu_f(), acInfoCalcVelocityEnu_i(), acInfoGetPositionEnu_f(), acInfoGetPositionEnu_i(), acInfoGetPositionLla_f(), acInfoGetPositionLla_i(), acInfoGetPositionUtm_f(), acInfoGetPositionUtm_i(), acInfoGetVelocityEnu_f(), acInfoGetVelocityEnu_i(), formation_flight(), jevois_mavlink_event(), lidar_lite_downlink(), lidar_sf11_downlink(), mavlink_event(), microrl_get_complite(), ms45xx_i2c_event(), msgqueue_pop_timeout(), new_line_handler(), parse_data(), parseFormationStatus(), py_check_status(), python_init(), rxSpiFrameStatus(), sdlog_check_free_space(), send_rotating_wing_state(), send_sdlog_status(), send_superbit(), set_ac_info_lla(), set_ac_info_utm(), start_formation(), stop_formation(), superbitrf_receive_packet_cb(), tcas_periodic_task_1Hz(), tfmini_send_lidar(), thd_lidar_vl53l5cx(), updateFormationStatus(), VL53L1X_BootState(), VL53L1X_CheckForDataReady(), VL53L1X_ClearInterrupt(), VL53L1X_GetAmbientPerSpad(), VL53L1X_GetAmbientRate(), VL53L1X_GetDistance(), VL53L1X_GetDistanceMode(), VL53L1X_GetDistanceThresholdHigh(), VL53L1X_GetDistanceThresholdLow(), VL53L1X_GetDistanceThresholdWindow(), VL53L1X_GetInterMeasurementInMs(), VL53L1X_GetInterruptPolarity(), VL53L1X_GetOffset(), VL53L1X_GetRangeStatus(), VL53L1X_GetResult(), VL53L1X_GetROI_XY(), VL53L1X_GetROICenter(), VL53L1X_GetSensorId(), VL53L1X_GetSigmaThreshold(), VL53L1X_GetSignalPerSpad(), VL53L1X_GetSignalRate(), VL53L1X_GetSignalThreshold(), VL53L1X_GetSpadNb(), VL53L1X_GetTimingBudgetInMs(), VL53L1X_GetXtalk(), VL53L1X_SensorInit(), VL53L1X_SetDistanceMode(), VL53L1X_SetDistanceThreshold(), VL53L1X_SetI2CAddress(), VL53L1X_SetInterMeasurementInMs(), VL53L1X_SetInterruptPolarity(), VL53L1X_SetOffset(), VL53L1X_SetROI(), VL53L1X_SetROICenter(), VL53L1X_SetSigmaThreshold(), VL53L1X_SetSignalThreshold(), VL53L1X_SetTimingBudgetInMs(), VL53L1X_SetXtalk(), VL53L1X_StartRanging(), VL53L1X_StartTemperatureUpdate(), VL53L1X_StopRanging(), vl53l5cx_check_data_ready(), vl53l5cx_dci_read_data(), vl53l5cx_dci_replace_data(), vl53l5cx_dci_write_data(), vl53l5cx_disable_internal_cp(), vl53l5cx_enable_internal_cp(), vl53l5cx_get_integration_time_ms(), vl53l5cx_get_power_mode(), vl53l5cx_get_ranging_data(), vl53l5cx_get_ranging_frequency_hz(), vl53l5cx_get_ranging_mode(), vl53l5cx_get_resolution(), vl53l5cx_get_sharpener_percent(), vl53l5cx_get_target_order(), vl53l5cx_init(), vl53l5cx_is_alive(), vl53l5cx_set_i2c_address(), vl53l5cx_set_integration_time_ms(), vl53l5cx_set_power_mode(), vl53l5cx_set_ranging_frequency_hz(), vl53l5cx_set_ranging_mode(), vl53l5cx_set_resolution(), vl53l5cx_set_sharpener_percent(), vl53l5cx_set_target_order(), vl53l5cx_start_ranging(), and vl53l5cx_stop_ranging().