Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add compiler options #30

Draft
wants to merge 14 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions problib/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -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 ###########
Expand Down
3 changes: 1 addition & 2 deletions problib/include/problib/globals.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@
#include <stdio.h>
#include <math.h>

#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_ */
4 changes: 2 additions & 2 deletions problib/src/pdfs/Gaussian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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(-)";
}
Expand Down
4 changes: 2 additions & 2 deletions problib/src/pdfs/Hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
Expand All @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion problib/src/pdfs/Mixture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ std::string Mixture::toString(const std::string& indent) const {
ss << "MIX{\n";
std::vector<double>::const_iterator it_w = ptr_->weights_.begin();
for (std::vector<PDF*>::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 << "}";
Expand Down
4 changes: 2 additions & 2 deletions problib/src/pdfs/PDF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
6 changes: 3 additions & 3 deletions problib/src/pdfs/PMF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand All @@ -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<std::string, double>::const_iterator it = ptr_->pmf_.begin();
if (it != ptr_->pmf_.end()) {
Expand Down
6 changes: 3 additions & 3 deletions problib/src/pdfs/Uniform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
}

Expand All @@ -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 << ")";
Expand Down
10 changes: 5 additions & 5 deletions problib/src/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,13 +52,13 @@ list<timespec> 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);

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

Expand Down Expand Up @@ -253,7 +253,7 @@ void test() {
delete pdf_exact_real;
}

int main(int argc, char **argv) {
int main() {

startTimer();
test();
Expand Down
15 changes: 9 additions & 6 deletions wire_core/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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})
Expand Down
2 changes: 1 addition & 1 deletion wire_core/src/WorldModelROS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion wire_core/src/core/PropertySet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand All @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion wire_core/src/models/FixedState.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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*/) {
Expand Down
2 changes: 1 addition & 1 deletion wire_core/src/util/ObjectModelParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
9 changes: 8 additions & 1 deletion wire_state_estimators/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -18,7 +21,11 @@ catkin_package(
pluginlib
)

include_directories(include ${catkin_INCLUDE_DIRS})
include_directories(
include
SYSTEM
${catkin_INCLUDE_DIRS}
)

## Build

Expand Down