From ee3ba4809735d7c37843ef7c4871b1f9d237677c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 5 Jun 2015 15:29:00 +0900 Subject: [PATCH] Copter: set Brake speed to 250 --- ArduCopter/config.h | 3 +++ ArduCopter/control_brake.cpp | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 1a0e2c8ac5..526d5b2ed0 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -595,6 +595,9 @@ ////////////////////////////////////////////////////////////////////////////// // Stop mode defaults // +#ifndef BRAKE_MODE_SPEED_Z + # define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode +#endif #ifndef BRAKE_MODE_DECEL_RATE # define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode #endif diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 234d1344e5..ddd3fb29cb 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -18,7 +18,7 @@ bool Copter::brake_init(bool ignore_checks) wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE); // initialize vertical speed and acceleration - pos_control.set_speed_z(0, 0); + pos_control.set_speed_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z); pos_control.set_accel_z(BRAKE_MODE_DECEL_RATE); // initialise altitude target to stopping point