ArduCopter: pass mavlink_message_t by const reference

This commit is contained in:
Pierre Kancir 2019-04-30 12:22:50 +02:00 committed by Peter Barker
parent 86406fdb02
commit c330b87592
4 changed files with 24 additions and 24 deletions

View File

@ -479,7 +479,7 @@ void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &
} }
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status, void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
mavlink_message_t &msg) const mavlink_message_t &msg)
{ {
#if ADSB_ENABLED == ENABLED #if ADSB_ENABLED == ENABLED
if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) { if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {
@ -513,13 +513,13 @@ void GCS_MAVLINK_Copter::send_banner()
} }
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes // a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
void GCS_MAVLINK_Copter::handle_rc_channels_override(const mavlink_message_t *msg) void GCS_MAVLINK_Copter::handle_rc_channels_override(const mavlink_message_t &msg)
{ {
copter.failsafe.last_heartbeat_ms = AP_HAL::millis(); copter.failsafe.last_heartbeat_ms = AP_HAL::millis();
GCS_MAVLINK::handle_rc_channels_override(msg); GCS_MAVLINK::handle_rc_channels_override(msg);
} }
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t* msg) void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
{ {
copter.command_ack_counter++; copter.command_ack_counter++;
GCS_MAVLINK::handle_command_ack(msg); GCS_MAVLINK::handle_command_ack(msg);
@ -839,15 +839,15 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
} }
} }
void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t* msg) void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
{ {
switch (msg->msgid) { switch (msg.msgid) {
#if MOUNT == ENABLED #if MOUNT == ENABLED
case MAVLINK_MSG_ID_MOUNT_CONTROL: case MAVLINK_MSG_ID_MOUNT_CONTROL:
if(!copter.camera_mount.has_pan_control()) { if(!copter.camera_mount.has_pan_control()) {
// if the mount doesn't do pan control then yaw the entire vehicle instead: // if the mount doesn't do pan control then yaw the entire vehicle instead:
copter.flightmode->auto_yaw.set_fixed_yaw( copter.flightmode->auto_yaw.set_fixed_yaw(
mavlink_msg_mount_control_get_input_c(msg) * 0.01f, mavlink_msg_mount_control_get_input_c(&msg) * 0.01f,
0.0f, 0.0f,
0, 0,
0); 0);
@ -859,26 +859,26 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t* msg)
GCS_MAVLINK::handle_mount_message(msg); GCS_MAVLINK::handle_mount_message(msg);
} }
void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
{ {
switch (msg->msgid) { switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: // MAV ID: 0 case MAVLINK_MSG_ID_HEARTBEAT: // MAV ID: 0
{ {
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes // We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
if(msg->sysid != copter.g.sysid_my_gcs) break; if(msg.sysid != copter.g.sysid_my_gcs) break;
copter.failsafe.last_heartbeat_ms = AP_HAL::millis(); copter.failsafe.last_heartbeat_ms = AP_HAL::millis();
break; break;
} }
case MAVLINK_MSG_ID_MANUAL_CONTROL: case MAVLINK_MSG_ID_MANUAL_CONTROL:
{ {
if (msg->sysid != copter.g.sysid_my_gcs) { if (msg.sysid != copter.g.sysid_my_gcs) {
break; // only accept control from our gcs break; // only accept control from our gcs
} }
mavlink_manual_control_t packet; mavlink_manual_control_t packet;
mavlink_msg_manual_control_decode(msg, &packet); mavlink_msg_manual_control_decode(&msg, &packet);
if (packet.target != copter.g.sysid_this_mav) { if (packet.target != copter.g.sysid_this_mav) {
break; // only accept control aimed at us break; // only accept control aimed at us
@ -905,7 +905,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
{ {
// decode packet // decode packet
mavlink_set_attitude_target_t packet; mavlink_set_attitude_target_t packet;
mavlink_msg_set_attitude_target_decode(msg, &packet); mavlink_msg_set_attitude_target_decode(&msg, &packet);
// exit if vehicle is not in Guided mode or Auto-Guided mode // exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) { if (!copter.flightmode->in_guided_mode()) {
@ -947,7 +947,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
{ {
// decode packet // decode packet
mavlink_set_position_target_local_ned_t packet; mavlink_set_position_target_local_ned_t packet;
mavlink_msg_set_position_target_local_ned_decode(msg, &packet); mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
// exit if vehicle is not in Guided mode or Auto-Guided mode // exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) { if (!copter.flightmode->in_guided_mode()) {
@ -1040,7 +1040,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
{ {
// decode packet // decode packet
mavlink_set_position_target_global_int_t packet; mavlink_set_position_target_global_int_t packet;
mavlink_msg_set_position_target_global_int_decode(msg, &packet); mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
// exit if vehicle is not in Guided mode or Auto-Guided mode // exit if vehicle is not in Guided mode or Auto-Guided mode
if (!copter.flightmode->in_guided_mode()) { if (!copter.flightmode->in_guided_mode()) {
@ -1126,7 +1126,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90 case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90
{ {
mavlink_hil_state_t packet; mavlink_hil_state_t packet;
mavlink_msg_hil_state_decode(msg, &packet); mavlink_msg_hil_state_decode(&msg, &packet);
// sanity check location // sanity check location
if (!check_latlng(packet.lat, packet.lon)) { if (!check_latlng(packet.lat, packet.lon)) {
@ -1192,7 +1192,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_SET_HOME_POSITION: case MAVLINK_MSG_ID_SET_HOME_POSITION:
{ {
mavlink_set_home_position_t packet; mavlink_set_home_position_t packet;
mavlink_msg_set_home_position_decode(msg, &packet); mavlink_msg_set_home_position_decode(&msg, &packet);
if((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { if((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
if (!copter.set_home_to_current_location(true)) { if (!copter.set_home_to_current_location(true)) {
// silently ignored // silently ignored

View File

@ -33,7 +33,7 @@ protected:
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
void handle_mount_message(const mavlink_message_t* msg) override; void handle_mount_message(const mavlink_message_t &msg) override;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
@ -47,15 +47,15 @@ protected:
private: private:
void handleMessage(mavlink_message_t * msg) override; void handleMessage(const mavlink_message_t &msg) override;
void handle_command_ack(const mavlink_message_t* msg) override; void handle_command_ack(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
void handle_rc_channels_override(const mavlink_message_t *msg) override; void handle_rc_channels_override(const mavlink_message_t &msg) override;
bool try_send_message(enum ap_message id) override; bool try_send_message(enum ap_message id) override;
void packetReceived(const mavlink_status_t &status, void packetReceived(const mavlink_status_t &status,
mavlink_message_t &msg) override; const mavlink_message_t &msg) override;
MAV_MODE base_mode() const override; MAV_MODE base_mode() const override;
MAV_STATE system_status() const override; MAV_STATE system_status() const override;

View File

@ -930,9 +930,9 @@ void ToyMode::blink_update(void)
} }
// handle a mavlink message // handle a mavlink message
void ToyMode::handle_message(mavlink_message_t *msg) void ToyMode::handle_message(const mavlink_message_t &msg)
{ {
if (msg->msgid != MAVLINK_MSG_ID_NAMED_VALUE_INT) { if (msg.msgid != MAVLINK_MSG_ID_NAMED_VALUE_INT) {
return; return;
} }
mavlink_named_value_int_t m; mavlink_named_value_int_t m;

View File

@ -26,7 +26,7 @@ public:
void throttle_adjust(float &throttle_control); void throttle_adjust(float &throttle_control);
// handle mavlink message // handle mavlink message
void handle_message(mavlink_message_t *msg); void handle_message(const mavlink_message_t &msg);
void load_test_run(void); void load_test_run(void);