Skip to content

Commit 4f930ea

Browse files
committed
AP_Relay: add rover motor reverse functions
1 parent 3e25b55 commit 4f930ea

File tree

3 files changed

+55
-11
lines changed

3 files changed

+55
-11
lines changed

libraries/AP_Relay/AP_Relay.cpp

Lines changed: 41 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,11 @@
1919
#include <AP_Parachute/AP_Parachute.h>
2020
#include <AP_Camera/AP_Camera.h>
2121

22+
#include <AP_Vehicle/AP_Vehicle_Type.h>
23+
#if APM_BUILD_TYPE(APM_BUILD_Rover)
24+
#include <AR_Motors/AP_MotorsUGV.h>
25+
#endif
26+
2227
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2328
#define RELAY1_PIN_DEFAULT 13
2429

@@ -146,6 +151,14 @@ void AP_Relay::convert_params()
146151
}
147152
#endif
148153

154+
#if APM_BUILD_TYPE(APM_BUILD_Rover)
155+
int8_t rover_relay[] = { -1, -1, -1, -1 };
156+
AP_MotorsUGV *motors = AP::motors_ugv();
157+
if (motors != nullptr) {
158+
motors->get_legacy_relay_index(rover_relay[0], rover_relay[1], rover_relay[2], rover_relay[3]);
159+
}
160+
#endif
161+
149162
// Find old default param
150163
int8_t default_state = 0; // off was the old behaviour
151164
const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state);
@@ -165,29 +178,47 @@ void AP_Relay::convert_params()
165178

166179
int8_t pin = 0;
167180
if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) {
168-
// Copy old pin parameter
181+
// Copy old pin parameter if valid
169182
_params[i].pin.set_and_save(pin);
170183
}
171-
if (_params[i].pin < 0) {
172-
// Don't enable if pin is invalid
173-
continue;
174-
}
175-
// Valid pin, this is either due to the param conversion or default value
176184

177185
// Work out what function this relay should be
186+
AP_Relay_Params::Function new_fun;
178187
if (i == chute_relay) {
179-
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::parachute));
188+
new_fun = AP_Relay_Params::Function::parachute;
180189

181190
} else if (i == ice_relay) {
182-
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::ignition));
191+
new_fun = AP_Relay_Params::Function::ignition;
183192

184193
} else if (i == cam_relay) {
185-
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::camera));
194+
new_fun = AP_Relay_Params::Function::camera;
195+
196+
#if APM_BUILD_TYPE(APM_BUILD_Rover)
197+
} else if (i == rover_relay[0]) {
198+
new_fun = AP_Relay_Params::Function::brushed_reverse_1;
199+
200+
} else if (i == rover_relay[1]) {
201+
new_fun = AP_Relay_Params::Function::brushed_reverse_2;
202+
203+
} else if (i == rover_relay[2]) {
204+
new_fun = AP_Relay_Params::Function::brushed_reverse_3;
205+
206+
} else if (i == rover_relay[3]) {
207+
new_fun = AP_Relay_Params::Function::brushed_reverse_4;
208+
#endif
186209

187210
} else {
188-
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay));
211+
if (_params[i].pin < 0) {
212+
// Don't enable as numbered relay if pin is invalid
213+
// Other functions should be enabled with a invalid pin
214+
// This will result in a pre-arm promoting the user to resolve
215+
continue;
216+
}
217+
new_fun = AP_Relay_Params::Function::relay;
189218

190219
}
220+
_params[i].function.set_and_save(int8_t(new_fun));
221+
191222

192223
// Set the default state
193224
if (have_default) {

libraries/AP_Relay/AP_Relay_Params.cpp

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,16 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
55
// @Param: FUNCTION
66
// @DisplayName: Relay function
77
// @Description: The function the relay channel is mapped to.
8-
// @Values: 0:None,1:Relay,2:Ignition,3:Parachute,4:Camera
8+
// @Values: 0:None
9+
// @Values: 1:Relay
10+
// @Values{Plane}: 2:Ignition
11+
// @Values{Plane, Copter}: 3:Parachute
12+
// @Values: 4:Camera
13+
// @Values{Rover}: 5:Bushed motor reverse 1 throttle or throttle-left or omni motor 1
14+
// @Values{Rover}: 6:Bushed motor reverse 2 throttle-right or omni motor 2
15+
// @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3
16+
// @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4
17+
918
// @User: Standard
1019
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
1120

libraries/AP_Relay/AP_Relay_Params.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,10 @@ class AP_Relay_Params {
2424
ignition = 2,
2525
parachute = 3,
2626
camera = 4,
27+
brushed_reverse_1 = 5,
28+
brushed_reverse_2 = 6,
29+
brushed_reverse_3 = 7,
30+
brushed_reverse_4 = 8,
2731
num_functions // must be the last entry
2832
};
2933

0 commit comments

Comments
 (0)