From ff20653adc7cab24ea9ff967dafee8b20dd06bde Mon Sep 17 00:00:00 2001 From: Morten Fyhn Amundsen Date: Mon, 16 Mar 2020 09:11:15 +0100 Subject: [PATCH] Fix build warnings --- mavros/src/lib/ftf_frame_conversions.cpp | 18 ++++++++++++++++++ mavros/src/plugins/3dr_radio.cpp | 4 ++-- mavros/src/plugins/home_position.cpp | 4 ++-- mavros/src/plugins/imu.cpp | 4 ++-- mavros/src/plugins/param.cpp | 4 ++-- mavros/src/plugins/rc_io.cpp | 4 ++-- mavros/src/plugins/sys_status.cpp | 8 ++++---- mavros/src/plugins/waypoint.cpp | 4 ++-- mavros_extras/src/plugins/fake_gps.cpp | 2 +- 9 files changed, 35 insertions(+), 17 deletions(-) diff --git a/mavros/src/lib/ftf_frame_conversions.cpp b/mavros/src/lib/ftf_frame_conversions.cpp index 003477dc8..a19e15381 100644 --- a/mavros/src/lib/ftf_frame_conversions.cpp +++ b/mavros/src/lib/ftf_frame_conversions.cpp @@ -84,6 +84,9 @@ Eigen::Quaterniond transform_orientation(const Eigen::Quaterniond &q, const Stat case StaticTF::AIRCRAFT_TO_BASELINK: case StaticTF::BASELINK_TO_AIRCRAFT: return q * AIRCRAFT_BASELINK_Q; + + default: + return q; // Not handled. } } @@ -98,6 +101,9 @@ Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const StaticT case StaticTF::AIRCRAFT_TO_BASELINK: case StaticTF::BASELINK_TO_AIRCRAFT: return AIRCRAFT_BASELINK_AFFINE * vec; + + default: + return vec; // Not handled. } } @@ -118,6 +124,9 @@ Covariance3d transform_static_frame(const Covariance3d &cov, const StaticTF tran case StaticTF::BASELINK_TO_AIRCRAFT: cov_out = cov_in * AIRCRAFT_BASELINK_Q; return cov_out_; + + default: + return cov; // Not handled. } } @@ -149,6 +158,9 @@ Covariance6d transform_static_frame(const Covariance6d &cov, const StaticTF tran cov_out = R * cov_in * R.transpose(); return cov_out_; + + default: + return cov; // Not handled. } } @@ -182,6 +194,9 @@ Covariance9d transform_static_frame(const Covariance9d &cov, const StaticTF tran cov_out = R * cov_in * R.transpose(); return cov_out_; + + default: + return cov; // Not handled. } } @@ -223,6 +238,9 @@ Eigen::Vector3d transform_static_frame(const Eigen::Vector3d &vec, const Eigen:: // ENU to ECEF rotation is just an inverse rotation from ECEF to ENU, which means transpose. R.transposeInPlace(); return R * vec; + + default: + return vec; // Not handled. } } diff --git a/mavros/src/plugins/3dr_radio.cpp b/mavros/src/plugins/3dr_radio.cpp index 1b4fe09c2..9d68bed30 100644 --- a/mavros/src/plugins/3dr_radio.cpp +++ b/mavros/src/plugins/3dr_radio.cpp @@ -32,7 +32,7 @@ class TDRRadioPlugin : public plugin::PluginBase { low_rssi(0) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -43,7 +43,7 @@ class TDRRadioPlugin : public plugin::PluginBase { enable_connection_cb(); } - Subscriptions get_subscriptions() + Subscriptions get_subscriptions() override { return { make_handler(&TDRRadioPlugin::handle_radio_status), diff --git a/mavros/src/plugins/home_position.cpp b/mavros/src/plugins/home_position.cpp index eb0aa2b3c..72ba2ee9f 100644 --- a/mavros/src/plugins/home_position.cpp +++ b/mavros/src/plugins/home_position.cpp @@ -36,7 +36,7 @@ class HomePositionPlugin : public plugin::PluginBase { REQUEST_POLL_TIME_DT(REQUEST_POLL_TIME_MS / 1000.0) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -49,7 +49,7 @@ class HomePositionPlugin : public plugin::PluginBase { enable_connection_cb(); } - Subscriptions get_subscriptions() + Subscriptions get_subscriptions() override { return { make_handler(&HomePositionPlugin::handle_home_position), diff --git a/mavros/src/plugins/imu.cpp b/mavros/src/plugins/imu.cpp index 3caa6a2e7..cfaa4900e 100644 --- a/mavros/src/plugins/imu.cpp +++ b/mavros/src/plugins/imu.cpp @@ -58,7 +58,7 @@ class IMUPlugin : public plugin::PluginBase { linear_accel_vec_frd(Eigen::Vector3d::Zero()) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -94,7 +94,7 @@ class IMUPlugin : public plugin::PluginBase { enable_connection_cb(); } - Subscriptions get_subscriptions() { + Subscriptions get_subscriptions() override { return { make_handler(&IMUPlugin::handle_attitude), make_handler(&IMUPlugin::handle_attitude_quaternion), diff --git a/mavros/src/plugins/param.cpp b/mavros/src/plugins/param.cpp index 594f5c5a3..2f04aee78 100644 --- a/mavros/src/plugins/param.cpp +++ b/mavros/src/plugins/param.cpp @@ -364,7 +364,7 @@ class ParamPlugin : public plugin::PluginBase { PARAM_TIMEOUT_DT(PARAM_TIMEOUT_MS / 1000.0) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -382,7 +382,7 @@ class ParamPlugin : public plugin::PluginBase { enable_connection_cb(); } - Subscriptions get_subscriptions() + Subscriptions get_subscriptions() override { return { make_handler(&ParamPlugin::handle_param_value), diff --git a/mavros/src/plugins/rc_io.cpp b/mavros/src/plugins/rc_io.cpp index e73b25994..186adc53f 100644 --- a/mavros/src/plugins/rc_io.cpp +++ b/mavros/src/plugins/rc_io.cpp @@ -34,7 +34,7 @@ class RCIOPlugin : public plugin::PluginBase { has_rc_channels_msg(false) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -45,7 +45,7 @@ class RCIOPlugin : public plugin::PluginBase { enable_connection_cb(); }; - Subscriptions get_subscriptions() { + Subscriptions get_subscriptions() override { return { make_handler(&RCIOPlugin::handle_rc_channels_raw), make_handler(&RCIOPlugin::handle_rc_channels), diff --git a/mavros/src/plugins/sys_status.cpp b/mavros/src/plugins/sys_status.cpp index 3a8069bd4..209ec7d66 100644 --- a/mavros/src/plugins/sys_status.cpp +++ b/mavros/src/plugins/sys_status.cpp @@ -430,7 +430,7 @@ class SystemStatusPlugin : public plugin::PluginBase conn_heartbeat_mav_type(MAV_TYPE::ONBOARD_CONTROLLER) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -497,7 +497,7 @@ class SystemStatusPlugin : public plugin::PluginBase enable_connection_cb(); } - Subscriptions get_subscriptions() { + Subscriptions get_subscriptions() override { return { make_handler(&SystemStatusPlugin::handle_heartbeat), make_handler(&SystemStatusPlugin::handle_sys_status), @@ -915,7 +915,7 @@ class SystemStatusPlugin : public plugin::PluginBase void handle_estimator_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status) { using ESF = mavlink::common::ESTIMATOR_STATUS_FLAGS; - + auto est_status_msg = boost::make_shared(); est_status_msg->header.stamp = ros::Time::now(); @@ -952,7 +952,7 @@ class SystemStatusPlugin : public plugin::PluginBase est_status_msg->gps_glitch_status_flag = !!(status.flags & enum_value(ESF::GPS_GLITCH)); est_status_msg->accel_error_status_flag = !!(status.flags & enum_value(ESF::ACCEL_ERROR)); // [[[end]]] (checksum: 7828381ee4002ea6b61a8f528ae4d12d) - + estimator_status_pub.publish(est_status_msg); } diff --git a/mavros/src/plugins/waypoint.cpp b/mavros/src/plugins/waypoint.cpp index ebd5747de..7a1f7740e 100644 --- a/mavros/src/plugins/waypoint.cpp +++ b/mavros/src/plugins/waypoint.cpp @@ -149,7 +149,7 @@ class WaypointPlugin : public plugin::PluginBase { RESCHEDULE_DT(RESCHEDULE_MS / 1000.0) { } - void initialize(UAS &uas_) + void initialize(UAS &uas_) override { PluginBase::initialize(uas_); @@ -171,7 +171,7 @@ class WaypointPlugin : public plugin::PluginBase { enable_connection_cb(); } - Subscriptions get_subscriptions() { + Subscriptions get_subscriptions() override { return { make_handler(&WaypointPlugin::handle_mission_item), make_handler(&WaypointPlugin::handle_mission_request), diff --git a/mavros_extras/src/plugins/fake_gps.cpp b/mavros_extras/src/plugins/fake_gps.cpp index 121636157..01a905e47 100644 --- a/mavros_extras/src/plugins/fake_gps.cpp +++ b/mavros_extras/src/plugins/fake_gps.cpp @@ -73,7 +73,7 @@ class FakeGPSPlugin : public plugin::PluginBase, fp_nh.param("fix_type", ft_i, utils::enum_value(GPS_FIX_TYPE::NO_GPS)); fix_type = static_cast(ft_i); fp_nh.param("gps_rate", _gps_rate, 5.0); // GPS data rate of 5hz - gps_rate: _gps_rate; + gps_rate = _gps_rate; fp_nh.param("eph", eph, 2.0); fp_nh.param("epv", epv, 2.0); fp_nh.param("satellites_visible", satellites_visible, 5);