I don't think we have a way to explicitly detect if BAT1 or BAT2
"bricks" are correct, so we have to assume they are, and rely on the
voltage/current shown.
Additionally, we can now power cycle sensor power.
- split up old module into two, one handling setpoint generation, one control
- add lateral and longitudinal control setpoints topics that can also be
injected from companion computer
- add configuration topics that (optionally) configure the controller
with limits and momentary settings
Signed-off-by: RomanBapst <bapstroman@gmail.com>
* hrt: Fix PPM input on channel 2
The CCMR1_PPM define for PPM input on channel 2 was incorrectly set to 2,
which was setting bits for channel 1 instead of channel 2. This prevented
PPM input from functioning properly on channel 2.
Changed CCMR1_PPM for channel 2 from 2 to (1 << 8), which correctly
configures the CC2S bits for input capture mode on TI2.
This fixes an issue noted in the existing code comment:
"FIXME! There is an interaction in the CCMR registers that prevents
using Chan 1 as the timer and chan 2 as the PPM"
Tested on STM32H743 with PPM input on PC7 (TIM8_CH2).
* rc_input: enable sharing serial and PPM pin
By setting RC_SERIAL_PORT_SHARED_PPM_PIN_GPIO_RX it is now possible to
use the same pin on the STM32 for PPM input as well as serial input.
* boards: Add support for Holybro KakuteH7-Wing
Signed-off-by: Silvan <silvan@auterion.com>
boards: increase max mission items for boards with >=1kb RAM to 1000
Signed-off-by: Silvan <silvan@auterion.com>
boards: increase NUM_MISSION_ITMES_SUPPORTED for SITL to 10000
Signed-off-by: Silvan <silvan@auterion.com>
This configures the RTC clock to use the HSE instead of the not existing
LSE clock which prevents boot waiting for the not existing LSE crystal
for a few seconds on startup.
* Bidirectional DShot
Co-authored-by: Julian Oes <julian@oes.ch>
* f4/f1 support, not supported
* fix f1 build target
* sanity check timer_channel value, fix CCxNP ifdef, debug stuff
* removed debug code, added define for H7 HAVE_GTIM_CCXNP
* round robin sampling for less than 4 DMA
* unlimited esc_status logging
* dshot: fix formatting
* dshot: add define for number of DMA channels to use
This allows individual boards to override the number of DShot channels
and hence avoid round robin capture of the RPM feedback.
* ARK: enable 4 DMA channels for DShot on 6X
* dshot: publish when all channels are updated
This slows down the ESC_STATUS publication in the case of round robin
capture. E.g. for 800 Hz output with one DMA channel, the ESC_STATUS is
now published at 200 Hz.
* dshot: avoid duplicate publications for bidir and telem
Instead of publishing both bidirectional dshot updates as well as
telemetry updates, we now combine the data from both streams, and
publish whenever we get RPM updates, as the latter arrives with higher
rate, e.g. 200 Hz with round robin, or faster otherwise.
When combining the data, we take RPM from bidirectional dshot, and the
rest from telemetry.
When we have only one of the two, either telemetry or bidirectional
dshot, we just publish that one.
* boards: add ark fpv and pi6x BOARD_DMA_NUM_DSHOT_CHANNELS
* dshot: turn off debug build
---------
Co-authored-by: Julian Oes <julian@oes.ch>
Co-authored-by: alexklimaj <alex@arkelectron.com>
* boards: change board ID of KakuteH7 mini
Holybro would like to consolidate the board ID to what is used in
ArduPilot.
* boards: update KakuteH7mini bootloader
This is due to the board ID change.
* usb: Added parameter to enable always starting mavlink on USB.
Refactored cdcacm_init into a module and added a paramter to allow always starting mavlink on
USB, also added a paramter to choose the mode. The current default behavior is to wait and listen
for data on USB and auto-detect the protocol (mavlink, nsh, ublox). This results in the mavlink
stream not starting until something else on the mavlink network sends a packet first. The new
default behavior is to always start mavlink.
Added parameters
MAV_USB_ENABLE -- default 1 (always start mavlink on USB)
MAV_USE_MODE -- default 3 (onboard)
* added 3 retries for opening serial port in mavlink, removed sleep before sercon
* added DRIVERS_CDCACM_AUTOSTART to ark-v6x default.px4board
* added CONFIG_DRIVERS_CDCACM_AUTOSTART=y to default.px4board for boards with CONFIG_CDCACM in their nsh/defconfig
* format
* remove PGA460 from COMMON_DISTANCE_SENSOR to save flash
* remove LIS2MDL from COMMON_MAGNETOMETER to save flash
* disable CONFIG_DRIVERS_CDCACM_AUTOSTART for fmu-v5 protected.px4board
* moved and renamed parameters, removed mode logic in mavlink
* changed parameter names, added mode none
* remove parameters from mavlink
If the output is set to 0 then the FMU had this channel disabled/no function mapped
to it. In that case we do not want to suddenly start outputing failsafe or disarmed
signals.
This adds the ICM42686p as a possible alternative to the existing IMUs.
Apparently, the ICM20689 was never actually used in these boards.
Signed-off-by: Julian Oes <julian@oes.ch>
The param is not really required anymore with the actuator
configuration. Also, when it is set to 0, RC doesn't work for some
boards which would be nice to avoid.
Signed-off-by: Julian Oes <julian@oes.ch>