Skip to content

Commit

Permalink
fixed warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
petrlmat committed Jan 25, 2024
1 parent a491499 commit 9f89a4e
Show file tree
Hide file tree
Showing 11 changed files with 46 additions and 45 deletions.
37 changes: 19 additions & 18 deletions include/mrs_uav_state_estimators/estimators/correction.h
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,8 @@ class Correction {
std::optional<measurement_t> getCorrectionFromVector(const geometry_msgs::Vector3StampedConstPtr msg);
void callbackVector(const geometry_msgs::Vector3Stamped::ConstPtr msg);

mrs_lib::SubscribeHandler<geometry_msgs::QuaternionStamped> sh_orientation_; // for obtaining heading rate
std::string orientation_topic_;
mrs_lib::SubscribeHandler<geometry_msgs::QuaternionStamped> sh_orientation_; // for obtaining heading rate
std::string orientation_topic_;

mrs_lib::SubscribeHandler<geometry_msgs::QuaternionStamped> sh_quat_;
measurement_t prev_hdg_measurement_;
Expand Down Expand Up @@ -342,7 +342,7 @@ Correction<n_measurements>::Correction(ros::NodeHandle& nh, const std::string& e
if (est_type_ == EstimatorType_t::HEADING && state_id_ == StateId_t::VELOCITY) {
ph->param_loader->loadParam("message/orientation_topic", orientation_topic_);
orientation_topic_ = "/" + ch_->uav_name + "/" + orientation_topic_;
sh_orientation_ = mrs_lib::SubscribeHandler<geometry_msgs::QuaternionStamped>(shopts, orientation_topic_);
sh_orientation_ = mrs_lib::SubscribeHandler<geometry_msgs::QuaternionStamped>(shopts, orientation_topic_);
}


Expand Down Expand Up @@ -1259,22 +1259,23 @@ std::optional<typename Correction<n_measurements>::measurement_t> Correction<n_m

switch (state_id_) {

case StateId_t::VELOCITY: {
try {
if (!sh_orientation_.hasMsg()) {
ROS_INFO_THROTTLE(1.0, "[%s]: %s orientation on topic: %s", getPrintName().c_str(), Support::waiting_for_string.c_str(), orientation_topic_.c_str());
return {};
}
measurement_t measurement;
measurement(0) = mrs_lib::AttitudeConverter(sh_orientation_.getMsg()->quaternion).getHeadingRate(msg->vector);
return measurement;
}
catch (...) {
ROS_ERROR_THROTTLE(1.0, "[%s]: Exception caught during getting heading rate (getCorrectionFromVector())", getPrintName().c_str());
case StateId_t::VELOCITY: {
try {
if (!sh_orientation_.hasMsg()) {
ROS_INFO_THROTTLE(1.0, "[%s]: %s orientation on topic: %s", getPrintName().c_str(), Support::waiting_for_string.c_str(),
orientation_topic_.c_str());
return {};
}
break;
measurement_t measurement;
measurement(0) = mrs_lib::AttitudeConverter(sh_orientation_.getMsg()->quaternion).getHeadingRate(msg->vector);
return measurement;
}
catch (...) {
ROS_ERROR_THROTTLE(1.0, "[%s]: Exception caught during getting heading rate (getCorrectionFromVector())", getPrintName().c_str());
return {};
}
break;
}

default: {
ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromVector() switch", getPrintName().c_str());
Expand All @@ -1292,8 +1293,8 @@ std::optional<typename Correction<n_measurements>::measurement_t> Correction<n_m

/*//{ getCorrectionFromQuat() */
template <int n_measurements>
std::optional<typename Correction<n_measurements>::measurement_t> Correction<n_measurements>::getCorrectionFromQuat(
const geometry_msgs::QuaternionStampedConstPtr msg) {
std::optional<typename Correction<n_measurements>::measurement_t> Correction<n_measurements>::getCorrectionFromQuat([
[maybe_unused]] const geometry_msgs::QuaternionStampedConstPtr msg) {

switch (est_type_) {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ ProcExcessiveTilt<n_measurements>::ProcExcessiveTilt(ros::NodeHandle& nh, const

/*//{ process() */
template <int n_measurements>
std::tuple<bool, bool> ProcExcessiveTilt<n_measurements>::process(measurement_t& measurement) {
std::tuple<bool, bool> ProcExcessiveTilt<n_measurements>::process([[maybe_unused]] measurement_t& measurement) {

if (!Processor<n_measurements>::enabled_) {
return {true, true};
Expand Down
2 changes: 1 addition & 1 deletion include/mrs_uav_state_estimators/processors/processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ class Processor {
virtual void reset() = 0;

protected:
Processor(ros::NodeHandle& nh, const std::string& correction_name, const std::string& name, const std::shared_ptr<CommonHandlers_t>& ch,
Processor([[maybe_unused]] ros::NodeHandle& nh, const std::string& correction_name, const std::string& name, const std::shared_ptr<CommonHandlers_t>& ch,
const std::shared_ptr<PrivateHandlers_t>& ph)
: correction_name_(correction_name), name_(name), ch_(ch), ph_(ph) {
} // protected constructor to prevent instantiation
Expand Down
4 changes: 2 additions & 2 deletions src/estimators/agl/garmin_agl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ bool GarminAgl::reset(void) {
/*//}*/

/* timerUpdate() //{*/
void GarminAgl::timerUpdate(const ros::TimerEvent &event) {
void GarminAgl::timerUpdate([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -173,7 +173,7 @@ void GarminAgl::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void GarminAgl::timerCheckHealth(const ros::TimerEvent &event) {
void GarminAgl::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down
10 changes: 5 additions & 5 deletions src/estimators/altitude/alt_generic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,7 +391,7 @@ void AltGeneric::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void AltGeneric::timerCheckHealth(const ros::TimerEvent &event) {
void AltGeneric::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -576,7 +576,7 @@ bool AltGeneric::isConverged() {

/*//{ getState() */
double AltGeneric::getState(const int &state_id_in, const int &axis_in) const {
return getState(stateIdToIndex(state_id_in, 0));
return getState(stateIdToIndex(state_id_in, axis_in));
}

double AltGeneric::getState(const int &state_idx_in) const {
Expand All @@ -586,7 +586,7 @@ double AltGeneric::getState(const int &state_idx_in) const {

/*//{ setState() */
void AltGeneric::setState(const double &state_in, const int &state_id_in, const int &axis_in) {
setState(state_in, stateIdToIndex(state_id_in, 0));
setState(state_in, stateIdToIndex(state_id_in, axis_in));
}

void AltGeneric::setState(const double &state_in, const int &state_idx_in) {
Expand All @@ -608,7 +608,7 @@ void AltGeneric::setStates(const states_t &states_in) {

/*//{ getCovariance() */
double AltGeneric::getCovariance(const int &state_id_in, const int &axis_in) const {
return getCovariance(stateIdToIndex(state_id_in, 0));
return getCovariance(stateIdToIndex(state_id_in, axis_in));
}

double AltGeneric::getCovariance(const int &state_idx_in) const {
Expand All @@ -634,7 +634,7 @@ double AltGeneric::getInnovation(const int &state_idx) const {
}

double AltGeneric::getInnovation(const int &state_id_in, const int &axis_in) const {
return getInnovation(stateIdToIndex(0, 0));
return getInnovation(stateIdToIndex(state_id_in, axis_in));
}
/*//}*/

Expand Down
6 changes: 3 additions & 3 deletions src/estimators/heading/hdg_generic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,7 +363,7 @@ void HdgGeneric::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void HdgGeneric::timerCheckHealth(const ros::TimerEvent &event) {
void HdgGeneric::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -561,7 +561,7 @@ void HdgGeneric::setStates(const states_t &states_in) {

/*//{ getCovariance() */
double HdgGeneric::getCovariance(const int &state_id_in, const int &axis_in) const {
return getCovariance(stateIdToIndex(state_id_in, 0));
return getCovariance(stateIdToIndex(state_id_in, axis_in));
}

double HdgGeneric::getCovariance(const int &state_idx_in) const {
Expand All @@ -587,7 +587,7 @@ double HdgGeneric::getInnovation(const int &state_idx) const {
}

double HdgGeneric::getInnovation(const int &state_id_in, const int &axis_in) const {
return getInnovation(stateIdToIndex(0, 0));
return getInnovation(stateIdToIndex(state_id_in, axis_in));
}
/*//}*/

Expand Down
12 changes: 6 additions & 6 deletions src/estimators/heading/hdg_passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ void HdgPassthrough::callbackAngularVelocity(const geometry_msgs::Vector3Stamped
/*//}*/

/* timerUpdate() //{*/
void HdgPassthrough::timerUpdate(const ros::TimerEvent &event) {
void HdgPassthrough::timerUpdate([[maybe_unused]] const ros::TimerEvent &event) {


if (!isInitialized()) {
Expand All @@ -180,7 +180,7 @@ void HdgPassthrough::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void HdgPassthrough::timerCheckHealth(const ros::TimerEvent &event) {
void HdgPassthrough::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -214,7 +214,7 @@ void HdgPassthrough::timerCheckHealth(const ros::TimerEvent &event) {

/*//{ getState() */
double HdgPassthrough::getState(const int &state_id_in, const int &axis_in) const {
return getState(stateIdToIndex(state_id_in, 0));
return getState(stateIdToIndex(state_id_in, axis_in));
}

double HdgPassthrough::getState(const int &state_idx_in) const {
Expand All @@ -224,7 +224,7 @@ double HdgPassthrough::getState(const int &state_idx_in) const {

/*//{ setState() */
void HdgPassthrough::setState(const double &state_in, const int &state_id_in, const int &axis_in) {
setState(state_in, stateIdToIndex(state_id_in, 0));
setState(state_in, stateIdToIndex(state_id_in, axis_in));
}

void HdgPassthrough::setState(const double &state_in, const int &state_idx_in) {
Expand Down Expand Up @@ -252,7 +252,7 @@ void HdgPassthrough::setStates(const states_t &states_in) {

/*//{ getCovariance() */
double HdgPassthrough::getCovariance(const int &state_id_in, const int &axis_in) const {
return getCovariance(stateIdToIndex(state_id_in, 0));
return getCovariance(stateIdToIndex(state_id_in, axis_in));
}

double HdgPassthrough::getCovariance(const int &state_idx_in) const {
Expand All @@ -278,7 +278,7 @@ double HdgPassthrough::getInnovation(const int &state_idx) const {
}

double HdgPassthrough::getInnovation(const int &state_id_in, const int &axis_in) const {
return getInnovation(stateIdToIndex(state_id_in, 0));
return getInnovation(stateIdToIndex(state_id_in, axis_in));
}
/*//}*/

Expand Down
2 changes: 1 addition & 1 deletion src/estimators/lateral/lat_generic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,7 +412,7 @@ void LatGeneric::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void LatGeneric::timerCheckHealth(const ros::TimerEvent &event) {
void LatGeneric::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down
6 changes: 3 additions & 3 deletions src/estimators/state/dummy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ bool Dummy::reset(void) {
/*//}*/

/* timerUpdate() //{*/
void Dummy::timerUpdate(const ros::TimerEvent &event) {
void Dummy::timerUpdate([[maybe_unused]] const ros::TimerEvent &event) {


if (!isInitialized()) {
Expand Down Expand Up @@ -175,7 +175,7 @@ void Dummy::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void Dummy::timerCheckHealth(const ros::TimerEvent &event) {
void Dummy::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -206,7 +206,7 @@ bool Dummy::isConverged() {
/*//}*/

/*//{ setUavState() */
bool Dummy::setUavState(const mrs_msgs::UavState &uav_state) {
bool Dummy::setUavState([[maybe_unused]] const mrs_msgs::UavState &uav_state) {

if (!isInState(STOPPED_STATE)) {
ROS_WARN("[%s]: Estimator state can be set only in the STOPPED state", getPrintName().c_str());
Expand Down
2 changes: 1 addition & 1 deletion src/estimators/state/ground_truth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ bool GroundTruth::isConverged() {
/*//}*/

/*//{ setUavState() */
bool GroundTruth::setUavState(const mrs_msgs::UavState &uav_state) {
bool GroundTruth::setUavState([[maybe_unused]] const mrs_msgs::UavState &uav_state) {

if (!isInState(STOPPED_STATE)) {
ROS_WARN("[%s]: Estimator state can be set only in the STOPPED state", getPrintName().c_str());
Expand Down
8 changes: 4 additions & 4 deletions src/estimators/state/state_generic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ bool StateGeneric::reset(void) {
/*//}*/

/* timerUpdate() //{*/
void StateGeneric::timerUpdate(const ros::TimerEvent &event) {
void StateGeneric::timerUpdate([[maybe_unused]] const ros::TimerEvent &event) {


if (!isInitialized()) {
Expand Down Expand Up @@ -288,7 +288,7 @@ void StateGeneric::timerUpdate(const ros::TimerEvent &event) {
/*//}*/

/*//{ timerCheckHealth() */
void StateGeneric::timerCheckHealth(const ros::TimerEvent &event) {
void StateGeneric::timerCheckHealth([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -362,7 +362,7 @@ void StateGeneric::timerCheckHealth(const ros::TimerEvent &event) {
/*//}*/

/* timerPubAttitude() //{*/
void StateGeneric::timerPubAttitude(const ros::TimerEvent &event) {
void StateGeneric::timerPubAttitude([[maybe_unused]] const ros::TimerEvent &event) {

if (!isInitialized()) {
return;
Expand Down Expand Up @@ -533,7 +533,7 @@ std::optional<double> StateGeneric::getHeading() const {
/*//}*/

/*//{ setUavState() */
bool StateGeneric::setUavState(const mrs_msgs::UavState &uav_state) {
bool StateGeneric::setUavState([[maybe_unused]] const mrs_msgs::UavState &uav_state) {

if (!isInState(STOPPED_STATE)) {
ROS_WARN("[%s]: Estimator state can be set only in the STOPPED state", getPrintName().c_str());
Expand Down

0 comments on commit 9f89a4e

Please sign in to comment.