22 #include <geometry_msgs/PoseStamped.h> 23 #include <geometry_msgs/PoseWithCovarianceStamped.h> 26 namespace extra_plugins{
38 sp_nh(
"~vision_pose"),
56 <<
" -> " << tf_child_frame_id);
92 if (last_transform_stamp == stamp) {
96 last_transform_stamp = stamp;
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;
std::shared_ptr< MAVConnInterface const > ConstPtr
void vision_cov_cb(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req)
#define ROS_DEBUG_STREAM_NAMED(name, args)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define ROS_DEBUG_THROTTLE_NAMED(rate, name,...)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void initialize(UAS &uas_) override
void tf2_start(const char *_thd_name, void(VisionPoseEstimatePlugin::*cbp)(const geometry_msgs::TransformStamped &))
#define ROS_INFO_STREAM_NAMED(name, args)
T transform_orientation_enu_ned(const T &in)
Eigen::Vector3d quaternion_to_rpy(const Eigen::Quaterniond &q)
ros::Subscriber vision_cov_sub
friend class TF2ListenerMixin
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define UAS_FCU(uasobjptr)
ros::Time last_transform_stamp
std::string tf_child_frame_id
void covariance_urt_to_mavlink(const T &covmap, std::array< float, ARR_SIZE > &covmsg)
geometry_msgs::PoseWithCovariance::_covariance_type Covariance6d
void vision_cb(const geometry_msgs::PoseStamped::ConstPtr &req)
T transform_frame_enu_ned(const T &in)
VisionPoseEstimatePlugin()
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
std::vector< HandlerInfo > Subscriptions
Subscriptions get_subscriptions() override
void transform_cb(const geometry_msgs::TransformStamped &transform)
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.
T transform_orientation_baselink_aircraft(const T &in)
void initialize(UAS &uas_) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Eigen::Map< const Eigen::Matrix< double, 6, 6, Eigen::RowMajor > > EigenMapConstCovariance6d
ros::Subscriber vision_sub