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/motors.cpp
Views: 1798
1
#include "Sub.h"
2
3
// enable_motor_output() - enable and output lowest possible value to motors
4
void Sub::enable_motor_output()
5
{
6
motors.output_min();
7
}
8
9
// motors_output - send output to motors library which will adjust and send to ESCs and servos
10
void Sub::motors_output()
11
{
12
// Motor detection mode controls the thrusters directly
13
if (control_mode == Mode::Number::MOTOR_DETECT){
14
return;
15
}
16
// check if we are performing the motor test
17
if (ap.motor_test) {
18
verify_motor_test();
19
} else {
20
motors.set_interlock(true);
21
auto &srv = AP::srv();
22
srv.cork();
23
SRV_Channels::calc_pwm();
24
SRV_Channels::output_ch_all();
25
motors.output();
26
srv.push();
27
}
28
}
29
30
// Initialize new style motor test
31
// Perform checks to see if it is ok to begin the motor test
32
// Returns true if motor test has begun
33
bool Sub::init_motor_test()
34
{
35
uint32_t tnow = AP_HAL::millis();
36
37
// Ten second cooldown period required with no do_set_motor requests required
38
// after failure.
39
if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {
40
gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cooldown required after motor test");
41
return false;
42
}
43
44
// check if safety switch has been pushed
45
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
46
gcs().send_text(MAV_SEVERITY_CRITICAL,"Disarm hardware safety switch before testing motors.");
47
return false;
48
}
49
50
// Make sure we are on the ground
51
if (!motors.armed()) {
52
gcs().send_text(MAV_SEVERITY_WARNING, "Arm motors before testing motors.");
53
return false;
54
}
55
56
enable_motor_output(); // set all motor outputs to zero
57
ap.motor_test = true;
58
59
return true;
60
}
61
62
// Verify new style motor test
63
// The motor test will fail if the interval between received
64
// MAV_CMD_DO_SET_MOTOR requests exceeds a timeout period
65
// Returns true if it is ok to proceed with new style motor test
66
bool Sub::verify_motor_test()
67
{
68
bool pass = true;
69
70
// Require at least 2 Hz incoming do_set_motor requests
71
if (AP_HAL::millis() > last_do_motor_test_ms + 500) {
72
gcs().send_text(MAV_SEVERITY_INFO, "Motor test timed out!");
73
pass = false;
74
}
75
76
if (!pass) {
77
ap.motor_test = false;
78
AP::arming().disarm(AP_Arming::Method::MOTORTEST);
79
last_do_motor_test_fail_ms = AP_HAL::millis();
80
return false;
81
}
82
83
return true;
84
}
85
86
bool Sub::handle_do_motor_test(mavlink_command_int_t command) {
87
last_do_motor_test_ms = AP_HAL::millis();
88
89
// If we are not already testing motors, initialize test
90
static uint32_t tLastInitializationFailed = 0;
91
if(!ap.motor_test) {
92
// Do not allow initializations attempt under 2 seconds
93
// If one fails, we need to give the user time to fix the issue
94
// instead of spamming error messages
95
if (AP_HAL::millis() > (tLastInitializationFailed + 2000)) {
96
if (!init_motor_test()) {
97
gcs().send_text(MAV_SEVERITY_WARNING, "motor test initialization failed!");
98
tLastInitializationFailed = AP_HAL::millis();
99
return false; // init fail
100
}
101
} else {
102
return false;
103
}
104
}
105
106
float motor_number = command.param1;
107
float throttle_type = command.param2;
108
float throttle = command.param3;
109
// float timeout_s = command.param4; // not used
110
// float motor_count = command.param5; // not used
111
const uint32_t test_type = command.y;
112
113
if (test_type != MOTOR_TEST_ORDER_BOARD) {
114
gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type);
115
return false; // test type not supported here
116
}
117
118
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PILOT)) {
119
gcs().send_text(MAV_SEVERITY_WARNING, "bad throttle type %0.2f", (double)throttle_type);
120
121
return false; // throttle type not supported here
122
}
123
124
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PWM)) {
125
return motors.output_test_num(motor_number, throttle); // true if motor output is set
126
}
127
128
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {
129
throttle = constrain_float(throttle, 0.0f, 100.0f);
130
throttle = channel_throttle->get_radio_min() + throttle * 0.01f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
131
return motors.output_test_num(motor_number, throttle); // true if motor output is set
132
}
133
134
return false;
135
}
136
137
138
// translate wpnav roll/pitch outputs to lateral/forward
139
void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
140
{
141
// get roll and pitch targets in centidegrees
142
int32_t lateral = wp_nav.get_roll();
143
int32_t forward = -wp_nav.get_pitch(); // output is reversed
144
145
// constrain target forward/lateral values
146
// The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values
147
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
148
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
149
150
// Normalize
151
lateral_out = (float)lateral/(float)aparm.angle_max;
152
forward_out = (float)forward/(float)aparm.angle_max;
153
}
154
155
// translate wpnav roll/pitch outputs to lateral/forward
156
void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)
157
{
158
// get roll and pitch targets in centidegrees
159
int32_t lateral = circle_nav.get_roll();
160
int32_t forward = -circle_nav.get_pitch(); // output is reversed
161
162
// constrain target forward/lateral values
163
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
164
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
165
166
// Normalize
167
lateral_out = (float)lateral/(float)aparm.angle_max;
168
forward_out = (float)forward/(float)aparm.angle_max;
169
}
170
171
// translate pos_control roll/pitch outputs to lateral/forward
172
void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)
173
{
174
// get roll and pitch targets in centidegrees
175
int32_t lateral = pos_control.get_roll_cd();
176
int32_t forward = -pos_control.get_pitch_cd(); // output is reversed
177
178
// constrain target forward/lateral values
179
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
180
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
181
182
// Normalize
183
lateral_out = (float)lateral/(float)aparm.angle_max;
184
forward_out = (float)forward/(float)aparm.angle_max;
185
}
186
187