Global position plugin. More...

Public Member Functions | |
| std::string const | get_name () const |
| Plugin name (CamelCase) | |
| const message_map | get_rx_handlers () |
| Return map with message rx handlers. | |
| GlobalPositionPlugin () | |
| void | initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater) |
| Plugin initializer. | |
Private Member Functions | |
| void | handle_global_position_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
Private Attributes | |
| std::string | child_frame_id |
| frame for TF and Pose | |
| ros::Publisher | fix_pub |
| std::string | frame_id |
| origin for TF | |
| ros::NodeHandle | gp_nh |
| ros::Publisher | hdg_pub |
| ros::Publisher | pos_pub |
| ros::Publisher | rel_alt_pub |
| double | rot_cov |
| bool | send_tf |
| tf::TransformBroadcaster | tf_broadcaster |
| UAS * | uas |
| ros::Publisher | vel_pub |
Global position plugin.
Publishes global position. Convertion from GPS to UTF allows publishing local position to TF and PoseWithCovarianceStamped.
Definition at line 51 of file global_position.cpp.