mirror of https://github.com/ArduPilot/ardupilot
Plane: use _send_buf() functions to reduce stack usage in MAVLink replies
this re-uses the incoming message buffer in constructing the reply
This commit is contained in:
parent
537e78f9fa
commit
7d3523b4a7
|
@ -1367,7 +1367,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_msg_command_ack_send(
|
mavlink_msg_command_ack_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
packet.command,
|
packet.command,
|
||||||
result);
|
result);
|
||||||
|
@ -1488,7 +1489,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
}
|
}
|
||||||
|
|
||||||
float value = vp->cast_to_float(p_type);
|
float value = vp->cast_to_float(p_type);
|
||||||
mavlink_msg_param_value_send(
|
mavlink_msg_param_value_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
param_name,
|
param_name,
|
||||||
value,
|
value,
|
||||||
|
@ -1565,7 +1567,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
set_guided_WP();
|
set_guided_WP();
|
||||||
|
|
||||||
// verify we recevied the command
|
// verify we recevied the command
|
||||||
mavlink_msg_mission_ack_send(
|
mavlink_msg_mission_ack_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
msg->sysid,
|
msg->sysid,
|
||||||
msg->compid,
|
msg->compid,
|
||||||
|
@ -1581,7 +1584,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
next_WP_loc.alt = cmd.content.location.alt;
|
next_WP_loc.alt = cmd.content.location.alt;
|
||||||
|
|
||||||
// verify we recevied the command
|
// verify we recevied the command
|
||||||
mavlink_msg_mission_ack_send(
|
mavlink_msg_mission_ack_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
msg->sysid,
|
msg->sysid,
|
||||||
msg->compid,
|
msg->compid,
|
||||||
|
@ -1627,7 +1631,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
waypoint_request_i++;
|
waypoint_request_i++;
|
||||||
|
|
||||||
if (waypoint_request_i >= waypoint_request_last) {
|
if (waypoint_request_i >= waypoint_request_last) {
|
||||||
mavlink_msg_mission_ack_send(
|
mavlink_msg_mission_ack_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
msg->sysid,
|
msg->sysid,
|
||||||
msg->compid,
|
msg->compid,
|
||||||
|
@ -1651,7 +1656,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
|
|
||||||
mission_failed:
|
mission_failed:
|
||||||
// we are rejecting the mission/waypoint
|
// we are rejecting the mission/waypoint
|
||||||
mavlink_msg_mission_ack_send(
|
mavlink_msg_mission_ack_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
msg->sysid,
|
msg->sysid,
|
||||||
msg->compid,
|
msg->compid,
|
||||||
|
@ -1689,8 +1695,8 @@ mission_failed:
|
||||||
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
|
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
|
||||||
} else {
|
} else {
|
||||||
Vector2l point = get_fence_point_with_index(packet.idx);
|
Vector2l point = get_fence_point_with_index(packet.idx);
|
||||||
mavlink_msg_fence_point_send(chan, msg->sysid, msg->compid, packet.idx, g.fence_total,
|
mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, g.fence_total,
|
||||||
point.x*1.0e-7, point.y*1.0e-7);
|
point.x*1.0e-7, point.y*1.0e-7);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -1741,10 +1747,11 @@ mission_failed:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_msg_rally_point_send(chan, msg->sysid, msg->compid, packet.idx,
|
mavlink_msg_rally_point_send_buf(msg,
|
||||||
g.rally_total, rally_point.lat, rally_point.lng,
|
chan, msg->sysid, msg->compid, packet.idx,
|
||||||
rally_point.alt, rally_point.break_alt, rally_point.land_dir,
|
g.rally_total, rally_point.lat, rally_point.lng,
|
||||||
rally_point.flags);
|
rally_point.alt, rally_point.break_alt, rally_point.land_dir,
|
||||||
|
rally_point.flags);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1804,7 +1811,8 @@ mission_failed:
|
||||||
// we send the value we actually set, which could be
|
// we send the value we actually set, which could be
|
||||||
// different from the value sent, in case someone sent
|
// different from the value sent, in case someone sent
|
||||||
// a fractional value to an integer type
|
// a fractional value to an integer type
|
||||||
mavlink_msg_param_value_send(
|
mavlink_msg_param_value_send_buf(
|
||||||
|
msg,
|
||||||
chan,
|
chan,
|
||||||
key,
|
key,
|
||||||
vp->cast_to_float(var_type),
|
vp->cast_to_float(var_type),
|
||||||
|
|
Loading…
Reference in New Issue