18 #include <mavros_msgs/TerrainReport.h>
21 namespace extra_plugins {
53 void handle_terrain_report(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::TERRAIN_REPORT &report) {
54 auto terrain_report_msg = boost::make_shared<mavros_msgs::TerrainReport>();
57 terrain_report_msg->header.frame_id =
"terrain";
59 terrain_report_msg->latitude = (double) report.lat / 1e7;
60 terrain_report_msg->longitude = (
double) report.lon / 1e7;
61 terrain_report_msg->spacing = report.spacing;
62 terrain_report_msg->terrain_height = report.terrain_height;
63 terrain_report_msg->current_height = report.current_height;
64 terrain_report_msg->pending = report.pending;
65 terrain_report_msg->loaded = report.loaded;