2017-08-22 08:53:36 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
|
|
|
// start cruise throttle and speed learning
|
|
|
|
void Rover::cruise_learn_start()
|
|
|
|
{
|
2017-08-24 08:32:58 -03:00
|
|
|
// if disarmed or no speed available do nothing
|
|
|
|
float speed;
|
|
|
|
if (!arming.is_armed() || !g2.attitude_control.get_forward_speed(speed)) {
|
2018-12-14 13:54:31 -04:00
|
|
|
cruise_learn.learn_start_ms = 0;
|
2017-08-24 08:32:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning NOT started");
|
2017-08-22 08:53:36 -03:00
|
|
|
return;
|
|
|
|
}
|
2017-08-24 08:32:58 -03:00
|
|
|
// start learning
|
|
|
|
cruise_learn.speed_filt.reset(speed);
|
|
|
|
cruise_learn.throttle_filt.reset(g2.motors.get_throttle());
|
2018-12-14 13:54:31 -04:00
|
|
|
cruise_learn.learn_start_ms = AP_HAL::millis();
|
|
|
|
cruise_learn.log_count = 0;
|
2024-01-10 00:21:43 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2018-12-14 13:54:31 -04:00
|
|
|
log_write_cruise_learn();
|
2024-01-10 00:21:43 -04:00
|
|
|
#endif
|
2017-08-24 08:32:58 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning started");
|
2017-08-22 08:53:36 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// update cruise learning with latest speed and throttle
|
|
|
|
// should be called at 50hz
|
|
|
|
void Rover::cruise_learn_update()
|
|
|
|
{
|
|
|
|
float speed;
|
2018-12-14 13:54:31 -04:00
|
|
|
if (cruise_learn.learn_start_ms > 0 && g2.attitude_control.get_forward_speed(speed)) {
|
2017-08-22 08:53:36 -03:00
|
|
|
// update filters with latest speed and throttle
|
|
|
|
cruise_learn.speed_filt.apply(speed, 0.02f);
|
|
|
|
cruise_learn.throttle_filt.apply(g2.motors.get_throttle(), 0.02f);
|
2018-12-14 13:54:31 -04:00
|
|
|
// 10Hz logging
|
2024-01-10 00:21:43 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2018-12-14 13:54:31 -04:00
|
|
|
if (cruise_learn.log_count % 5 == 0) {
|
|
|
|
log_write_cruise_learn();
|
|
|
|
}
|
|
|
|
cruise_learn.log_count += 1;
|
2024-01-10 00:21:43 -04:00
|
|
|
#endif
|
2018-12-14 13:54:31 -04:00
|
|
|
// check how long it took to learn
|
|
|
|
if (AP_HAL::millis() - cruise_learn.learn_start_ms >= 2000) {
|
|
|
|
cruise_learn_complete();
|
|
|
|
}
|
2017-08-22 08:53:36 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// complete cruise learning and save results
|
|
|
|
void Rover::cruise_learn_complete()
|
|
|
|
{
|
|
|
|
// when switch is moved low, save learned cruise value
|
2018-12-14 13:54:31 -04:00
|
|
|
if (cruise_learn.learn_start_ms > 0) {
|
2017-08-24 08:32:58 -03:00
|
|
|
const float thr = cruise_learn.throttle_filt.get();
|
|
|
|
const float speed = cruise_learn.speed_filt.get();
|
2017-08-22 08:53:36 -03:00
|
|
|
if (thr >= 10.0f && thr <= 100.0f && is_positive(speed)) {
|
|
|
|
g.throttle_cruise.set_and_save(thr);
|
|
|
|
g.speed_cruise.set_and_save(speed);
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learned: Thr:%d Speed:%3.1f", (int)g.throttle_cruise, (double)g.speed_cruise);
|
|
|
|
} else {
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning failed");
|
|
|
|
}
|
2018-12-14 13:54:31 -04:00
|
|
|
cruise_learn.learn_start_ms = 0;
|
2024-01-10 00:21:43 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2018-12-14 13:54:31 -04:00
|
|
|
log_write_cruise_learn();
|
2024-01-10 00:21:43 -04:00
|
|
|
#endif
|
2017-08-22 08:53:36 -03:00
|
|
|
}
|
|
|
|
}
|
2018-12-14 13:54:31 -04:00
|
|
|
|
2024-01-10 00:21:43 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2018-12-14 13:54:31 -04:00
|
|
|
// logging for cruise learn
|
2021-02-01 12:26:24 -04:00
|
|
|
void Rover::log_write_cruise_learn() const
|
2018-12-14 13:54:31 -04:00
|
|
|
{
|
2020-04-22 04:44:40 -03:00
|
|
|
// @LoggerMessage: CRSE
|
|
|
|
// @Description: Cruise Learn messages
|
|
|
|
// @URL: https://ardupilot.org/rover/docs/rover-tuning-throttle-and-speed.html
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: State: True if Cruise Learn has started
|
|
|
|
// @Field: Speed: Determined target Cruise speed in auto missions
|
|
|
|
// @Field: Throttle: Determined base throttle percentage to be used in auto missions
|
|
|
|
|
2021-08-17 06:58:17 -03:00
|
|
|
AP::logger().WriteStreaming("CRSE", "TimeUS,State,Speed,Throttle", "Qbff",
|
2019-05-09 08:14:27 -03:00
|
|
|
AP_HAL::micros64(),
|
|
|
|
cruise_learn.learn_start_ms > 0,
|
|
|
|
cruise_learn.speed_filt.get(),
|
|
|
|
cruise_learn.throttle_filt.get());
|
2018-12-14 13:54:31 -04:00
|
|
|
}
|
2024-01-10 00:21:43 -04:00
|
|
|
#endif
|