mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: pass mavlink_message_t by const reference
This commit is contained in:
parent
b1506ca652
commit
4180345fdc
|
@ -294,7 +294,7 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||||
MAVLINK_MSG_ID_SCALED_PRESSUREs
|
MAVLINK_MSG_ID_SCALED_PRESSUREs
|
||||||
*/
|
*/
|
||||||
void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,
|
void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,
|
||||||
mavlink_message_t &msg)
|
const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
// return immediately if sysid doesn't match our target sysid
|
// return immediately if sysid doesn't match our target sysid
|
||||||
if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {
|
if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {
|
||||||
|
@ -420,16 +420,16 @@ bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool lock) {
|
||||||
return tracker.set_home(loc);
|
return tracker.set_home(loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
void GCS_MAVLINK_Tracker::handleMessage(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
switch (msg->msgid) {
|
switch (msg.msgid) {
|
||||||
|
|
||||||
// When mavproxy 'wp sethome'
|
// When mavproxy 'wp sethome'
|
||||||
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
||||||
{
|
{
|
||||||
// decode
|
// decode
|
||||||
mavlink_mission_write_partial_list_t packet;
|
mavlink_mission_write_partial_list_t packet;
|
||||||
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
|
mavlink_msg_mission_write_partial_list_decode(&msg, &packet);
|
||||||
if (packet.start_index == 0)
|
if (packet.start_index == 0)
|
||||||
{
|
{
|
||||||
// New home at wp index 0. Ask for it
|
// New home at wp index 0. Ask for it
|
||||||
|
@ -446,7 +446,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
||||||
mavlink_mission_item_t packet;
|
mavlink_mission_item_t packet;
|
||||||
MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
|
MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
|
||||||
|
|
||||||
mavlink_msg_mission_item_decode(msg, &packet);
|
mavlink_msg_mission_item_decode(&msg, &packet);
|
||||||
|
|
||||||
struct Location tell_command;
|
struct Location tell_command;
|
||||||
|
|
||||||
|
@ -528,8 +528,8 @@ mission_failed:
|
||||||
// we are rejecting the mission/waypoint
|
// we are rejecting the mission/waypoint
|
||||||
mavlink_msg_mission_ack_send(
|
mavlink_msg_mission_ack_send(
|
||||||
chan,
|
chan,
|
||||||
msg->sysid,
|
msg.sysid,
|
||||||
msg->compid,
|
msg.compid,
|
||||||
result,
|
result,
|
||||||
MAV_MISSION_TYPE_MISSION);
|
MAV_MISSION_TYPE_MISSION);
|
||||||
break;
|
break;
|
||||||
|
@ -538,7 +538,7 @@ mission_failed:
|
||||||
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
||||||
{
|
{
|
||||||
mavlink_manual_control_t packet;
|
mavlink_manual_control_t packet;
|
||||||
mavlink_msg_manual_control_decode(msg, &packet);
|
mavlink_msg_manual_control_decode(&msg, &packet);
|
||||||
tracker.tracking_manual_control(packet);
|
tracker.tracking_manual_control(packet);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -547,7 +547,7 @@ mission_failed:
|
||||||
{
|
{
|
||||||
// decode
|
// decode
|
||||||
mavlink_global_position_int_t packet;
|
mavlink_global_position_int_t packet;
|
||||||
mavlink_msg_global_position_int_decode(msg, &packet);
|
mavlink_msg_global_position_int_decode(&msg, &packet);
|
||||||
tracker.tracking_update_position(packet);
|
tracker.tracking_update_position(packet);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -556,7 +556,7 @@ mission_failed:
|
||||||
{
|
{
|
||||||
// decode
|
// decode
|
||||||
mavlink_scaled_pressure_t packet;
|
mavlink_scaled_pressure_t packet;
|
||||||
mavlink_msg_scaled_pressure_decode(msg, &packet);
|
mavlink_msg_scaled_pressure_decode(&msg, &packet);
|
||||||
tracker.tracking_update_pressure(packet);
|
tracker.tracking_update_pressure(packet);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -649,7 +649,7 @@ void GCS_MAVLINK_Tracker::send_global_position_int()
|
||||||
|
|
||||||
|
|
||||||
/* dummy methods to avoid having to link against AP_Camera */
|
/* dummy methods to avoid having to link against AP_Camera */
|
||||||
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
void AP_Camera::control_msg(const mavlink_message_t &) {}
|
||||||
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
||||||
void AP_Camera::control(float, float, float, float, float, float) {}
|
void AP_Camera::control(float, float, float, float, float, float) {}
|
||||||
void AP_Camera::send_feedback(mavlink_channel_t chan) {}
|
void AP_Camera::send_feedback(mavlink_channel_t chan) {}
|
||||||
|
|
|
@ -34,9 +34,9 @@ protected:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
||||||
void mavlink_check_target(const mavlink_message_t &msg);
|
void mavlink_check_target(const mavlink_message_t &msg);
|
||||||
void handleMessage(mavlink_message_t * msg) override;
|
void handleMessage(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 send_global_position_int() override;
|
void send_global_position_int() override;
|
||||||
|
|
Loading…
Reference in New Issue