forked from Archive/PX4-Autopilot
Delete unnecessary #includes from mavlink_main.cpp and relocate a few #defines to mavlink_main.h for future variable initialization work.
This commit is contained in:
parent
77ab9b617e
commit
cb49ed55fe
|
@ -40,22 +40,7 @@
|
|||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_module.h>
|
||||
#include <px4_cli.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <assert.h>
|
||||
#include <math.h>
|
||||
#include <termios.h>
|
||||
#include <time.h>
|
||||
|
||||
#ifdef CONFIG_NET
|
||||
#include <arpa/inet.h>
|
||||
|
@ -63,34 +48,12 @@
|
|||
#include <netutils/netlib.h>
|
||||
#endif
|
||||
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <dataman/dataman.h>
|
||||
#include <version/version.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <version/version.h>
|
||||
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/vehicle_command_ack.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/mavlink_log.h>
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_main.h"
|
||||
#include "mavlink_messages.h"
|
||||
#include "mavlink_receiver.h"
|
||||
#include "mavlink_rate_limiter.h"
|
||||
#include "mavlink_command_sender.h"
|
||||
#include "mavlink_main.h"
|
||||
|
||||
// Guard against MAVLink misconfiguration
|
||||
#ifndef MAVLINK_CRC_EXTRA
|
||||
|
@ -108,17 +71,14 @@
|
|||
#define MAVLINK_NET_ADDED_STACK 0
|
||||
#endif
|
||||
|
||||
#define DEFAULT_REMOTE_PORT_UDP 14550 ///< GCS port per MAVLink spec
|
||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||
#define MAX_DATA_RATE 10000000 ///< max data rate in bytes/s
|
||||
#define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate
|
||||
#define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it.
|
||||
//#define MAVLINK_PRINT_PACKETS
|
||||
#define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it.
|
||||
#define MAX_DATA_RATE 10000000 ///< max data rate in bytes/s
|
||||
#define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate
|
||||
|
||||
static Mavlink *_mavlink_instances = nullptr;
|
||||
|
||||
/**
|
||||
* mavlink app start / stop handling function
|
||||
* Mavlink app start / stop handling function.
|
||||
*
|
||||
* @ingroup apps
|
||||
*/
|
||||
|
|
|
@ -42,44 +42,51 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <px4_posix.h>
|
||||
#include <px4_module_params.h>
|
||||
|
||||
#include <pthread.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include <nuttx/fs/fs.h>
|
||||
#else
|
||||
#include <sys/socket.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <drivers/device/device.h>
|
||||
#include <sys/socket.h>
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_NET) || !defined(__PX4_NUTTX)
|
||||
#include <netinet/in.h>
|
||||
#include <net/if.h>
|
||||
#include <netinet/in.h>
|
||||
#endif
|
||||
|
||||
#include <containers/List.hpp>
|
||||
#include <systemlib/uthash/utlist.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <parameters/param.h>
|
||||
#include <perf/perf_counter.h>
|
||||
#include <pthread.h>
|
||||
#include <px4_cli.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_defines.h>
|
||||
#include <px4_getopt.h>
|
||||
#include <px4_module.h>
|
||||
#include <px4_module_params.h>
|
||||
#include <px4_posix.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <systemlib/uthash/utlist.h>
|
||||
#include <uORB/topics/mavlink_log.h>
|
||||
#include <uORB/topics/mission_result.h>
|
||||
#include <uORB/topics/radio_status.h>
|
||||
#include <uORB/topics/telemetry_status.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "mavlink_orb_subscription.h"
|
||||
#include "mavlink_stream.h"
|
||||
#include "mavlink_command_sender.h"
|
||||
#include "mavlink_messages.h"
|
||||
#include "mavlink_orb_subscription.h"
|
||||
#include "mavlink_shell.h"
|
||||
#include "mavlink_ulog.h"
|
||||
|
||||
#define DEFAULT_REMOTE_PORT_UDP 14550 ///< GCS port per MAVLink spec
|
||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||
#define HASH_PARAM "_HASH_CHECK"
|
||||
|
||||
enum Protocol {
|
||||
SERIAL = 0,
|
||||
UDP,
|
||||
|
@ -88,8 +95,6 @@ enum Protocol {
|
|||
|
||||
using namespace time_literals;
|
||||
|
||||
#define HASH_PARAM "_HASH_CHECK"
|
||||
|
||||
class Mavlink : public ModuleParams
|
||||
{
|
||||
|
||||
|
|
Loading…
Reference in New Issue