mirror of https://github.com/ArduPilot/ardupilot
Copter: use enum-class and AP_Enum for ThrowType
This commit is contained in:
parent
de2802e322
commit
bd0dff1b0e
|
@ -757,7 +757,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @Description: Used by Throw mode. Specifies whether Copter is thrown upward or dropped.
|
||||
// @Values: 0:Upward Throw,1:Drop
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, ModeThrow::ThrowType_Upward),
|
||||
AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, (float)ModeThrow::ThrowType::Upward),
|
||||
#endif
|
||||
|
||||
// @Param: GND_EFFECT_COMP
|
||||
|
|
|
@ -497,7 +497,7 @@ public:
|
|||
#if MODE_THROW_ENABLED == ENABLED
|
||||
// Throw mode parameters
|
||||
AP_Int8 throw_nextmode;
|
||||
AP_Int8 throw_type;
|
||||
AP_Enum<ModeThrow::ThrowType> throw_type;
|
||||
#endif
|
||||
|
||||
// ground effect compensation enable/disable
|
||||
|
|
|
@ -1335,9 +1335,9 @@ public:
|
|||
bool is_autopilot() const override { return false; }
|
||||
|
||||
// Throw types
|
||||
enum ThrowModeType {
|
||||
ThrowType_Upward = 0,
|
||||
ThrowType_Drop = 1
|
||||
enum class ThrowType {
|
||||
Upward = 0,
|
||||
Drop = 1
|
||||
};
|
||||
|
||||
protected:
|
||||
|
|
|
@ -60,7 +60,7 @@ void ModeThrow::run()
|
|||
|
||||
// initialise the demanded height to 3m above the throw height
|
||||
// we want to rapidly clear surrounding obstacles
|
||||
if (g2.throw_type == ThrowType_Drop) {
|
||||
if (g2.throw_type == ThrowType::Drop) {
|
||||
pos_control->set_alt_target(inertial_nav.get_altitude() - 100);
|
||||
} else {
|
||||
pos_control->set_alt_target(inertial_nav.get_altitude() + 300);
|
||||
|
@ -244,7 +244,7 @@ bool ModeThrow::throw_detected()
|
|||
|
||||
// check for upwards or downwards trajectory (airdrop) of 50cm/s
|
||||
bool changing_height;
|
||||
if (g2.throw_type == ThrowType_Drop) {
|
||||
if (g2.throw_type == ThrowType::Drop) {
|
||||
changing_height = inertial_nav.get_velocity().z < -THROW_VERTICAL_SPEED;
|
||||
} else {
|
||||
changing_height = inertial_nav.get_velocity().z > THROW_VERTICAL_SPEED;
|
||||
|
|
Loading…
Reference in New Issue