Skip to content

Commit

Permalink
Copter: use enum-class and AP_Enum for ThrowType
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tridge committed Dec 8, 2020
1 parent de2802e commit bd0dff1
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -497,7 +497,7 @@ class ParametersG2 {
#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
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1335,9 +1335,9 @@ class ModeThrow : public Mode {
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:
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/mode_throw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit bd0dff1

Please sign in to comment.