Skip to content

Commit

Permalink
Add additional compiler warning options
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Dec 13, 2018
1 parent 8612aff commit 4f6c735
Show file tree
Hide file tree
Showing 88 changed files with 886 additions and 602 deletions.
12 changes: 10 additions & 2 deletions trajopt/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(trajopt)

add_compile_options(-std=c++11 -Wall -Wextra)
add_compile_options(
-std=c++11
-Wall
-Wextra
-Wsuggest-override
-Wconversion
-Wsign-conversion)

find_package(catkin REQUIRED COMPONENTS
trajopt_sco
Expand Down Expand Up @@ -33,7 +39,9 @@ set(TRAJOPT_SOURCE_FILES
)

catkin_package(
INCLUDE_DIRS include
INCLUDE_DIRS
include
${EIGEN3_INCLUDE_DIRS}
LIBRARIES
${PROJECT_NAME}
${JSONCPP_LIBRARIES}
Expand Down
2 changes: 1 addition & 1 deletion trajopt/include/trajopt/cache.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,6 @@ public:
ValueT* get(const KeyT& key)
{
KeyT* it = std::find(&keybuf[0], &keybuf[0] + bufsize, key);
return (it == &keybuf[0] + bufsize) ? NULL : &valbuf[it - &keybuf[0]];
return (it == &keybuf[0] + bufsize) ? nullptr : &valbuf[it - &keybuf[0]];
}
};
36 changes: 18 additions & 18 deletions trajopt/include/trajopt/collision_terms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ struct CollisionEvaluator
: env_(env), manip_(manip), safety_margin_data_(safety_margin_data)
{
}
virtual ~CollisionEvaluator() {}
virtual ~CollisionEvaluator() = default;
virtual void CalcDistExpressions(const DblVec& x, sco::AffExprVector& exprs) = 0;
virtual void CalcDists(const DblVec& x, DblVec& exprs) = 0;
virtual void CalcCollisions(const DblVec& x, tesseract::ContactResultVector& dist_results) = 0;
Expand Down Expand Up @@ -54,14 +54,14 @@ struct SingleTimestepCollisionEvaluator : public CollisionEvaluator
For each contact generated, return a linearization of the signed distance
function
*/
void CalcDistExpressions(const DblVec& x, sco::AffExprVector& exprs);
void CalcDistExpressions(const DblVec& x, sco::AffExprVector& exprs) override;
/**
* Same as CalcDistExpressions, but just the distances--not the expressions
*/
void CalcDists(const DblVec& x, DblVec& exprs);
void CalcCollisions(const DblVec& x, tesseract::ContactResultVector& dist_results);
void Plot(const tesseract::BasicPlottingPtr plotter, const DblVec& x);
sco::VarVector GetVars() { return m_vars; }
void CalcDists(const DblVec& x, DblVec& exprs) override;
void CalcCollisions(const DblVec& x, tesseract::ContactResultVector& dist_results) override;
void Plot(const tesseract::BasicPlottingPtr plotter, const DblVec& x) override;
sco::VarVector GetVars() override { return m_vars; }
private:
sco::VarVector m_vars;
tesseract::DiscreteContactManagerBasePtr contact_manager_;
Expand All @@ -75,11 +75,11 @@ struct CastCollisionEvaluator : public CollisionEvaluator
SafetyMarginDataConstPtr safety_margin_data,
const sco::VarVector& vars0,
const sco::VarVector& vars1);
void CalcDistExpressions(const DblVec& x, sco::AffExprVector& exprs);
void CalcDists(const DblVec& x, DblVec& exprs);
void CalcCollisions(const DblVec& x, tesseract::ContactResultVector& dist_results);
void Plot(const tesseract::BasicPlottingPtr plotter, const DblVec& x);
sco::VarVector GetVars() { return concat(m_vars0, m_vars1); }
void CalcDistExpressions(const DblVec& x, sco::AffExprVector& exprs) override;
void CalcDists(const DblVec& x, DblVec& exprs) override;
void CalcCollisions(const DblVec& x, tesseract::ContactResultVector& dist_results) override;
void Plot(const tesseract::BasicPlottingPtr plotter, const DblVec& x) override;
sco::VarVector GetVars() override { return concat(m_vars0, m_vars1); }
private:
sco::VarVector m_vars0;
sco::VarVector m_vars1;
Expand All @@ -100,10 +100,10 @@ class TRAJOPT_API CollisionCost : public sco::Cost, public Plotter
SafetyMarginDataConstPtr safety_margin_data,
const sco::VarVector& vars0,
const sco::VarVector& vars1);
virtual sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model);
virtual double value(const DblVec&);
void Plot(const tesseract::BasicPlottingPtr& plotter, const DblVec& x);
sco::VarVector getVars() { return m_calc->GetVars(); }
virtual sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override;
virtual double value(const DblVec&) override;
void Plot(const tesseract::BasicPlottingPtr& plotter, const DblVec& x) override;
sco::VarVector getVars() override { return m_calc->GetVars(); }
private:
CollisionEvaluatorPtr m_calc;
};
Expand All @@ -122,10 +122,10 @@ class TRAJOPT_API CollisionConstraint : public sco::IneqConstraint
SafetyMarginDataConstPtr safety_margin_data,
const sco::VarVector& vars0,
const sco::VarVector& vars1);
virtual sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model);
virtual DblVec value(const DblVec&);
virtual sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override;
virtual DblVec value(const DblVec&) override;
void Plot(const DblVec& x);
sco::VarVector getVars() { return m_calc->GetVars(); }
sco::VarVector getVars() override { return m_calc->GetVars(); }
private:
CollisionEvaluatorPtr m_calc;
};
Expand Down
4 changes: 3 additions & 1 deletion trajopt/include/trajopt/json_marshal.hpp
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
#pragma once
#include <trajopt_utils/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Eigen>
#include <boost/format.hpp>
#include <jsoncpp/json/json.h>
#include <sstream>
#include <string>
#include <trajopt_utils/macros.h>
#include <vector>
TRAJOPT_IGNORE_WARNINGS_POP

namespace json_marshal
{
Expand Down
13 changes: 8 additions & 5 deletions trajopt/include/trajopt/kinematic_terms.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
#pragma once

#include <trajopt_utils/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Core>
TRAJOPT_IGNORE_WARNINGS_POP

#include <tesseract_core/basic_env.h>
#include <tesseract_core/basic_kin.h>
#include <trajopt/common.hpp>
Expand Down Expand Up @@ -34,7 +37,7 @@ struct DynamicCartPoseErrCalculator : public TrajOptVectorOfVector

void Plot(const tesseract::BasicPlottingPtr& plotter, const Eigen::VectorXd& dof_vals) override;

Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const;
Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override;
};

/**
Expand All @@ -60,7 +63,7 @@ struct CartPoseErrCalculator : public TrajOptVectorOfVector

void Plot(const tesseract::BasicPlottingPtr& plotter, const Eigen::VectorXd& dof_vals) override;

Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const;
Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override;
};

/**
Expand All @@ -84,7 +87,7 @@ struct CartVelJacCalculator : sco::MatrixOfVector
{
}

Eigen::MatrixXd operator()(const Eigen::VectorXd& dof_vals) const;
Eigen::MatrixXd operator()(const Eigen::VectorXd& dof_vals) const override;
};

/**
Expand All @@ -108,6 +111,6 @@ struct CartVelErrCalculator : sco::VectorOfVector
{
}

Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const;
Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override;
};
}
38 changes: 19 additions & 19 deletions trajopt/include/trajopt/problem_description.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class TRAJOPT_API TrajOptProb : public sco::OptProb
public:
TrajOptProb();
TrajOptProb(int n_steps, const ProblemConstructionInfo& pci);
~TrajOptProb() {}
virtual ~TrajOptProb() = default;
sco::VarVector GetVarRow(int i) { return m_traj_vars.row(i); }
sco::Var& GetVar(int i, int j) { return m_traj_vars.at(i, j); }
VarArray& GetVars() { return m_traj_vars; }
Expand Down Expand Up @@ -131,7 +131,7 @@ struct TRAJOPT_API TermInfo
typedef TermInfoPtr (*MakerFunc)(void);
static void RegisterMaker(const std::string& type, MakerFunc);

virtual ~TermInfo() {}
virtual ~TermInfo() = default;

private:
static std::map<std::string, MakerFunc> name2maker;
Expand Down Expand Up @@ -181,9 +181,9 @@ struct DynamicCartPoseTermInfo : public TermInfo, public MakesCost, public Makes
DynamicCartPoseTermInfo();

/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(DynamicCartPoseTermInfo)
};

Expand Down Expand Up @@ -211,9 +211,9 @@ struct CartPoseTermInfo : public TermInfo, public MakesCost, public MakesConstra
CartPoseTermInfo();

/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(CartPoseTermInfo)
};

Expand All @@ -228,12 +228,12 @@ struct CartVelTermInfo : public TermInfo, public MakesCost, public MakesConstrai
/** @brief Timesteps over which to apply term */
int first_step, last_step;
/** @brief Link to which the term is applied */
std::string link; // LEVI This may need to be moveit LinkModel
std::string link;
double max_displacement;
/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(CartVelTermInfo)
};

Expand Down Expand Up @@ -262,9 +262,9 @@ struct JointPosTermInfo : public TermInfo, public MakesCost, public MakesConstra
/** @brief Last time step to which the term is applied*/
int last_step = -1;
/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(JointPosTermInfo)
};

Expand Down Expand Up @@ -309,9 +309,9 @@ struct JointVelTermInfo : public TermInfo, public MakesCost, public MakesConstra
/** @brief Last time step to which the term is applied*/
int last_step;
/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(JointVelTermInfo)
};

Expand Down Expand Up @@ -351,9 +351,9 @@ struct JointAccTermInfo : public TermInfo, public MakesCost, public MakesConstra
/** @brief Last time step to which the term is applied */
int last_step;
/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(JointAccTermInfo)
};

Expand Down Expand Up @@ -393,9 +393,9 @@ struct JointJerkTermInfo : public TermInfo, public MakesCost, public MakesConstr
/** @brief Last time step to which the term is applied */
int last_step;
/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(JointJerkTermInfo)
};

Expand Down Expand Up @@ -428,9 +428,9 @@ struct CollisionTermInfo : public TermInfo, public MakesCost
std::vector<SafetyMarginDataPtr> info;

/** @brief Used to add term to pci from json */
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v);
void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override;
/** @brief Converts term info into cost/constraint and adds it to trajopt problem */
void hatch(TrajOptProb& prob);
void hatch(TrajOptProb& prob) override;
DEFINE_CREATE(CollisionTermInfo)
};

Expand Down
Loading

0 comments on commit 4f6c735

Please sign in to comment.