Skip to content

Commit

Permalink
Update message definitions Fri Nov 3 16:02:34 UTC 2023
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Nov 3, 2023
1 parent 46e8a97 commit 8921ebc
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 2 deletions.
2 changes: 1 addition & 1 deletion msg/EstimatorStates.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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
8 changes: 8 additions & 0 deletions msg/FigureEightStatus.msg
Original file line number Diff line number Diff line change
@@ -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.
8 changes: 7 additions & 1 deletion msg/PositionSetpoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -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

Expand Down
1 change: 1 addition & 0 deletions msg/VehicleCommand.msg
Original file line number Diff line number Diff line change
Expand Up @@ -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|
Expand Down

0 comments on commit 8921ebc

Please sign in to comment.