Skip to content

Commit

Permalink
update serial driver for JRE
Browse files Browse the repository at this point in the history
  • Loading branch information
jfbblue0922 committed Jul 28, 2023
1 parent 4306254 commit 3b2efcc
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 21 deletions.
24 changes: 12 additions & 12 deletions libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ define ANALOG_VCC_5V_PIN 5
define HAL_HAVE_BOARD_VOLTAGE 1
PB3 VBUS_RESERVED INPUT

# JFB110 has no SERVORAIL ADC
# JFB110 has SERVORAIL ADC
# Set SENSOR_3.3V power signal insted.
PC1 SCALED_V3V3 ADC1 SCALE(2) # ADC1_11
PA3 FMU_SERVORAIL_VCC ADC1 SCALE(2) # ADC1_15
Expand Down Expand Up @@ -161,11 +161,11 @@ define HAL_GPIO_SPEKTRUM_PWR 69
define HAL_SPEKTRUM_PWR_ENABLED 1

#Checked in Analogin.cpp -> MAV_POWER_STATUS
PG1 VDD_BRICK_nVALID INPUT PULLUP
PG2 VDD_BRICK2_nVALID INPUT PULLUP
PG3 VBUS_nVALID INPUT PULLUP
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
PG1 VDD_BRICK_nVALID INPUT
PG2 VDD_BRICK2_nVALID INPUT
PG3 VBUS_nVALID INPUT
PE15 VDD_5V_PERIPH_nOC INPUT
PF13 VDD_5V_HIPOWER_nOC INPUT

# ID pins
PG0 HW_VER_REV_DRIVE OUTPUT LOW SPEED_VERYLOW
Expand Down Expand Up @@ -204,10 +204,10 @@ PG15 IIM42652_2_CS CS SPEED_VERYLOW # SPI4_CS2
#PE2 SPI5_CS1 CS SPEED_VERYLOW

# IMU Device Ready Signal Input
PF3 DRDY1_IIM42652_1 INPUT PULLUP
PF2 DRDY2_IIM42652_1 INPUT PULLUP
PA15 DRDY1_IIM42652_2 INPUT PULLUP
PA1 DRDY2_IIM42652_2 INPUT PULLUP
PF3 DRDY1_IIM42652_1 INPUT
PF2 DRDY2_IIM42652_1 INPUT
PA15 DRDY1_IIM42652_2 INPUT
PA1 DRDY2_IIM42652_2 INPUT

PE7 SCHA63T_RESET OUTPUT LOW

Expand Down Expand Up @@ -259,8 +259,8 @@ PD11 PWM_OE OUTPUT HIGH
PD5 PWM_OE2 OUTPUT HIGH

# GPIOs
PE11 FMU_CAP1 INPUT GPIO(66) PULLUP
PB11 FMU_CAP2 INPUT GPIO(67) PULLUP
PE11 FMU_CAP1 INPUT GPIO(66)
PB11 FMU_CAP2 INPUT GPIO(67)

# CAN bus
PD0 CAN1_RX CAN1 SPEED_VERYLOW
Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,20 +31,20 @@
/* CRC16CCITT */
static uint16_t CalcCRC16CCITT(uint8_t *cbuffer, uint16_t csize)
{
uint16_t crc = CCITT_INITPARA;
for (int i = 0; i < csize; i++) {
crc ^= *cbuffer++;
for (int j = 0; j < 8; j++) {
uint16_t crc = CCITT_INITPARA;
for (int i = 0; i < csize; i++) {
crc ^= *cbuffer++;
for (int j = 0; j < 8; j++) {
if ((crc & 0x0001) != 0) {
crc >>= 1;
crc ^= CCITT_POLYNOMIAL;
} else {
crc >>= 1;
}
}
}
crc = crc ^ CCITT_OUTPARA;
return crc;
}
}
crc = crc ^ CCITT_OUTPARA;
return crc;
}

bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m)
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial
return MAV_DISTANCE_SENSOR_RADAR;
}

bool get_signal_quality_pct(uint8_t &quality_pct) const override {
bool get_signal_quality_pct(uint8_t &quality_pct) const override
{
quality_pct = no_signal ? 0 : 100;
return true;
}
Expand Down

0 comments on commit 3b2efcc

Please sign in to comment.