Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
mavros::extra_plugins::FakeGPSPlugin Class Reference

Fake GPS plugin. More...

Inheritance diagram for mavros::extra_plugins::FakeGPSPlugin:
Inheritance graph
[legend]

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW FakeGPSPlugin ()
 
Subscriptions get_subscriptions ()
 
void initialize (UAS &uas_)
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void mocap_pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
 
void mocap_tf_cb (const geometry_msgs::TransformStamped::ConstPtr &trans)
 
void send_fake_gps (const ros::Time &stamp, const Eigen::Vector3d &ecef_offset)
 Send fake GPS coordinates through HIL_GPS Mavlink msg. More...
 
void transform_cb (const geometry_msgs::TransformStamped &trans)
 
void vision_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
 
- Private Member Functions inherited from mavros::plugin::TF2ListenerMixin< FakeGPSPlugin >
void tf2_start (const char *_thd_name, void(FakeGPSPlugin::*cbp)(const geometry_msgs::TransformStamped &))
 
void tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(FakeGPSPlugin::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
 

Private Attributes

GeographicLib::Geocentric earth
 
Eigen::Vector3d ecef_origin
 geocentric origin [m] More...
 
double eph
 
double epv
 
GPS_FIX_TYPE fix_type
 
ros::NodeHandle fp_nh
 
ros::Rate gps_rate
 
ros::Time last_pos_time
 
ros::Time last_transform_stamp
 
Eigen::Vector3d map_origin
 geodetic origin [lla] More...
 
ros::Subscriber mocap_pose_sub
 
ros::Subscriber mocap_tf_sub
 
bool mocap_transform
 set use of mocap data (TransformStamped msg) More...
 
Eigen::Vector3d old_ecef
 previous geocentric position [m] More...
 
double old_stamp
 previous stamp [s] More...
 
int satellites_visible
 
std::string tf_child_frame_id
 
std::string tf_frame_id
 
bool tf_listen
 set use of TF Listener data More...
 
double tf_rate
 
bool use_mocap
 set use of mocap data (PoseStamped msg) More...
 
bool use_vision
 set use of vision data More...
 
ros::Subscriber vision_pose_sub
 
- Private Attributes inherited from mavros::plugin::TF2ListenerMixin< FakeGPSPlugin >
std::string tf_thd_name
 
std::thread tf_thread
 

Friends

class TF2ListenerMixin
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
typedef boost::shared_ptr< PluginBase const > ConstPtr
 
typedef mavconn::MAVConnInterface::ReceivedCb HandlerCb
 
typedef std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCbHandlerInfo
 
typedef boost::shared_ptr< PluginBasePtr
 
typedef std::vector< HandlerInfoSubscriptions
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void connection_cb (bool connected)
 
void enable_connection_cb ()
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Fake GPS plugin.

Sends fake GPS from local position estimation source data (motion capture, vision) to FCU - processed in HIL mode or out of it if parameter MAV_USEHILGPS is set on PX4 Pro Autopilot Firmware; Ardupilot Firmware already supports it without a flag set.

Definition at line 40 of file fake_gps.cpp.


The documentation for this class was generated from the following file:


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18