Skip to content

Commit

Permalink
Revert "drivers/gnss/septentrio : 1.15-compatible extracted septentri…
Browse files Browse the repository at this point in the history
…o driver, with new features and fixes (#23386)"

This reverts commit 4ea8348.
  • Loading branch information
mrpollo committed Jul 25, 2024
1 parent 5216453 commit d298be9
Show file tree
Hide file tree
Showing 27 changed files with 67 additions and 4,153 deletions.
1 change: 0 additions & 1 deletion boards/cuav/nora/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
Expand Down
1 change: 0 additions & 1 deletion boards/cubepilot/cubeorange/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
Expand Down
1 change: 0 additions & 1 deletion boards/cubepilot/cubeorangeplus/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
Expand Down
1 change: 0 additions & 1 deletion boards/mro/pixracerpro/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI085=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_ST_L3GD20=y
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v3/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v4/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
Expand Down
12 changes: 7 additions & 5 deletions msg/GpsDump.msg
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
# This message is used to dump the raw gps communication to the log.
# Set the parameter GPS_DUMP_COMM to 1 to use this.

uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)

uint8 instance # Instance of GNSS receiver
uint8 len # length of data, MSB bit set = message to the gps device,
# clear = message from the device
uint8[79] data # data to write to the log
uint8 instance # Instance of GNSS receiver

uint8 len # length of data, MSB bit set = message to the gps device,
# clear = message from the device
uint8[79] data # data to write to the log

uint8 ORB_QUEUE_LENGTH = 8
9 changes: 1 addition & 8 deletions msg/SensorGps.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,7 @@ float64 altitude_ellipsoid_m # Altitude above Ellipsoid, meters

float32 s_variance_m_s # GPS speed accuracy estimate, (metres/sec)
float32 c_variance_rad # GPS course accuracy estimate, (radians)
uint8 FIX_TYPE_NONE = 1 # Value 0 is also valid to represent no fix.
uint8 FIX_TYPE_2D = 2
uint8 FIX_TYPE_3D = 3
uint8 FIX_TYPE_RTCM_CODE_DIFFERENTIAL = 4
uint8 FIX_TYPE_RTK_FLOAT = 5
uint8 FIX_TYPE_RTK_FIXED = 6
uint8 FIX_TYPE_EXTRAPOLATED = 8
uint8 fix_type # Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.

float32 eph # GPS horizontal position accuracy (metres)
float32 epv # GPS vertical position accuracy (metres)
Expand Down
1 change: 0 additions & 1 deletion src/drivers/gnss/Kconfig

This file was deleted.

50 changes: 0 additions & 50 deletions src/drivers/gnss/septentrio/CMakeLists.txt

This file was deleted.

5 changes: 0 additions & 5 deletions src/drivers/gnss/septentrio/Kconfig

This file was deleted.

6 changes: 0 additions & 6 deletions src/drivers/gnss/septentrio/README.md

This file was deleted.

80 changes: 0 additions & 80 deletions src/drivers/gnss/septentrio/module.h

This file was deleted.

Loading

0 comments on commit d298be9

Please sign in to comment.