Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Relay: Refactor to support RELAYx_FUNCTION #25108

Merged
merged 16 commits into from
Dec 18, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,9 +451,9 @@ const AP_Param::Info Copter::var_info[] = {
#endif

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

#if PARACHUTE == ENABLED
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -757,9 +757,9 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(arming, "ARMING_", AP_Arming_Plane),

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

#if PARACHUTE == ENABLED
Expand Down
4 changes: 2 additions & 2 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -476,9 +476,9 @@ const AP_Param::Info Sub::var_info[] = {
#endif

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

// @Group: COMPASS_
Expand Down
4 changes: 2 additions & 2 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,9 +223,9 @@ const AP_Param::Info Rover::var_info[] = {
GOBJECT(barometer, "BARO", AP_Baro),

#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Group: RELAY
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
GOBJECT(relay, "RELAY", AP_Relay),
#endif

// @Group: RCMAP_
Expand Down
7 changes: 5 additions & 2 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1124,9 +1124,12 @@ def TestFlaps(self):

def TestRCRelay(self):
'''Test Relay RC Channel Option'''
self.set_parameter("RC12_OPTION", 28) # Relay On/Off
self.set_parameters({
"RELAY1_FUNCTION": 1, # Enable relay as a standard relay pin
"RC12_OPTION": 28 # Relay On/Off
})
self.set_rc(12, 1000)
self.reboot_sitl() # needed for RC12_OPTION to take effect
self.reboot_sitl() # needed for RC12_OPTION and RELAY1_FUNCTION to take effect

off = self.get_parameter("SIM_PIN_MASK")
if off:
Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/default_params/rover.parm
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ RC1_MAX 2000
RC1_MIN 1000
RC3_MAX 2000
RC3_MIN 1000
RELAY_PIN 1
RELAY_PIN2 2
RELAY1_PIN 1
RELAY2_PIN 2
SERVO1_MIN 1000
SERVO1_MAX 2000
SERVO3_MAX 2000
Expand Down
5 changes: 1 addition & 4 deletions Tools/autotest/default_params/vee-gull 005.param
Original file line number Diff line number Diff line change
Expand Up @@ -456,10 +456,7 @@ RCMAP_ROLL,1
RCMAP_THROTTLE,3
RCMAP_YAW,4
RELAY_DEFAULT,0
RELAY_PIN,13
RELAY_PIN2,-1
RELAY_PIN3,-1
RELAY_PIN4,-1
RELAY1_PIN,13
RLL_RATE_D,0.000000
RLL_RATE_FF,0.255000
RLL_RATE_I,0.050000
Expand Down
20 changes: 17 additions & 3 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -568,6 +568,13 @@ def ServoRelayEvents(self):
'''Test ServoRelayEvents'''
for method in self.run_cmd, self.run_cmd_int:
self.context_push()

self.set_parameters({
"RELAY1_FUNCTION": 1, # Enable relay 1 as a standard relay pin
"RELAY2_FUNCTION": 1, # Enable relay 2 as a standard relay pin
})
self.reboot_sitl() # Needed for relay functions to take effect

method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
off = self.get_parameter("SIM_PIN_MASK")
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
Expand Down Expand Up @@ -602,8 +609,14 @@ def ServoRelayEvents(self):
"on": 0,
})

# add another servo:
self.set_parameter("RELAY_PIN6", 14)
# add another relay and ensure that it changes the "present field"
self.set_parameters({
"RELAY6_FUNCTION": 1, # Enable relay 6 as a standard relay pin
"RELAY6_PIN": 14, # Set pin number
})
self.reboot_sitl() # Needed for relay function to take effect
self.set_message_rate_hz("RELAY_STATUS", 10) # Need to re-request the message since reboot

self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 0,
Expand Down Expand Up @@ -5352,7 +5365,8 @@ def test_scripting_auxfunc(self):
self.context_collect("STATUSTEXT")
self.set_parameters({
"SCR_ENABLE": 1,
"RELAY_PIN": 1,
"RELAY1_FUNCTION": 1,
"RELAY1_PIN": 1
})
self.install_example_script_context("RCIN_test.lua")
self.reboot_sitl()
Expand Down
20 changes: 20 additions & 0 deletions libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -771,6 +771,26 @@ void AP_Camera::convert_params()
}
}

#if AP_RELAY_ENABLED
// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions
bool AP_Camera::get_legacy_relay_index(int8_t &index) const
{
// PARAMETER_CONVERSION - Added: Dec-2023

// Note that this assumes that the camera param conversion has already been done
// Copter, Plane, Sub and Rover all have both relay and camera and all init relay first
// This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.4
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
if ((CameraType)_params[i].type.get() == CameraType::RELAY) {
// Camera was hard coded to relay 0
index = 0;
return true;
}
}
return false;
}
#endif

// singleton instance
AP_Camera *AP_Camera::_singleton;

Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,9 @@ class AP_Camera {
bool get_state(uint8_t instance, camera_state_t& cam_state);
#endif

// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions
bool get_legacy_relay_index(int8_t &index) const;

// allow threads to lock against AHRS update
HAL_Semaphore &get_semaphore() { return _rsem; }

Expand Down
12 changes: 2 additions & 10 deletions libraries/AP_Camera/AP_Camera_Relay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,7 @@ void AP_Camera_Relay::update()
if (ap_relay == nullptr) {
return;
}
if (_params.relay_on) {
ap_relay->off(0);
} else {
ap_relay->on(0);
}
ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, !_params.relay_on);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This pattern precludes us having two relay cameras, it seems. You might be in the second camera backend here.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Your right, but this is the current behavior. We certainly could add a second camera relay function in the future.

}

// call parent update
Expand All @@ -39,11 +35,7 @@ bool AP_Camera_Relay::trigger_pic()
return false;
}

if (_params.relay_on) {
ap_relay->on(0);
} else {
ap_relay->off(0);
}
ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, _params.relay_on);

// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)
trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
Expand Down
34 changes: 20 additions & 14 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,14 +165,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0),
#endif

#if AP_RELAY_ENABLED
// @Param: IGNITION_RLY
// @DisplayName: Ignition relay channel
// @Description: This is a a relay channel to use for ignition control
// @User: Standard
// @Values: 0:None,1:Relay1,2:Relay2,3:Relay3,4:Relay4,5:Relay5,6:Relay6
AP_GROUPINFO("IGNITION_RLY", 18, AP_ICEngine, ignition_relay, 0),
#endif
// 18 was IGNITION_RLY


AP_GROUPEND
};
Expand Down Expand Up @@ -608,15 +602,14 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle)
void AP_ICEngine::set_ignition(bool on)
{
SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, on? pwm_ignition_on : pwm_ignition_off);

#if AP_RELAY_ENABLED
// optionally use a relay as well
if (ignition_relay > 0) {
auto *relay = AP::relay();
if (relay != nullptr) {
relay->set(ignition_relay-1, on);
}
AP_Relay *relay = AP::relay();
if (relay != nullptr) {
relay->set(AP_Relay_Params::FUNCTION::IGNITION, on);
}
#endif // AP_RELAY_ENABLED

}

/*
Expand All @@ -638,6 +631,19 @@ bool AP_ICEngine::allow_throttle_while_disarmed() const
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;
}

#if AP_RELAY_ENABLED
bool AP_ICEngine::get_legacy_ignition_relay_index(int8_t &num)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There is a case that we could just skip the param conversion here, the relay index param has only been in master for a few weeks.

{
// PARAMETER_CONVERSION - Added: Dec-2023
if (!enable || !AP_Param::get_param_by_index(this, 18, AP_PARAM_INT8, &num)) {
return false;
}
// convert to zero indexed
num -= 1;
return true;
}
#endif

// singleton instance. Should only ever be set in the constructor.
AP_ICEngine *AP_ICEngine::_singleton;
namespace AP {
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,11 @@ class AP_ICEngine {
// do we have throttle while disarmed enabled?
bool allow_throttle_while_disarmed(void) const;

#if AP_RELAY_ENABLED
// Needed for param conversion from relay numbers to functions
bool get_legacy_ignition_relay_index(int8_t &num);
#endif

static AP_ICEngine *get_singleton() { return _singleton; }

private:
Expand Down Expand Up @@ -136,11 +141,6 @@ class AP_ICEngine {
AP_Float idle_slew;
#endif

#if AP_RELAY_ENABLED
// relay number for ignition
AP_Int8 ignition_relay;
#endif

// height when we enter ICE_START_HEIGHT_DELAY
float initial_height;

Expand Down
1 change: 0 additions & 1 deletion libraries/AP_LandingGear/AP_LandingGear.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

#if AP_LANDINGGEAR_ENABLED

#include <AP_Relay/AP_Relay.h>
#include <AP_Math/AP_Math.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_HAL/AP_HAL.h>
Expand Down
21 changes: 17 additions & 4 deletions libraries/AP_Parachute/AP_Parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ void AP_Parachute::update()
// set relay
AP_Relay*_relay = AP::relay();
if (_relay != nullptr) {
_relay->on(_release_type);
_relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, true);
}
#endif
}
Expand All @@ -159,7 +159,7 @@ void AP_Parachute::update()
// set relay back to zero volts
AP_Relay*_relay = AP::relay();
if (_relay != nullptr) {
_relay->off(_release_type);
_relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, false);
}
#endif
}
Expand Down Expand Up @@ -218,8 +218,8 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
} else {
#if AP_RELAY_ENABLED
AP_Relay*_relay = AP::relay();
if (_relay == nullptr || !_relay->enabled(_release_type)) {
hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", int(_release_type));
if (_relay == nullptr || !_relay->enabled(AP_Relay_Params::FUNCTION::PARACHUTE)) {
hal.util->snprintf(buffer, buflen, "Chute has no relay");
return false;
}
#else
Expand All @@ -235,6 +235,19 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
return true;
}

#if AP_RELAY_ENABLED
// Return the relay index that would be used for param conversion to relay functions
bool AP_Parachute::get_legacy_relay_index(int8_t &index) const
{
// PARAMETER_CONVERSION - Added: Dec-2023
if (!enabled() || (_release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3)) {
return false;
}
index = _release_type;
return true;
}
#endif

// singleton instance
AP_Parachute *AP_Parachute::_singleton;

Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_Parachute/AP_Parachute.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,10 @@ class AP_Parachute {

// check settings are valid
bool arming_checks(size_t buflen, char *buffer) const;


// Return the relay index that would be used for param conversion to relay functions
bool get_legacy_relay_index(int8_t &index) const;

static const struct AP_Param::GroupInfo var_info[];

// get singleton instance
Expand Down
Loading