Browse Source

beautify some identation

sbg
TSC21 7 years ago committed by Beat Küng
parent
commit
86baa6a90a
  1. 4
      msg/actuator_outputs.msg
  2. 2
      msg/airspeed.msg
  3. 14
      msg/ekf2_innovations.msg
  4. 2
      msg/ekf2_timestamps.msg
  5. 2
      msg/esc_report.msg
  6. 2
      msg/esc_status.msg
  7. 2
      msg/home_position.msg
  8. 4
      msg/manual_control_setpoint.msg
  9. 2
      msg/mission.msg
  10. 2
      msg/mission_result.msg
  11. 4
      msg/mount_orientation.msg
  12. 2
      msg/parameter_update.msg
  13. 2
      msg/position_setpoint.msg
  14. 2
      msg/sensor_accel.msg
  15. 4
      msg/sensor_combined.msg
  16. 20
      msg/ulog_stream.msg
  17. 4
      msg/vehicle_air_data.msg
  18. 8
      msg/vehicle_attitude.msg
  19. 32
      msg/vehicle_attitude_setpoint.msg
  20. 2
      msg/vehicle_command.msg
  21. 2
      msg/vehicle_constraints.msg
  22. 6
      msg/vehicle_land_detected.msg
  23. 16
      msg/vehicle_local_position_setpoint.msg
  24. 10
      msg/vehicle_rates_setpoint.msg
  25. 12
      msg/vehicle_roi.msg
  26. 2
      msg/vehicle_status.msg
  27. 2
      msg/vehicle_status_flags.msg
  28. 4
      msg/vtol_vehicle_status.msg

4
msg/actuator_outputs.msg

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 NUM_ACTUATOR_OUTPUTS = 16
uint8 NUM_ACTUATOR_OUTPUT_GROUPS = 4 # for sanity checking
uint32 noutputs # valid outputs
float32[16] output # output data, in natural output units
float32[16] output # output data, in natural output units

2
msg/airspeed.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float32 indicated_airspeed_m_s # indicated airspeed in m/s

14
msg/ekf2_innovations.msg

@ -1,11 +1,11 @@ @@ -1,11 +1,11 @@
uint64 timestamp # time since system start (microseconds)
float32[6] vel_pos_innov # velocity and position innovations
float32[3] mag_innov # earth magnetic field innovations
float32 heading_innov # heading innovation
float32 airspeed_innov # airspeed innovation
float32 beta_innov # synthetic sideslip innovation
float32[2] flow_innov # flow innovation
float32 hagl_innov # innovation from the terrain estimator for the height above ground level measurement (m)
float32[6] vel_pos_innov # velocity and position innovations
float32[3] mag_innov # earth magnetic field innovations
float32 heading_innov # heading innovation
float32 airspeed_innov # airspeed innovation
float32 beta_innov # synthetic sideslip innovation
float32[2] flow_innov # flow innovation
float32 hagl_innov # innovation from the terrain estimator for the height above ground level measurement (m)
float32[6] vel_pos_innov_var # velocity and position innovation variances
float32[3] mag_innov_var # earth magnetic field innovation variance
float32 heading_innov_var # heading innovation variance

2
msg/ekf2_timestamps.msg

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
# the timestamp field is the ekf2 reference time and matches the timestamp of
# the sensor_combined topic.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
int16 RELATIVE_TIMESTAMP_INVALID = 32767 # (0x7fff) If one of the relative timestamps
# is set to this value, it means the associated sensor values did not update

2
msg/esc_report.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 esc_vendor # Vendor of current ESC
uint32 esc_errorcount # Number of reported errors by ESC - if supported
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported

2
msg/esc_status.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs
uint8 ESC_VENDOR_GENERIC = 0 # generic ESC

2
msg/home_position.msg

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
# GPS home position in WGS84 coordinates.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude in degrees
float64 lon # Longitude in degrees

4
msg/manual_control_setpoint.msg

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 SWITCH_POS_NONE = 0 # switch is not mapped
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0)
uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1)
int8 MODE_SLOT_NONE = -1 # no mode slot assigned

2
msg/mission.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1
uint16 count # count of the missions stored in the dataman

2
msg/mission_result.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 MISSION_EXECUTION_MODE_NORMAL = 0 # Execute the mission according to the planned items
uint8 MISSION_EXECUTION_MODE_REVERSE = 1 # Execute the mission in reverse order, ignoring commands and converting all waypoints to normal ones
uint8 MISSION_EXECUTION_MODE_FAST_FORWARD = 2 # Execute the mission as fast as possible, for example converting loiter waypoints to normal ones

4
msg/mount_orientation.msg

@ -1,2 +1,2 @@ @@ -1,2 +1,2 @@
uint64 timestamp # time since system start (microseconds)
float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad
uint64 timestamp # time since system start (microseconds)
float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad

2
msg/parameter_update.msg

@ -2,4 +2,4 @@ @@ -2,4 +2,4 @@
uint64 timestamp # time since system start (microseconds)
uint32 instance # Instance count - constantly incrementing
uint32 instance # Instance count - constantly incrementing

2
msg/position_setpoint.msg

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
# this file is only used in the position_setpoint triple as a dependency
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 SETPOINT_TYPE_POSITION=0 # position setpoint
uint8 SETPOINT_TYPE_VELOCITY=1 # velocity setpoint

2
msg/sensor_accel.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
uint64 error_count

4
msg/sensor_combined.msg

@ -5,9 +5,9 @@ @@ -5,9 +5,9 @@
# change with board revisions and sensor updates.
#
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
int32 RELATIVE_TIMESTAMP_INVALID = 2147483647 # (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid
# gyro timstamp is equal to the timestamp of the message
float32[3] gyro_rad # average angular rate measured in the XYZ body frame in rad/s over the last gyro sampling period

20
msg/ulog_stream.msg

@ -4,14 +4,14 @@ @@ -4,14 +4,14 @@
uint64 timestamp # time since system start (microseconds)
# flags bitmasks
uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked.
# Acked messages are published synchronous: a
# publisher waits for an ack before sending the
# next message
uint8 FLAGS_NEED_ACK = 1 # if set, this message requires to be acked.
# Acked messages are published synchronous: a
# publisher waits for an ack before sending the
# next message
uint8 length # length of data
uint8 first_message_offset # offset into data where first message starts. This
# can be used for recovery, when a previous message got lost
uint16 sequence # allows determine drops
uint8 flags # see FLAGS_*
uint8[249] data # ulog data
uint8 length # length of data
uint8 first_message_offset # offset into data where first message starts. This
# can be used for recovery, when a previous message got lost
uint16 sequence # allows determine drops
uint8 flags # see FLAGS_*
uint8[249] data # ulog data

4
msg/vehicle_air_data.msg

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH.
float32 baro_temp_celcius # Temperature in degrees celsius
float32 baro_pressure_pa # Absolute pressure in pascals
float32 rho # air density
float32 rho # air density

8
msg/vehicle_attitude.msg

@ -2,11 +2,11 @@ @@ -2,11 +2,11 @@
uint64 timestamp # time since system start (microseconds)
float32 rollspeed # Bias corrected angular velocity about X body axis in rad/s
float32 pitchspeed # Bias corrected angular velocity about Y body axis in rad/s
float32 yawspeed # Bias corrected angular velocity about Z body axis in rad/s
float32 rollspeed # Bias corrected angular velocity about X body axis in rad/s
float32 pitchspeed # Bias corrected angular velocity about Y body axis in rad/s
float32 yawspeed # Bias corrected angular velocity about Z body axis in rad/s
float32[4] q # Quaternion rotation from NED earth frame to XYZ body frame
float32[4] q # Quaternion rotation from NED earth frame to XYZ body frame
float32[4] delta_q_reset # Amount by which quaternion has changed during last reset
uint8 quat_reset_counter # Quaternion reset counter

32
msg/vehicle_attitude_setpoint.msg

@ -2,29 +2,29 @@ uint64 timestamp # time since system start (microseconds) @@ -2,29 +2,29 @@ uint64 timestamp # time since system start (microseconds)
int8 LANDING_GEAR_UP = 1 # landing gear up
int8 LANDING_GEAR_DOWN = -1 # landing gear down
float32 roll_body # body angle in NED frame
float32 pitch_body # body angle in NED frame
float32 yaw_body # body angle in NED frame
float32 roll_body # body angle in NED frame
float32 pitch_body # body angle in NED frame
float32 yaw_body # body angle in NED frame
float32 yaw_sp_move_rate # rad/s (commanded by user)
float32 yaw_sp_move_rate # rad/s (commanded by user)
# For quaternion-based attitude control
float32[4] q_d # Desired quaternion for quaternion control
bool q_d_valid # Set to true if quaternion vector is valid
float32[4] q_d # Desired quaternion for quaternion control
bool q_d_valid # Set to true if quaternion vector is valid
float32 thrust # Thrust in Newton the power system should generate
float32 thrust # Thrust in Newton the power system should generate
bool roll_reset_integral # Reset roll integral part (navigation logic change)
bool pitch_reset_integral # Reset pitch integral part (navigation logic change)
bool yaw_reset_integral # Reset yaw integral part (navigation logic change)
bool roll_reset_integral # Reset roll integral part (navigation logic change)
bool pitch_reset_integral # Reset pitch integral part (navigation logic change)
bool yaw_reset_integral # Reset yaw integral part (navigation logic change)
bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway)
bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode)
bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway)
bool disable_mc_yaw_control # control yaw for mc (used for vtol weather-vane mode)
uint8 apply_flaps # flap config specifier
uint8 FLAPS_OFF = 0 # no flaps
uint8 FLAPS_LAND = 1 # landing config flaps
uint8 FLAPS_TAKEOFF = 2 # take-off config flaps
uint8 apply_flaps # flap config specifier
uint8 FLAPS_OFF = 0 # no flaps
uint8 FLAPS_LAND = 1 # landing config flaps
uint8 FLAPS_TAKEOFF = 2 # take-off config flaps
float32 landing_gear

2
msg/vehicle_command.msg

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint16 VEHICLE_CMD_CUSTOM_0 = 0 # test command
uint16 VEHICLE_CMD_CUSTOM_1 = 1 # test command

2
msg/vehicle_constraints.msg

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
# Local setpoint constraints in NED frame
# setting something to NaN means that no limit is provided
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float32 yawspeed # in radians/sec
float32 speed_xy # in meters/sec

6
msg/vehicle_land_detected.msg

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
uint64 timestamp # time since system start (microseconds)
bool landed # true if vehicle is currently landed on the ground
bool freefall # true if vehicle is currently in free-fall
bool ground_contact # true if vehicle has ground contact but is not landed
bool maybe_landed # true if the vehicle might have landed
bool freefall # true if vehicle is currently in free-fall
bool ground_contact # true if vehicle has ground contact but is not landed
bool maybe_landed # true if the vehicle might have landed
float32 alt_max # maximum altitude in [m] that can be reached

16
msg/vehicle_local_position_setpoint.msg

@ -1,16 +1,16 @@ @@ -1,16 +1,16 @@
# Local position setpoint in NED frame
# setting something to NaN means the state should not be controlled
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float32 x # in meters NED
float32 y # in meters NED
float32 z # in meters NED
float32 yaw # in radians NED -PI..+PI
float32 x # in meters NED
float32 y # in meters NED
float32 z # in meters NED
float32 yaw # in radians NED -PI..+PI
float32 yawspeed # in radians/sec
float32 vx # in meters/sec
float32 vy # in meters/sec
float32 vz # in meters/sec
float32 vx # in meters/sec
float32 vy # in meters/sec
float32 vz # in meters/sec
float32 acc_x # in meters/(sec*sec)
float32 acc_y # in meters/(sec*sec)
float32 acc_z # in meters/(sec*sec)

10
msg/vehicle_rates_setpoint.msg

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
float32 roll # body angular rates in NED frame
float32 pitch # body angular rates in NED frame
float32 yaw # body angular rates in NED frame
float32 thrust # thrust normalized to 0..1
float32 roll # body angular rates in NED frame
float32 pitch # body angular rates in NED frame
float32 yaw # body angular rates in NED frame
float32 thrust # thrust normalized to 0..1
# TOPICS vehicle_rates_setpoint mc_virtual_rates_setpoint fw_virtual_rates_setpoint

12
msg/vehicle_roi.msg

@ -1,12 +1,12 @@ @@ -1,12 +1,12 @@
# Vehicle Region Of Interest (ROI)
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 ROI_NONE = 0 # No region of interest
uint8 ROI_WPNEXT = 1 # Point toward next MISSION with optional offset
uint8 ROI_WPINDEX = 2 # Point toward given MISSION
uint8 ROI_LOCATION = 3 # Point toward fixed location
uint8 ROI_TARGET = 4 # Point toward target
uint8 ROI_NONE = 0 # No region of interest
uint8 ROI_WPNEXT = 1 # Point toward next MISSION with optional offset
uint8 ROI_WPINDEX = 2 # Point toward given MISSION
uint8 ROI_LOCATION = 3 # Point toward fixed location
uint8 ROI_TARGET = 4 # Point toward target
uint8 ROI_ENUM_END = 5
uint8 mode # ROI mode (see above)

2
msg/vehicle_status.msg

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
# If you change the order, add or remove arming_state_t states make sure to update the arrays
# in state_machine_helper.cpp as well.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
uint8 ARMING_STATE_INIT = 0
uint8 ARMING_STATE_STANDBY = 1

2
msg/vehicle_status_flags.msg

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
# This is a struct used by the commander internally.
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
bool condition_calibration_enabled
bool condition_system_sensors_initialized

4
msg/vtol_vehicle_status.msg

@ -5,10 +5,10 @@ uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2 @@ -5,10 +5,10 @@ uint8 VEHICLE_VTOL_STATE_TRANSITION_TO_MC = 2
uint8 VEHICLE_VTOL_STATE_MC = 3
uint8 VEHICLE_VTOL_STATE_FW = 4
uint64 timestamp # time since system start (microseconds)
uint64 timestamp # time since system start (microseconds)
bool vtol_in_rw_mode # true: vtol vehicle is in rotating wing mode
bool vtol_in_trans_mode
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
bool vtol_transition_failsafe # vtol in transition failsafe mode
bool vtol_transition_failsafe # vtol in transition failsafe mode
bool fw_permanent_stab # In fw mode stabilize attitude even if in manual mode

Loading…
Cancel
Save