Skip to content

Commit

Permalink
GCS_MAVLink: cope with NaNs being passed in when doing conversion to …
Browse files Browse the repository at this point in the history
…command_int
  • Loading branch information
peterbarker committed Oct 5, 2023
1 parent 3b2dec7 commit 77945be
Showing 1 changed file with 18 additions and 7 deletions.
25 changes: 18 additions & 7 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4895,6 +4895,21 @@ bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command)
return false;
}

// returns a value suitable for COMMAND_INT.x or y based on a value
// coming in from COMMAND_LONG.p5 or p6:
static int32_t convert_COMMAND_LONG_loc_param(float param, bool stores_location)
{
if (isnan(param)) {
return 0;
}

if (stores_location) {
return param *1e7;
}

return param;
}

void GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame)
{
out = {};
Expand All @@ -4908,13 +4923,9 @@ void GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long
out.param2 = in.param2;
out.param3 = in.param3;
out.param4 = in.param4;
if (command_long_stores_location((MAV_CMD)in.command)) {
out.x = in.param5 *1e7;
out.y = in.param6 *1e7;
} else {
out.x = in.param5;
out.y = in.param6;
}
const bool stores_location = command_long_stores_location((MAV_CMD)in.command);
out.x = convert_COMMAND_LONG_loc_param(in.param5, stores_location);
out.y = convert_COMMAND_LONG_loc_param(in.param6, stores_location);
out.z = in.param7;
}

Expand Down

0 comments on commit 77945be

Please sign in to comment.