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

Bi-directional dshot on iomcu F103 #25197

Merged
merged 19 commits into from
Dec 18, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
f580690
AP_IOMCU: bdshot for iomcu
andyp1per Jun 23, 2023
d207946
AP_ESC_Telem: don't set up parameters on iofirmware
andyp1per Oct 3, 2023
ec1d36f
AP_BLHeli: add accessor for motor poles and telemetry rate
andyp1per Oct 6, 2023
a32eec9
AP_HAL: add methods to directly access erpm array from rcout
andyp1per Oct 6, 2023
91b5515
AP_Notify: ensure dshot LEDs work with EDT ESCs
andyp1per Oct 8, 2023
a702c17
AP_HAL_ChibiOS: bdshot for f103 iofirmware
andyp1per Sep 24, 2023
845e451
AP_HAL_ChibiOS: utility to print out bdshot encoded data
andyp1per Oct 19, 2023
5833371
AP_IOMCU: reset erpm to zero on timeout
andyp1per Oct 23, 2023
1a7f6ec
AP_HAL_ChibiOS: cache values of io_dshot() and io_enabled()
andyp1per Oct 19, 2023
9ec480d
AP_IOMCU: constrain PWM channels to 8, telem channels to 4 and RC cha…
andyp1per Nov 13, 2023
82da53e
AP_HAL_ChibiOS: allow dshot to be used even if bdshot was specified.
andyp1per Nov 16, 2023
581cef4
AP_HAL: allow bdshot iomcu on non-bdshot fmu
andyp1per Nov 16, 2023
cc441c4
AP_BLHeli: allow bdshot iomcu on non-bdshot fmu
andyp1per Nov 16, 2023
a549279
AP_IOMCU: allow bdshot iomcu on non-bdshot fmu
andyp1per Nov 16, 2023
fd396e4
AP_HAL_ChibiOS: allow bdshot iomcu on non-bdshot fmu
andyp1per Nov 16, 2023
c57b109
AP_IOMCU: treat register_write() as a successful interaction
andyp1per Nov 22, 2023
755f070
AP_IOMCU: always run iofirmware loop at 1Khz to avoid uart races
andyp1per Nov 25, 2023
58566e1
AP_HAL_ChibiOS: ensure dshot commands are send to all FMU channels wh…
andyp1per Dec 16, 2023
710b4a1
IO_Firmware: iofirmware for bdshot on f103.
andyp1per Dec 11, 2023
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
Binary file modified Tools/IO_Firmware/iofirmware_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_lowpolh.bin
Binary file not shown.
4 changes: 3 additions & 1 deletion libraries/AP_BLHeli/AP_BLHeli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0),

#ifdef HAL_WITH_BIDIR_DSHOT
#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT
// @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.
Expand Down Expand Up @@ -1409,6 +1409,8 @@ void AP_BLHeli::init(uint32_t mask, AP_HAL::RCOutput::output_mode otype)
#ifdef HAL_WITH_BIDIR_DSHOT
// possibly enable bi-directional dshot
hal.rcout->set_motor_poles(motor_poles);
#endif
#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT
hal.rcout->set_bidir_dshot_mask(uint32_t(channel_bidir_dshot_mask.get()) & digital_mask);
#endif
// add motors from channel mask
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_BLHeli/AP_BLHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class AP_BLHeli : public AP_ESC_Telem_Backend {
}

uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }
uint8_t get_motor_poles() const { return motor_poles.get(); }
uint16_t get_telemetry_rate() const { return telem_rate.get(); }

static AP_BLHeli *get_singleton(void) {
return _singleton;
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ AP_ESC_Telem::AP_ESC_Telem()
AP_HAL::panic("Too many AP_ESC_Telem instances");
}
_singleton = this;
#if !defined(IOMCU_FW)
AP_Param::setup_object_defaults(this, var_info);
#endif
}

// return the average motor RPM
Expand Down Expand Up @@ -416,7 +418,7 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem
// can only get slightly more up-to-date information that perhaps they were expecting or might
// read data that has just gone stale - both of these are safe and avoid the overhead of locking

if (esc_index >= ESC_TELEM_MAX_ESCS) {
if (esc_index >= ESC_TELEM_MAX_ESCS || data_mask == 0) {
return;
}

Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,11 @@ class AP_ESC_Telem {
// get an individual ESC's raw rpm if available
bool get_raw_rpm(uint8_t esc_index, float& rpm) const;

// get raw telemetry data, used by IOMCU
const volatile AP_ESC_Telem_Backend::TelemetryData& get_telem_data(uint8_t esc_index) const {
return _telem_data[esc_index];
}

// return the average motor RPM
float get_average_motor_rpm(uint32_t servo_channel_mask) const;

Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_HAL/AP_HAL_Boards.h
Original file line number Diff line number Diff line change
Expand Up @@ -170,8 +170,12 @@
#define HAL_WITH_IO_MCU 0
#endif

#ifndef HAL_WITH_IO_MCU_BIDIR_DSHOT
#define HAL_WITH_IO_MCU_BIDIR_DSHOT 0
#endif

#ifndef HAL_WITH_IO_MCU_DSHOT
#define HAL_WITH_IO_MCU_DSHOT 0
#define HAL_WITH_IO_MCU_DSHOT HAL_WITH_IO_MCU_BIDIR_DSHOT
#endif

// this is used as a general mechanism to make a 'small' build by
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_HAL/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,11 @@ class AP_HAL::RCOutput {
*/
virtual uint16_t get_erpm(uint8_t chan) const { return 0; }
virtual float get_erpm_error_rate(uint8_t chan) const { return 100.0f; }
/*
allow all erpm values to be read and for new updates to be detected - primarily for IOMCU
*/
virtual bool new_erpm() { return false; }
virtual uint32_t read_erpm(uint16_t* erpm, uint8_t len) { return 0; }

/*
enable PX4IO SBUS out at the given rate
Expand Down
Loading