diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index c52e732ea3..ce9278ed85 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -419,7 +419,7 @@ public: AP_Int16 throttle_behavior; AP_Float pilot_takeoff_alt; - AP_Int16 rtl_altitude; + AP_Int32 rtl_altitude; AP_Int16 rtl_speed_cms; AP_Float rtl_cone_slope; #if RANGEFINDER_ENABLED == ENABLED diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 88c1e88ed4..c27c93978b 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -118,7 +118,7 @@ void Copter::esc_calibration_auto() // delay for 5 seconds while outputting pulses uint32_t tstart = millis(); - while (millis() - tstart < 5000) { + while (millis() - tstart < 3000) { SRV_Channels::cork(); motors->set_throttle_passthrough_for_esc_calibration(1.0f); SRV_Channels::push(); diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 13e01790d8..6e9d80e7c8 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -487,7 +487,7 @@ void AP_Camera::uavcan_pic() //altitude_rel = current_loc.alt - ahrs.get_home().alt; } - gcs().send_text(MAV_SEVERITY_INFO, "alt:%f", camera_can_msg.alt); + // gcs().send_text(MAV_SEVERITY_INFO, "alt:%f", camera_can_msg.alt); camera_can_msg.pitch = ahrs.pitch_sensor * 1e-2f; camera_can_msg.roll = ahrs.roll_sensor * 1e-2f; camera_can_msg.yaw = ahrs.yaw_sensor * 1e-2f; diff --git a/modules/mavlink b/modules/mavlink index 0013b46db8..18cab69509 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 0013b46db8cb437b6ad77d736263597d90a2262d +Subproject commit 18cab6950986cd7b9b7a507ec35f3501d4a7e019