AP_Mission: better mission errors

This commit is contained in:
DonLakeFlyer 2015-12-21 16:02:23 +11:00 committed by Andrew Tridgell
parent ac08eece84
commit 7cd3d8bfdc
2 changed files with 13 additions and 10 deletions

View File

@ -471,8 +471,8 @@ void AP_Mission::write_home_to_storage()
} }
// mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom // mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
// return true on success, false on failure // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd) MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd)
{ {
bool copy_location = false; bool copy_location = false;
bool copy_alt = false; bool copy_alt = false;
@ -711,7 +711,7 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
default: default:
// unrecognised command // unrecognised command
return false; return MAV_MISSION_UNSUPPORTED;
} }
// copy location from mavlink to command // copy location from mavlink to command
@ -719,12 +719,15 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
// sanity check location // sanity check location
if (copy_location) { if (copy_location) {
if (fabsf(packet.x) > 90.0f || fabsf(packet.y) > 180.0f) { if (fabsf(packet.x) > 90.0f) {
return false; return MAV_MISSION_INVALID_PARAM5_X;
}
if (fabsf(packet.y) > 180.0f) {
return MAV_MISSION_INVALID_PARAM6_Y;
} }
} }
if (fabsf(packet.z) >= LOCATION_ALT_MAX_M) { if (fabsf(packet.z) >= LOCATION_ALT_MAX_M) {
return false; return MAV_MISSION_INVALID_PARAM7;
} }
switch (packet.frame) { switch (packet.frame) {
@ -788,12 +791,12 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
#endif #endif
default: default:
return false; return MAV_MISSION_UNSUPPORTED_FRAME;
} }
} }
// if we got this far then it must have been succesful // if we got this far then it must have been succesful
return true; return MAV_MISSION_ACCEPTED;
} }
// mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS

View File

@ -365,8 +365,8 @@ public:
void write_home_to_storage(); void write_home_to_storage();
// mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom // mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
// return true on success, false on failure // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
static bool mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd); static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd);
// mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
// return true on success, false on failure // return true on success, false on failure