mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: subclass GCS_MAVLink in place of defining its functions for it
This commit is contained in:
parent
a1c97f4585
commit
df190d1e86
@ -1,5 +1,7 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "GCS_Mavlink.h"
|
||||
|
||||
#include "Tracker.h"
|
||||
#include "version.h"
|
||||
|
||||
@ -150,19 +152,19 @@ void Tracker::send_simstate(mavlink_channel_t chan)
|
||||
#endif
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::handle_guided_request(AP_Mission::Mission_Command&)
|
||||
bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
|
||||
{
|
||||
// do nothing
|
||||
return false;
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handle_change_alt_request(AP_Mission::Mission_Command&)
|
||||
void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&)
|
||||
{
|
||||
// do nothing
|
||||
}
|
||||
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
||||
{
|
||||
switch (id) {
|
||||
case MSG_HEARTBEAT:
|
||||
@ -375,7 +377,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
float GCS_MAVLINK_Tracker::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
{
|
||||
if (_queued_parameter != nullptr) {
|
||||
return 0.25f;
|
||||
@ -385,7 +387,7 @@ float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK::data_stream_send(void)
|
||||
GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||
{
|
||||
if (_queued_parameter != NULL) {
|
||||
if (streamRates[STREAM_PARAMS].get() <= 0) {
|
||||
@ -535,7 +537,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
target_set = true;
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
||||
|
22
AntennaTracker/GCS_Mavlink.h
Normal file
22
AntennaTracker/GCS_Mavlink.h
Normal file
@ -0,0 +1,22 @@
|
||||
#pragma once
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
class GCS_MAVLINK_Tracker : public GCS_MAVLINK
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
void data_stream_send(void) override;
|
||||
|
||||
protected:
|
||||
|
||||
private:
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num) override;
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||
bool try_send_message(enum ap_message id) override;
|
||||
|
||||
};
|
@ -43,7 +43,6 @@
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
|
||||
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <DataFlash/DataFlash.h>
|
||||
@ -69,7 +68,7 @@
|
||||
#include "defines.h"
|
||||
|
||||
#include "Parameters.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include "GCS_Mavlink.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
@ -77,7 +76,7 @@
|
||||
|
||||
class Tracker : public AP_HAL::HAL::Callbacks {
|
||||
public:
|
||||
friend class GCS_MAVLINK;
|
||||
friend class GCS_MAVLINK_Tracker;
|
||||
friend class Parameters;
|
||||
|
||||
Tracker(void);
|
||||
@ -135,7 +134,7 @@ private:
|
||||
|
||||
AP_SerialManager serial_manager;
|
||||
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||
GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||
GCS_MAVLINK_Tracker gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
AP_BoardConfig BoardConfig;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user