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

hwdef: added baro in HolybroG4_GPS #28781

Merged
merged 4 commits into from
Dec 9, 2024
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
16 changes: 14 additions & 2 deletions Tools/AP_Periph/imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,15 @@ extern const AP_HAL::HAL &hal;
void AP_Periph_FW::can_imu_update(void)
{
while (true) {
// sleep for a bit to avoid flooding the CPU
hal.scheduler->delay_microseconds(100);
// we need to delay by a ms value as hal->schedule->delay_microseconds_boost
// used in wait_for_sample() takes uint16_t
const uint32_t delay_ms = 1000U / g.imu_sample_rate;
hal.scheduler->delay(delay_ms);

if (delay_ms == 0) {
// sleep for a bit to avoid flooding the CPU
hal.scheduler->delay_microseconds(100);
}

imu.update();

Expand All @@ -38,6 +45,11 @@ void AP_Periph_FW::can_imu_update(void)
pkt.accelerometer_latest[1] = tmp.y;
pkt.accelerometer_latest[2] = tmp.z;

tmp = imu.get_gyro();
pkt.rate_gyro_latest[0] = tmp.x;
pkt.rate_gyro_latest[1] = tmp.y;
pkt.rate_gyro_latest[2] = tmp.z;

uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_RAWIMU_MAX_SIZE];
uint16_t total_size = uavcan_equipment_ahrs_RawIMU_encode(&pkt, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_AHRS_RAWIMU_SIGNATURE,
Expand Down
2 changes: 2 additions & 0 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -949,6 +949,7 @@ def configure_env(self, cfg, env):
HAL_PERIPH_ENABLE_AIRSPEED = 1,
HAL_PERIPH_ENABLE_MAG = 1,
HAL_PERIPH_ENABLE_BARO = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
HAL_PERIPH_ENABLE_BATTERY = 1,
HAL_PERIPH_ENABLE_EFI = 1,
Expand All @@ -963,6 +964,7 @@ def configure_env(self, cfg, env):
HAL_WITH_ESC_TELEM = 1,
AP_EXTENDED_ESC_TELEM_ENABLED = 1,
AP_TERRAIN_AVAILABLE = 1,
HAL_GYROFFT_ENABLED = 0,
)

class sitl_periph_gps(sitl_periph):
Expand Down
18 changes: 15 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ define HAL_I2C_INTERNAL_MASK 3
I2C_ORDER I2C1 I2C2

# one SPI bus (for IMU, unused)
#PA5 SPI1_SCK SPI1
#PA6 SPI1_MISO SPI1
#PA7 SPI1_MOSI SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI CS
PC4 GYR_CS CS
Expand All @@ -95,6 +95,10 @@ COMPASS IST8310 I2C:0:0x0E false ROTATION_NONE
# compass RM3100 on can-F9P-v2
COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE

# baro, disabled by default
BARO ICP201XX I2C:0:0x64
define AP_PERIPH_BARO_ENABLE_DEFAULT 0

define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
Expand Down Expand Up @@ -130,9 +134,17 @@ DMA_NOSHARE USART3*
# add support for moving baseline yaw
define GPS_MOVING_BASELINE 1

SPIDEV icm42688 SPI1 DEVID1 ICM_CS MODE0 24*MHZ 24*MHZ

IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180

define HAL_PERIPH_ENABLE_IMU

# GPS+MAG+LEDs
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_IMU
define HAL_PERIPH_ENABLE_NOTIFY
define HAL_PERIPH_ENABLE_RC_OUT

Expand Down
Loading