mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 09:47:36 +08:00
Cleaned up MAVLink include hierarchy
This commit is contained in:
@@ -49,7 +49,6 @@
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
@@ -471,7 +470,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
|
||||
}
|
||||
|
||||
void
|
||||
mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
|
||||
mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length)
|
||||
{
|
||||
write(uart, ch, (size_t)(sizeof(uint8_t) * length));
|
||||
}
|
||||
@@ -479,7 +478,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
|
||||
/*
|
||||
* Internal function to give access to the channel status for each channel
|
||||
*/
|
||||
mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
|
||||
extern mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
|
||||
{
|
||||
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
|
||||
return &m_mavlink_status[channel];
|
||||
@@ -488,7 +487,7 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
|
||||
/*
|
||||
* Internal function to give access to the channel buffer for each channel
|
||||
*/
|
||||
mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
|
||||
extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
|
||||
{
|
||||
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
|
||||
return &m_mavlink_buffer[channel];
|
||||
|
||||
@@ -73,9 +73,11 @@ extern mavlink_system_t mavlink_system;
|
||||
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
|
||||
* @param ch Character to send
|
||||
*/
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int length);
|
||||
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length);
|
||||
|
||||
mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
|
||||
mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
|
||||
extern mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
|
||||
extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
|
||||
|
||||
#include <v1.0/common/mavlink.h>
|
||||
|
||||
#endif /* MAVLINK_BRIDGE_HEADER_H */
|
||||
|
||||
@@ -40,7 +40,6 @@
|
||||
*/
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include "mavlink_parameters.h"
|
||||
#include <uORB/uORB.h>
|
||||
#include "math.h" /* isinf / isnan checks */
|
||||
|
||||
@@ -49,7 +49,6 @@
|
||||
#include <fcntl.h>
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
@@ -503,7 +502,6 @@ handle_message(mavlink_message_t *msg)
|
||||
} else {
|
||||
orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
|
||||
}
|
||||
warnx("IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);
|
||||
|
||||
hil_global_pos.lat = hil_state.lat;
|
||||
hil_global_pos.lon = hil_state.lon;
|
||||
|
||||
@@ -48,7 +48,6 @@
|
||||
#include <mqueue.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
|
||||
//extern void mavlink_wpm_send_message(mavlink_message_t *msg);
|
||||
//extern void mavlink_wpm_send_gcs_string(const char *string);
|
||||
|
||||
@@ -47,7 +47,6 @@
|
||||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <time.h>
|
||||
#include <float.h>
|
||||
|
||||
@@ -45,6 +45,7 @@
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include "missionlib.h"
|
||||
#include "waypoints.h"
|
||||
#include "util.h"
|
||||
|
||||
@@ -47,11 +47,11 @@
|
||||
|
||||
#include <v1.0/mavlink_types.h>
|
||||
|
||||
#ifndef MAVLINK_SEND_UART_BYTES
|
||||
#define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
|
||||
#endif
|
||||
extern mavlink_system_t mavlink_system;
|
||||
#include <v1.0/common/mavlink.h>
|
||||
// #ifndef MAVLINK_SEND_UART_BYTES
|
||||
// #define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
|
||||
// #endif
|
||||
//extern mavlink_system_t mavlink_system;
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <stdbool.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
|
||||
Reference in New Issue
Block a user