gps_input.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2019 Amilcar Lucas.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include "mavros_msgs/GPSINPUT.h"
19 
20 namespace mavros {
21 namespace extra_plugins {
22 using mavlink::common::GPS_FIX_TYPE;
23 using mavlink::common::GPS_INPUT_IGNORE_FLAGS;
24 
31 public:
33  gps_input_nh("~gps_input"),
34  gps_rate(5.0)
35  { }
36 
37  void initialize(UAS &uas_)
38  {
40 
41  double _gps_rate;
42 
43  last_pos_time = ros::Time(0.0);
44  gps_input_nh.param("gps_rate", _gps_rate, 5.0); // GPS data rate of 5hz
45  gps_rate = _gps_rate;
46 
48  }
49 
51  {
52  return { /* Rx disabled */ };
53  }
54 
55 private:
58 
61 
62  /* -*- callbacks -*- */
63 
68  // Throttle incoming messages to 5hz
70  return;
71  }
73 
78  mavlink::common::msg::GPS_INPUT gps_input {};
79 
80  // Fill in and send message
81  gps_input.time_usec = ros_msg->header.stamp.toNSec() / 1000;
82  gps_input.gps_id = ros_msg->gps_id;
83  gps_input.ignore_flags = ros_msg->ignore_flags;
84  gps_input.time_week_ms = ros_msg->time_week_ms;
85  gps_input.time_week = ros_msg->time_week;
86  gps_input.speed_accuracy = ros_msg->speed_accuracy;
87  gps_input.horiz_accuracy = ros_msg->horiz_accuracy;
88  gps_input.vert_accuracy = ros_msg->vert_accuracy;
89  gps_input.lat = ros_msg->lat;
90  gps_input.lon = ros_msg->lon;
91  gps_input.alt = ros_msg->alt;
92  gps_input.vn = ros_msg->vn;
93  gps_input.ve = ros_msg->ve;
94  gps_input.vd = ros_msg->vd;
95  gps_input.hdop = ros_msg->hdop;
96  gps_input.vdop = ros_msg->vdop;
97  gps_input.fix_type = ros_msg->fix_type;
98  gps_input.satellites_visible = ros_msg->satellites_visible;
99 
100  UAS_FCU(m_uas)->send_message_ignore_drop(gps_input);
101  }
102 };
103 } // namespace extra_plugins
104 } // namespace mavros
105 
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::extra_plugins::GpsInputPlugin::gps_input_sub
ros::Subscriber gps_input_sub
Definition: gps_input.cpp:57
mavros::extra_plugins::GpsInputPlugin::send_cb
void send_cb(const mavros_msgs::GPSINPUT::ConstPtr ros_msg)
Send GPS coordinates through GPS_INPUT Mavlink message.
Definition: gps_input.cpp:67
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
mavros::plugin::PluginBase::PluginBase
PluginBase()
UAS_FCU
#define UAS_FCU(uasobjptr)
mavros::UAS
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
mavros::extra_plugins::GpsInputPlugin::get_subscriptions
Subscriptions get_subscriptions()
Definition: gps_input.cpp:50
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros_plugin.h
mavros::extra_plugins::GpsInputPlugin::last_pos_time
ros::Time last_pos_time
Definition: gps_input.cpp:60
mavros::extra_plugins::GpsInputPlugin::initialize
void initialize(UAS &uas_)
Definition: gps_input.cpp:37
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mavros::extra_plugins::GpsInputPlugin::gps_input_nh
ros::NodeHandle gps_input_nh
Definition: gps_input.cpp:56
mavros::extra_plugins::GpsInputPlugin::gps_rate
ros::Rate gps_rate
Definition: gps_input.cpp:59
mavros
ros::Time
mavros::extra_plugins::GpsInputPlugin
GPS_INPUT GPS plugin.
Definition: gps_input.cpp:30
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
mavros::extra_plugins::GpsInputPlugin::GpsInputPlugin
GpsInputPlugin()
Definition: gps_input.cpp:32
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
ros::Duration
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08