Copter: add throw mode defines for required speed

No functional change
This commit is contained in:
Randy Mackay 2016-08-02 14:30:32 +09:00
parent 25940c8e0f
commit 8e58ea9277
2 changed files with 15 additions and 5 deletions

View File

@ -599,6 +599,16 @@
# define AUTO_DISARMING_DELAY 10
#endif
//////////////////////////////////////////////////////////////////////////////
// Throw mode configuration
//
#ifndef THROW_HIGH_SPEED
# define THROW_HIGH_SPEED 500.0f // vehicle much reach this total 3D speed in cm/s (or be free falling)
#endif
#ifndef THROW_VERTICAL_SPEED
# define THROW_VERTICAL_SPEED 50.0f // motors start when vehicle reaches this total 3D speed in cm/s
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//

View File

@ -201,15 +201,15 @@ bool Copter::throw_detected()
return false;
}
// Check for high speed (note get_inertial_nav methods use a cm length scale)
bool high_speed = inertial_nav.get_velocity().length() > 500.0f;
// Check for high speed (>500 cm/s)
bool high_speed = inertial_nav.get_velocity().length() > THROW_HIGH_SPEED;
// check for upwards or downwards trajectory (airdrop)
// check for upwards or downwards trajectory (airdrop) of 50cm/s
bool changing_height;
if (g2.throw_type == ThrowType_Drop) {
changing_height = inertial_nav.get_velocity().z < -50.0f;
changing_height = inertial_nav.get_velocity().z < -THROW_VERTICAL_SPEED;
} else {
changing_height = inertial_nav.get_velocity().z > 50.0f;
changing_height = inertial_nav.get_velocity().z > THROW_VERTICAL_SPEED;
}
// Check the vertical acceleraton is greater than 0.25g