Browse Source

GCS_MAVLink: support member functions for rover

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
71b550d7b5
  1. 14
      libraries/GCS_MAVLink/GCS.h
  2. 6
      libraries/GCS_MAVLink/GCS_Common.cpp

14
libraries/GCS_MAVLink/GCS.h

@ -70,7 +70,12 @@ class GCS_MAVLINK @@ -70,7 +70,12 @@ class GCS_MAVLINK
{
public:
GCS_MAVLINK();
void update(void (*run_cli)(AP_HAL::UARTDriver *));
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
typedef DELEGATE_FUNCTION1(void, AP_HAL::UARTDriver*) run_cli_fn;
#else
typedef void (*run_cli_fn)(AP_HAL::UARTDriver *);
#endif
void update(run_cli_fn run_cli);
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan);
void setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance);
void send_message(enum ap_message id);
@ -294,7 +299,12 @@ private: @@ -294,7 +299,12 @@ private:
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
void lock_channel(mavlink_channel_t chan, bool lock);
void handle_set_mode(mavlink_message_t* msg, bool (*set_mode)(uint8_t mode));
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
typedef DELEGATE_FUNCTION1(bool, uint8_t) set_mode_fn;
#else
typedef bool (*set_mode_fn)(uint8_t);
#endif
void handle_set_mode(mavlink_message_t* msg, set_mode_fn set_mode);
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const;
void handle_gps_inject(const mavlink_message_t *msg, AP_GPS &gps);

6
libraries/GCS_MAVLink/GCS_Common.cpp

@ -19,6 +19,8 @@ @@ -19,6 +19,8 @@
#include <GCS.h>
#include <AP_AHRS.h>
#include <AP_HAL.h>
#include <AP_Vehicle.h>
extern const AP_HAL::HAL& hal;
@ -825,7 +827,7 @@ void GCS_MAVLINK::send_message(enum ap_message id) @@ -825,7 +827,7 @@ void GCS_MAVLINK::send_message(enum ap_message id)
}
void
GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
GCS_MAVLINK::update(run_cli_fn run_cli)
{
// receive new packets
mavlink_message_t msg;
@ -1177,7 +1179,7 @@ void GCS_MAVLINK::send_battery2(const AP_BattMonitor &battery) @@ -1177,7 +1179,7 @@ void GCS_MAVLINK::send_battery2(const AP_BattMonitor &battery)
/*
handle a SET_MODE MAVLink message
*/
void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg, bool (*set_mode)(uint8_t mode))
void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg, set_mode_fn set_mode)
{
uint8_t result = MAV_RESULT_FAILED;
mavlink_set_mode_t packet;

Loading…
Cancel
Save