Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
mavros::std_plugins::SetpointPositionPlugin Class Reference

Setpoint position plugin. More...

Inheritance diagram for mavros::std_plugins::SetpointPositionPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions ()
 Return vector of MAVLink message subscriptions (handlers) More...
 
void initialize (UAS &uas_)
 Plugin initializer. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SetpointPositionPlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void gps_cb (const sensor_msgs::NavSatFix::ConstPtr &msg)
 
void local_cb (const geometry_msgs::PoseStamped::ConstPtr &msg)
 
void send_position_target (const ros::Time &stamp, const Eigen::Affine3d &tr)
 Send setpoint to FCU position controller. More...
 
bool set_mav_frame_cb (mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res)
 
void setpoint_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
 
void setpointg_cb (const mavros_msgs::GlobalPositionTarget::ConstPtr &req)
 
void transform_cb (const geometry_msgs::TransformStamped &transform)
 
- Private Member Functions inherited from mavros::plugin::SetPositionTargetLocalNEDMixin< SetpointPositionPlugin >
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)
 Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED. More...
 
- Private Member Functions inherited from mavros::plugin::TF2ListenerMixin< SetpointPositionPlugin >
void tf2_start (const char *_thd_name, void(SetpointPositionPlugin::*cbp)(const geometry_msgs::TransformStamped &))
 start tf listener More...
 
void tf2_start (const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(SetpointPositionPlugin::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
 start tf listener syncronized with another topic More...
 

Private Attributes

Eigen::Vector3d current_gps
 geodetic coordinates LLA More...
 
Eigen::Vector3d current_local_pos
 Current local position in ENU. More...
 
ros::Subscriber gps_sub
 current GPS More...
 
ros::Subscriber local_sub
 current local ENU More...
 
MAV_FRAME mav_frame
 
ros::ServiceServer mav_frame_srv
 
uint32_t old_gps_stamp = 0
 old time gps time stamp in [ms], to check if new gps msg is received More...
 
ros::Subscriber setpoint_sub
 
ros::Subscriber setpointg_sub
 GPS setpoint. 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< SetpointPositionPlugin >
std::string tf_thd_name
 
std::thread tf_thread
 

Friends

class SetPositionTargetLocalNEDMixin
 
class TF2ListenerMixin
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
using HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb >
 Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void connection_cb (bool connected)
 
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Setpoint position plugin.

Send setpoint positions to FCU controller.

Definition at line 37 of file setpoint_position.cpp.


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


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11