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

guided target plugin More...

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

Public Member Functions

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

Private Member Functions

void gp_origin_cb (const geographic_msgs::GeoPointStamped::ConstPtr &msg)
 Send setpoint to FCU position controller. More...
 
void handle_position_target_global_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &position_target)
 handle POSITION_TARGET_GLOBAL_INT mavlink msg handles and publishes position target received from FCU More...
 
- Private Member Functions inherited from mavros::plugin::SetPositionTargetLocalNEDMixin< GuidedTargetPlugin >
void set_position_target_local_ned (uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, Eigen::Vector3d p, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
 
- Private Member Functions inherited from mavros::plugin::SetPositionTargetGlobalIntMixin< GuidedTargetPlugin >
void set_position_target_global_int (uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate)
 
- Private Member Functions inherited from mavros::plugin::TF2ListenerMixin< GuidedTargetPlugin >
void tf2_start (const char *_thd_name, void(GuidedTargetPlugin ::*cbp)(const geometry_msgs::TransformStamped &))
 
void tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(GuidedTargetPlugin ::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
 

Private Attributes

double arr [2] = {0, 0}
 
Eigen::Vector3d current_gps
 geodetic coordinates LLA More...
 
Eigen::Vector3d current_local_pos
 Current local position in ENU. More...
 
Eigen::Vector3d ecef_origin {}
 geocentric origin [m] More...
 
ros::Subscriber gp_origin_sub
 global origin LLA More...
 
bool is_map_init
 
Eigen::Vector3d map_origin {}
 oigin of map frame [lla] More...
 
uint32_t old_gps_stamp = 0
 old time gps time stamp in [ms], to check if new gps msg is received More...
 
ros::Publisher setpointg_pub
 global position target from FCU More...
 
ros::NodeHandle sp_nh
 
ros::NodeHandle spg_nh
 to get local position and gps coord which are not under sp_h() More...
 
std::string tf_child_frame_id
 
std::string tf_frame_id
 
bool tf_listen
 
double tf_rate
 
- Private Attributes inherited from mavros::plugin::TF2ListenerMixin< GuidedTargetPlugin >
std::string tf_thd_name
 
std::thread tf_thread
 

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 capabilities_cb (UAS::MAV_CAP capabilities)
 
virtual void connection_cb (bool connected)
 
void enable_capabilities_cb ()
 
void enable_connection_cb ()
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

guided target plugin

Send and receive setpoint positions from FCU controller.

Definition at line 40 of file guided_target.cpp.


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


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue Jun 13 2023 02:17:59