aboutsummaryrefslogtreecommitdiff
path: root/msg
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-28 07:54:58 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-28 16:31:19 +0100
commitc67cb25f9a4cb4ec507029865dd70837417ef894 (patch)
treee28ab7be748639e6bf66fbaa52ddbbf913162d6a /msg
parent856b10cc1a5a36a7b7d2978477185155792366c2 (diff)
downloadpx4-firmware-c67cb25f9a4cb4ec507029865dd70837417ef894.tar.gz
px4-firmware-c67cb25f9a4cb4ec507029865dd70837417ef894.tar.bz2
px4-firmware-c67cb25f9a4cb4ec507029865dd70837417ef894.zip
port more uorb headers to msg
Diffstat (limited to 'msg')
-rw-r--r--msg/position_setpoint.msg35
-rw-r--r--msg/position_setpoint_triplet.msg8
-rw-r--r--msg/vehicle_global_velocity_setpoint.msg4
-rw-r--r--msg/vehicle_local_position.msg36
-rw-r--r--msg/vehicle_local_position_setpoint.msg7
5 files changed, 90 insertions, 0 deletions
diff --git a/msg/position_setpoint.msg b/msg/position_setpoint.msg
new file mode 100644
index 000000000..ae6756aa8
--- /dev/null
+++ b/msg/position_setpoint.msg
@@ -0,0 +1,35 @@
+# this file is only used in the position_setpoint triple as a dependency
+
+uint8 SETPOINT_TYPE_POSITION=0 # position setpoint
+uint8 SETPOINT_TYPE_VELOCITY=1 # velocity setpoint
+uint8 SETPOINT_TYPE_LOITER=2 # loiter setpoint
+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 SETPOINT_TYPE_OFFBOARD=6 # setpoint in NED frame (x, y, z, vx, vy, vz) set by offboard
+
+bool valid # true if setpoint is valid
+uint8 type # setpoint type to adjust behavior of position controller
+float32 x # local position setpoint in m in NED
+float32 y # local position setpoint in m in NED
+float32 z # local position setpoint in m in NED
+bool position_valid # true if local position setpoint valid
+float32 vx # local velocity setpoint in m/s in NED
+float32 vy # local velocity setpoint in m/s in NED
+float32 vz # local velocity setpoint in m/s in NED
+bool velocity_valid # true if local velocity setpoint valid
+float64 lat # latitude, in deg
+float64 lon # longitude, in deg
+float32 alt # altitude AMSL, in m
+float32 yaw # yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw
+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
+int8 loiter_direction # loiter direction: 1 = CW, -1 = CCW
+float32 pitch_min # minimal pitch angle for fixed wing takeoff waypoints
+float32 a_x # acceleration x setpoint
+float32 a_y # acceleration y setpoint
+float32 a_z # acceleration z setpoint
+bool acceleration_valid # true if acceleration setpoint is valid/should be used
+bool acceleration_is_force # interprete acceleration as force
diff --git a/msg/position_setpoint_triplet.msg b/msg/position_setpoint_triplet.msg
new file mode 100644
index 000000000..8717f65d0
--- /dev/null
+++ b/msg/position_setpoint_triplet.msg
@@ -0,0 +1,8 @@
+# Global position setpoint triplet in WGS84 coordinates.
+# This are the three next waypoints (or just the next two or one).
+
+px4/position_setpoint previous
+px4/position_setpoint current
+px4/position_setpoint next
+
+uint8 nav_state # report the navigation state
diff --git a/msg/vehicle_global_velocity_setpoint.msg b/msg/vehicle_global_velocity_setpoint.msg
new file mode 100644
index 000000000..ca7dcc826
--- /dev/null
+++ b/msg/vehicle_global_velocity_setpoint.msg
@@ -0,0 +1,4 @@
+# Velocity setpoint in NED frame
+float32 vx # in m/s NED
+float32 vy # in m/s NED
+float32 vz # in m/s NED
diff --git a/msg/vehicle_local_position.msg b/msg/vehicle_local_position.msg
new file mode 100644
index 000000000..4da027ae7
--- /dev/null
+++ b/msg/vehicle_local_position.msg
@@ -0,0 +1,36 @@
+# Fused local position in NED.
+
+uint64 timestamp # Time of this estimate, in microseconds since system start
+bool xy_valid # true if x and y are valid
+bool z_valid # true if z is valid
+bool v_xy_valid # true if vy and vy are valid
+bool v_z_valid # true if vz is valid
+
+# Position in local NED frame
+float32 x # X position in meters in NED earth-fixed frame
+float32 y # X position in meters in NED earth-fixed frame
+float32 z # Z position in meters in NED earth-fixed frame (negative altitude)
+
+# Velocity in NED frame
+float32 vx # Ground X Speed (Latitude), m/s in NED
+float32 vy # Ground Y Speed (Longitude), m/s in NED
+float32 vz # Ground Z Speed (Altitude), m/s in NED
+
+# Heading
+float32 yaw
+
+# Reference position in GPS / WGS84 frame
+bool xy_global # true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon)
+bool z_global # true if z is valid and has valid global reference (ref_alt)
+uint64 ref_timestamp # Time when reference position was set
+float64 ref_lat # Reference point latitude in degrees
+float64 ref_lon # Reference point longitude in degrees
+float32 ref_alt # Reference altitude AMSL in meters, MUST be set to current (not at reference point!) ground level
+
+# Distance to surface
+float32 dist_bottom # Distance to bottom surface (ground)
+float32 dist_bottom_rate # Distance to bottom surface (ground) change rate
+uint64 surface_bottom_timestamp # Time when new bottom surface found
+bool dist_bottom_valid # true if distance to bottom surface is valid
+float32 eph
+float32 epv
diff --git a/msg/vehicle_local_position_setpoint.msg b/msg/vehicle_local_position_setpoint.msg
new file mode 100644
index 000000000..a2ff8a4ae
--- /dev/null
+++ b/msg/vehicle_local_position_setpoint.msg
@@ -0,0 +1,7 @@
+# Local position in NED frame
+
+uint64 timestamp # timestamp of the setpoint
+float32 x # in meters NED
+float32 y # in meters NED
+float32 z # in meters NED
+float32 yaw # in radians NED -PI..+PI