mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Arming: retrieve RC channels directly from RC_Channels
... instead of retrieving values from rcmap and then getting the channel from RC_Channels
This commit is contained in:
parent
1871170f98
commit
8e6a1a2b02
@ -44,7 +44,6 @@
|
|||||||
#include <AP_Scripting/AP_Scripting.h>
|
#include <AP_Scripting/AP_Scripting.h>
|
||||||
#include <AP_Camera/AP_RunCam.h>
|
#include <AP_Camera/AP_RunCam.h>
|
||||||
#include <AP_GyroFFT/AP_GyroFFT.h>
|
#include <AP_GyroFFT/AP_GyroFFT.h>
|
||||||
#include <AP_RCMapper/AP_RCMapper.h>
|
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||||
#include <AP_Parachute/AP_Parachute.h>
|
#include <AP_Parachute/AP_Parachute.h>
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
@ -736,19 +735,21 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
|
|||||||
check_failed(ARMING_CHECK_PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number());
|
check_failed(ARMING_CHECK_PARAMETERS, true, "Mode channel and RC%d_OPTION conflict", rc().flight_mode_channel_number());
|
||||||
check_passed = false;
|
check_passed = false;
|
||||||
}
|
}
|
||||||
const RCMapper * rcmap = AP::rcmap();
|
{
|
||||||
if (rcmap != nullptr) {
|
|
||||||
if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) {
|
if (!rc().option_is_enabled(RC_Channels::Option::ARMING_SKIP_CHECK_RPY)) {
|
||||||
const char *names[3] = {"Roll", "Pitch", "Yaw"};
|
const struct {
|
||||||
const uint8_t channels[3] = {rcmap->roll(), rcmap->pitch(), rcmap->yaw()};
|
const char *name;
|
||||||
for (uint8_t i = 0; i < ARRAY_SIZE(channels); i++) {
|
const RC_Channel *channel;
|
||||||
const RC_Channel *c = rc().channel(channels[i] - 1);
|
} channels_to_check[] {
|
||||||
if (c == nullptr) {
|
{ "Roll", &rc().get_roll_channel(), },
|
||||||
continue;
|
{ "Pitch", &rc().get_pitch_channel(), },
|
||||||
}
|
{ "Yaw", &rc().get_yaw_channel(), },
|
||||||
|
};
|
||||||
|
for (const auto &channel_to_check : channels_to_check) {
|
||||||
|
const auto *c = channel_to_check.channel;
|
||||||
if (c->get_control_in() != 0) {
|
if (c->get_control_in() != 0) {
|
||||||
if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming
|
if ((method != Method::RUDDER) || (c != rc().get_arming_channel())) { // ignore the yaw input channel if rudder arming
|
||||||
check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", names[i], channels[i]);
|
check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", channel_to_check.name, c->ch());
|
||||||
check_passed = false;
|
check_passed = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -757,13 +758,11 @@ bool AP_Arming::rc_arm_checks(AP_Arming::Method method)
|
|||||||
|
|
||||||
// if throttle check is enabled, require zero input
|
// if throttle check is enabled, require zero input
|
||||||
if (rc().arming_check_throttle()) {
|
if (rc().arming_check_throttle()) {
|
||||||
RC_Channel *c = rc().channel(rcmap->throttle() - 1);
|
const RC_Channel *c = &rc().get_throttle_channel();
|
||||||
if (c != nullptr) {
|
|
||||||
if (c->get_control_in() != 0) {
|
if (c->get_control_in() != 0) {
|
||||||
check_failed(ARMING_CHECK_RC, true, "Throttle (RC%d) is not neutral", rcmap->throttle());
|
check_failed(ARMING_CHECK_RC, true, "%s (RC%d) is not neutral", "Throttle", c->ch());
|
||||||
check_passed = false;
|
check_passed = false;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
|
c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::FWD_THR);
|
||||||
if (c != nullptr) {
|
if (c != nullptr) {
|
||||||
uint8_t fwd_thr = c->percent_input();
|
uint8_t fwd_thr = c->percent_input();
|
||||||
|
Loading…
Reference in New Issue
Block a user