mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Changed the prototype of handle_guided_request() to report error
while setting guided points.
This commit is contained in:
parent
6839ee4f37
commit
8fcf5cf0c1
@ -306,7 +306,7 @@ private:
|
||||
// vehicle specific message send function
|
||||
bool try_send_message(enum ap_message id);
|
||||
|
||||
void handle_guided_request(AP_Mission::Mission_Command &cmd);
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd);
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd);
|
||||
|
||||
void handle_log_request_list(mavlink_message_t *msg, DataFlash_Class &dataflash);
|
||||
|
@ -641,10 +641,10 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
|
||||
if (packet.current == 2) {
|
||||
// current = 2 is a flag to tell us this is a "guided mode"
|
||||
// waypoint and not for the mission
|
||||
handle_guided_request(cmd);
|
||||
result = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED
|
||||
: MAV_MISSION_ERROR) ;
|
||||
|
||||
// verify we received the command
|
||||
result = MAV_MISSION_ACCEPTED;
|
||||
goto mission_ack;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user