CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/mode_poshold.cpp
Views: 1798
1
// ArduSub position hold flight mode
2
// GPS required
3
// Jacob Walser August 2016
4
5
#include "Sub.h"
6
7
#if POSHOLD_ENABLED
8
9
// poshold_init - initialise PosHold controller
10
bool ModePoshold::init(bool ignore_checks)
11
{
12
// fail to initialise PosHold mode if no GPS lock
13
if (!sub.position_ok()) {
14
return false;
15
}
16
17
// initialize vertical speeds and acceleration
18
position_control->set_max_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration());
19
position_control->set_correction_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration());
20
position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
21
position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
22
23
// initialise position and desired velocity
24
position_control->init_xy_controller_stopping_point();
25
position_control->init_z_controller();
26
27
// Stop all thrusters
28
attitude_control->set_throttle_out(0.5f ,true, g.throttle_filt);
29
attitude_control->relax_attitude_controllers();
30
position_control->relax_z_controller(0.5f);
31
32
sub.last_pilot_heading = ahrs.yaw_sensor;
33
34
return true;
35
}
36
37
// poshold_run - runs the PosHold controller
38
// should be called at 100hz or more
39
void ModePoshold::run()
40
{
41
uint32_t tnow = AP_HAL::millis();
42
// When unarmed, disable motors and stabilization
43
if (!motors.armed()) {
44
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
45
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
46
attitude_control->set_throttle_out(0.5f ,true, g.throttle_filt);
47
attitude_control->relax_attitude_controllers();
48
position_control->init_xy_controller_stopping_point();
49
position_control->relax_z_controller(0.5f);
50
sub.last_pilot_heading = ahrs.yaw_sensor;
51
return;
52
}
53
54
// set motors to full range
55
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
56
57
///////////////////////
58
// update xy outputs //
59
float pilot_lateral = channel_lateral->norm_input();
60
float pilot_forward = channel_forward->norm_input();
61
62
float lateral_out = 0;
63
float forward_out = 0;
64
65
if (sub.position_ok()) {
66
// Allow pilot to reposition the sub
67
if (fabsf(pilot_lateral) > 0.1 || fabsf(pilot_forward) > 0.1) {
68
position_control->init_xy_controller_stopping_point();
69
}
70
sub.translate_pos_control_rp(lateral_out, forward_out);
71
position_control->update_xy_controller();
72
} else {
73
position_control->init_xy_controller_stopping_point();
74
}
75
motors.set_forward(forward_out + pilot_forward);
76
motors.set_lateral(lateral_out + pilot_lateral);
77
/////////////////////
78
// Update attitude //
79
80
// get pilot's desired yaw rate
81
float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim());
82
float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input);
83
84
// convert pilot input to lean angles
85
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
86
float target_roll, target_pitch;
87
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max);
88
89
// update attitude controller targets
90
if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input
91
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
92
sub.last_pilot_heading = ahrs.yaw_sensor;
93
sub.last_pilot_yaw_input_ms = tnow; // time when pilot last changed heading
94
95
} else { // hold current heading
96
97
// this check is required to prevent bounce back after very fast yaw manoeuvres
98
// the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped
99
if (tnow < sub.last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading
100
target_yaw_rate = 0; // Stop rotation on yaw axis
101
102
// call attitude controller with target yaw rate = 0 to decelerate on yaw axis
103
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
104
sub.last_pilot_heading = ahrs.yaw_sensor; // update heading to hold
105
106
} else { // call attitude controller holding absolute absolute bearing
107
attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, sub.last_pilot_heading, true);
108
}
109
}
110
111
// Update z axis //
112
control_depth();
113
}
114
#endif // POSHOLD_ENABLED
115
116