aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/ros/nodes/mavlink/mavlink.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-02-15 11:40:07 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-02-28 18:25:35 +0100
commitca250d21eb13b9887773422e63ff664447dfe264 (patch)
tree8ef0c92eff61140be1826072cf3fda4c5ff6556a /src/platforms/ros/nodes/mavlink/mavlink.h
parent8d36305f8b5d9393003f6074327ba279c98622ce (diff)
downloadpx4-firmware-ca250d21eb13b9887773422e63ff664447dfe264.tar.gz
px4-firmware-ca250d21eb13b9887773422e63ff664447dfe264.tar.bz2
px4-firmware-ca250d21eb13b9887773422e63ff664447dfe264.zip
ros: mavlink dummy node: listen to vehicle local position and publish to mavlink (LOCAL_POSITION_NED)
Diffstat (limited to 'src/platforms/ros/nodes/mavlink/mavlink.h')
-rw-r--r--src/platforms/ros/nodes/mavlink/mavlink.h12
1 files changed, 11 insertions, 1 deletions
diff --git a/src/platforms/ros/nodes/mavlink/mavlink.h b/src/platforms/ros/nodes/mavlink/mavlink.h
index 2ee383b4f..a246af4a4 100644
--- a/src/platforms/ros/nodes/mavlink/mavlink.h
+++ b/src/platforms/ros/nodes/mavlink/mavlink.h
@@ -43,6 +43,7 @@
#include "ros/ros.h"
#include <mavconn/interface.h>
#include <px4/vehicle_attitude.h>
+#include <px4/vehicle_local_position.h>
#include <px4/vehicle_attitude_setpoint.h>
#include <px4/offboard_control_mode.h>
@@ -61,17 +62,26 @@ protected:
ros::NodeHandle _n;
mavconn::MAVConnInterface::Ptr _link;
ros::Subscriber _v_att_sub;
+ ros::Subscriber _v_local_pos_sub;
ros::Publisher _v_att_sp_pub;
ros::Publisher _offboard_control_mode_pub;
/**
*
* Simulates output of attitude data from the FCU
- * Equivalent to the mavlink stream ATTITUDE
+ * Equivalent to the mavlink stream ATTITUDE_QUATERNION
*
* */
void VehicleAttitudeCallback(const vehicle_attitudeConstPtr &msg);
+ /**
+ *
+ * Simulates output of local position data from the FCU
+ * Equivalent to the mavlink stream LOCAL_POSITION_NED
+ *
+ * */
+ void VehicleLocalPositionCallback(const vehicle_local_positionConstPtr &msg);
+
/**
*