mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Relay: add rover motor reverse functions
This commit is contained in:
parent
a0eb3396f8
commit
f907694c6e
@ -19,6 +19,11 @@
|
|||||||
#include <AP_Parachute/AP_Parachute.h>
|
#include <AP_Parachute/AP_Parachute.h>
|
||||||
#include <AP_Camera/AP_Camera.h>
|
#include <AP_Camera/AP_Camera.h>
|
||||||
|
|
||||||
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
|
#include <AR_Motors/AP_MotorsUGV.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#define RELAY1_PIN_DEFAULT 13
|
#define RELAY1_PIN_DEFAULT 13
|
||||||
|
|
||||||
@ -146,6 +151,14 @@ void AP_Relay::convert_params()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
|
int8_t rover_relay[] = { -1, -1, -1, -1 };
|
||||||
|
AP_MotorsUGV *motors = AP::motors_ugv();
|
||||||
|
if (motors != nullptr) {
|
||||||
|
motors->get_legacy_relay_index(rover_relay[0], rover_relay[1], rover_relay[2], rover_relay[3]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Find old default param
|
// Find old default param
|
||||||
int8_t default_state = 0; // off was the old behaviour
|
int8_t default_state = 0; // off was the old behaviour
|
||||||
const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state);
|
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()
|
|||||||
|
|
||||||
int8_t pin = 0;
|
int8_t pin = 0;
|
||||||
if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) {
|
if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) {
|
||||||
// Copy old pin parameter
|
// Copy old pin parameter if valid
|
||||||
_params[i].pin.set_and_save(pin);
|
_params[i].pin.set_and_save(pin);
|
||||||
}
|
}
|
||||||
if (_params[i].pin < 0) {
|
|
||||||
// Don't enable if pin is invalid
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
// Valid pin, this is either due to the param conversion or default value
|
|
||||||
|
|
||||||
// Work out what function this relay should be
|
// Work out what function this relay should be
|
||||||
|
AP_Relay_Params::Function new_fun;
|
||||||
if (i == chute_relay) {
|
if (i == chute_relay) {
|
||||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::parachute));
|
new_fun = AP_Relay_Params::Function::parachute;
|
||||||
|
|
||||||
} else if (i == ice_relay) {
|
} else if (i == ice_relay) {
|
||||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::ignition));
|
new_fun = AP_Relay_Params::Function::ignition;
|
||||||
|
|
||||||
} else if (i == cam_relay) {
|
} else if (i == cam_relay) {
|
||||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::camera));
|
new_fun = AP_Relay_Params::Function::camera;
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
|
} else if (i == rover_relay[0]) {
|
||||||
|
new_fun = AP_Relay_Params::Function::brushed_reverse_1;
|
||||||
|
|
||||||
|
} else if (i == rover_relay[1]) {
|
||||||
|
new_fun = AP_Relay_Params::Function::brushed_reverse_2;
|
||||||
|
|
||||||
|
} else if (i == rover_relay[2]) {
|
||||||
|
new_fun = AP_Relay_Params::Function::brushed_reverse_3;
|
||||||
|
|
||||||
|
} else if (i == rover_relay[3]) {
|
||||||
|
new_fun = AP_Relay_Params::Function::brushed_reverse_4;
|
||||||
|
#endif
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
_params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay));
|
if (_params[i].pin < 0) {
|
||||||
|
// Don't enable as numbered relay if pin is invalid
|
||||||
|
// Other functions should be enabled with a invalid pin
|
||||||
|
// This will result in a pre-arm promoting the user to resolve
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
new_fun = AP_Relay_Params::Function::relay;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
_params[i].function.set_and_save(int8_t(new_fun));
|
||||||
|
|
||||||
|
|
||||||
// Set the default state
|
// Set the default state
|
||||||
if (have_default) {
|
if (have_default) {
|
||||||
|
@ -5,7 +5,16 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = {
|
|||||||
// @Param: FUNCTION
|
// @Param: FUNCTION
|
||||||
// @DisplayName: Relay function
|
// @DisplayName: Relay function
|
||||||
// @Description: The function the relay channel is mapped to.
|
// @Description: The function the relay channel is mapped to.
|
||||||
// @Values: 0:None,1:Relay,2:Ignition,3:Parachute,4:Camera
|
// @Values: 0:None
|
||||||
|
// @Values: 1:Relay
|
||||||
|
// @Values{Plane}: 2:Ignition
|
||||||
|
// @Values{Plane, Copter}: 3:Parachute
|
||||||
|
// @Values: 4:Camera
|
||||||
|
// @Values{Rover}: 5:Bushed motor reverse 1 throttle or throttle-left or omni motor 1
|
||||||
|
// @Values{Rover}: 6:Bushed motor reverse 2 throttle-right or omni motor 2
|
||||||
|
// @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3
|
||||||
|
// @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4
|
||||||
|
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
|
@ -24,6 +24,10 @@ public:
|
|||||||
ignition = 2,
|
ignition = 2,
|
||||||
parachute = 3,
|
parachute = 3,
|
||||||
camera = 4,
|
camera = 4,
|
||||||
|
brushed_reverse_1 = 5,
|
||||||
|
brushed_reverse_2 = 6,
|
||||||
|
brushed_reverse_3 = 7,
|
||||||
|
brushed_reverse_4 = 8,
|
||||||
num_functions // must be the last entry
|
num_functions // must be the last entry
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user