#include "Sub.h"
#define INVALID_TARGET (-1)
#define HAS_VALID_TARGET (rangefinder_target_cm > 0)
ModeSurftrak::ModeSurftrak() :
rangefinder_target_cm(INVALID_TARGET),
pilot_in_control(false),
pilot_control_start_z_cm(0)
{ }
bool ModeSurftrak::init(bool ignore_checks)
{
if (!ModeAlthold::init(ignore_checks)) {
return false;
}
reset();
if (!sub.rangefinder_alt_ok()) {
sub.gcs().send_text(MAV_SEVERITY_INFO, "waiting for a rangefinder reading");
#if AP_RANGEFINDER_ENABLED
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to hold range", sub.g.surftrak_depth * 0.01f);
#endif
}
return true;
}
void ModeSurftrak::run()
{
run_pre();
if (!motors.armed()) {
reset();
} else {
control_range();
}
run_post();
}
bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)
{
bool success = false;
#if AP_RANGEFINDER_ENABLED
if (sub.control_mode != Number::SURFTRAK) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);
} else if (target_cm < sub.rangefinder_state.min*100) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");
} else if (target_cm > sub.rangefinder_state.max*100) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target above maximum, ignored");
} else {
success = true;
}
if (success) {
rangefinder_target_cm = target_cm;
sub.gcs().send_text(MAV_SEVERITY_INFO, "rangefinder target is %.2f meters", rangefinder_target_cm * 0.01f);
auto terrain_offset_cm = sub.inertial_nav.get_position_z_up_cm() - rangefinder_target_cm;
sub.pos_control.init_pos_terrain_U_cm(terrain_offset_cm);
} else {
reset();
}
#endif
return success;
}
void ModeSurftrak::reset()
{
rangefinder_target_cm = INVALID_TARGET;
sub.pos_control.init_pos_terrain_U_cm(0);
}
void ModeSurftrak::control_range() {
float target_climb_rate_cms = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate_cms = constrain_float(target_climb_rate_cms, -sub.get_pilot_speed_dn(), g.pilot_speed_up);
if (fabsf(target_climb_rate_cms) < 0.05f) {
if (pilot_in_control) {
set_rangefinder_target_cm(rangefinder_target_cm + inertial_nav.get_position_z_up_cm() - pilot_control_start_z_cm);
pilot_in_control = false;
}
if (sub.ap.at_surface) {
position_control->set_pos_desired_U_cm(MIN(position_control->get_pos_desired_U_cm(), g.surface_depth - 5.0f));
reset();
} else if (sub.ap.at_bottom) {
position_control->set_pos_desired_U_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_U_cm()));
reset();
} else {
update_surface_offset();
}
} else if (HAS_VALID_TARGET && !pilot_in_control) {
pilot_control_start_z_cm = inertial_nav.get_position_z_up_cm();
pilot_in_control = true;
}
position_control->D_set_pos_target_from_climb_rate_cms(target_climb_rate_cms);
position_control->D_update_controller();
}
void ModeSurftrak::update_surface_offset()
{
#if AP_RANGEFINDER_ENABLED
if (sub.rangefinder_alt_ok()) {
float rangefinder_terrain_offset_cm = sub.rangefinder_state.rangefinder_terrain_offset_cm;
if (!HAS_VALID_TARGET && sub.rangefinder_state.inertial_alt_cm < sub.g.surftrak_depth) {
set_rangefinder_target_cm(sub.rangefinder_state.inertial_alt_cm - rangefinder_terrain_offset_cm);
}
if (HAS_VALID_TARGET) {
float desired_z_cm = rangefinder_terrain_offset_cm + rangefinder_target_cm;
if (desired_z_cm >= sub.g.surftrak_depth) {
rangefinder_terrain_offset_cm += sub.g.surftrak_depth - desired_z_cm;
}
sub.pos_control.set_pos_terrain_target_U_cm(rangefinder_terrain_offset_cm);
}
}
#endif
}