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

Trajopt clang-tidy clean-up #411

Merged
merged 5 commits into from
Jul 13, 2024
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
21 changes: 11 additions & 10 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -53,15 +53,16 @@ BreakBeforeBraces: Custom

# Control of individual brace wrapping cases
BraceWrapping: {
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum : 'true'
AfterFunction : 'true'
AfterNamespace : 'true'
AfterStruct : 'true'
AfterUnion : 'true'
BeforeCatch : 'true'
BeforeElse : 'true'
IndentBraces : 'false'
AfterCaseLabel: 'true',
AfterClass: 'true',
AfterControlStatement: 'true',
AfterEnum : 'true',
AfterFunction : 'true',
AfterNamespace : 'true',
AfterStruct : 'true',
AfterUnion : 'true',
BeforeCatch : 'true',
BeforeElse : 'true',
IndentBraces : 'false',
}
...
2 changes: 2 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ Checks: >
-cppcoreguidelines-non-private-member-variables-in-classes,
-cppcoreguidelines-owning-memory,
misc-*,
-misc-include-cleaner,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
modernize-*,
Expand Down Expand Up @@ -56,6 +57,7 @@ WarningsAsErrors: >
-cppcoreguidelines-non-private-member-variables-in-classes,
-cppcoreguidelines-owning-memory,
misc-*,
-misc-include-cleaner,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
modernize-*,
Expand Down
1 change: 0 additions & 1 deletion trajopt/include/trajopt/json_marshal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Eigen>
#include <boost/format.hpp>
#include <sstream>
#include <string>
#include <vector>
TRAJOPT_IGNORE_WARNINGS_POP
Expand Down
7 changes: 3 additions & 4 deletions trajopt/include/trajopt/problem_description.hpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#pragma once
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <unordered_map>
#include <type_traits>
TRAJOPT_IGNORE_WARNINGS_POP

Expand Down Expand Up @@ -99,7 +98,7 @@ class TrajOptProb : public sco::OptProb

private:
/** @brief If true, the last column in the optimization matrix will be 1/dt */
bool has_time;
bool has_time{ false };
VarArray m_traj_vars;
std::shared_ptr<const tesseract_kinematics::JointGroup> m_kin;
std::shared_ptr<const tesseract_environment::Environment> m_env;
Expand Down Expand Up @@ -314,7 +313,7 @@ struct DynamicCartPoseTermInfo : public TermInfo
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

/** @brief Timestep at which to apply term */
int timestep;
int timestep{ 0 };
/** @brief Coefficients for position and rotation */
Eigen::Vector3d pos_coeffs, rot_coeffs;
/** @brief Link which should reach desired pos */
Expand Down Expand Up @@ -354,7 +353,7 @@ struct CartPoseTermInfo : public TermInfo
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

/** @brief Timestep at which to apply term */
int timestep;
int timestep{ 0 };
Eigen::Vector3d pos_coeffs, rot_coeffs;

/** @brief Link which should reach desired pos */
Expand Down
1 change: 0 additions & 1 deletion trajopt/include/trajopt/typedefs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <Eigen/Core>
#include <map>
#include <vector>
#include <tesseract_visualization/fwd.h>
TRAJOPT_IGNORE_WARNINGS_POP
Expand Down
1 change: 0 additions & 1 deletion trajopt/include/trajopt/utils.hpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#pragma once
#include <trajopt_common/macros.h>
TRAJOPT_IGNORE_WARNINGS_PUSH
#include <unordered_map>
#include <Eigen/Geometry>
TRAJOPT_IGNORE_WARNINGS_POP

Expand Down
14 changes: 7 additions & 7 deletions trajopt/src/collision_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -606,7 +606,7 @@ void CollisionEvaluator::CalcDists(const DblVec& x, DblVec& dists)
CollisionsToDistances(*dist_results, dists);
}

inline size_t hash(const DblVec& x) { return boost::hash_range(x.begin(), x.end()); }
inline std::size_t hash(const DblVec& x) { return boost::hash_range(x.begin(), x.end()); }
ContactResultVectorConstPtr CollisionEvaluator::GetContactResultVectorCached(const DblVec& x)
{
std::pair<ContactResultMapConstPtr, ContactResultVectorConstPtr> pair = GetContactResultCached(x);
Expand All @@ -622,7 +622,7 @@ ContactResultMapConstPtr CollisionEvaluator::GetContactResultMapCached(const Dbl
std::pair<ContactResultMapConstPtr, ContactResultVectorConstPtr>
CollisionEvaluator::GetContactResultCached(const DblVec& x)
{
size_t key = hash(sco::getDblVec(x, GetVars()));
std::size_t key = hash(sco::getDblVec(x, GetVars()));
auto* it = m_cache.get(key);
if (it != nullptr)
{
Expand Down Expand Up @@ -985,7 +985,7 @@ void SingleTimestepCollisionEvaluator::Plot(const std::shared_ptr<tesseract_visu

tesseract_collision::ContactResultVector dist_results_copy(dist_results.size());
Eigen::VectorXd safety_distance(dist_results.size());
for (auto i = 0u; i < dist_results.size(); ++i)
for (auto i = 0U; i < dist_results.size(); ++i)
{
const tesseract_collision::ContactResult& res = dist_results[i].get();
dist_results_copy[i] = res;
Expand Down Expand Up @@ -1206,7 +1206,7 @@ void DiscreteCollisionEvaluator::Plot(const std::shared_ptr<tesseract_visualizat

tesseract_collision::ContactResultVector dist_results_copy(dist_results.size());
Eigen::VectorXd safety_distance(dist_results.size());
for (auto i = 0u; i < dist_results.size(); ++i)
for (auto i = 0U; i < dist_results.size(); ++i)
{
const tesseract_collision::ContactResult& res = dist_results[i].get();
dist_results_copy[i] = res;
Expand Down Expand Up @@ -1401,11 +1401,11 @@ void CastCollisionEvaluator::CalcCollisions(const Eigen::Ref<const Eigen::Vector
if (dist > longest_valid_segment_length_)
{
// Calculate the number state to interpolate
size_t cnt = static_cast<size_t>(std::ceil(dist / longest_valid_segment_length_)) + 1;
auto cnt = static_cast<long>(std::ceil(dist / longest_valid_segment_length_)) + 1;

// Create interpolated trajectory between two states that satisfies the longest valid segment length.
tesseract_common::TrajArray subtraj(cnt, dof_vals0.size());
for (size_t i = 0; i < dof_vals0.size(); ++i)
for (long i = 0; i < dof_vals0.size(); ++i)
subtraj.col(i) = Eigen::VectorXd::LinSpaced(cnt, dof_vals0(i), dof_vals1(i));

// Perform casted collision checking for sub trajectory and store results in contacts_vector
Expand Down Expand Up @@ -1461,7 +1461,7 @@ void CastCollisionEvaluator::Plot(const std::shared_ptr<tesseract_visualization:

tesseract_collision::ContactResultVector dist_results_copy(dist_results.size());
Eigen::VectorXd safety_distance(dist_results.size());
for (auto i = 0u; i < dist_results.size(); ++i)
for (auto i = 0U; i < dist_results.size(); ++i)
{
const tesseract_collision::ContactResult& res = dist_results[i].get();
dist_results_copy[i] = res;
Expand Down
6 changes: 4 additions & 2 deletions trajopt/src/file_write_callback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ std::function<void(sco::OptProb*, sco::OptResults&)> WriteCallback(std::shared_p

// Write joint names
std::vector<std::string> joint_names = prob->GetEnv()->getActiveJointNames();
for (size_t i = 0; i < joint_names.size(); i++)
for (std::size_t i = 0; i < joint_names.size(); i++)
{
if (i != 0)
{
Expand Down Expand Up @@ -136,6 +136,8 @@ std::function<void(sco::OptProb*, sco::OptResults&)> WriteCallback(std::shared_p
*file << std::endl;

// return callback function
return bind(&WriteFile, file, prob->GetKin(), std::ref(prob->GetVars()), std::placeholders::_2);
return [file, capture0 = prob->GetKin(), &capture1 = prob->GetVars()](auto&&, auto&& PH2) {
WriteFile(file, capture0, capture1, std::forward<decltype(PH2)>(PH2));
};
}
} // namespace trajopt
12 changes: 6 additions & 6 deletions trajopt/src/kinematic_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,10 +322,10 @@ CartPoseJacCalculator::CartPoseJacCalculator(
, source_frame_offset_(source_frame_offset)
, target_frame_(std::move(target_frame))
, target_frame_offset_(target_frame_offset)
, is_target_active_(manip_->isActiveLinkName(target_frame_))
, indices_(indices)
, epsilon_(DEFAULT_EPSILON)
{
is_target_active_ = manip_->isActiveLinkName(target_frame_);
assert(indices_.size() <= 6);

if (is_target_active_)
Expand Down Expand Up @@ -459,16 +459,16 @@ Eigen::VectorXd JointVelErrCalculator::operator()(const VectorXd& var_vals) cons
MatrixXd JointVelJacCalculator::operator()(const VectorXd& var_vals) const
{
// var_vals = (theta_t1, theta_t2, theta_t3 ... 1/dt_1, 1/dt_2, 1/dt_3 ...)
auto num_vals = static_cast<int>(var_vals.rows());
int half = num_vals / 2;
int num_vels = half - 1;
auto num_vals = var_vals.rows();
auto half = num_vals / 2;
auto num_vels = half - 1;
MatrixXd jac = MatrixXd::Zero(num_vels * 2, num_vals);

for (int i = 0; i < num_vels; i++)
for (auto i = 0; i < num_vels; i++)
{
// v = (j_i+1 - j_i)*(1/dt)
// We calculate v with the dt from the second pt
int time_index = i + half + 1;
auto time_index = i + half + 1;
// dv_i/dj_i = -(1/dt)
jac(i, i) = -1.0 * var_vals(time_index);
// dv_i/dj_i+1 = (1/dt)
Expand Down
Loading
Loading