Skip to content

Commit

Permalink
Plane: convert to new quicktune approach
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Jul 27, 2024
1 parent 2cc0fb8 commit 933266e
Show file tree
Hide file tree
Showing 6 changed files with 22 additions and 34 deletions.
15 changes: 15 additions & 0 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AC_PRECLAND_ENABLED
SCHED_TASK(precland_update, 400, 50, 160),
#endif
#if AP_QUICKTUNE_ENABLED
SCHED_TASK(update_quicktune, 40, 100, 163),
#endif
};

void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
Expand Down Expand Up @@ -979,4 +982,16 @@ void Plane::precland_update(void)
}
#endif

#if AP_QUICKTUNE_ENABLED
/*
update AP_Quicktune object. We pass the supports_quicktune() method
in so that quicktune can detect if the user changes to a
non-quicktune capable mode while tuning and the gains can be reverted
*/
void Plane::update_quicktune(void)
{
quicktune.update(control_mode->supports_quicktune());
}
#endif

AP_HAL_MAIN_CALLBACKS(&plane);
5 changes: 0 additions & 5 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -424,11 +424,6 @@ void Plane::stabilize()
#endif
} else {
plane.control_mode->run();
#if AP_QUICKTUNE_ENABLED
if (plane.quicktune != nullptr && control_mode->supports_quicktune()) {
plane.quicktune->update();
}
#endif
}

/*
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1000,7 +1000,7 @@ const AP_Param::Info Plane::var_info[] = {
#if AP_QUICKTUNE_ENABLED == ENABLED
// @Group: QUIK_
// @Path: ../libraries/AP_Quicktune/AP_Quicktune.cpp
GOBJECTPTR(quicktune, "QUIK_", AP_Quicktune),
GOBJECT(quicktune, "QUIK_", AP_Quicktune),
#endif

AP_VAREND
Expand Down
6 changes: 5 additions & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -307,7 +307,7 @@ class Plane : public AP_Vehicle {
#endif

#if AP_QUICKTUNE_ENABLED
AP_Quicktune *quicktune;
AP_Quicktune quicktune;
#endif

// This is the state of the flight control system
Expand Down Expand Up @@ -846,6 +846,10 @@ class Plane : public AP_Vehicle {
static const TerrainLookupTable Terrain_lookup[];
#endif

#if AP_QUICKTUNE_ENABLED
void update_quicktune(void);
#endif

// Attitude.cpp
void adjust_nav_pitch_throttle(void);
void update_load_factor(void);
Expand Down
25 changes: 1 addition & 24 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -442,7 +442,7 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch

#if AP_QUICKTUNE_ENABLED
case AUX_FUNC::QUICKTUNE:
do_aux_function_quicktune(ch_flag);
plane.quicktune.update_switch_pos(ch_flag);
break;
#endif

Expand All @@ -452,26 +452,3 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch

return true;
}

#if AP_QUICKTUNE_ENABLED
// called on any Quicktune Aux function change
void RC_Channel_Plane::do_aux_function_quicktune(const AuxSwitchPos ch_flag)
{
if (plane.quicktune == nullptr && !plane.arming.is_armed()) {
//first call, allocate quicktune object
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Quicktune: Initialised.");
plane.quicktune = NEW_NOTHROW AP_Quicktune();
if (plane.quicktune == nullptr) {
// Can't use BoardConfig error as this might happen while flying.
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Quicktune: unable to allocate.");
return;
}
AP_Param::load_object_from_eeprom(plane.quicktune, plane.quicktune->var_info);
} else if (plane.quicktune == nullptr && plane.arming.is_armed()){
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Quicktune: Must be disarmed to initialise.");
}
if (plane.quicktune != nullptr) {
plane.quicktune->update_switch_pos(ch_flag);
}
}
#endif
3 changes: 0 additions & 3 deletions ArduPlane/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@ class RC_Channel_Plane : public RC_Channel
void do_aux_function_soaring_3pos(AuxSwitchPos ch_flag);

void do_aux_function_flare(AuxSwitchPos ch_flag);
#if AP_QUICKTUNE_ENABLED
void do_aux_function_quicktune(const AuxSwitchPos ch_flag);
#endif
};

class RC_Channels_Plane : public RC_Channels
Expand Down

0 comments on commit 933266e

Please sign in to comment.