22 #include <geometry_msgs/TwistWithCovarianceStamped.h>
25 namespace std_plugins {
40 PluginBase::initialize(uas_);
61 void handle_apm_wind(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::WIND &wind)
63 const double speed = wind.speed;
66 auto twist_cov = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
68 twist_cov->twist.twist.linear.x = speed * std::sin(course);
69 twist_cov->twist.twist.linear.y = speed * std::cos(course);
70 twist_cov->twist.twist.linear.z = -wind.speed_z;
83 void handle_px4_wind(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::WIND_COV &wind)
85 auto twist_cov = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
89 twist_cov->twist.twist.linear);
94 cov_map(0, 0) = wind.var_horiz;
95 cov_map(2, 2) = wind.var_vert;