21 #include <mavros_msgs/OpticalFlowRad.h>
22 #include <sensor_msgs/Temperature.h>
23 #include <sensor_msgs/Range.h>
26 namespace extra_plugins {
98 flow_rad.integrated_x,
99 flow_rad.integrated_y,
103 flow_rad.integrated_xgyro,
104 flow_rad.integrated_ygyro,
105 flow_rad.integrated_zgyro));
107 auto flow_rad_msg = boost::make_shared<mavros_msgs::OpticalFlowRad>();
109 flow_rad_msg->header =
header;
110 flow_rad_msg->integration_time_us = flow_rad.integration_time_us;
112 flow_rad_msg->integrated_x = int_xy.x();
113 flow_rad_msg->integrated_y = int_xy.y();
115 flow_rad_msg->integrated_xgyro = int_gyro.x();
116 flow_rad_msg->integrated_ygyro = int_gyro.y();
117 flow_rad_msg->integrated_zgyro = int_gyro.z();
119 flow_rad_msg->temperature = flow_rad.temperature / 100.0f;
120 flow_rad_msg->time_delta_distance_us = flow_rad.time_delta_distance_us;
121 flow_rad_msg->distance = flow_rad.distance;
122 flow_rad_msg->quality = flow_rad.quality;
127 auto temp_msg = boost::make_shared<sensor_msgs::Temperature>();
129 temp_msg->header =
header;
130 temp_msg->temperature = flow_rad_msg->temperature;
143 auto range_msg = boost::make_shared<sensor_msgs::Range>();
145 range_msg->header =
header;
147 range_msg->radiation_type = sensor_msgs::Range::ULTRASOUND;
151 range_msg->range = flow_rad.distance;
158 mavlink::common::msg::OPTICAL_FLOW_RAD flow_rad_msg = {};
167 msg->integrated_xgyro,
168 msg->integrated_ygyro,
169 msg->integrated_zgyro));
171 flow_rad_msg.time_usec =
msg->header.stamp.toNSec() / 1000;
172 flow_rad_msg.sensor_id = 0;
173 flow_rad_msg.integration_time_us =
msg->integration_time_us;
174 flow_rad_msg.integrated_x = int_xy.x();
175 flow_rad_msg.integrated_y = int_xy.y();
176 flow_rad_msg.integrated_xgyro = int_gyro.x();
177 flow_rad_msg.integrated_ygyro = int_gyro.y();
178 flow_rad_msg.integrated_zgyro = int_gyro.z();
179 flow_rad_msg.temperature =
msg->temperature * 100.0f;
180 flow_rad_msg.quality =
msg->quality;
181 flow_rad_msg.time_delta_distance_us =
msg->time_delta_distance_us;
182 flow_rad_msg.distance =
msg->distance;