mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
GCS_MAVLink: factor vehicle's mavlink send_heartbeat
This commit is contained in:
parent
a21eb12f9e
commit
4fd2ec1cef
@ -149,6 +149,7 @@ public:
|
||||
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
|
||||
|
||||
// common send functions
|
||||
void send_heartbeat(void);
|
||||
void send_meminfo(void);
|
||||
void send_power_status(void);
|
||||
void send_battery_status(const AP_BattMonitor &battery, const uint8_t instance) const;
|
||||
@ -174,7 +175,6 @@ public:
|
||||
void send_vibration(const AP_InertialSensor &ins) const;
|
||||
void send_home(const Location &home) const;
|
||||
void send_ekf_origin(const Location &ekf_origin) const;
|
||||
void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status);
|
||||
void send_servo_output_raw(bool hil);
|
||||
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
|
||||
void send_accelcal_vehicle_position(uint32_t position);
|
||||
@ -234,6 +234,11 @@ protected:
|
||||
virtual const AP_FWVersion &get_fwver() const = 0;
|
||||
virtual void set_ekf_origin(const Location& loc) = 0;
|
||||
|
||||
virtual MAV_TYPE frame_type() const = 0;
|
||||
virtual MAV_MODE base_mode() const = 0;
|
||||
virtual uint32_t custom_mode() const = 0;
|
||||
virtual MAV_STATE system_status() const = 0;
|
||||
|
||||
bool waypoint_receiving; // currently receiving
|
||||
// the following two variables are only here because of Tracker
|
||||
uint16_t waypoint_request_i; // request index
|
||||
|
@ -1516,17 +1516,17 @@ void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
|
||||
}
|
||||
|
||||
/*
|
||||
wrapper for sending heartbeat
|
||||
Send MAVLink heartbeat
|
||||
*/
|
||||
void GCS_MAVLINK::send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
|
||||
void GCS_MAVLINK::send_heartbeat()
|
||||
{
|
||||
mavlink_msg_heartbeat_send(
|
||||
chan,
|
||||
type,
|
||||
frame_type(),
|
||||
MAV_AUTOPILOT_ARDUPILOTMEGA,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
system_status);
|
||||
base_mode(),
|
||||
custom_mode(),
|
||||
system_status());
|
||||
}
|
||||
|
||||
float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
|
@ -34,6 +34,12 @@ protected:
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
bool set_mode(uint8_t mode) override { return false; };
|
||||
|
||||
// dummy information:
|
||||
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
||||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -41,6 +41,12 @@ protected:
|
||||
const AP_FWVersion &get_fwver() const override { return fwver; }
|
||||
void set_ekf_origin(const Location& loc) override { };
|
||||
|
||||
// dummy information:
|
||||
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
||||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg) { }
|
||||
|
Loading…
Reference in New Issue
Block a user