ardupilot/ArduSub/mode_surface.cpp

64 lines
2.2 KiB
C++
Raw Normal View History

2016-08-25 00:08:30 -03:00
#include "Sub.h"
2023-04-03 09:11:21 -03:00
bool ModeSurface::init(bool ignore_checks)
2016-08-25 00:08:30 -03:00
{
2023-04-03 09:11:21 -03:00
if(!sub.control_check_barometer()) {
return false;
}
2016-08-25 00:08:30 -03:00
2021-04-27 03:50:06 -03:00
// initialize vertical speeds and acceleration
2023-04-03 09:11:21 -03:00
position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
2016-08-25 00:08:30 -03:00
// initialise position and desired velocity
2023-04-03 09:11:21 -03:00
position_control->init_z_controller();
2016-08-25 00:08:30 -03:00
return true;
}
2023-04-03 09:11:21 -03:00
void ModeSurface::run()
2016-08-25 00:08:30 -03:00
{
float target_roll, target_pitch;
// if not armed set throttle to zero and exit immediately
if (!motors.armed()) {
motors.output_min();
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
2023-04-03 09:11:21 -03:00
attitude_control->set_throttle_out(0,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->init_z_controller();
2016-08-25 00:08:30 -03:00
return;
}
// Already at surface, hold depth at surface
2023-04-03 09:11:21 -03:00
if (sub.ap.at_surface) {
set_mode(Mode::Number::ALT_HOLD, ModeReason::SURFACE_COMPLETE);
}
2016-08-25 00:08:30 -03:00
// convert pilot input to lean angles
2023-04-03 09:11:21 -03:00
// To-Do: convert sub.get_pilot_desired_lean_angles to return angles as floats
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);
2016-08-25 00:08:30 -03:00
// get pilot's desired yaw rate
2023-04-03 09:11:21 -03:00
float target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
2016-08-25 00:08:30 -03:00
// call attitude controller
2023-04-03 09:11:21 -03:00
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
2016-08-25 00:08:30 -03:00
// set target climb rate
2023-04-03 09:11:21 -03:00
float cmb_rate = constrain_float(fabsf(sub.wp_nav.get_default_speed_up()), 1, position_control->get_max_speed_up_cms());
2016-08-25 00:08:30 -03:00
// record desired climb rate for logging
2023-04-03 09:11:21 -03:00
sub.desired_climb_rate = cmb_rate;
2016-08-25 00:08:30 -03:00
// update altitude target and call position controller
2023-04-03 09:11:21 -03:00
position_control->set_pos_target_z_from_climb_rate_cm(cmb_rate);
position_control->update_z_controller();
2016-08-25 00:08:30 -03:00
// pilot has control for repositioning
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
2016-08-25 00:08:30 -03:00
}