mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
GCS_MAVLink: routing example: use GCS_Dummy in place of custom GCS
This commit is contained in:
parent
061b4b7e70
commit
c11da6a85d
@ -5,6 +5,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
#include <GCS_MAVLink/GCS_Dummy.h>
|
||||||
#include <AP_Common/AP_FWVersion.h>
|
#include <AP_Common/AP_FWVersion.h>
|
||||||
|
|
||||||
void setup();
|
void setup();
|
||||||
@ -12,55 +13,7 @@ void loop();
|
|||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
const AP_FWVersion AP_FWVersion::fwver
|
GCS_Dummy _gcs;
|
||||||
{
|
|
||||||
major: 3,
|
|
||||||
minor: 1,
|
|
||||||
patch: 4,
|
|
||||||
fw_type: FIRMWARE_VERSION_TYPE_DEV,
|
|
||||||
fw_string: "routing example",
|
|
||||||
fw_hash_str: "",
|
|
||||||
middleware_name: "",
|
|
||||||
middleware_hash_str: "",
|
|
||||||
os_name: "",
|
|
||||||
os_hash_str: "",
|
|
||||||
os_sw_version: 0
|
|
||||||
};
|
|
||||||
|
|
||||||
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] {};
|
|
||||||
|
|
||||||
class GCS_MAVLINK_routing : public GCS_MAVLINK
|
|
||||||
{
|
|
||||||
|
|
||||||
public:
|
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
uint32_t telem_delay() const override { return 0; }
|
|
||||||
uint8_t sysid_my_gcs() const override { return 1; }
|
|
||||||
bool set_mode(uint8_t mode) override { return false; };
|
|
||||||
|
|
||||||
// dummy information:
|
|
||||||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
|
||||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
|
||||||
void send_nav_controller_output() const override {};
|
|
||||||
void send_pid_tuning() override {};
|
|
||||||
|
|
||||||
bool set_home_to_current_location(bool lock) override { return false; }
|
|
||||||
bool set_home(const Location& loc, bool lock) override { return false; }
|
|
||||||
|
|
||||||
private:
|
|
||||||
|
|
||||||
void handleMessage(mavlink_message_t * msg) override { }
|
|
||||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return false ; }
|
|
||||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override { }
|
|
||||||
bool try_send_message(enum ap_message id) override { return false; }
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
|
||||||
static GCS_MAVLINK_routing gcs_link[num_gcs];
|
|
||||||
|
|
||||||
extern mavlink_system_t mavlink_system;
|
extern mavlink_system_t mavlink_system;
|
||||||
|
|
||||||
@ -73,7 +26,7 @@ static MAVLink_routing routing;
|
|||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
hal.console->printf("routing test startup...");
|
hal.console->printf("routing test startup...");
|
||||||
gcs_link[0].init(hal.uartA, MAVLINK_COMM_0);
|
gcs().chan(0).init(hal.uartA, MAVLINK_COMM_0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void)
|
void loop(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user