forked from Archive/PX4-Autopilot
Deprecate #defines that are not needed, format whitespace and minor (incomplete) alphebetization of a few lists.
This commit is contained in:
parent
cb9d483cb8
commit
8a6a5cc310
|
@ -40,33 +40,18 @@
|
|||
* @author Thomas Gubler <thomas@px4.io>
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
#include <px4_time.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_posix.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <airspeed/airspeed.h>
|
||||
#include <commander/px4_custom_mode.h>
|
||||
#include <conversion/rotation.h>
|
||||
#include <drivers/drv_accel.h>
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <drivers/drv_tone_alarm.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
#include <unistd.h>
|
||||
#ifndef __PX4_POSIX
|
||||
#include <termios.h>
|
||||
#endif
|
||||
#include <ecl/geo/geo.h>
|
||||
|
||||
#ifdef CONFIG_NET
|
||||
#include <net/if.h>
|
||||
|
@ -74,11 +59,6 @@
|
|||
#include <netinet/in.h>
|
||||
#endif
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdlib.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
#ifdef __PX4_DARWIN
|
||||
#include <sys/param.h>
|
||||
#include <sys/mount.h>
|
||||
|
@ -86,23 +66,13 @@
|
|||
#include <sys/statfs.h>
|
||||
#endif
|
||||
|
||||
#include <airspeed/airspeed.h>
|
||||
#include <ecl/geo/geo.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <conversion/rotation.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#ifndef __PX4_POSIX
|
||||
#include <termios.h>
|
||||
#endif
|
||||
|
||||
#include <commander/px4_custom_mode.h>
|
||||
|
||||
#include <uORB/topics/radio_status.h>
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_receiver.h"
|
||||
#include "mavlink_main.h"
|
||||
#include "mavlink_command_sender.h"
|
||||
#include "mavlink_main.h"
|
||||
#include "mavlink_receiver.h"
|
||||
|
||||
#ifdef CONFIG_NET
|
||||
#define MAVLINK_RECEIVER_NET_ADDED_STACK 1360
|
||||
|
|
|
@ -50,10 +50,10 @@
|
|||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/collision_report.h>
|
||||
#include <uORB/topics/debug_array.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
#include <uORB/topics/debug_value.h>
|
||||
#include <uORB/topics/debug_vect.h>
|
||||
#include <uORB/topics/debug_array.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/follow_target.h>
|
||||
#include <uORB/topics/gps_inject_data.h>
|
||||
|
@ -67,13 +67,12 @@
|
|||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
#include <uORB/topics/vehicle_trajectory_waypoint.h>
|
||||
#include <uORB/topics/transponder_report.h>
|
||||
#include <uORB/topics/telemetry_status.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/transponder_report.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
|
@ -82,6 +81,7 @@
|
|||
#include <uORB/topics/vehicle_odometry.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_trajectory_waypoint.h>
|
||||
|
||||
#include "mavlink_ftp.h"
|
||||
#include "mavlink_log_handler.h"
|
||||
|
@ -107,7 +107,7 @@ public:
|
|||
/**
|
||||
* Display the mavlink status.
|
||||
*/
|
||||
void print_status();
|
||||
void print_status();
|
||||
|
||||
/**
|
||||
* Start the receiver thread
|
||||
|
@ -128,11 +128,13 @@ private:
|
|||
template<class T>
|
||||
void handle_message_command_both(mavlink_message_t *msg, const T &cmd_mavlink,
|
||||
const vehicle_command_s &vehicle_command);
|
||||
|
||||
void handle_message_adsb_vehicle(mavlink_message_t *msg);
|
||||
void handle_message_att_pos_mocap(mavlink_message_t *msg);
|
||||
void handle_message_command_ack(mavlink_message_t *msg);
|
||||
void handle_message_optical_flow_rad(mavlink_message_t *msg);
|
||||
void handle_message_hil_optical_flow(mavlink_message_t *msg);
|
||||
void handle_message_set_mode(mavlink_message_t *msg);
|
||||
void handle_message_att_pos_mocap(mavlink_message_t *msg);
|
||||
void handle_message_vision_position_estimate(mavlink_message_t *msg);
|
||||
void handle_message_gps_global_origin(mavlink_message_t *msg);
|
||||
void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
|
||||
|
@ -149,7 +151,6 @@ private:
|
|||
void handle_message_distance_sensor(mavlink_message_t *msg);
|
||||
void handle_message_follow_target(mavlink_message_t *msg);
|
||||
void handle_message_landing_target(mavlink_message_t *msg);
|
||||
void handle_message_adsb_vehicle(mavlink_message_t *msg);
|
||||
void handle_message_collision(mavlink_message_t *msg);
|
||||
void handle_message_gps_rtcm_data(mavlink_message_t *msg);
|
||||
void handle_message_battery_status(mavlink_message_t *msg);
|
||||
|
@ -189,7 +190,7 @@ private:
|
|||
*/
|
||||
int decode_switch_pos_n(uint16_t buttons, unsigned sw);
|
||||
|
||||
bool evaluate_target_ok(int command, int target_system, int target_component);
|
||||
bool evaluate_target_ok(int command, int target_system, int target_component);
|
||||
|
||||
void send_flight_information();
|
||||
|
||||
|
@ -201,13 +202,15 @@ private:
|
|||
MavlinkParametersManager _parameters_manager;
|
||||
MavlinkFTP _mavlink_ftp;
|
||||
MavlinkLogHandler _mavlink_log_handler;
|
||||
MavlinkTimesync _mavlink_timesync;
|
||||
MavlinkTimesync _mavlink_timesync;
|
||||
|
||||
mavlink_status_t _status; ///< receiver status, used for mavlink_parse_char()
|
||||
|
||||
struct vehicle_attitude_s _att;
|
||||
struct vehicle_local_position_s _hil_local_pos;
|
||||
struct vehicle_land_detected_s _hil_land_detector;
|
||||
struct vehicle_control_mode_s _control_mode;
|
||||
|
||||
orb_advert_t _global_pos_pub;
|
||||
orb_advert_t _local_pos_pub;
|
||||
orb_advert_t _attitude_pub;
|
||||
|
@ -245,19 +248,25 @@ private:
|
|||
orb_advert_t _debug_value_pub;
|
||||
orb_advert_t _debug_vect_pub;
|
||||
orb_advert_t _debug_array_pub;
|
||||
static const int _gps_inject_data_queue_size = 6;
|
||||
orb_advert_t _gps_inject_data_pub;
|
||||
orb_advert_t _command_ack_pub;
|
||||
int _control_mode_sub;
|
||||
|
||||
static const int _gps_inject_data_queue_size = 6;
|
||||
|
||||
int _actuator_armed_sub;
|
||||
int _vehicle_attitude_sub;
|
||||
uint64_t _global_ref_timestamp;
|
||||
int _control_mode_sub;
|
||||
int _hil_frames;
|
||||
int _vehicle_attitude_sub;
|
||||
|
||||
uint64_t _global_ref_timestamp;
|
||||
uint64_t _old_timestamp;
|
||||
|
||||
bool _hil_local_proj_inited;
|
||||
float _hil_local_alt0;
|
||||
|
||||
struct map_projection_reference_s _hil_local_proj_ref;
|
||||
struct offboard_control_mode_s _offboard_control_mode;
|
||||
|
||||
int _orb_class_instance;
|
||||
|
||||
static constexpr unsigned MOM_SWITCH_COUNT = 8;
|
||||
|
|
Loading…
Reference in New Issue