From 93f8fc33c890bb961f0fba03537cc54bf8a88d1f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 12 Feb 2015 20:43:52 +0100 Subject: ros mavlink node: handle set_attitude_target --- src/platforms/ros/nodes/mavlink/mavlink.h | 26 +++++++++++++++++++++++++- 1 file changed, 25 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 e683597a9..6f7536436 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 namespace px4 { @@ -59,8 +60,31 @@ protected: ros::NodeHandle _n; mavconn::MAVConnInterface::Ptr _link; ros::Subscriber _v_att_sub; + ros::Publisher _v_att_sp_pub; + + /** + * + * Simulates output of attitude data from the FCU + * Equivalent to the mavlink stream ATTITUDE + * + * */ + void VehicleAttitudeCallback(const vehicle_attitudeConstPtr &msg); + + + /** + * + * Handle incoming mavlink messages ant publish them to ROS ("Mavlink Receiver") + * + * */ + void handle_msg(const mavlink_message_t *mmsg, uint8_t sysid, uint8_t compid); + + /** + * + * Handle SET_ATTITUDE_TARGET mavlink messages + * + * */ + void handle_msg_set_attitude_target(const mavlink_message_t *mmsg); - void VehicleAttitudeCallback(const px4::vehicle_attitudeConstPtr &msg); }; } -- cgit v1.2.3