Copter: set Brake speed to 250

This commit is contained in:
Randy Mackay 2015-06-05 15:29:00 +09:00
parent 6ea60aa662
commit ee3ba48097
2 changed files with 4 additions and 1 deletions

View File

@ -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

View File

@ -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