Go to the documentation of this file.
22 #include <geometry_msgs/PoseStamped.h>
23 #include <geometry_msgs/PoseWithCovarianceStamped.h>
26 namespace extra_plugins {
38 sp_nh(
"~vision_pose"),
106 auto urt_view = Eigen::Matrix<double, 6, 6>(cov_map.triangularView<Eigen::Upper>());
109 mavlink::common::msg::VISION_POSITION_ESTIMATE vp{};
111 vp.usec = stamp.
toNSec() / 1000;
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
T transform_frame_enu_ned(const T &in)
std::vector< HandlerInfo > Subscriptions
void vision_cb(const geometry_msgs::PoseStamped::ConstPtr &req)
#define ROS_DEBUG_THROTTLE_NAMED(period, name,...)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define UAS_FCU(uasobjptr)
std::shared_ptr< MAVConnInterface const > ConstPtr
Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapConstCovariance6d
void transform_cb(const geometry_msgs::TransformStamped &transform)
void tf2_start(const char *_thd_name, message_filters::Subscriber< T > &topic_sub, void(D::*cbp)(const geometry_msgs::TransformStamped &, const typename T::ConstPtr &))
ros::Subscriber vision_cov_sub
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::string tf_child_frame_id
ros::Subscriber vision_sub
T transform_orientation_baselink_aircraft(const T &in)
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
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())
void vision_cov_cb(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req)
Subscriptions get_subscriptions() override
T transform_orientation_enu_ned(const T &in)
virtual void initialize(UAS &uas)
void initialize(UAS &uas_) override
ros::Time last_transform_stamp
T param(const std::string ¶m_name, const T &default_val) const
#define ROS_INFO_STREAM_NAMED(name, args)
Eigen::Vector3d quaternion_to_rpy(const Eigen::Quaterniond &q)
friend class TF2ListenerMixin
void covariance_urt_to_mavlink(const T &covmap, std::array< float, ARR_SIZE > &covmsg)
void send_vision_estimate(const ros::Time &stamp, const Eigen::Affine3d &tr, const geometry_msgs::PoseWithCovariance::_covariance_type &cov)
Send vision estimate transform to FCU position controller.
VisionPoseEstimatePlugin()
geometry_msgs::PoseWithCovariance::_covariance_type Covariance6d
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08