mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-03-23 18:13:49 +08:00
docs: uORB messages doc standard tweaks
This commit is contained in:
committed by
Matthias Grob
parent
4ac8ceff31
commit
6bf73d9d89
@@ -17,10 +17,10 @@ VALID_FIELDS = { #Note, also have to add the message types as those can be field
|
||||
'uint32'
|
||||
}
|
||||
|
||||
ALLOWED_UNITS = set(["m", "m/s", "m/s^2", "(m/s)^2", "deg", "deg/s", "rad", "rad/s", "rad^2", "rpm" ,"V", "A", "mA", "mAh", "W", "dBm", "h", "s", "ms", "us", "Ohm", "MB", "Kb/s", "degC","Pa","%","-"])
|
||||
ALLOWED_UNITS = set(["m", "m/s", "m/s^2", "(m/s)^2", "deg", "deg/s", "rad", "rad/s", "rad^2", "rpm" ,"V", "A", "mA", "mAh", "W", "Wh", "dBm", "h", "minutes", "s", "ms", "us", "Ohm", "MB", "Kb/s", "degC","Pa", "%", "norm", "-"])
|
||||
invalid_units = set()
|
||||
ALLOWED_FRAMES = set(["NED","Body"])
|
||||
ALLOWED_INVALID_VALUES = set(["NaN", "0"])
|
||||
ALLOWED_FRAMES = set(["NED", "Body", "FRD", "ENU"])
|
||||
ALLOWED_INVALID_VALUES = set(["NaN", "0", "-1"])
|
||||
ALLOWED_CONSTANTS_NOT_IN_ENUM = set(["ORB_QUEUE_LENGTH","MESSAGE_VERSION"])
|
||||
|
||||
class Error:
|
||||
|
||||
@@ -4,23 +4,23 @@
|
||||
# It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action.
|
||||
# Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules.
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
uint8 action # [@enum ACTION] Requested action
|
||||
uint8 ACTION_DISARM = 0 # Disarm vehicle
|
||||
uint8 ACTION_ARM = 1 # Arm vehicle
|
||||
uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming
|
||||
uint8 ACTION_UNKILL = 3 # Revert a kill action
|
||||
uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors)
|
||||
uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field.
|
||||
uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight
|
||||
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight
|
||||
uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute
|
||||
uint8 action # [@enum ACTION] Requested action
|
||||
uint8 ACTION_DISARM = 0 # Disarm vehicle
|
||||
uint8 ACTION_ARM = 1 # Arm vehicle
|
||||
uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming
|
||||
uint8 ACTION_UNKILL = 3 # Revert a kill action
|
||||
uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors)
|
||||
uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field.
|
||||
uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight
|
||||
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight
|
||||
uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute
|
||||
|
||||
uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture
|
||||
uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position
|
||||
uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position
|
||||
uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held
|
||||
uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism
|
||||
uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture
|
||||
uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position
|
||||
uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position
|
||||
uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held
|
||||
uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism
|
||||
|
||||
uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration.
|
||||
uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration.
|
||||
|
||||
@@ -5,12 +5,12 @@
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
|
||||
|
||||
uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible
|
||||
uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible
|
||||
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 #
|
||||
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
|
||||
|
||||
uint8 NUM_CONTROLS = 12 #
|
||||
float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors)
|
||||
uint8 NUM_CONTROLS = 12
|
||||
float32[12] control # [@range -1, 1] Normalized thrust. Where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors)
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
|
||||
|
||||
uint8 NUM_CONTROLS = 8 #
|
||||
float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed.
|
||||
uint8 NUM_CONTROLS = 8
|
||||
float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed.
|
||||
|
||||
@@ -3,25 +3,24 @@
|
||||
# Provides information about airspeed (indicated, true, calibrated) and the source of the data.
|
||||
# Used by controllers, estimators and for airspeed reporting to operator.
|
||||
|
||||
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS)
|
||||
float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS)
|
||||
float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS)
|
||||
float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS)
|
||||
float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS)
|
||||
float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS)
|
||||
|
||||
int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values
|
||||
int8 SOURCE_DISABLED = -1 # Disabled
|
||||
int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind
|
||||
int8 SOURCE_SENSOR_1 = 1 # Sensor 1
|
||||
int8 SOURCE_SENSOR_2 = 2 # Sensor 2
|
||||
int8 SOURCE_SENSOR_3 = 3 # Sensor 3
|
||||
int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed
|
||||
int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values
|
||||
int8 SOURCE_DISABLED = -1 # Disabled
|
||||
int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind
|
||||
int8 SOURCE_SENSOR_1 = 1 # Sensor 1
|
||||
int8 SOURCE_SENSOR_2 = 2 # Sensor 2
|
||||
int8 SOURCE_SENSOR_3 = 3 # Sensor 3
|
||||
int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed
|
||||
|
||||
float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption
|
||||
float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed
|
||||
float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative
|
||||
float32 throttle_filtered # [-] Filtered fixed-wing throttle
|
||||
float32 pitch_filtered # [rad] Filtered pitch
|
||||
float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption
|
||||
float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed
|
||||
float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative
|
||||
float32 throttle_filtered # [-] Filtered fixed-wing throttle
|
||||
float32 pitch_filtered # [rad] Filtered pitch
|
||||
|
||||
@@ -7,37 +7,37 @@
|
||||
# Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply).
|
||||
# The message is not used by internal/FMU components, as their mode requirements are known at compile time.
|
||||
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # [us] Time since system start.
|
||||
|
||||
uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response
|
||||
uint8 registration_id # [-] Id of external component emitting this response
|
||||
uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response
|
||||
uint8 registration_id # [-] Id of external component emitting this response
|
||||
|
||||
uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies
|
||||
uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies
|
||||
|
||||
uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX]
|
||||
bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX]
|
||||
bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json)
|
||||
|
||||
bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed
|
||||
bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed
|
||||
|
||||
uint8 num_events # Number of queued failure messages (Event) in the events field
|
||||
uint8 num_events # Number of queued failure messages (Event) in the events field
|
||||
|
||||
Event[5] events # Arming failure reasons (Queue of events to report to GCS)
|
||||
Event[5] events # Arming failure reasons (Queue of events to report to GCS)
|
||||
|
||||
# Mode requirements
|
||||
bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope)
|
||||
bool mode_req_attitude # Requires an attitude estimate
|
||||
bool mode_req_local_alt # Requires a local altitude estimate
|
||||
bool mode_req_local_position # Requires a local position estimate
|
||||
bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate
|
||||
bool mode_req_global_position # Requires a global position estimate
|
||||
bool mode_req_global_position_relaxed # Requires a relaxed global position estimate
|
||||
bool mode_req_mission # Requires an uploaded mission
|
||||
bool mode_req_home_position # Requires a home position (such as RTL/Return mode)
|
||||
bool mode_req_prevent_arming # Prevent arming (such as in Land mode)
|
||||
bool mode_req_manual_control # Requires a manual controller
|
||||
bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope)
|
||||
bool mode_req_attitude # Requires an attitude estimate
|
||||
bool mode_req_local_alt # Requires a local altitude estimate
|
||||
bool mode_req_local_position # Requires a local position estimate
|
||||
bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate
|
||||
bool mode_req_global_position # Requires a global position estimate
|
||||
bool mode_req_global_position_relaxed # Requires a relaxed global position estimate
|
||||
bool mode_req_mission # Requires an uploaded mission
|
||||
bool mode_req_home_position # Requires a home position (such as RTL/Return mode)
|
||||
bool mode_req_prevent_arming # Prevent arming (such as in Land mode)
|
||||
bool mode_req_manual_control # Requires a manual controller
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 4
|
||||
uint8 ORB_QUEUE_LENGTH = 4
|
||||
|
||||
@@ -9,8 +9,8 @@
|
||||
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages.
|
||||
uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages.
|
||||
|
||||
uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive)
|
||||
|
||||
@@ -7,73 +7,72 @@
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
uint8 MAX_INSTANCES = 3
|
||||
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold.
|
||||
float32 voltage_v # [V] [@invalid 0] Battery voltage
|
||||
float32 current_a # [A] [@invalid -1] Battery current
|
||||
float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight)
|
||||
float32 discharged_mah # [mAh] [@invalid -1] Discharged amount
|
||||
float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity
|
||||
float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag
|
||||
float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load
|
||||
float32 temperature # [°C] [@invalid NaN] Temperature of the battery
|
||||
uint8 cell_count # [-] [@invalid 0] Number of cells
|
||||
bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold.
|
||||
float32 voltage_v # [V] [@invalid 0] Battery voltage
|
||||
float32 current_a # [A] [@invalid -1] Battery current
|
||||
float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight)
|
||||
float32 discharged_mah # [mAh] [@invalid -1] Discharged amount
|
||||
float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity
|
||||
float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag
|
||||
float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load
|
||||
float32 temperature # [degC] [@invalid NaN] Temperature of the battery
|
||||
uint8 cell_count # [-] [@invalid 0] Number of cells
|
||||
|
||||
uint8 source # [@enum SOURCE] Battery source
|
||||
uint8 SOURCE_POWER_MODULE = 0 # Power module (analog ADC or I2C power monitor)
|
||||
uint8 SOURCE_EXTERNAL = 1 # External (MAVLink, CAN, or external driver)
|
||||
uint8 SOURCE_ESCS = 2 # ESCs (via ESC telemetry)
|
||||
|
||||
uint8 source # [@enum SOURCE] Battery source
|
||||
uint8 SOURCE_POWER_MODULE = 0 # Power module (analog ADC or I2C power monitor)
|
||||
uint8 SOURCE_EXTERNAL = 1 # External (MAVLink, CAN, or external driver)
|
||||
uint8 SOURCE_ESCS = 2 # ESCs (via ESC telemetry)
|
||||
uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
|
||||
uint16 capacity # [mAh] Capacity of the battery when fully charged
|
||||
uint16 cycle_count # [-] Number of discharge cycles the battery has experienced
|
||||
uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge
|
||||
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 # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity
|
||||
uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation
|
||||
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
|
||||
|
||||
uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
|
||||
uint16 capacity # [mAh] Capacity of the battery when fully charged
|
||||
uint16 cycle_count # [-] Number of discharge cycles the battery has experienced
|
||||
uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge
|
||||
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 # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity
|
||||
uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation
|
||||
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
|
||||
float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages
|
||||
float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages
|
||||
|
||||
float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages
|
||||
float32 max_cell_voltage_delta # [V] 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 warning # [@enum WARNING STATE] Current battery warning
|
||||
uint8 WARNING_NONE = 0 # No battery low voltage warning active
|
||||
uint8 WARNING_LOW = 1 # Low voltage warning
|
||||
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately
|
||||
uint8 WARNING_EMERGENCY = 3 # Immediate landing required
|
||||
uint8 WARNING_FAILED = 4 # Battery has failed completely
|
||||
uint8 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 STATE_CHARGING = 7 # Battery is charging
|
||||
|
||||
uint8 warning # [@enum WARNING STATE] Current battery warning
|
||||
uint8 WARNING_NONE = 0 # No battery low voltage warning active
|
||||
uint8 WARNING_LOW = 1 # Low voltage warning
|
||||
uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately
|
||||
uint8 WARNING_EMERGENCY = 3 # Immediate landing required
|
||||
uint8 WARNING_FAILED = 4 # Battery has failed completely
|
||||
uint8 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 STATE_CHARGING = 7 # Battery is charging
|
||||
uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication
|
||||
uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
|
||||
uint8 FAULT_SPIKES = 1 # Voltage spikes
|
||||
uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed
|
||||
uint8 FAULT_OVER_CURRENT = 3 # Over-current
|
||||
uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature
|
||||
uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
|
||||
uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)
|
||||
uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
|
||||
uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
|
||||
uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem
|
||||
uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
|
||||
uint8 FAULT_COUNT = 11 # Counter. Keep this as last element
|
||||
|
||||
uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication
|
||||
uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
|
||||
uint8 FAULT_SPIKES = 1 # Voltage spikes
|
||||
uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed
|
||||
uint8 FAULT_OVER_CURRENT = 3 # Over-current
|
||||
uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature
|
||||
uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
|
||||
uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)
|
||||
uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
|
||||
uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
|
||||
uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem
|
||||
uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
|
||||
uint8 FAULT_COUNT = 11 # Counter. Keep this as last element
|
||||
float32 full_charge_capacity_wh # [Wh] Compensated battery capacity
|
||||
float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining
|
||||
uint16 over_discharge_count # [-] Number of battery overdischarge
|
||||
float32 nominal_voltage # [V] Nominal voltage of the battery pack
|
||||
|
||||
float32 full_charge_capacity_wh # [Wh] Compensated battery capacity
|
||||
float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining
|
||||
uint16 over_discharge_count # [-] Number of battery overdischarge
|
||||
float32 nominal_voltage # [V] Nominal voltage of the battery pack
|
||||
|
||||
float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate
|
||||
float32 ocv_estimate # [V] Open circuit voltage estimate
|
||||
float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate
|
||||
float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate
|
||||
float32 voltage_prediction # [V] Predicted voltage
|
||||
float32 prediction_error # [V] Prediction error
|
||||
float32 estimation_covariance_norm # [-] Norm of the covariance matrix
|
||||
float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate
|
||||
float32 ocv_estimate # [V] Open circuit voltage estimate
|
||||
float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate
|
||||
float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate
|
||||
float32 voltage_prediction # [V] Predicted voltage
|
||||
float32 prediction_error # [V] Prediction error
|
||||
float32 estimation_covariance_norm # [-] Norm of the covariance matrix
|
||||
|
||||
@@ -1,11 +1,12 @@
|
||||
# Fixed Wing Lateral Setpoint message
|
||||
#
|
||||
# Used by the fw_lateral_longitudinal_control module
|
||||
# At least one of course, airspeed_direction, or lateral_acceleration must be finite.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly.
|
||||
float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite.
|
||||
float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite.
|
||||
float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly.
|
||||
float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite.
|
||||
float32 lateral_acceleration # [m/s^2] [@frame FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite.
|
||||
|
||||
@@ -1,14 +1,15 @@
|
||||
# Fixed Wing Longitudinal Setpoint message
|
||||
#
|
||||
# Used by the fw_lateral_longitudinal_control module
|
||||
# If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion.
|
||||
# If both altitude and height_rate are NAN, the controller maintains the current altitude.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite
|
||||
float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not controlled directly
|
||||
float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used
|
||||
float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller
|
||||
float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller
|
||||
float32 altitude # [m] Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite
|
||||
float32 height_rate # [m/s] [@frame ENU] Scalar height rate setpoint. NAN if not controlled directly
|
||||
float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used
|
||||
float32 pitch_direct # [rad] [@range -pi, pi] [@frame FRD] NAN if not controlled, overrides total energy controller
|
||||
float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller
|
||||
|
||||
@@ -1,26 +1,27 @@
|
||||
# Position and (optional) heading setpoints with corresponding speed constraints
|
||||
# Setpoints are intended as inputs to position and heading smoothers, respectively
|
||||
# Setpoints do not need to be kinematically consistent
|
||||
# Optional heading setpoints may be specified as controlled by the respective flag
|
||||
# Unset optional setpoints are not controlled
|
||||
# Unset optional constraints default to vehicle specifications
|
||||
#
|
||||
# Setpoints are intended as inputs to position and heading smoothers, respectively.
|
||||
# Setpoints do not need to be kinematically consistent.
|
||||
# Optional heading setpoints may be specified as controlled by the respective flag.
|
||||
# Unset optional setpoints are not controlled.
|
||||
# Unset optional constraints default to vehicle specifications.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
# setpoints
|
||||
float32[3] position # [m] NED local world frame
|
||||
float32[3] position # [m] [@frame NED] NED local world frame
|
||||
|
||||
bool flag_control_heading # true if heading is to be controlled
|
||||
float32 heading # (optional) [rad] [-pi,pi] from North
|
||||
|
||||
# constraints
|
||||
bool flag_set_max_horizontal_speed # true if setting a non-default horizontal speed limit
|
||||
float32 max_horizontal_speed # (optional) [m/s] maximum speed (absolute) in the NE-plane
|
||||
float32 max_horizontal_speed # [m/s] (optional) Maximum speed (absolute) in the NE-plane
|
||||
|
||||
bool flag_set_max_vertical_speed # true if setting a non-default vertical speed limit
|
||||
float32 max_vertical_speed # (optional) [m/s] maximum speed (absolute) in the D-axis
|
||||
float32 max_vertical_speed # [m/s] (optional) Maximum speed (absolute) in the D-axis
|
||||
|
||||
bool flag_set_max_heading_rate # true if setting a non-default heading rate limit
|
||||
float32 max_heading_rate # (optional) [rad/s] maximum heading rate (absolute)
|
||||
float32 max_heading_rate # [rad/s] (optional) Maximum heading rate (absolute)
|
||||
|
||||
@@ -1,8 +1,9 @@
|
||||
# Fixed Wing Lateral Control Configuration message
|
||||
#
|
||||
# Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY
|
||||
float32 lateral_accel_max # [m/s^2] Currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY
|
||||
|
||||
@@ -1,17 +1,18 @@
|
||||
# Fixed Wing Longitudinal Control Configuration message
|
||||
#
|
||||
# Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages
|
||||
# and configure the resultant setpoints.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 pitch_min # [rad][@range -pi, pi] defaults to FW_P_LIM_MIN if NAN.
|
||||
float32 pitch_max # [rad][@range -pi, pi] defaults to FW_P_LIM_MAX if NAN.
|
||||
float32 throttle_min # [norm] [@range 0,1] deaults to FW_THR_MIN if NAN.
|
||||
float32 throttle_max # [norm] [@range 0,1] defaults to FW_THR_MAX if NAN.
|
||||
float32 climb_rate_target # [m/s] target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint.
|
||||
float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint.
|
||||
float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only
|
||||
bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking
|
||||
bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller
|
||||
float32 pitch_min # [rad] [@range -pi, pi] Defaults to FW_P_LIM_MIN if NAN.
|
||||
float32 pitch_max # [rad] [@range -pi, pi] Defaults to FW_P_LIM_MAX if NAN.
|
||||
float32 throttle_min # [norm] [@range 0,1] Defaults to FW_THR_MIN if NAN.
|
||||
float32 throttle_max # [norm] [@range 0,1] Defaults to FW_THR_MAX if NAN.
|
||||
float32 climb_rate_target # [m/s] Target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint.
|
||||
float32 sink_rate_target # [m/s] Target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint.
|
||||
float32 speed_weight # [-] [@range 0,2] 0=pitch controls altitude only, 2=pitch controls airspeed only
|
||||
bool enforce_low_height_condition # If true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking
|
||||
bool disable_underspeed_protection # If true, underspeed handling is disabled in the altitude controller
|
||||
|
||||
Reference in New Issue
Block a user