forked from Archive/PX4-Autopilot
enable force setpoint message for multiplatform
This commit is contained in:
parent
ca250d21eb
commit
6e69558b42
|
@ -77,6 +77,7 @@ add_message_files(
|
||||||
vehicle_local_position_setpoint.msg
|
vehicle_local_position_setpoint.msg
|
||||||
vehicle_global_velocity_setpoint.msg
|
vehicle_global_velocity_setpoint.msg
|
||||||
offboard_control_mode.msg
|
offboard_control_mode.msg
|
||||||
|
vehicle_force_setpoint.msg
|
||||||
)
|
)
|
||||||
|
|
||||||
## Generate services in the 'srv' folder
|
## Generate services in the 'srv' folder
|
||||||
|
|
|
@ -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)
|
|
@ -67,6 +67,7 @@
|
||||||
#include <px4_vehicle_local_position.h>
|
#include <px4_vehicle_local_position.h>
|
||||||
#include <px4_position_setpoint_triplet.h>
|
#include <px4_position_setpoint_triplet.h>
|
||||||
#include <px4_offboard_control_mode.h>
|
#include <px4_offboard_control_mode.h>
|
||||||
|
#include <px4_vehicle_force_setpoint.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
@ -95,6 +96,7 @@
|
||||||
#include <platforms/nuttx/px4_messages/px4_vehicle_local_position.h>
|
#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_position_setpoint_triplet.h>
|
||||||
#include <platforms/nuttx/px4_messages/px4_offboard_control_mode.h>
|
#include <platforms/nuttx/px4_messages/px4_offboard_control_mode.h>
|
||||||
|
#include <platforms/nuttx/px4_messages/px4_vehicle_force_setpoint.h>
|
||||||
#endif
|
#endif
|
||||||
#include <systemlib/err.h>
|
#include <systemlib/err.h>
|
||||||
#include <systemlib/param/param.h>
|
#include <systemlib/param/param.h>
|
||||||
|
|
Loading…
Reference in New Issue