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

Fix enable and clang-tidy errors #332

Merged
Merged
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
18 changes: 17 additions & 1 deletion .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ Checks: >
clang-analyzer-*,
-clang-analyzer-cplusplus*,
bugprone-*,
-bugprone-easily-swappable-parameters,
-bugprone-exception-escape,
cppcoreguidelines-*,
-cppcoreguidelines-macro-usage,
-cppcoreguidelines-pro-type-static-cast-downcast,
Expand All @@ -16,8 +18,10 @@ Checks: >
-cppcoreguidelines-pro-bounds-constant-array-index,
-cppcoreguidelines-avoid-magic-numbers,
-cppcoreguidelines-non-private-member-variables-in-classes,
-cppcoreguidelines-owning-memory,
misc-*,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
modernize-*,
-modernize-use-trailing-return-type,
-modernize-use-nodiscard,
Expand All @@ -27,14 +31,19 @@ Checks: >
-readability-named-parameter,
-readability-magic-numbers,
-readability-isolate-declaration,
-readability-function-cognitive-complexity
-readability-function-cognitive-complexity,
-readability-use-anyofallof,
-readability-identifier-length,
-readability-suspicious-call-argument
WarningsAsErrors: >
-*,
clang-diagnostic-*,
-clang-diagnostic-unknown-warning-option,
clang-analyzer-*,
-clang-analyzer-cplusplus*,
bugprone-*,
-bugprone-easily-swappable-parameters,
-bugprone-exception-escape,
cppcoreguidelines-*,
-cppcoreguidelines-macro-usage,
-cppcoreguidelines-pro-type-static-cast-downcast,
Expand All @@ -45,8 +54,10 @@ WarningsAsErrors: >
-cppcoreguidelines-pro-bounds-constant-array-index,
-cppcoreguidelines-avoid-magic-numbers,
-cppcoreguidelines-non-private-member-variables-in-classes,
-cppcoreguidelines-owning-memory,
misc-*,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
modernize-*,
-modernize-use-trailing-return-type,
-modernize-use-nodiscard,
Expand All @@ -57,6 +68,9 @@ WarningsAsErrors: >
-readability-magic-numbers,
-readability-isolate-declaration,
-readability-function-cognitive-complexity
-readability-use-anyofallof,
-readability-identifier-length,
-readability-suspicious-call-argument
HeaderFilterRegex: '.*'
AnalyzeTemporaryDtors: false
FormatStyle: none
Expand All @@ -67,4 +81,6 @@ CheckOptions:
value: '1'
- key: cppcoreguidelines-special-member-functions.AllowSoleDefaultDtor
value: '1'
- key: cppcoreguidelines-pro-type-member-init.IgnoreArrays
value: '1'
...
2 changes: 1 addition & 1 deletion trajopt_sco/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ target_compile_options(${PROJECT_NAME} PRIVATE ${TRAJOPT_COMPILE_OPTIONS_PRIVATE
target_compile_options(${PROJECT_NAME} PUBLIC ${TRAJOPT_COMPILE_OPTIONS_PUBLIC})
target_compile_definitions(${PROJECT_NAME} PUBLIC ${TRAJOPT_COMPILE_DEFINITIONS})
target_cxx_version(${PROJECT_NAME} PUBLIC VERSION ${TRAJOPT_CXX_VERSION})
# target_clang_tidy(${PROJECT_NAME} ENABLE ${TRAJOPT_ENABLE_CLANG_TIDY})
target_clang_tidy(${PROJECT_NAME} ENABLE ${TRAJOPT_ENABLE_CLANG_TIDY})
target_include_directories(${PROJECT_NAME} PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")

Expand Down
10 changes: 5 additions & 5 deletions trajopt_sco/include/trajopt_sco/bpmpd_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void ser(int fp, std::vector<T>& x, SerMode mode)

struct bpmpd_input
{
int m, n, nz, qn, qnz;
int m{ 0 }, n{ 0 }, nz{ 0 }, qn{ 0 }, qnz{ 0 };
std::vector<int> acolcnt, acolidx;
std::vector<double> acolnzs;
std::vector<int> qcolcnt, qcolidx;
Expand Down Expand Up @@ -114,7 +114,7 @@ const char CHECK_CHAR = 111;

inline void ser(int fp, bpmpd_input& bi, SerMode mode)
{
char scorrect = 'z', s = (mode == SER) ? scorrect : 0;
char scorrect = 'z', s = (mode == SER) ? scorrect : 0; // NOLINT
ser(fp, s, mode);
if (s == EXIT_CHAR)
{
Expand Down Expand Up @@ -142,8 +142,8 @@ struct bpmpd_output
{
std::vector<double> primal, dual;
std::vector<int> status;
int code;
double opt;
int code{ 0 };
double opt{ 0 };
bpmpd_output() = default;
bpmpd_output(std::vector<double> primal, std::vector<double> dual, std::vector<int> status, int code, double opt)
: primal(std::move(primal)), dual(std::move(dual)), status(std::move(status)), code(code), opt(opt)
Expand All @@ -153,7 +153,7 @@ struct bpmpd_output

inline void ser(int fp, bpmpd_output& bo, SerMode mode)
{
char scorrect = CHECK_CHAR, s = (mode == SER) ? scorrect : 0;
char scorrect = CHECK_CHAR, s = (mode == SER) ? scorrect : 0; // NOLINT
ser(fp, s, mode);
if (s == EXIT_CHAR)
{
Expand Down
4 changes: 2 additions & 2 deletions trajopt_sco/include/trajopt_sco/modeling.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,10 @@ class ConvexObjective
void addL2Norm(const AffExprVector&);
void addMax(const AffExprVector&);

bool inModel() { return model_ != nullptr; }
bool inModel() const { return model_ != nullptr; }
void addConstraintsToModel();
void removeFromModel();
double value(const DblVec& x);
double value(const DblVec& x) const;

Model* model_;
/// The objective Function
Expand Down
18 changes: 10 additions & 8 deletions trajopt_sco/include/trajopt_sco/optimizers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <functional>
#include <string>
#include <array>
TRAJOPT_IGNORE_WARNINGS_POP

#include <trajopt_sco/modeling.hpp>
Expand All @@ -22,24 +23,25 @@ enum OptStatus
OPT_FAILED,
INVALID
};
static const char* OptStatus_strings[] = { "CONVERGED",
"SCO_ITERATION_LIMIT",
"PENALTY_ITERATION_LIMIT",
"FAILED",
"INVALID" };
static const std::array<std::string, 5> OptStatus_strings = { "CONVERGED",
"SCO_ITERATION_LIMIT",
"PENALTY_ITERATION_LIMIT",
"FAILED",
"INVALID" };
inline std::string statusToString(OptStatus status) { return OptStatus_strings[status]; }
struct OptResults
{
DblVec x; // solution estimate
OptStatus status;
double total_cost;
OptStatus status{ INVALID };
double total_cost{ 0 };
DblVec cost_vals;
DblVec cnt_viols;
int n_func_evals, n_qp_solves;
int n_func_evals{ 0 }, n_qp_solves{ 0 };
void clear()
{
x.clear();
status = INVALID;
total_cost = 0;
cost_vals.clear();
cnt_viols.clear();
n_func_evals = 0;
Expand Down
4 changes: 2 additions & 2 deletions trajopt_sco/include/trajopt_sco/osqp_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ struct OSQPModelConfig : public ModelConfig

OSQPModelConfig();

OSQPSettings settings;
OSQPSettings settings{};
};

/**
Expand All @@ -35,7 +35,7 @@ class OSQPModel : public Model
{
/** OSQPData. Some fields here (`osp_data_.A` and `osp_data_.P`) are * automatically allocated by OSQP, but
* deallocated by us. */
OSQPData osqp_data_;
OSQPData osqp_data_{};

/** OSQP Workspace. Memory here is managed by OSQP */
OSQPWorkspace* osqp_workspace_{ nullptr };
Expand Down
16 changes: 10 additions & 6 deletions trajopt_sco/include/trajopt_sco/qpoases_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,11 @@ class qpOASESModel : public Model

public:
qpOASESModel();
virtual ~qpOASESModel();
~qpOASESModel() override;
qpOASESModel(const qpOASESModel&) = default;
qpOASESModel& operator=(const qpOASESModel&) = default;
qpOASESModel(qpOASESModel&&) = default;
qpOASESModel& operator=(qpOASESModel&&) = default;

Var addVar(const std::string& name) override;
Cnt addEqCnt(const AffExpr&, const std::string& name) override;
Expand All @@ -85,10 +89,10 @@ class qpOASESModel : public Model
void update() override;
void setVarBounds(const VarVector& vars, const DblVec& lower, const DblVec& upper) override;
DblVec getVarValues(const VarVector& vars) const override;
virtual CvxOptStatus optimize() override;
virtual void setObjective(const AffExpr&) override;
virtual void setObjective(const QuadExpr&) override;
virtual void writeToFile(const std::string& fname) const override;
virtual VarVector getVars() const override;
CvxOptStatus optimize() override;
void setObjective(const AffExpr&) override;
void setObjective(const QuadExpr&) override;
void writeToFile(const std::string& fname) const override;
VarVector getVars() const override;
};
} // namespace sco
8 changes: 4 additions & 4 deletions trajopt_sco/include/trajopt_sco/solver_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,17 +136,17 @@ struct CntRep
{
using Ptr = std::shared_ptr<CntRep>;

CntRep(std::size_t _index, void* _creator) : index(_index), removed(false), creator(_creator) {}
CntRep(std::size_t _index, void* _creator) : index(_index), creator(_creator) {}
CntRep(const CntRep&) = default;
CntRep& operator=(const CntRep&) = default;
CntRep(CntRep&&) = default;
CntRep& operator=(CntRep&&) = default;
~CntRep() = default;

std::size_t index;
bool removed;
bool removed{ false };
void* creator;
ConstraintType type;
ConstraintType type{ ConstraintType::EQ };
std::string expr; // todo placeholder
};

Expand Down Expand Up @@ -181,7 +181,7 @@ struct AffExpr
AffExpr& operator=(AffExpr&&) = default;

explicit AffExpr(double a) : constant(a) {}
explicit AffExpr(const Var& v) : constant(0), coeffs(1, 1), vars(1, v) {}
explicit AffExpr(const Var& v) : coeffs(1, 1), vars(1, v) {}

size_t size() const { return coeffs.size(); }
double value(const double* x) const;
Expand Down
8 changes: 4 additions & 4 deletions trajopt_sco/include/trajopt_sco/solver_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ void exprToEigen(const QuadExpr& expr,
void exprToEigen(const AffExprVector& expr_vec,
Eigen::SparseMatrix<double>& sparse_matrix,
Eigen::VectorXd& vector,
const Eigen::Index& n_vars = -1);
Eigen::Index n_vars = -1);
/**
* @brief Converts triplets to an `Eigen::SparseMatrix`.
* @param [in] rows_i a vector of row indices
Expand Down Expand Up @@ -121,7 +121,7 @@ void eigenToCSC(Eigen::SparseMatrix<double>& sparse_matrix,
if (sizeof(T) != sizeof(int))
{
IntVec row_indices_int, column_pointers_int;
auto si_p = sm_ref.get().innerIndexPtr();
auto* si_p = sm_ref.get().innerIndexPtr();
row_indices_int.assign(si_p, si_p + sm_ref.get().nonZeros());
row_indices.clear();
row_indices.reserve(row_indices_int.size());
Expand All @@ -137,7 +137,7 @@ void eigenToCSC(Eigen::SparseMatrix<double>& sparse_matrix,
}
else
{
auto si_p = sm_ref.get().innerIndexPtr();
auto* si_p = sm_ref.get().innerIndexPtr();
row_indices.assign(si_p, si_p + sm_ref.get().nonZeros());

si_p = sm_ref.get().outerIndexPtr();
Expand All @@ -148,7 +148,7 @@ void eigenToCSC(Eigen::SparseMatrix<double>& sparse_matrix,
// pointers ends with the number of non-zero elements
column_pointers.push_back(static_cast<T>(sm_ref.get().nonZeros()));

auto csc_v = sm_ref.get().valuePtr();
auto* csc_v = sm_ref.get().valuePtr();
values.assign(csc_v, csc_v + sm_ref.get().nonZeros());
}
} // namespace sco
24 changes: 12 additions & 12 deletions trajopt_sco/src/bpmpd_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ logfile it generates.

namespace sco
{
static double BPMPD_BIG = 1e+30;
static const double BPMPD_BIG = 1e+30;

Model::Ptr createBPMPDModel()
{
Expand All @@ -163,10 +163,10 @@ Model::Ptr createBPMPDModel()

pid_t popen2(const char* command, int* infp, int* outfp)
{
int p_stdin[2], p_stdout[2];
pid_t pid;
std::array<int, 2> p_stdin{}, p_stdout{};
pid_t pid{ 0 };

if (pipe(p_stdin) != 0 || pipe(p_stdout) != 0)
if (pipe(p_stdin.data()) != 0 || pipe(p_stdout.data()) != 0)
return -1;

pid = fork();
Expand Down Expand Up @@ -202,14 +202,14 @@ pid_t popen2(const char* command, int* infp, int* outfp)
return pid;
}

static pid_t gPID = 0;
static int gPipeIn = 0;
static int gPipeOut = 0;
static pid_t gPID = 0; // NOLINT
static int gPipeIn = 0; // NOLINT
static int gPipeOut = 0; // NOLINT

void fexit()
{
char text[1] = { bpmpd_io::EXIT_CHAR };
long n = write(gPipeIn, text, 1);
std::array<char, 1> text{ bpmpd_io::EXIT_CHAR };
long n = write(gPipeIn, text.data(), 1);
ALWAYS_ASSERT(n == 1);
}

Expand Down Expand Up @@ -271,7 +271,7 @@ void BPMPDModel::removeCnts(const CntVector& cnts)
{
SizeTVec inds;
cnts2inds(cnts, inds);
for (auto& cnt : cnts)
for (auto& cnt : cnts) // NOLINT
cnt.cnt_rep->removed = true;
}

Expand Down Expand Up @@ -438,8 +438,8 @@ CvxOptStatus BPMPDModel::optimize()
}

#define VECINC(vec) \
for (unsigned i = 0; i < (vec).size(); ++i) \
++(vec)[i];
for (auto& v : (vec)) \
++v;
VECINC(acolidx);
VECINC(qcolidx);
#undef VECINC
Expand Down
13 changes: 7 additions & 6 deletions trajopt_sco/src/modeling.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ void ConvexObjective::addAffExpr(const AffExpr& affexpr) { exprInc(quad_, affexp
void ConvexObjective::addQuadExpr(const QuadExpr& quadexpr) { exprInc(quad_, quadexpr); }
void ConvexObjective::addHinge(const AffExpr& affexpr, double coeff)
{
Var hinge = model_->addVar("hinge", 0, INFINITY);
Var hinge = model_->addVar("hinge", 0, static_cast<double>(INFINITY));
vars_.push_back(hinge);
ineqs_.push_back(affexpr);
exprDec(ineqs_.back(), hinge);
Expand All @@ -30,8 +30,8 @@ void ConvexObjective::addHinge(const AffExpr& affexpr, double coeff)
void ConvexObjective::addAbs(const AffExpr& affexpr, double coeff)
{
// Add variables that will enforce ABS
Var neg = model_->addVar("neg", 0, INFINITY);
Var pos = model_->addVar("pos", 0, INFINITY);
Var neg = model_->addVar("neg", 0, static_cast<double>(INFINITY));
Var pos = model_->addVar("pos", 0, static_cast<double>(INFINITY));
vars_.push_back(neg);
vars_.push_back(pos);
// Coeff will be applied whenever neg/pos are not 0
Expand Down Expand Up @@ -76,7 +76,7 @@ void ConvexObjective::addL2Norm(const AffExprVector& ev)

void ConvexObjective::addMax(const AffExprVector& ev)
{
Var m = model_->addVar("max", -INFINITY, INFINITY);
Var m = model_->addVar("max", static_cast<double>(-INFINITY), static_cast<double>(INFINITY));
ineqs_.reserve(ineqs_.size() + ev.size());
for (const auto& i : ev)
{
Expand Down Expand Up @@ -148,7 +148,7 @@ ConvexConstraints::~ConvexConstraints()
removeFromModel();
}

double ConvexObjective::value(const DblVec& x) { return quad_.value(x); }
double ConvexObjective::value(const DblVec& x) const { return quad_.value(x); }
DblVec Constraint::violations(const DblVec& x)
{
DblVec val = value(x);
Expand All @@ -175,7 +175,8 @@ OptProb::OptProb(ModelType convex_solver, const ModelConfig::ConstPtr& convex_so
}
VarVector OptProb::createVariables(const std::vector<std::string>& names)
{
return createVariables(names, DblVec(names.size(), -INFINITY), DblVec(names.size(), INFINITY));
return createVariables(
names, DblVec(names.size(), static_cast<double>(-INFINITY)), DblVec(names.size(), static_cast<double>(INFINITY)));
}

VarVector OptProb::createVariables(const std::vector<std::string>& names, const DblVec& lb, const DblVec& ub)
Expand Down
Loading
Loading