From 8921ebcd9b841f242059d7b9d3378082ce6f3291 Mon Sep 17 00:00:00 2001 From: PX4 BuildBot Date: Fri, 3 Nov 2023 16:02:34 +0000 Subject: [PATCH] Update message definitions Fri Nov 3 16:02:34 UTC 2023 --- msg/EstimatorStates.msg | 2 +- msg/FigureEightStatus.msg | 8 ++++++++ msg/PositionSetpoint.msg | 8 +++++++- msg/VehicleCommand.msg | 1 + 4 files changed, 17 insertions(+), 2 deletions(-) create mode 100644 msg/FigureEightStatus.msg diff --git a/msg/EstimatorStates.msg b/msg/EstimatorStates.msg index f4e3f0f2..787a005f 100644 --- a/msg/EstimatorStates.msg +++ b/msg/EstimatorStates.msg @@ -4,4 +4,4 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds) float32[24] states # Internal filter states uint8 n_states # Number of states effectively used -float32[24] covariances # Diagonal Elements of Covariance Matrix +float32[23] covariances # Diagonal Elements of Covariance Matrix diff --git a/msg/FigureEightStatus.msg b/msg/FigureEightStatus.msg new file mode 100644 index 00000000..e14d8f0d --- /dev/null +++ b/msg/FigureEightStatus.msg @@ -0,0 +1,8 @@ +uint64 timestamp # time since system start (microseconds) +float32 major_radius # Major axis radius of the figure eight [m]. Positive values orbit clockwise, negative values orbit counter-clockwise. +float32 minor_radius # Minor axis radius of the figure eight [m]. +float32 orientation # Orientation of the major axis of the figure eight [rad]. +uint8 frame # The coordinate system of the fields: x, y, z. +int32 x # X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. +int32 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7. +float32 z # Altitude of center point. Coordinate system depends on frame field. diff --git a/msg/PositionSetpoint.msg b/msg/PositionSetpoint.msg index 2323a67b..268e4b93 100644 --- a/msg/PositionSetpoint.msg +++ b/msg/PositionSetpoint.msg @@ -9,6 +9,9 @@ uint8 SETPOINT_TYPE_TAKEOFF=3 # takeoff setpoint uint8 SETPOINT_TYPE_LAND=4 # land setpoint, altitude must be ignored, descend until landing uint8 SETPOINT_TYPE_IDLE=5 # do nothing, switch off motors or keep at idle speed (MC) +uint8 LOITER_TYPE_ORBIT=0 # Circular pattern +uint8 LOITER_TYPE_FIGUREEIGHT=1 # Pattern resembling an 8 + bool valid # true if setpoint is valid uint8 type # setpoint type to adjust behavior of position controller @@ -25,8 +28,11 @@ bool yaw_valid # true if yaw setpoint valid float32 yawspeed # yawspeed (only for multirotors, in rad/s) bool yawspeed_valid # true if yawspeed setpoint valid -float32 loiter_radius # loiter radius (only for fixed wing), in m +float32 loiter_radius # loiter major axis radius in m +float32 loiter_minor_radius # loiter minor axis radius (used for non-circular loiter shapes) in m bool loiter_direction_counter_clockwise # loiter direction is clockwise by default and can be changed using this field +float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi) +uint8 loiter_pattern # loitern pattern to follow float32 acceptance_radius # navigation acceptance_radius if we're doing waypoint navigation diff --git a/msg/VehicleCommand.msg b/msg/VehicleCommand.msg index 19e2761c..9ded9095 100644 --- a/msg/VehicleCommand.msg +++ b/msg/VehicleCommand.msg @@ -15,6 +15,7 @@ uint16 VEHICLE_CMD_NAV_LAND = 21 # Land at location |Empty| Empty| Empty| Desi uint16 VEHICLE_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| uint16 VEHICLE_CMD_NAV_PRECLAND = 23 # Attempt a precision landing uint16 VEHICLE_CMD_DO_ORBIT = 34 # Start orbiting on the circumference of a circle defined by the parameters. |Radius [m] |Velocity [m/s] |Yaw behaviour |Empty |Latitude/X |Longitude/Y |Altitude/Z | +uint16 VEHICLE_CMD_DO_FIGUREEIGHT = 35 # Start flying on the outline of a figure eight defined by the parameters. |Major Radius [m] |Minor Radius [m] |Velocity [m/s] |Orientation |Latitude/X |Longitude/Y |Altitude/Z | uint16 VEHICLE_CMD_NAV_ROI = 80 # Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| uint16 VEHICLE_CMD_NAV_PATHPLANNING = 81 # Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| uint16 VEHICLE_CMD_NAV_VTOL_TAKEOFF = 84 # Takeoff from ground / hand and transition to fixed wing |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|