mirror of https://github.com/ArduPilot/ardupilot
APM: removed unnecessary waypoint_sending flag
This commit is contained in:
parent
0a1f428669
commit
26e526c3ab
|
@ -180,7 +180,6 @@ private:
|
|||
uint16_t waypoint_request_last; // last request index
|
||||
uint16_t waypoint_dest_sysid; // where to send requests
|
||||
uint16_t waypoint_dest_compid; // "
|
||||
bool waypoint_sending; // currently in send process
|
||||
bool waypoint_receiving; // currently receiving
|
||||
uint16_t waypoint_count;
|
||||
uint32_t waypoint_timelast_send; // milliseconds
|
||||
|
|
|
@ -787,7 +787,7 @@ GCS_MAVLINK::update(void)
|
|||
// Update packet drops counter
|
||||
packet_drops += status.packet_rx_drop_count;
|
||||
|
||||
if (!waypoint_receiving && !waypoint_sending) {
|
||||
if (!waypoint_receiving) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -800,11 +800,6 @@ GCS_MAVLINK::update(void)
|
|||
send_message(MSG_NEXT_WAYPOINT);
|
||||
}
|
||||
|
||||
// stop waypoint sending if timeout
|
||||
if (waypoint_sending && (millis() - waypoint_timelast_send) > waypoint_send_timeout) {
|
||||
waypoint_sending = false;
|
||||
}
|
||||
|
||||
// stop waypoint receiving if timeout
|
||||
if (waypoint_receiving && (millis() - waypoint_timelast_receive) > waypoint_receive_timeout) {
|
||||
waypoint_receiving = false;
|
||||
|
@ -819,8 +814,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
|
|||
|
||||
// send at a much lower rate while handling waypoints and
|
||||
// parameter sends
|
||||
if (waypoint_receiving || waypoint_sending ||
|
||||
_queued_parameter != NULL) {
|
||||
if (waypoint_receiving || _queued_parameter != NULL) {
|
||||
rate *= 0.25;
|
||||
}
|
||||
|
||||
|
@ -1158,7 +1152,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
g.command_total + 1); // + home
|
||||
|
||||
waypoint_timelast_send = millis();
|
||||
waypoint_sending = true;
|
||||
waypoint_receiving = false;
|
||||
waypoint_dest_sysid = msg->sysid;
|
||||
waypoint_dest_compid = msg->compid;
|
||||
|
@ -1169,10 +1162,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
// XXX read a WP from EEPROM and send it to the GCS
|
||||
case MAVLINK_MSG_ID_MISSION_REQUEST:
|
||||
{
|
||||
// Check if sending waypiont
|
||||
//if (!waypoint_sending) break;
|
||||
// 5/10/11 - We are trying out relaxing the requirement that we be in waypoint sending mode to respond to a waypoint request. DEW
|
||||
|
||||
// decode
|
||||
mavlink_mission_request_t packet;
|
||||
mavlink_msg_mission_request_decode(msg, &packet);
|
||||
|
@ -1277,9 +1266,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
mavlink_mission_ack_t packet;
|
||||
mavlink_msg_mission_ack_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
|
||||
|
||||
// turn off waypoint send
|
||||
waypoint_sending = false;
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1380,7 +1366,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
waypoint_timelast_receive = millis();
|
||||
waypoint_timelast_request = 0;
|
||||
waypoint_receiving = true;
|
||||
waypoint_sending = false;
|
||||
waypoint_request_i = 0;
|
||||
waypoint_request_last= g.command_total;
|
||||
break;
|
||||
|
@ -1404,7 +1389,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
waypoint_timelast_receive = millis();
|
||||
waypoint_timelast_request = 0;
|
||||
waypoint_receiving = true;
|
||||
waypoint_sending = false;
|
||||
waypoint_request_i = packet.start_index;
|
||||
waypoint_request_last= packet.end_index;
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue