From ca250d21eb13b9887773422e63ff664447dfe264 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 15 Feb 2015 11:40:07 +0100 Subject: ros: mavlink dummy node: listen to vehicle local position and publish to mavlink (LOCAL_POSITION_NED) --- src/platforms/ros/nodes/mavlink/mavlink.h | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) (limited to 'src/platforms/ros/nodes/mavlink/mavlink.h') 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 #include +#include #include #include @@ -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); + /** * -- cgit v1.2.3