diff --git a/problib/CMakeLists.txt b/problib/CMakeLists.txt index eac1491..295d942 100644 --- a/problib/CMakeLists.txt +++ b/problib/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 3.0.2) project(problib) +add_compile_options(-Wall -Werror=all) +add_compile_options(-Wextra -Werror=extra) + ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages @@ -28,9 +31,10 @@ catkin_package( ########### include_directories( - ${ARMADILLO_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - include + include + SYSTEM + ${catkin_INCLUDE_DIRS} + ${ARMADILLO_INCLUDE_DIRS} ) ########## feature extraction ########### diff --git a/problib/include/problib/globals.h b/problib/include/problib/globals.h index d75468b..69073b1 100644 --- a/problib/include/problib/globals.h +++ b/problib/include/problib/globals.h @@ -46,10 +46,9 @@ #include #include -#include "problib/pdfs/PDF.h" #include "problib/datatypes.h" //#define assert_msg(_Expression, _Msg) if (!_Expression) { printf(_Msg); printf("\n"); throw std::logic_error(""); } -#define assert_msg(_Expression, _Msg) do { if (!_Expression) { printf(_Msg); printf("\n"); assert(_Expression); } } while (false); +#define assert_msg(_Expression, _Msg) do { if (!(_Expression)) { printf(_Msg); printf("\n"); assert(_Expression); } } while (false); #endif /* GLOBALS_H_ */ diff --git a/problib/src/pdfs/Gaussian.cpp b/problib/src/pdfs/Gaussian.cpp index 484947a..6c91d4b 100644 --- a/problib/src/pdfs/Gaussian.cpp +++ b/problib/src/pdfs/Gaussian.cpp @@ -108,7 +108,7 @@ double Gaussian::getDensity(const arma::vec& v, double max_mah_dist) const { return getDensity(v, ptr_->mu_, ptr_->cov_, max_mah_dist); } -double Gaussian::getDensity(const Gaussian& G, double max_mah_dist) const { +double Gaussian::getDensity(const Gaussian& G, double /*max_mah_dist*/) const { CHECK_INITIALIZED arma::mat S = G.getCovariance() + ptr_->cov_; return getDensity(ptr_->mu_, G.getMean(), S); @@ -188,7 +188,7 @@ const arma::mat& Gaussian::getCovariance() const { return ptr_->cov_; } -std::string Gaussian::toString(const std::string& indent) const { +std::string Gaussian::toString(const std::string& /*indent*/) const { if (!ptr_) { return "N(-)"; } diff --git a/problib/src/pdfs/Hybrid.cpp b/problib/src/pdfs/Hybrid.cpp index 8d76286..c59ddb7 100644 --- a/problib/src/pdfs/Hybrid.cpp +++ b/problib/src/pdfs/Hybrid.cpp @@ -84,7 +84,7 @@ void Hybrid::cloneStruct() { } } -double Hybrid::getLikelihood(const PDF& pdf) const { +double Hybrid::getLikelihood(const PDF& /*pdf*/) const { assert_msg(false, "Likelihood method not implemented. Please create a subclass of Hybrid and implement your own method."); return 0.; // Never reached because of assertion of false } @@ -104,7 +104,7 @@ double Hybrid::getMaxDensity() const { return 0; } -void Hybrid::addPDF(const PDF& pdf, double priority) { +void Hybrid::addPDF(const PDF& pdf, double /*priority*/) { if (dimensions_ < 0) { dimensions_ = pdf.dimensions(); } else { diff --git a/problib/src/pdfs/Mixture.cpp b/problib/src/pdfs/Mixture.cpp index ced2dbb..f16f3b9 100644 --- a/problib/src/pdfs/Mixture.cpp +++ b/problib/src/pdfs/Mixture.cpp @@ -170,7 +170,7 @@ std::string Mixture::toString(const std::string& indent) const { ss << "MIX{\n"; std::vector::const_iterator it_w = ptr_->weights_.begin(); for (std::vector::const_iterator it_pdf = ptr_->components_.begin(); it_pdf != ptr_->components_.end(); ++it_pdf) { - ss << new_indent << (*it_w) << " : " << (*it_pdf)->toString(new_indent) << "\n"; + ss << new_indent << (*it_w) << ": " << (*it_pdf)->toString(new_indent) << "\n"; ++it_w; } ss << indent << "}"; diff --git a/problib/src/pdfs/PDF.cpp b/problib/src/pdfs/PDF.cpp index 3dd7f9e..737f1e7 100644 --- a/problib/src/pdfs/PDF.cpp +++ b/problib/src/pdfs/PDF.cpp @@ -57,10 +57,10 @@ PDF::PDFType PDF::type() const { return type_; } -bool PDF::getExpectedValue(std::string& v) const { +bool PDF::getExpectedValue(std::string& /*v*/) const { return false; } -bool PDF::getExpectedValue(arma::vec& v) const { +bool PDF::getExpectedValue(arma::vec& /*v*/) const { return false; } diff --git a/problib/src/pdfs/PMF.cpp b/problib/src/pdfs/PMF.cpp index c038d69..51d1f98 100644 --- a/problib/src/pdfs/PMF.cpp +++ b/problib/src/pdfs/PMF.cpp @@ -280,7 +280,7 @@ void PMF::normalize() { ptr_->total_prob_ = 1; } -double PMF::getDensity(const arma::vec& v) const { +double PMF::getDensity(const arma::vec& /*v*/) const { assert_msg(false, "Cannot get density of a PMF"); return 0; } @@ -290,9 +290,9 @@ double PMF::getMaxDensity() const { return 0; } -std::string PMF::toString(const std::string& indent) const { +std::string PMF::toString(const std::string& /*indent*/) const { std::stringstream ss; - ss << indent << "PMF(" << ptr_->domain_size_ << ")["; + ss << "PMF(" << ptr_->domain_size_ << ")["; std::map::const_iterator it = ptr_->pmf_.begin(); if (it != ptr_->pmf_.end()) { diff --git a/problib/src/pdfs/Uniform.cpp b/problib/src/pdfs/Uniform.cpp index b010fb9..1aa92f9 100644 --- a/problib/src/pdfs/Uniform.cpp +++ b/problib/src/pdfs/Uniform.cpp @@ -125,7 +125,7 @@ void Uniform::setDensity(const double& density) { size_is_set_ = false; } -double Uniform::getDensity(const arma::vec& vec) const { +double Uniform::getDensity(const arma::vec& /*vec*/) const { return uniform_probability_; } @@ -151,12 +151,12 @@ void Uniform::calculateUniformDensity() { size_is_set_ = true; } -std::string Uniform::toString(const std::string& indent) const { +std::string Uniform::toString(const std::string& /*indent*/) const { std::stringstream s; s << "U(" << uniform_probability_; if (size_is_set_) { - s << ", mean = " << mean_ << ", size = " << size_; + s << ", mean =\n" << mean_ << ", size =\n" << size_; } s << ")"; diff --git a/problib/src/test.cpp b/problib/src/test.cpp index c38b699..728cb50 100644 --- a/problib/src/test.cpp +++ b/problib/src/test.cpp @@ -52,13 +52,13 @@ list TIMERS; stringstream TIMER_LOG; stringstream OUTPUT_LOG; -inline void startTimer(int ID = 0) { +inline void startTimer(int /*ID*/=0) { timespec t_start; clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &t_start); TIMERS.push_back(t_start); } -inline void stopTimer(string msg, int ID = 0, double factor = 1) { +inline void stopTimer(string msg, int /*ID*/=0, double factor=1) { timespec t_end; clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &t_end); @@ -148,7 +148,7 @@ void test() { for (int i = 0; i < 1000; ++i) { d = mix2.getLikelihood(exact2); } - cout << "Density of mixture at " << mean2 << " = " << d << endl << endl; + cout << "Density of mixture at:\n" << mean2 << " = " << d << endl << endl; cout << "Converting to msg ..." << endl << endl; problib_msgs::PDF pdf_msg; @@ -159,7 +159,7 @@ void test() { PDF* received_pdf = pbl::msgToPDF(pdf_msg); cout << "Result:" << endl << received_pdf->toString() << endl << endl; - cout << "Density of mixture at " << mean2 << " = " << received_pdf->getLikelihood(exact2) << endl << endl; + cout << "Density of mixture at:\n" << mean2 << " = " << received_pdf->getLikelihood(exact2) << endl << endl; delete received_pdf; @@ -253,7 +253,7 @@ void test() { delete pdf_exact_real; } -int main(int argc, char **argv) { +int main() { startTimer(); test(); diff --git a/wire_core/CMakeLists.txt b/wire_core/CMakeLists.txt index 8d89326..3773cc2 100644 --- a/wire_core/CMakeLists.txt +++ b/wire_core/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 3.0.2) project(wire_core) +add_compile_options(-Wall -Werror=all) +add_compile_options(-Wextra -Werror=extra) + ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages @@ -32,13 +35,14 @@ catkin_package( TinyXML2 ) -include_directories(include ${catkin_INCLUDE_DIRS} ${TinyXML2_INCLUDE_DIRS}) +include_directories( + include + SYSTEM + ${catkin_INCLUDE_DIRS} + ${TinyXML2_INCLUDE_DIRS} +) ## Build -add_compile_options(-Wreturn-type) # Return type checking -add_compile_options(-Wreorder) - - add_library(wire src/WorldModelROS.cpp src/models/FixedState.cpp @@ -74,7 +78,6 @@ add_library(wire include/wire/logic/AssignmentMatrix.h include/wire/logic/Hypothesis.h include/wire/logic/HypothesesTree.h - ) target_link_libraries(wire ${catkin_LIBRARIES} ${TinyXML2_LIBRARIES}) diff --git a/wire_core/src/WorldModelROS.cpp b/wire_core/src/WorldModelROS.cpp index f3406b7..7a3d031 100644 --- a/wire_core/src/WorldModelROS.cpp +++ b/wire_core/src/WorldModelROS.cpp @@ -301,7 +301,7 @@ void WorldModelROS::processEvidence(const wire_msgs::WorldEvidence& world_eviden } } -bool WorldModelROS::resetWorldModel(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) { +bool WorldModelROS::resetWorldModel(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/) { delete world_model_; world_model_ = new HypothesisTree(max_num_hyps_, min_prob_ratio_); return true; diff --git a/wire_core/src/core/PropertySet.cpp b/wire_core/src/core/PropertySet.cpp index d25d408..f1f1b89 100644 --- a/wire_core/src/core/PropertySet.cpp +++ b/wire_core/src/core/PropertySet.cpp @@ -103,7 +103,7 @@ void PropertySet::propagate(const Time& time) { timestamp_ = time; } -void PropertySet::update(const pbl::PDF& z, const Time& time) { +void PropertySet::update(const pbl::PDF& /*z*/, const Time& /*time*/) { assert(false); } @@ -115,6 +115,7 @@ void PropertySet::reset() { const pbl::PDF& PropertySet::getValue() const { assert(false); + return pbl::PDF(0, pbl::PDF::UNKNOWN); } double PropertySet::getLikelihood(const PropertySet& P) const { diff --git a/wire_core/src/models/FixedState.cpp b/wire_core/src/models/FixedState.cpp index 15bf3fd..36373e9 100644 --- a/wire_core/src/models/FixedState.cpp +++ b/wire_core/src/models/FixedState.cpp @@ -27,7 +27,7 @@ FixedState* FixedState::clone() const { return new FixedState(*this); } -void FixedState::update(const pbl::PDF& z, const mhf::Time& /*time*/) { +void FixedState::update(const pbl::PDF& /*z*/, const mhf::Time& /*time*/) { } void FixedState::propagate(const mhf::Time& /*time*/) { diff --git a/wire_core/src/util/ObjectModelParser.cpp b/wire_core/src/util/ObjectModelParser.cpp index 286cc06..8734614 100644 --- a/wire_core/src/util/ObjectModelParser.cpp +++ b/wire_core/src/util/ObjectModelParser.cpp @@ -104,7 +104,7 @@ bool ObjectModelParser::parseStateEstimator(ClassModel* obj_model, const tinyxml // check behavior model's attribute and model type std::string attribute_name, model_type; if (!getAttributeValue(elem, "attribute", attribute_name, error) - | !getAttributeValue(elem, "model", model_type, error)) { + || !getAttributeValue(elem, "model", model_type, error)) { return false; } diff --git a/wire_state_estimators/CMakeLists.txt b/wire_state_estimators/CMakeLists.txt index 092df7c..e631aba 100644 --- a/wire_state_estimators/CMakeLists.txt +++ b/wire_state_estimators/CMakeLists.txt @@ -1,6 +1,9 @@ cmake_minimum_required(VERSION 3.0.2) project(wire_state_estimators) +add_compile_options(-Wall -Werror=all) +add_compile_options(-Wextra -Werror=extra) + ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages @@ -18,7 +21,11 @@ catkin_package( pluginlib ) -include_directories(include ${catkin_INCLUDE_DIRS}) +include_directories( + include + SYSTEM + ${catkin_INCLUDE_DIRS} +) ## Build