GCS_MAVLINK: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:16:38 -03:00 committed by Andrew Tridgell
parent 45a819c98e
commit e8e41c512e
4 changed files with 18 additions and 18 deletions

View File

@ -348,7 +348,7 @@ protected:
// overridable method to check for packet acceptance. Allows for
// enforcement of GCS sysid
bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg);
bool accept_packet(const mavlink_status_t &status, const mavlink_message_t &msg) const;
void set_ekf_origin(const Location& loc);
virtual MAV_MODE base_mode() const = 0;
@ -386,9 +386,9 @@ protected:
MAV_RESULT handle_command_do_set_home(const mavlink_command_long_t &packet);
void handle_mission_request_list(const mavlink_message_t &msg);
void handle_mission_request(const mavlink_message_t &msg);
void handle_mission_request_int(const mavlink_message_t &msg);
void handle_mission_clear_all(const mavlink_message_t &msg);
void handle_mission_request(const mavlink_message_t &msg) const;
void handle_mission_request_int(const mavlink_message_t &msg) const;
void handle_mission_clear_all(const mavlink_message_t &msg) const;
virtual void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg);
void handle_mission_count(const mavlink_message_t &msg);
void handle_mission_write_partial_list(const mavlink_message_t &msg);
@ -398,7 +398,7 @@ protected:
void handle_obstacle_distance(const mavlink_message_t &msg);
void handle_obstacle_distance_3d(const mavlink_message_t &msg);
void handle_osd_param_config(const mavlink_message_t &msg);
void handle_osd_param_config(const mavlink_message_t &msg) const;
void handle_common_param_message(const mavlink_message_t &msg);
void handle_param_set(const mavlink_message_t &msg);
@ -409,7 +409,7 @@ protected:
void handle_system_time_message(const mavlink_message_t &msg);
void handle_common_rally_message(const mavlink_message_t &msg);
void handle_rally_fetch_point(const mavlink_message_t &msg);
void handle_rally_point(const mavlink_message_t &msg);
void handle_rally_point(const mavlink_message_t &msg) const;
virtual void handle_mount_message(const mavlink_message_t &msg);
void handle_fence_message(const mavlink_message_t &msg);
void handle_param_value(const mavlink_message_t &msg);
@ -419,7 +419,7 @@ protected:
void handle_common_message(const mavlink_message_t &msg);
void handle_set_gps_global_origin(const mavlink_message_t &msg);
void handle_setup_signing(const mavlink_message_t &msg);
void handle_setup_signing(const mavlink_message_t &msg) const;
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet);
// reset a message interval via mavlink:
@ -451,7 +451,7 @@ protected:
const uint16_t interval_ms = 10000;
} _timesync_request;
void handle_statustext(const mavlink_message_t &msg);
void handle_statustext(const mavlink_message_t &msg) const;
bool telemetry_delayed() const;
virtual uint32_t telem_delay() const = 0;
@ -906,7 +906,7 @@ public:
static MissionItemProtocol_Rally *_missionitemprotocol_rally;
static MissionItemProtocol_Fence *_missionitemprotocol_fence;
MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
void try_send_queued_message_for_type(MAV_MISSION_TYPE type);
void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const;
void update_send();
void update_receive();

View File

@ -479,7 +479,7 @@ void GCS_MAVLINK::handle_mission_request_list(const mavlink_message_t &msg)
/*
handle a MISSION_REQUEST mavlink packet
*/
void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg) const
{
// decode
mavlink_mission_request_int_t packet;
@ -492,7 +492,7 @@ void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg)
prot->handle_mission_request_int(*this, packet, msg);
}
void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg) const
{
// decode
mavlink_mission_request_t packet;
@ -545,7 +545,7 @@ void GCS_MAVLINK::handle_mission_count(const mavlink_message_t &msg)
/*
handle a MISSION_CLEAR_ALL mavlink packet
*/
void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg) const
{
// decode
mavlink_mission_clear_all_t packet;
@ -2865,7 +2865,7 @@ void GCS_MAVLINK::send_timesync()
);
}
void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg) const
{
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
@ -3232,7 +3232,7 @@ void GCS_MAVLINK::handle_obstacle_distance_3d(const mavlink_message_t &msg)
}
}
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg) const
{
#if OSD_PARAM_ENABLED
AP_OSD *osd = AP::osd();
@ -4296,7 +4296,7 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg)
hal.util->persistent_data.last_mavlink_cmd = 0;
}
void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) {
void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) const {
MissionItemProtocol *prot = get_prot_for_mission_type(type);
if (prot == nullptr) {
return;
@ -4999,7 +4999,7 @@ uint32_t GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(uint64_t offboard_us
return true if we will accept this packet. Used to implement SYSID_ENFORCE
*/
bool GCS_MAVLINK::accept_packet(const mavlink_status_t &status,
const mavlink_message_t &msg)
const mavlink_message_t &msg) const
{
if (msg.sysid == mavlink_system.sysid) {
// accept packets from our own components

View File

@ -21,7 +21,7 @@
#include <AP_Rally/AP_Rally.h>
#include <AP_Logger/AP_Logger.h>
void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg) const
{
AP_Rally *r = AP::rally();
if (r == nullptr) {

View File

@ -63,7 +63,7 @@ bool GCS_MAVLINK::signing_key_load(struct SigningKey &key)
/*
handle a setup_signing message
*/
void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg)
void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg) const
{
// setting up signing key when armed generally not useful /
// possibly not a good idea