Skip to content

Commit

Permalink
Fix formatting using clang
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Dec 21, 2018
1 parent 418c59b commit 5f72fae
Show file tree
Hide file tree
Showing 42 changed files with 303 additions and 333 deletions.
2 changes: 1 addition & 1 deletion .clang-format
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
---
# find . -path ./trajopt_ext/vhacd -prune -o -regex '.*\.\(cpp\|hpp\|cc\|cxx\|h\|hxx\)' -exec clang-format -style=file -i {} \;
# find . -type f -regex '.*\.\(cpp\|hpp\|cc\|cxx\|h\|hxx\)' -exec clang-format -style=file -i {} \;
BasedOnStyle: Google
AccessModifierOffset: -2
AlignEscapedNewlinesLeft: false
Expand Down
2 changes: 0 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ env:
matrix:
include:
- env: ROS_DISTRO=kinetic CLANG_FORMAT_CHECK=file
git:
submodules: false
- env: ROS_DISTRO=kinetic ROS_REPO=ros NOT_TEST_INSTALL=true
- env: ROS_DISTRO=kinetic ROS_REPO=ros-shadow-fixed NOT_TEST_INSTALL=true
- env: ROS_DISTRO=melodic ROS_REPO=ros NOT_TEST_INSTALL=true
Expand Down
3 changes: 1 addition & 2 deletions trajopt/include/trajopt/file_write_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,5 @@

namespace trajopt
{
sco::Optimizer::Callback WriteCallback(std::shared_ptr<std::ofstream> file,
const TrajOptProbPtr& prob);
sco::Optimizer::Callback WriteCallback(std::shared_ptr<std::ofstream> file, const TrajOptProbPtr& prob);
}
25 changes: 12 additions & 13 deletions trajopt/include/trajopt/kinematic_terms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ TRAJOPT_IGNORE_WARNINGS_POP

namespace trajopt
{

/**
* @brief Used to calculate the error for CartPoseTermInfo
* This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc
Expand All @@ -27,10 +26,10 @@ struct DynamicCartPoseErrCalculator : public TrajOptVectorOfVector
std::string link_;
Eigen::Isometry3d tcp_;
DynamicCartPoseErrCalculator(const std::string& target,
tesseract::BasicKinConstPtr manip,
tesseract::BasicEnvConstPtr env,
std::string link,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
tesseract::BasicKinConstPtr manip,
tesseract::BasicEnvConstPtr env,
std::string link,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
: target_(target), manip_(manip), env_(env), link_(link), tcp_(tcp)
{
}
Expand All @@ -53,10 +52,10 @@ struct CartPoseErrCalculator : public TrajOptVectorOfVector
std::string link_;
Eigen::Isometry3d tcp_;
CartPoseErrCalculator(const Eigen::Isometry3d& pose,
tesseract::BasicKinConstPtr manip,
tesseract::BasicEnvConstPtr env,
std::string link,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
tesseract::BasicKinConstPtr manip,
tesseract::BasicEnvConstPtr env,
std::string link,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
: pose_inv_(pose.inverse()), manip_(manip), env_(env), link_(link), tcp_(tcp)
{
}
Expand Down Expand Up @@ -103,10 +102,10 @@ struct CartVelErrCalculator : sco::VectorOfVector
double limit_;
Eigen::Isometry3d tcp_;
CartVelErrCalculator(tesseract::BasicKinConstPtr manip,
tesseract::BasicEnvConstPtr env,
std::string link,
double limit,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
tesseract::BasicEnvConstPtr env,
std::string link,
double limit,
Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity())
: manip_(manip), env_(env), link_(link), limit_(limit), tcp_(tcp)
{
}
Expand Down
23 changes: 10 additions & 13 deletions trajopt/include/trajopt/problem_description.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class TRAJOPT_API TrajOptProb : public sco::OptProb
TrajOptProb();
TrajOptProb(int n_steps, const ProblemConstructionInfo& pci);
virtual ~TrajOptProb() = default;
sco::VarVector GetVarRow(int i, int start_col, int num_col){ return m_traj_vars.rblock(i, start_col, num_col);}
sco::VarVector GetVarRow(int i, int start_col, int num_col) { return m_traj_vars.rblock(i, start_col, num_col); }
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 All @@ -66,11 +66,9 @@ class TRAJOPT_API TrajOptProb : public sco::OptProb
TrajArray GetInitTraj() { return m_init_traj; }
friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&);
/** @brief Returns TrajOptProb.has_time */
bool GetHasTime() { return has_time;}
bool GetHasTime() { return has_time; }
/** @brief Sets TrajOptProb.has_time */
void SetHasTime(bool tmp) { has_time = tmp;}


void SetHasTime(bool tmp) { has_time = tmp; }
private:
/** @brief If true, the last column in the optimization matrix will be 1/dt */
bool has_time;
Expand Down Expand Up @@ -115,14 +113,15 @@ Initialization info read from json
*/
struct InitInfo
{
/** @brief Methods of initializing the optimization matrix
/** @brief Methods of initializing the optimization matrix
STATIONARY: Initializes all joint values to the initial value (the current value in the env pci.env->getCurrentJointValues)
JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data
GIVEN_TRAJ: Initializes the matrix to a given trajectory
STATIONARY: Initializes all joint values to the initial value (the current value in the env
pci.env->getCurrentJointValues)
JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data
GIVEN_TRAJ: Initializes the matrix to a given trajectory
In all cases the dt column (if present) is appended the selected method is defined.
*/
In all cases the dt column (if present) is appended the selected method is defined.
*/
enum Type
{
STATIONARY,
Expand Down Expand Up @@ -154,7 +153,6 @@ struct TRAJOPT_API TermInfo
std::string name;
int term_type;
int getSupportedTypes() { return supported_term_types_; }

virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0;
virtual void hatch(TrajOptProb& prob) = 0;

Expand All @@ -171,7 +169,6 @@ struct TRAJOPT_API TermInfo

protected:
TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) {}

private:
static std::map<std::string, MakerFunc> name2maker;
int supported_term_types_;
Expand Down
29 changes: 0 additions & 29 deletions trajopt/include/trajopt/trajectory_costs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ class TRAJOPT_API JointPosEqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -38,7 +37,6 @@ class TRAJOPT_API JointPosEqCost : public sco::Cost
int first_step_;
/** @brief Last time step to which the term is applied */
int last_step_;

};

/**
Expand All @@ -61,7 +59,6 @@ class TRAJOPT_API JointPosIneqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -79,7 +76,6 @@ class TRAJOPT_API JointPosIneqCost : public sco::Cost
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointPosEqConstraint : public sco::EqConstraint
Expand All @@ -101,7 +97,6 @@ class TRAJOPT_API JointPosEqConstraint : public sco::EqConstraint
/** Sum of violations */
double violation(const DblVec& x);
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand Down Expand Up @@ -133,7 +128,6 @@ class TRAJOPT_API JointPosIneqConstraint : public sco::IneqConstraint
/** @brief Numerically evaluate cost given the vector of values */
DblVec value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -151,10 +145,8 @@ class TRAJOPT_API JointPosIneqConstraint : public sco::IneqConstraint
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */
std::vector<sco::AffExpr> expr_vec_;

};


class TRAJOPT_API JointVelEqCost : public sco::Cost
{
public:
Expand All @@ -169,7 +161,6 @@ class TRAJOPT_API JointVelEqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values using Eigen*/
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -183,7 +174,6 @@ class TRAJOPT_API JointVelEqCost : public sco::Cost
int first_step_;
/** @brief Last time step to which the term is applied */
int last_step_;

};

class TRAJOPT_API JointVelIneqCost : public sco::Cost
Expand All @@ -202,7 +192,6 @@ class TRAJOPT_API JointVelIneqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -220,7 +209,6 @@ class TRAJOPT_API JointVelIneqCost : public sco::Cost
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointVelEqConstraint : public sco::EqConstraint
Expand All @@ -242,7 +230,6 @@ class TRAJOPT_API JointVelEqConstraint : public sco::EqConstraint
/** Sum of violations */
double violation(const DblVec& x);
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand Down Expand Up @@ -274,7 +261,6 @@ class TRAJOPT_API JointVelIneqConstraint : public sco::IneqConstraint
/** @brief Numerically evaluate cost given the vector of values */
DblVec value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -292,7 +278,6 @@ class TRAJOPT_API JointVelIneqConstraint : public sco::IneqConstraint
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-1)*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointAccEqCost : public sco::Cost
Expand All @@ -309,7 +294,6 @@ class TRAJOPT_API JointAccEqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -323,7 +307,6 @@ class TRAJOPT_API JointAccEqCost : public sco::Cost
int first_step_;
/** @brief Last time step to which the term is applied */
int last_step_;

};

class TRAJOPT_API JointAccIneqCost : public sco::Cost
Expand All @@ -342,7 +325,6 @@ class TRAJOPT_API JointAccIneqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -360,7 +342,6 @@ class TRAJOPT_API JointAccIneqCost : public sco::Cost
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-2)*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointAccEqConstraint : public sco::EqConstraint
Expand All @@ -382,7 +363,6 @@ class TRAJOPT_API JointAccEqConstraint : public sco::EqConstraint
/** Sum of violations */
double violation(const DblVec& x);
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand Down Expand Up @@ -414,7 +394,6 @@ class TRAJOPT_API JointAccIneqConstraint : public sco::IneqConstraint
/** @brief Numerically evaluate cost given the vector of values */
DblVec value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -432,7 +411,6 @@ class TRAJOPT_API JointAccIneqConstraint : public sco::IneqConstraint
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-2)*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointJerkEqCost : public sco::Cost
Expand All @@ -449,7 +427,6 @@ class TRAJOPT_API JointJerkEqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -463,7 +440,6 @@ class TRAJOPT_API JointJerkEqCost : public sco::Cost
int first_step_;
/** @brief Last time step to which the term is applied */
int last_step_;

};

class TRAJOPT_API JointJerkIneqCost : public sco::Cost
Expand All @@ -482,7 +458,6 @@ class TRAJOPT_API JointJerkIneqCost : public sco::Cost
/** @brief Numerically evaluate cost given the vector of values */
double value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -500,7 +475,6 @@ class TRAJOPT_API JointJerkIneqCost : public sco::Cost
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-4)*2 */
std::vector<sco::AffExpr> expr_vec_;

};

class TRAJOPT_API JointJerkEqConstraint : public sco::EqConstraint
Expand All @@ -522,7 +496,6 @@ class TRAJOPT_API JointJerkEqConstraint : public sco::EqConstraint
/** Sum of violations */
double violation(const DblVec& x);
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand Down Expand Up @@ -554,7 +527,6 @@ class TRAJOPT_API JointJerkIneqConstraint : public sco::IneqConstraint
/** @brief Numerically evaluate cost given the vector of values */
DblVec value(const DblVec&) override;
sco::VarVector getVars() override { return vars_.flatten(); }

private:
/** @brief The variables being optimized. Used to properly index the vector being optimized */
VarArray vars_;
Expand All @@ -572,6 +544,5 @@ class TRAJOPT_API JointJerkIneqConstraint : public sco::IneqConstraint
int last_step_;
/** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-4)*2 */
std::vector<sco::AffExpr> expr_vec_;

};
} // namespace trajopt
Loading

0 comments on commit 5f72fae

Please sign in to comment.