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

Plane: combined patches for 4.2 on large quadplanes #21031

Open
wants to merge 61 commits into
base: Plane-4.2
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
61 commits
Select commit Hold shift + click to select a range
7843eb9
AP_Logger: add loging of servo out 15 to 32
IamPete1 Jan 12, 2021
d1dabf8
AP_PiccoloCAN: update ESC_BM Bitmask
IamPete1 Jan 12, 2021
6e1c8b0
AP_UAVCAN: update ESC_BM and SRV_BM Bitmask
IamPete1 Jan 12, 2021
890f795
AP_Voltz: update MASK Bitmask
IamPete1 Jan 12, 2021
bd0a775
SITL: move to 32 servo outs
IamPete1 Jan 12, 2021
02908d5
AP_HAL: enable 32 servo outs
IamPete1 Jan 12, 2021
47f32ed
AP_HAL_ChibiOS: enable 32 servo outs
IamPete1 Jan 12, 2021
7c4b8d2
AP_HAL_SITL: enable 32 servo outs
IamPete1 Jan 12, 2021
640c58d
AP_SerialLED: enable 32 servo outs
IamPete1 Jan 12, 2021
96b4118
SRV_Channel: add upto 32 servo outs
IamPete1 Jan 12, 2021
2d97ab3
GCS_MAVLink: send servo raw 17-32 using port 1
IamPete1 Jan 12, 2021
ddf9587
AP_Motors: convert to 32 bit motor mask
IamPete1 Dec 10, 2021
8c59366
AR_MotorsUGV: convert to 32 bit motor mask
IamPete1 Dec 10, 2021
014fe12
AP_BLHeli: support upto 32 servo outputs
IamPete1 Dec 10, 2021
020bb1e
SITL: JSON Master: only copy the first 16 servos
IamPete1 Dec 10, 2021
78e323f
SRV_Channel: add invalid mask for GPIO outputs
IamPete1 Jan 2, 2022
71b4474
AP_Logger: RCOUT only log if there is a valid output channel
IamPete1 Jan 2, 2022
4fd4ada
SRV_Channels: set channels above 16 to GPIO by defualt
IamPete1 Jan 2, 2022
70ea9fd
SITL: move to 32 servo outs
IamPete1 Jan 2, 2022
b89b361
Copter: 32 servo conversion
tridge May 15, 2022
25cb30e
Plane: 32 servo conversion
tridge May 15, 2022
5d7f579
AP_Periph: 32 servo conversion
tridge May 15, 2022
14fc9dc
AP_BLHeli: more changes for 32 bit servo mask
tridge May 15, 2022
212ba92
AP_BoardConfig: more changes for 32 bit servo mask
tridge May 15, 2022
07b1f1d
AP_ESC_Telem: more changes for 32 bit servo mask
tridge May 15, 2022
2070b16
AP_HAL_ChibiOS: more changes for 32 bit servo mask
tridge May 15, 2022
6e93761
AP_HAL_ESP32: more changes for 32 bit servo mask
tridge May 15, 2022
28785bb
AP_HAL: more changes for 32 bit servo mask
tridge May 15, 2022
05d04e5
AP_HAL_Linux: more changes for 32 bit servo mask
tridge May 15, 2022
ce28ecb
AP_KDECAN: more changes for 32 bit servo mask
tridge May 15, 2022
5ccdfdd
AP_Motors: more changes for 32 bit servo mask
tridge May 15, 2022
8643229
AP_RobotisServo: more changes for 32 bit servo mask
tridge May 15, 2022
0add4a1
AP_ToshibaCAN: more changes for 32 bit servo mask
tridge May 15, 2022
3670932
SRV_Channel: more changes for 32 bit servo mask
tridge May 15, 2022
0b6c147
SRV_Channel: added a SERVO_32_ENABLE parameter
tridge May 15, 2022
579c7b7
SRV_Channel: only support 32 channels on 2M flash boards
tridge May 19, 2022
868ad48
AP_Periph: allow peripherals to handle servos beyond 16
tridge May 20, 2022
fd641cc
AP_UAVCAN: allow CAN output for function==0 and allow for 32 CAN servos
tridge May 20, 2022
2c95c0f
AP_EFI: allow EFI to be used in AP_Periph
tridge Jun 3, 2022
7edd2e5
AP_UAVCAN: support DroneCAN EFI
tridge Jun 3, 2022
91a423c
AP_EFI: added DroneCAN EFI driver
tridge Jun 3, 2022
9511478
Filter: added EnableOnAllIMUs option to harmonic notch filter
tridge Feb 17, 2022
f2ee4a5
Ap_Inertialsensor: by default only run harmonic notch on the active gyro
tridge Feb 17, 2022
a2e90df
Filter: fixed reset of notch filters
tridge Jun 5, 2022
7dde3df
AP_InertialSensor: count filters to match notch options
tridge Jun 7, 2022
7257fb1
AP_ESC_Telem: support ESC telem for ESCs 13 to 32
tridge Jun 6, 2022
28ebb37
AP_Vehicle: added parameter table for ESC telemetry
tridge Jun 24, 2022
00d4e31
AP_ESC_Telem: added ESC_TLM_MAV_OFS parameter
tridge Jun 6, 2022
6911802
AP_ESC_Telem: disable ESC telem with zero channels
tridge Jun 6, 2022
9ad9c48
AP_HAL: increase max filters
tridge Jun 7, 2022
8bc075c
AP_InertialSensor: allow concurrent logging of both pre- and post-fil…
andyp1per Jun 25, 2022
3bb2bf4
AP_InertialSensor: implement triple notches
tridge Jul 5, 2022
1425629
Filter: add triple harmonic notches
andyp1per Jun 23, 2022
71e093a
Plane: Quadplane: QRTL climb to QRTL alt first if in Q mode
IamPete1 May 31, 2022
06a8bd5
SITL switched to motor_mask for which actuators are motors
tridge Aug 18, 2022
357c054
Filter: allow for expansion of dynamic filters
tridge Aug 18, 2022
2f7e227
AP_Vehicle: removed num_dynamic_notches limit in dynamic harmonic
tridge Aug 18, 2022
3a139b4
AP_InertialSensor: use motor_mask from SITL for which outputs are motors
tridge Aug 18, 2022
864dc25
HAL_SITL: use motor mask for noise checking for motors
tridge Aug 18, 2022
320fde2
AP_ESC_TELEM: allow for non-continguous ESC telem motor sets
tridge Aug 18, 2022
a3fc056
SITL: allow for extra actuators to be marked as motors
tridge Aug 18, 2022
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/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,8 +323,8 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
// check we have an ESC present for every SERVOx_FUNCTION = motorx
// find and report first missing ESC, extra ESCs are OK
AP_ToshibaCAN *tcan = AP_ToshibaCAN::get_tcan(tcan_index);
const uint16_t motors_mask = copter.motors->get_motor_mask();
const uint16_t esc_mask = tcan->get_present_mask();
const uint32_t motors_mask = copter.motors->get_motor_mask();
const uint32_t esc_mask = tcan->get_present_mask();
uint8_t escs_missing = 0;
uint8_t first_missing = 0;
for (uint8_t i = 0; i < 16; i++) {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/afs_copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void)

#if FRAME_CONFIG != HELI_FRAME
// setup AP_Motors outputs for failsafe
uint16_t mask = copter.motors->get_motor_mask();
uint32_t mask = copter.motors->get_motor_mask();
hal.rcout->set_failsafe_pwm(mask, copter.motors->get_pwm_output_min());
#endif
}
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/afs_plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void)
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.available()) {
// setup AP_Motors outputs for failsafe
uint16_t mask = plane.quadplane.motors->get_motor_mask();
uint32_t mask = plane.quadplane.motors->get_motor_mask();
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min());
}
#endif
Expand Down
7 changes: 7 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -597,6 +597,13 @@ class ModeQRTL : public Mode
protected:

bool _enter() override;

private:

enum class SubMode {
climb,
RTL,
} submode;
};

class ModeQAcro : public Mode
Expand Down
123 changes: 95 additions & 28 deletions ArduPlane/mode_qrtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,28 +11,52 @@ bool ModeQRTL::_enter()
plane.set_mode(plane.mode_qland, ModeReason::QLAND_INSTEAD_OF_RTL);
return true;
}
submode = SubMode::RTL;
plane.prev_WP_loc = plane.current_loc;

// clear QPOS state
quadplane.poscontrol.set_state(QuadPlane::QPOS_NONE);

const int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
// VTOL motors are active, either in VTOL flight or assisted flight
Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm);

const float dist = plane.current_loc.get_distance(destination);
const float radius = MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius));

const float dist_to_climb = quadplane.qrtl_alt - plane.relative_ground_altitude(plane.g.rangefinder_landing);
if (dist < 1.5*radius) {
// we're close to destination and already running VTOL motors, don't transition and don't climb
gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 d=%.1f r=%.1f", dist, radius);
poscontrol.set_state(QuadPlane::QPOS_POSITION1);

} else if (is_positive(dist_to_climb)) {
// climb before returning, only next waypoint altitude is used
submode = SubMode::climb;
plane.next_WP_loc = plane.current_loc;
#if AP_TERRAIN_AVAILABLE
if (plane.terrain_enabled_in_mode(mode_number())) {
plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt * 100UL, Location::AltFrame::ABOVE_TERRAIN);
return true;
}
#endif
plane.next_WP_loc.set_alt_cm(plane.current_loc.alt + dist_to_climb * 100UL, plane.current_loc.get_alt_frame());
return true;
}
}

// use do_RTL() to setup next_WP_loc
plane.do_RTL(plane.home.alt + quadplane.qrtl_alt*100UL);
plane.prev_WP_loc = plane.current_loc;
pos_control->set_accel_desired_xy_cmss(Vector2f());
pos_control->init_xy_controller();
plane.do_RTL(RTL_alt_abs_cm);
quadplane.poscontrol_init_approach();
float dist = plane.next_WP_loc.get_distance(plane.current_loc);
const float radius = MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius));
if (dist < 1.5*radius &&
quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
// we're close to destination and already running VTOL motors, don't transition
gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 d=%.1f r=%.1f", dist, radius);
poscontrol.set_state(QuadPlane::QPOS_POSITION1);
}

int32_t from_alt;
int32_t to_alt;
if (plane.current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,from_alt) && plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,to_alt)) {
poscontrol.slow_descent = from_alt > to_alt;
return true;
}
// defualt back to old method
// default back to old method
poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt);
return true;
}
Expand All @@ -47,20 +71,63 @@ void ModeQRTL::update()
*/
void ModeQRTL::run()
{
quadplane.vtol_position_controller();
if (poscontrol.get_state() > QuadPlane::QPOS_POSITION2) {
// change target altitude to home alt
plane.next_WP_loc.alt = plane.home.alt;
}
if (poscontrol.get_state() >= QuadPlane::QPOS_POSITION2) {
// start landing logic
quadplane.verify_vtol_land();
}
switch (submode) {
case SubMode::climb: {
// request zero velocity
Vector2f vel, accel;
pos_control->input_vel_accel_xy(vel, accel);
quadplane.run_xy_controller();

// nav roll and pitch are controller by position controller
plane.nav_roll_cd = pos_control->get_roll_cd();
plane.nav_pitch_cd = pos_control->get_pitch_cd();
if (quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) {
pos_control->set_externally_limited_xy();
}
// weathervane with no pilot input
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
plane.nav_pitch_cd,
quadplane.get_weathervane_yaw_rate_cds());

// climb at full WP nav speed
quadplane.set_climb_rate_cms(quadplane.wp_nav->get_default_speed_up(), false);
quadplane.run_z_controller();

ftype alt_diff;
if (!plane.current_loc.get_alt_distance(plane.next_WP_loc, alt_diff) || is_positive(alt_diff)) {
// climb finshed or cant get alt diff, head home
submode = SubMode::RTL;
plane.prev_WP_loc = plane.current_loc;
plane.do_RTL(plane.home.alt + quadplane.qrtl_alt*100UL);
quadplane.poscontrol_init_approach();
if (plane.current_loc.get_alt_distance(plane.next_WP_loc, alt_diff)) {
poscontrol.slow_descent = is_positive(alt_diff);
} else {
// default back to old method
poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt);
}
}
break;
}

case SubMode::RTL: {
quadplane.vtol_position_controller();
if (poscontrol.get_state() > QuadPlane::QPOS_POSITION2) {
// change target altitude to home alt
plane.next_WP_loc.alt = plane.home.alt;
}
if (poscontrol.get_state() >= QuadPlane::QPOS_POSITION2) {
// start landing logic
quadplane.verify_vtol_land();
}

// when in approach allow stick mixing
if (quadplane.poscontrol.get_state() == QuadPlane::QPOS_AIRBRAKE ||
quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH) {
plane.stabilize_stick_mixing_fbw();
// when in approach allow stick mixing
if (quadplane.poscontrol.get_state() == QuadPlane::QPOS_AIRBRAKE ||
quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH) {
plane.stabilize_stick_mixing_fbw();
}
break;
}
}
}

Expand All @@ -72,7 +139,7 @@ bool ModeQRTL::update_target_altitude()
/*
update height target in approach
*/
if (plane.quadplane.poscontrol.get_state() != QuadPlane::QPOS_APPROACH) {
if ((submode != SubMode::RTL) || (plane.quadplane.poscontrol.get_state() != QuadPlane::QPOS_APPROACH)) {
return false;
}

Expand All @@ -99,7 +166,7 @@ bool ModeQRTL::update_target_altitude()
// only nudge during approach
bool ModeQRTL::allows_throttle_nudging() const
{
return plane.quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH;
return (submode == SubMode::RTL) && (plane.quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH);
}

#endif
5 changes: 3 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -730,7 +730,7 @@ bool QuadPlane::setup(void)

// setup the trim of any motors used by AP_Motors so I/O board
// failsafe will disable motors
uint16_t mask = plane.quadplane.motors->get_motor_mask();
uint32_t mask = plane.quadplane.motors->get_motor_mask();
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min());

// default QAssist state as set with Q_OPTIONS
Expand Down Expand Up @@ -2187,6 +2187,7 @@ void QuadPlane::poscontrol_init_approach(void)
}
poscontrol.pilot_correction_done = false;
poscontrol.xy_correction.zero();
poscontrol.slow_descent = false;
}

/*
Expand Down Expand Up @@ -3524,13 +3525,13 @@ void QuadPlane::guided_start(void)
setup_target_position();
int32_t from_alt;
int32_t to_alt;
poscontrol_init_approach();
if (plane.current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,from_alt) && plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,to_alt)) {
poscontrol.slow_descent = from_alt > to_alt;
} else {
// default back to old method
poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt);
}
poscontrol_init_approach();
}

/*
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -984,7 +984,7 @@ void Plane::servos_output(void)

// support MANUAL_RCMASK
if (g2.manual_rc_mask.get() != 0 && control_mode == &mode_manual) {
SRV_Channels::copy_radio_in_out_mask(uint16_t(g2.manual_rc_mask.get()));
SRV_Channels::copy_radio_in_out_mask(uint32_t(g2.manual_rc_mask.get()));
}

SRV_Channels::calc_pwm();
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/rc_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
// Raw ESC command normalized into [-8192, 8191]
#define UAVCAN_ESC_MAX_VALUE 8191

#define SERVO_OUT_RCIN_MAX 16 // SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16
#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum
#define SERVO_OUT_MOTOR_MAX 12 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12

extern const AP_HAL::HAL &hal;
Expand Down Expand Up @@ -49,7 +49,7 @@ void AP_Periph_FW::rcout_init()
SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000);
}

uint16_t esc_mask = 0;
uint32_t esc_mask = 0;
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
uint8_t chan;
Expand Down
26 changes: 13 additions & 13 deletions libraries/AP_BLHeli/AP_BLHeli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @Param: MASK
// @DisplayName: BLHeli Channel Bitmask
// @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any)
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0),
Expand Down Expand Up @@ -129,7 +129,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @Param: 3DMASK
// @DisplayName: BLHeli bitmask of 3D channels
// @Description: Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0),
Expand All @@ -138,15 +138,15 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @Param: BDMASK
// @DisplayName: BLHeli bitmask of bi-directional dshot channels
// @Description: Mask of channels which support bi-directional dshot. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch.
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("BDMASK", 11, AP_BLHeli, channel_bidir_dshot_mask, 0),
#endif
// @Param: RVMASK
// @DisplayName: BLHeli bitmask of reversed channels
// @Description: Mask of channels which are reversed. This is used to configure ESCs in reversed mode
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("RVMASK", 12, AP_BLHeli, channel_reversed_mask, 0),
Expand Down Expand Up @@ -1333,7 +1333,7 @@ void AP_BLHeli::init(void)
}
#endif

uint16_t mask = uint16_t(channel_mask.get());
uint32_t mask = uint32_t(channel_mask.get());

/*
allow mode override - this makes it possible to use DShot for
Expand All @@ -1359,7 +1359,7 @@ void AP_BLHeli::init(void)
break;
}

uint16_t digital_mask = 0;
uint32_t digital_mask = 0;
// setting the digital mask changes the min/max PWM values
// it's important that this is NOT done for non-digital channels as otherwise
// PWM min can result in motors turning. set for individual overrides first
Expand All @@ -1377,7 +1377,7 @@ void AP_BLHeli::init(void)
AP_Motors *motors = AP::motors();
#endif
if (motors) {
uint16_t motormask = motors->get_motor_mask();
uint32_t motormask = motors->get_motor_mask();
// set the rest of the digital channels
if (motors->is_digital_pwm_type()) {
digital_mask |= motormask;
Expand All @@ -1386,15 +1386,15 @@ void AP_BLHeli::init(void)
}
#endif
// tell SRV_Channels about ESC capabilities
SRV_Channels::set_digital_outputs(digital_mask, uint16_t(channel_reversible_mask.get()) & digital_mask);
SRV_Channels::set_digital_outputs(digital_mask, uint32_t(channel_reversible_mask.get()) & digital_mask);
// the dshot ESC type is required in order to send the reversed/reversible dshot command correctly
hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());
hal.rcout->set_reversible_mask(uint16_t(channel_reversible_mask.get()) & digital_mask);
hal.rcout->set_reversed_mask(uint16_t(channel_reversed_mask.get()) & digital_mask);
hal.rcout->set_reversible_mask(uint32_t(channel_reversible_mask.get()) & digital_mask);
hal.rcout->set_reversed_mask(uint32_t(channel_reversed_mask.get()) & digital_mask);
#ifdef HAL_WITH_BIDIR_DSHOT
// possibly enable bi-directional dshot
hal.rcout->set_motor_poles(motor_poles);
hal.rcout->set_bidir_dshot_mask(uint16_t(channel_bidir_dshot_mask.get()) & digital_mask);
hal.rcout->set_bidir_dshot_mask(uint32_t(channel_bidir_dshot_mask.get()) & digital_mask);
#endif
// add motors from channel mask
for (uint8_t i=0; i<16 && num_motors < max_motors; i++) {
Expand All @@ -1404,7 +1404,7 @@ void AP_BLHeli::init(void)
}
}
motor_mask = mask;
debug("ESC: %u motors mask=0x%04x", num_motors, mask);
debug("ESC: %u motors mask=0x%08lx", num_motors, mask);

// check if we have a combination of reversable and normal
mixed_type = (mask != (mask & channel_reversible_mask.get())) && (channel_reversible_mask.get() != 0);
Expand Down Expand Up @@ -1581,7 +1581,7 @@ void AP_BLHeli::update_telemetry(void)
break;
}
}
uint16_t mask = 1U << motor_map[idx];
uint32_t mask = 1U << motor_map[idx];
if (SRV_Channels::have_digital_outputs(mask)) {
hal.rcout->set_telem_request_mask(mask);
last_telem_esc = idx;
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_BLHeli/AP_BLHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend {
return channel_bidir_dshot_mask.get() & (1U << motor_map[esc_index]);
}

uint16_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }
uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }

static AP_BLHeli *get_singleton(void) {
return _singleton;
Expand Down Expand Up @@ -232,7 +232,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend {
// have we disabled motor outputs?
bool motors_disabled;
// mask of channels that should normally be disabled
uint16_t motors_disabled_mask;
uint32_t motors_disabled_mask;

// have we locked the UART?
bool uart_locked;
Expand All @@ -242,7 +242,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend {

// mapping from BLHeli motor numbers to RC output channels
uint8_t motor_map[max_motors];
uint16_t motor_mask;
uint32_t motor_mask;

// convert between servo number and FMU channel number for ESC telemetry
uint8_t chan_offset;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_BoardConfig/AP_BoardConfig.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,7 +375,7 @@ void AP_BoardConfig::init()
}

// set default value for BRD_SAFETY_MASK
void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
void AP_BoardConfig::set_default_safety_ignore_mask(uint32_t mask)
{
state.ignore_safety_channels.set_default(mask);
}
Expand Down
Loading