diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2015-02-15 12:39:32 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2015-02-28 18:25:35 +0100 |
commit | 6e69558b42243a2b661d6fc48fc07a22961d4e9e (patch) | |
tree | c0a6305ef700e2c74fe9429b38e703f7a9a61277 | |
parent | ca250d21eb13b9887773422e63ff664447dfe264 (diff) | |
download | px4-firmware-6e69558b42243a2b661d6fc48fc07a22961d4e9e.tar.gz px4-firmware-6e69558b42243a2b661d6fc48fc07a22961d4e9e.tar.bz2 px4-firmware-6e69558b42243a2b661d6fc48fc07a22961d4e9e.zip |
enable force setpoint message for multiplatform
-rw-r--r-- | CMakeLists.txt | 1 | ||||
-rw-r--r-- | msg/vehicle_force_setpoint.msg | 8 | ||||
-rw-r--r-- | src/platforms/px4_includes.h | 2 |
3 files changed, 11 insertions, 0 deletions
diff --git a/CMakeLists.txt b/CMakeLists.txt index 4e91fb3be..c3e894388 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,6 +77,7 @@ add_message_files( vehicle_local_position_setpoint.msg vehicle_global_velocity_setpoint.msg offboard_control_mode.msg + vehicle_force_setpoint.msg ) ## Generate services in the 'srv' folder diff --git a/msg/vehicle_force_setpoint.msg b/msg/vehicle_force_setpoint.msg new file mode 100644 index 000000000..9e2322005 --- /dev/null +++ b/msg/vehicle_force_setpoint.msg @@ -0,0 +1,8 @@ +# Definition of force (NED) setpoint uORB topic. Typically this can be used +# by a position control app together with an attitude control app. + + +float32 x # in N NED +float32 y # in N NED +float32 z # in N NED +float32 yaw # right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) diff --git a/src/platforms/px4_includes.h b/src/platforms/px4_includes.h index 364a5f31b..0e98783fd 100644 --- a/src/platforms/px4_includes.h +++ b/src/platforms/px4_includes.h @@ -67,6 +67,7 @@ #include <px4_vehicle_local_position.h> #include <px4_position_setpoint_triplet.h> #include <px4_offboard_control_mode.h> +#include <px4_vehicle_force_setpoint.h> #endif #else @@ -95,6 +96,7 @@ #include <platforms/nuttx/px4_messages/px4_vehicle_local_position.h> #include <platforms/nuttx/px4_messages/px4_position_setpoint_triplet.h> #include <platforms/nuttx/px4_messages/px4_offboard_control_mode.h> +#include <platforms/nuttx/px4_messages/px4_vehicle_force_setpoint.h> #endif #include <systemlib/err.h> #include <systemlib/param/param.h> |