diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 3026e280f9..44fd86d0ab 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1337,7 +1337,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAV_CMD_NAV_ROI: case MAV_CMD_DO_SET_ROI: - param1 = tell_command.p1; // MAV_ROI (aka roi mode) is held in wp's parameter but we actually do nothing with it because we only support pointing at a specific location provided by x,y and z parameters + param1 = tell_command.p1; // MAV_ROI (aka roi mode) is held in wp's parameter but we actually do nothing with it because we only support pointing at a specific location provided by x,y and z parameters + x = tell_command.lat/1.0e7f; // local (x), global (latitude) + y = tell_command.lng/1.0e7f; // local (y), global (longitude) + z = tell_command.alt/1.0e2f; // local (z), global/relative (altitude) break; case MAV_CMD_CONDITION_YAW: