123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346 |
- #include "AP_Tuning.h"
- #include <AP_Logger/AP_Logger.h>
- #include <GCS_MAVLink/GCS.h>
- #include <RC_Channel/RC_Channel.h>
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_Tuning::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO("CHAN", 1, AP_Tuning, channel, 0),
-
-
-
-
-
-
- AP_GROUPINFO("CHAN_MIN", 2, AP_Tuning, channel_min, 1000),
-
-
-
-
-
- AP_GROUPINFO("CHAN_MAX", 3, AP_Tuning, channel_max, 2000),
-
-
-
-
-
- AP_GROUPINFO("SELECTOR", 4, AP_Tuning, selector, 0),
-
-
-
-
-
- AP_GROUPINFO("RANGE", 5, AP_Tuning, range, 2.0f),
-
-
-
-
-
- AP_GROUPINFO("MODE_REVERT", 6, AP_Tuning, mode_revert, 1),
-
-
-
-
-
- AP_GROUPINFO("ERR_THRESH", 7, AP_Tuning, error_threshold, 0.15f),
-
- AP_GROUPEND
- };
- void AP_Tuning::check_selector_switch(void)
- {
- if (selector == 0) {
-
- return;
- }
- if (!rc().has_valid_input()) {
- selector_start_ms = 0;
- return;
- }
- RC_Channel *selchan = rc().channel(selector-1);
- if (selchan == nullptr) {
- return;
- }
- uint16_t selector_in = selchan->get_radio_in();
- if (selector_in >= 1700) {
-
- if (selector_start_ms == 0) {
- selector_start_ms = AP_HAL::millis();
- }
- uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
- if (hold_time > 5000 && changed) {
-
- save_parameters();
- re_center();
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: Saved");
- AP_Notify::events.tune_save = 1;
- changed = false;
- need_revert = 0;
- }
- } else if (selector_in <= 1300) {
-
- if (selector_start_ms != 0) {
- uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
- if (hold_time < 200) {
-
- } else if (hold_time < 2000) {
-
- re_center();
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
- } else if (hold_time < 5000) {
-
- next_parameter();
- }
- selector_start_ms = 0;
- }
- }
- }
- void AP_Tuning::re_center(void)
- {
- AP_Float *f = get_param_pointer(current_parm);
- if (f != nullptr) {
- center_value = f->get();
- }
- mid_point_wait = true;
- }
- void AP_Tuning::check_input(uint8_t flightmode)
- {
- if (channel <= 0 || parmset <= 0) {
-
- return;
- }
-
- if (flightmode != last_flightmode) {
- if (need_revert != 0 && mode_revert != 0) {
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: reverted");
- revert_parameters();
- re_center();
- }
- last_flightmode = flightmode;
- }
-
-
- uint32_t now = AP_HAL::millis();
- uint32_t dt_ms = now - last_check_ms;
- if (dt_ms < 100) {
- return;
- }
- last_check_ms = now;
- if (channel > RC_Channels::get_valid_channel_count()) {
-
- return;
- }
-
- if (range < 1.1f) {
- range.set(1.1f);
- }
- if (current_parm == 0) {
- next_parameter();
- }
-
- if (current_set != parmset) {
- re_center();
- }
- current_set = parmset;
-
- check_selector_switch();
- if (selector_start_ms) {
-
- return;
- }
- if (current_parm == 0) {
- return;
- }
-
- RC_Channel *chan = rc().channel(channel-1);
- if (chan == nullptr) {
- return;
- }
- float chan_value = linear_interpolate(-1, 1, chan->get_radio_in(), channel_min, channel_max);
- if (dt_ms > 500) {
- last_channel_value = chan_value;
- }
-
- check_controller_error();
-
- if (fabsf(chan_value - last_channel_value) < 0.01) {
-
- return;
- }
-
- if (mid_point_wait) {
-
-
- const float dead_zone = 0.02;
- if ((chan_value > dead_zone && last_channel_value > 0) ||
- (chan_value < -dead_zone && last_channel_value < 0)) {
-
- return;
- }
-
- mid_point_wait = false;
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm));
- AP_Notify::events.tune_started = 1;
- }
- last_channel_value = chan_value;
- float new_value;
- if (chan_value > 0) {
- new_value = linear_interpolate(center_value, range*center_value, chan_value, 0, 1);
- } else {
- new_value = linear_interpolate(center_value/range, center_value, chan_value, -1, 0);
- }
- changed = true;
- need_revert |= (1U << current_parm_index);
- set_value(current_parm, new_value);
- Log_Write_Parameter_Tuning(new_value);
- }
- void AP_Tuning::Log_Write_Parameter_Tuning(float value)
- {
- AP::logger().Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff",
- AP_HAL::micros64(),
- parmset,
- current_parm,
- (double)value,
- (double)center_value);
- }
- void AP_Tuning::save_parameters(void)
- {
- uint8_t set = (uint8_t)parmset.get();
- if (set < set_base) {
-
- save_value(set);
- return;
- }
-
- for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
- if (tuning_sets[i].set+set_base == set) {
- for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
- save_value(tuning_sets[i].parms[p]);
- }
- break;
- }
- }
- }
- void AP_Tuning::revert_parameters(void)
- {
- uint8_t set = (uint8_t)parmset.get();
- if (set < set_base) {
-
- reload_value(set);
- return;
- }
- for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
- if (tuning_sets[i].set+set_base == set) {
- for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
- if (p >= 32 || (need_revert & (1U<<p))) {
- reload_value(tuning_sets[i].parms[p]);
- }
- }
- need_revert = 0;
- break;
- }
- }
- }
- void AP_Tuning::next_parameter(void)
- {
- uint8_t set = (uint8_t)parmset.get();
- if (set < set_base) {
-
- current_parm = set;
- re_center();
- return;
- }
- for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
- if (tuning_sets[i].set+set_base == set) {
- if (current_parm == 0) {
- current_parm_index = 0;
- } else {
- current_parm_index = (current_parm_index + 1) % tuning_sets[i].num_parms;
- }
- current_parm = tuning_sets[i].parms[current_parm_index];
- re_center();
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm));
- AP_Notify::events.tune_next = current_parm_index+1;
- break;
- }
- }
- }
- const char *AP_Tuning::get_tuning_name(uint8_t parm)
- {
- for (uint8_t i=0; tuning_names[i].name != nullptr; i++) {
- if (parm == tuning_names[i].parm) {
- return tuning_names[i].name;
- }
- }
- return "UNKNOWN";
- }
- void AP_Tuning::check_controller_error(void)
- {
- float err = controller_error(current_parm);
- if (err > error_threshold) {
- uint32_t now = AP_HAL::millis();
- if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
- AP_Notify::events.tune_error = 1;
- gcs().send_text(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
- last_controller_error_ms = now;
- }
- }
- }
|