22 #include <GeographicLib/Geocentric.hpp>
24 #include <std_msgs/Float64.h>
25 #include <std_msgs/UInt32.h>
26 #include <nav_msgs/Odometry.h>
27 #include <sensor_msgs/NavSatFix.h>
28 #include <sensor_msgs/NavSatStatus.h>
29 #include <geometry_msgs/PoseStamped.h>
30 #include <geometry_msgs/TwistStamped.h>
31 #include <geometry_msgs/TransformStamped.h>
32 #include <geographic_msgs/GeoPointStamped.h>
34 #include <mavros_msgs/HomePosition.h>
37 namespace std_plugins {
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 gp_nh(
"~global_position"),
51 hp_nh(
"~home_position"),
60 PluginBase::initialize(uas_);
144 template<
typename MsgT>
147 fix->latitude =
msg.lat / 1E7;
148 fix->longitude =
msg.lon / 1E7;
154 fix->position_covariance.fill(0.0);
155 fix->position_covariance[0] = -1.0;
156 fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
161 void handle_gps_raw_int(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RAW_INT &raw_gps)
163 auto fix = boost::make_shared<sensor_msgs::NavSatFix>();
167 fix->status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
168 if (raw_gps.fix_type > 2)
169 fix->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
172 fix->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
177 float eph = (raw_gps.eph != UINT16_MAX) ? raw_gps.eph / 1E2F : NAN;
178 float epv = (raw_gps.epv != UINT16_MAX) ? raw_gps.epv / 1E2F : NAN;
183 if (
msg->magic == MAVLINK_STX &&
184 raw_gps.h_acc > 0 && raw_gps.v_acc > 0) {
185 gps_cov.diagonal() << std::pow(raw_gps.h_acc / 1E3, 2), std::pow(raw_gps.h_acc / 1E3, 2), std::pow(raw_gps.v_acc / 1E3, 2);
186 fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
189 else if (!std::isnan(eph) && !std::isnan(epv)) {
191 fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
201 if (raw_gps.vel != UINT16_MAX &&
202 raw_gps.cog != UINT16_MAX) {
203 double speed = raw_gps.vel / 1E2;
206 auto vel = boost::make_shared<geometry_msgs::TwistStamped>();
208 vel->header.stamp = fix->header.stamp;
212 vel->twist.linear.x = speed * std::sin(course);
213 vel->twist.linear.y = speed * std::cos(course);
219 auto sat_cnt = boost::make_shared<std_msgs::UInt32>();
220 sat_cnt->data = raw_gps.satellites_visible;
226 auto g_origin = boost::make_shared<geographic_msgs::GeoPointStamped>();
232 g_origin->position.latitude = glob_orig.latitude / 1E7;
233 g_origin->position.longitude = glob_orig.longitude / 1E7;
243 auto odom = boost::make_shared<nav_msgs::Odometry>();
244 auto fix = boost::make_shared<sensor_msgs::NavSatFix>();
245 auto relative_alt = boost::make_shared<std_msgs::Float64>();
246 auto compass_heading = boost::make_shared<std_msgs::Float64>();
258 fix->status.service = raw_fix->status.service;
259 fix->status.status = raw_fix->status.status;
260 fix->position_covariance = raw_fix->position_covariance;
261 fix->position_covariance_type = raw_fix->position_covariance_type;
265 fix->status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
266 fix->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
272 relative_alt->data = gpos.relative_alt / 1E3;
273 compass_heading->data = (gpos.hdg != UINT16_MAX) ? gpos.hdg / 1E2 : NAN;
288 odom->header.stamp =
header.stamp;
294 odom->twist.twist.linear);
298 vel_cov_out.fill(0.0);
299 vel_cov_out(0) = -1.0;
302 Eigen::Vector3d map_point;
312 GeographicLib::Geocentric map(GeographicLib::Constants::WGS84_a(),
313 GeographicLib::Constants::WGS84_f());
323 map.Forward(fix->latitude, fix->longitude, fix->altitude,
324 map_point.x(), map_point.y(), map_point.z());
327 if (!
is_map_init && fix->status.status >= sensor_msgs::NavSatStatus::STATUS_FIX) {
336 catch (
const std::exception& e) {
350 odom->pose.pose.position.z = relative_alt->data;
357 pos_cov_out.setZero();
358 pos_cov_out.block<3, 3>(0, 0) = gps_cov;
359 pos_cov_out.block<3, 3>(3, 3).diagonal() <<
372 geometry_msgs::TransformStamped transform;
374 transform.header.stamp = odom->header.stamp;
379 transform.transform.rotation = odom->pose.pose.orientation;
382 transform.transform.translation.x = odom->pose.pose.position.x;
383 transform.transform.translation.y = odom->pose.pose.position.y;
384 transform.transform.translation.z = odom->pose.pose.position.z;
392 auto global_offset = boost::make_shared<geometry_msgs::PoseStamped>();
407 geometry_msgs::TransformStamped transform;
409 transform.header.stamp = global_offset->header.stamp;
414 transform.transform.rotation = global_offset->pose.orientation;
417 transform.transform.translation.x = global_offset->pose.position.x;
418 transform.transform.translation.y = global_offset->pose.position.y;
419 transform.transform.translation.z = global_offset->pose.position.z;
428 int fix_type, satellites_visible;
433 if (satellites_visible <= 0)
434 stat.
summary(2,
"No satellites");
435 else if (fix_type < 2)
437 else if (fix_type == 2)
439 else if (fix_type >= 3)
442 stat.
addf(
"Satellites visible",
"%zd", satellites_visible);
443 stat.
addf(
"Fix type",
"%d", fix_type);
445 if (!std::isnan(eph))
446 stat.
addf(
"EPH (m)",
"%.2f", eph);
448 stat.
add(
"EPH (m)",
"Unknown");
450 if (!std::isnan(epv))
451 stat.
addf(
"EPV (m)",
"%.2f", epv);
453 stat.
add(
"EPV (m)",
"Unknown");
468 GeographicLib::Geocentric map(GeographicLib::Constants::WGS84_a(),
469 GeographicLib::Constants::WGS84_f());
475 catch (
const std::exception& e) {
484 mavlink::common::msg::SET_GPS_GLOBAL_ORIGIN gpo = {};
486 Eigen::Vector3d global_position;
491 gpo.latitude = req->position.latitude * 1E7;
492 gpo.longitude = req->position.longitude * 1E7;