Skip to content

Commit

Permalink
Merge pull request mavlink#8 from scoutdi/issue/7/fix-warnings
Browse files Browse the repository at this point in the history
Fix build warnings
  • Loading branch information
mortenfyhn authored Mar 26, 2020
2 parents 3513250 + ff20653 commit 98c90bd
Show file tree
Hide file tree
Showing 9 changed files with 35 additions and 17 deletions.
18 changes: 18 additions & 0 deletions mavros/src/lib/ftf_frame_conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
}
}

Expand All @@ -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.
}
}

Expand All @@ -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.
}
}

Expand Down Expand Up @@ -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.
}
}

Expand Down Expand Up @@ -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.
}
}

Expand Down Expand Up @@ -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.
}
}

Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/3dr_radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class TDRRadioPlugin : public plugin::PluginBase {
low_rssi(0)
{ }

void initialize(UAS &uas_)
void initialize(UAS &uas_) override
{
PluginBase::initialize(uas_);

Expand All @@ -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),
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/home_position.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand All @@ -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),
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/imu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand Down Expand Up @@ -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),
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand All @@ -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),
Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/rc_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand All @@ -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),
Expand Down
8 changes: 4 additions & 4 deletions mavros/src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand Down Expand Up @@ -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),
Expand Down Expand Up @@ -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<mavros_msgs::EstimatorStatus>();
est_status_msg->header.stamp = ros::Time::now();

Expand Down Expand Up @@ -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);
}

Expand Down
4 changes: 2 additions & 2 deletions mavros/src/plugins/waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);

Expand All @@ -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),
Expand Down
2 changes: 1 addition & 1 deletion mavros_extras/src/plugins/fake_gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class FakeGPSPlugin : public plugin::PluginBase,
fp_nh.param<int>("fix_type", ft_i, utils::enum_value(GPS_FIX_TYPE::NO_GPS));
fix_type = static_cast<GPS_FIX_TYPE>(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<int>("satellites_visible", satellites_visible, 5);
Expand Down

0 comments on commit 98c90bd

Please sign in to comment.