Skip to content

Commit

Permalink
Merge branch 'main' into display-x11-docker
Browse files Browse the repository at this point in the history
  • Loading branch information
Martin-Schlodinski authored Sep 8, 2024
2 parents 8edbd42 + bb0210e commit 0b40c1a
Show file tree
Hide file tree
Showing 119 changed files with 3,235 additions and 1,613 deletions.
1 change: 1 addition & 0 deletions .ci/Jenkinsfile-compile
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ pipeline {
"matek_h743-mini_default",
"matek_h743-slim_default",
"matek_h743_default",
"micoair_h743_default",
"modalai_fc-v1_default",
"modalai_fc-v2_default",
"mro_ctrl-zero-classic_default",
Expand Down
5 changes: 5 additions & 0 deletions .vscode/cmake-variants.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,11 @@ CONFIG:
buildType: MiniSizeRel
settings:
CONFIG: matek_gnss-m9n-f4_default
micoair_h743_default:
short: micoair_h743
buildType: MinSizeRel
settings:
CONFIG: micoair_h743_default
modalai_fc-v1_default:
short: modalai_fc-v1
buildType: MinSizeRel
Expand Down
1 change: 1 addition & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -340,6 +340,7 @@ bootloaders_update: \
matek_h743_bootloader \
matek_h743-mini_bootloader \
matek_h743-slim_bootloader \
micoair_h743_bootloader \
modalai_fc-v2_bootloader \
mro_ctrl-zero-classic_bootloader \
mro_ctrl-zero-h7_bootloader \
Expand Down
12 changes: 7 additions & 5 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,17 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge
# Rover parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAN_YAW_SCALE 0.1
param set-default RD_YAW_RATE_I 0.1
param set-default RD_YAW_RATE_P 5
param set-default RD_MAX_ACCEL 6
param set-default RD_MAX_JERK 30
param set-default RD_MAX_SPEED 7
param set-default RD_HEADING_P 5
param set-default RD_HEADING_I 0.1
param set-default RD_YAW_RATE_P 5
param set-default RD_YAW_RATE_I 0
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0
param set-default RD_SPEED_P 1
param set-default RD_SPEED_I 0
param set-default RD_MAX_YAW_RATE 180
param set-default RD_MISS_SPD_DEF 7
param set-default RD_MISS_SPD_DEF 5
param set-default RD_TRANS_DRV_TRN 0.349066
param set-default RD_TRANS_TRN_DRV 0.174533

Expand Down
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ param set-default RD_YAW_RATE_P 5
param set-default RD_MAX_ACCEL 1
param set-default RD_MAX_JERK 3
param set-default RD_MAX_SPEED 8
param set-default RD_HEADING_P 5
param set-default RD_HEADING_I 0.1
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0.1
param set-default RD_MAX_YAW_RATE 30
param set-default RD_MISS_SPD_DEF 8
param set-default RD_TRANS_DRV_TRN 0.349066
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#!/bin/sh
#
# @name Gazebo x500 mono cam
#
# @type Quadrotor
#

PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_mono_cam_down}

. ${R}etc/init.d-posix/airframes/4001_gz_x500
1 change: 1 addition & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ px4_add_romfs_files(
4011_gz_lawnmower
4012_gz_rover_ackermann
4013_gz_x500_lidar
4014_gz_x500_mono_cam_down

6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
Expand Down
22 changes: 22 additions & 0 deletions ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover
Original file line number Diff line number Diff line change
Expand Up @@ -20,3 +20,25 @@ param set-default RBCLW_ADDRESS 128
param set-default RBCLW_FUNC1 101
param set-default RBCLW_FUNC2 102
param set-default RBCLW_REV 1 # reverse right wheels

# Rover parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAN_YAW_SCALE 1
param set-default RD_MAX_ACCEL 5
param set-default RD_MAX_JERK 50
param set-default RD_MAX_SPEED 2
param set-default RD_YAW_RATE_P 0.1
param set-default RD_YAW_RATE_I 0
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0
param set-default RD_SPEED_P 0.5
param set-default RD_SPEED_I 0.1
param set-default RD_MAX_YAW_RATE 300
param set-default RD_MISS_SPD_DEF 1.8
param set-default RD_TRANS_DRV_TRN 0.349066
param set-default RD_TRANS_TRN_DRV 0.174533

# Pure pursuit parameters
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
param set-default PP_LOOKAHD_GAIN 1
2 changes: 1 addition & 1 deletion Tools/setup/ubuntu.sh
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ if [[ $INSTALL_SIM == "true" ]]; then

# Gazebo / Gazebo classic installation
if [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
echo "Gazebo (Garden) will be installed"
echo "Gazebo (Harmonic) will be installed"
echo "Earlier versions will be removed"
# Add Gazebo binary repository
sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
Expand Down
2 changes: 0 additions & 2 deletions boards/ark/fmu-v6x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,6 @@ CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
Expand Down
3 changes: 0 additions & 3 deletions boards/cuav/x7pro/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
Expand All @@ -91,12 +90,10 @@ CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
2 changes: 2 additions & 0 deletions boards/px4/fmu-v4pro/test.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_BOARD_TESTING=y
Expand Down
2 changes: 2 additions & 0 deletions boards/px4/fmu-v5/cryptotest.px4board
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_BOARD_CRYPTO=y
CONFIG_DRIVERS_STUB_KEYSTORE=y
CONFIG_DRIVERS_SW_CRYPTO=y
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v5x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_INS=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v6x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -377,7 +377,6 @@
*(.text._ZN19StickAccelerationXYC1EP12ModuleParams)
*(.text.imxrt_epsubmit)
*(.text._ZN15PositionControl6updateEf)
*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE)
*(.text._ZN23MavlinkStreamScaledIMU24sendEv)
*(.text._ZN5PX4IO10io_reg_getEhhPtj)
*(.text.imxrt_dma_send)
Expand Down
2 changes: 1 addition & 1 deletion msg/ActionRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7

uint8 source # how the request was triggered
uint8 SOURCE_RC_STICK_GESTURE = 0
uint8 SOURCE_STICK_GESTURE = 0
uint8 SOURCE_RC_SWITCH = 1
uint8 SOURCE_RC_BUTTON = 2
uint8 SOURCE_RC_MODE_SLOT = 3
Expand Down
100 changes: 50 additions & 50 deletions msg/BatteryStatus.msg
Original file line number Diff line number Diff line change
@@ -1,67 +1,67 @@
uint64 timestamp # time since system start (microseconds)
bool connected # Whether or not a battery is connected, based on a voltage threshold
float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown
float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown
float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown
float32 temperature # temperature of the battery. NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown
uint64 timestamp # time since system start (microseconds)
bool connected # Whether or not a battery is connected, based on a voltage threshold
float32 voltage_v # Battery voltage in volts, 0 if unknown
float32 current_a # Battery current in amperes, -1 if unknown
float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown
float32 discharged_mah # Discharged amount in mAh, -1 if unknown
float32 remaining # From 1 to 0, -1 if unknown
float32 scale # Power scaling factor, >= 1, or -1 if unknown
float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown
float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown

uint8 BATTERY_SOURCE_POWER_MODULE = 0
uint8 BATTERY_SOURCE_EXTERNAL = 1
uint8 BATTERY_SOURCE_ESCS = 2
uint8 source # Battery source
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
uint16 cycle_count # number of discharge cycles the battery has experienced
uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min
uint16 serial_number # serial number of the battery pack
uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%.
uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100%
uint8 source # Battery source
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
uint16 cycle_count # number of discharge cycles the battery has experienced
uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min
uint16 serial_number # serial number of the battery pack
uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512
uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%.
uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100%
uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed.
uint16 interface_error # interface error counter
uint16 interface_error # interface error counter

float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown
float32 max_cell_voltage_delta # Max difference between individual cell voltages
float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown
float32 max_cell_voltage_delta # Max difference between individual cell voltages

bool is_powering_off # Power off event imminent indication, false if unknown
bool is_required # Set if the battery is explicitly required before arming
bool is_powering_off # Power off event imminent indication, false if unknown
bool is_required # Set if the battery is explicitly required before arming


uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage
uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
uint8 BATTERY_WARNING_EMERGENCY = 3 # immediate landing required
uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely
uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging
uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage
uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
uint8 BATTERY_WARNING_EMERGENCY = 3 # immediate landing required
uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely
uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging

uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes
uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed
uint8 BATTERY_FAULT_OVER_CURRENT = 3 # Over-current
uint8 BATTERY_FAULT_OVER_TEMPERATURE = 4 # Over-temperature
uint8 BATTERY_FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with battery one
uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem
uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element!
uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes
uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed
uint8 BATTERY_FAULT_OVER_CURRENT = 3 # Over-current
uint8 BATTERY_FAULT_OVER_TEMPERATURE = 4 # Over-temperature
uint8 BATTERY_FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with battery one
uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem
uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element!

uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint8 warning # Current battery warning
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint8 warning # Current battery warning

uint8 MAX_INSTANCES = 4

float32 full_charge_capacity_wh # The compensated battery capacity
float32 remaining_capacity_wh # The compensated battery capacity remaining
uint16 over_discharge_count # Number of battery overdischarge
float32 nominal_voltage # Nominal voltage of the battery pack
float32 full_charge_capacity_wh # The compensated battery capacity
float32 remaining_capacity_wh # The compensated battery capacity remaining
uint16 over_discharge_count # Number of battery overdischarge
float32 nominal_voltage # Nominal voltage of the battery pack

float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate
float32 ocv_estimate # [V] Open circuit voltage estimate
Expand Down
5 changes: 5 additions & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,10 @@ set(msg_files
ObstacleDistance.msg
OffboardControlMode.msg
OnboardComputerStatus.msg
OpenDroneIdArmStatus.msg
OpenDroneIdOperatorId.msg
OpenDroneIdSelfId.msg
OpenDroneIdSystem.msg
OrbitStatus.msg
OrbTest.msg
OrbTestLarge.msg
Expand Down Expand Up @@ -182,6 +186,7 @@ set(msg_files
RoverAckermannGuidanceStatus.msg
RoverAckermannStatus.msg
RoverDifferentialGuidanceStatus.msg
RoverDifferentialSetpoint.msg
RoverDifferentialStatus.msg
Rpm.msg
RtlStatus.msg
Expand Down
5 changes: 5 additions & 0 deletions msg/DistanceSensor.msg
Original file line number Diff line number Diff line change
Expand Up @@ -40,3 +40,8 @@ uint8 ROTATION_UPWARD_FACING = 24 # MAV_SENSOR_ROTATION_PITCH_90
uint8 ROTATION_DOWNWARD_FACING = 25 # MAV_SENSOR_ROTATION_PITCH_270

uint8 ROTATION_CUSTOM = 100 # MAV_SENSOR_ROTATION_CUSTOM

uint8 mode # mode of operation
uint8 DISTANCE_SENSOR_MODE_UNKNOWN = 0 # Unknown mode
uint8 DISTANCE_SENSOR_MODE_RUN = 1 # sensor is running continuosly
uint8 DISTANCE_SENSOR_MODE_DISABLED = 2 # sensor is disabled per request
1 change: 0 additions & 1 deletion msg/EstimatorStatusFlags.msg
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ bool fs_bad_airspeed # 5 - true if fusion of the airspeed has encounte
bool fs_bad_sideslip # 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis has encountered a numerical error
bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error
bool fs_bad_acc_bias # 9 - true if bad delta velocity bias estimates have been detected
bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected
bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing)

Expand Down
3 changes: 3 additions & 0 deletions msg/OpenDroneIdArmStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
uint64 timestamp
uint8 status
char[50] error
4 changes: 4 additions & 0 deletions msg/OpenDroneIdOperatorId.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
uint64 timestamp
uint8[20] id_or_mac
uint8 operator_id_type
char[20] operator_id
4 changes: 4 additions & 0 deletions msg/OpenDroneIdSelfId.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
uint64 timestamp
uint8[20] id_or_mac
uint8 description_type
char[23] description
13 changes: 13 additions & 0 deletions msg/OpenDroneIdSystem.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
uint64 timestamp
uint8[20] id_or_mac
uint8 operator_location_type
uint8 classification_type
int32 operator_latitude
int32 operator_longitude
uint16 area_count
uint16 area_radius
float32 area_ceiling
float32 area_floor
uint8 category_eu
uint8 class_eu
float32 operator_altitude_geo
3 changes: 0 additions & 3 deletions msg/RoverDifferentialGuidanceStatus.msg
Original file line number Diff line number Diff line change
@@ -1,10 +1,7 @@
uint64 timestamp # time since system start (microseconds)

float32 desired_speed # [m/s] Desired forward speed for the rover
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error_deg # [deg] Heading error of the pure pursuit controller
float32 pid_heading_integral # Integral of the PID for the desired yaw rate during missions
float32 pid_throttle_integral # Integral of the PID for the throttle during missions
uint8 state_machine # Driving state of the rover [0: SPOT_TURNING, 1: DRIVING, 2: GOAL_REACHED]

# TOPICS rover_differential_guidance_status
9 changes: 9 additions & 0 deletions msg/RoverDifferentialSetpoint.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
uint64 timestamp # time since system start (microseconds)

float32 forward_speed_setpoint # [m/s] Desired forward speed for the rover
float32 forward_speed_setpoint_normalized # [-1, 1] Normalized forward speed for the rover
float32 yaw_rate_setpoint # [rad/s] Desired yaw rate for the rover (Overriden by yaw controller if yaw_setpoint is used)
float32 yaw_rate_setpoint_normalized # [-1, 1] Normalized yaw rate for the rover
float32 yaw_setpoint # [rad] Desired yaw (heading) for the rover

# TOPICS rover_differential_setpoint
Loading

0 comments on commit 0b40c1a

Please sign in to comment.