Skip to content

Commit

Permalink
Clang formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
marrts committed Dec 7, 2023
1 parent 5678904 commit 89c1c82
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
3 changes: 2 additions & 1 deletion trajopt/src/kinematic_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,8 @@ CartPoseErrCalculator::CartPoseErrCalculator(tesseract_kinematics::JointGroup::C
// Check to see if the waypoint is toleranced and set the error function accordingly
if ((lower_tolerance.size() == 0 && upper_tolerance.size() == 0) || lower_tolerance.isApprox(upper_tolerance, 1e-6))
{
error_function_ = [this](const Eigen::Isometry3d& source_tf, const Eigen::Isometry3d& target_tf) -> Eigen::VectorXd {
error_function_ = [this](const Eigen::Isometry3d& source_tf,
const Eigen::Isometry3d& target_tf) -> Eigen::VectorXd {
return tesseract_common::calcTransformError(source_tf, target_tf);
};
}
Expand Down
4 changes: 2 additions & 2 deletions trajopt/src/problem_description.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -798,8 +798,8 @@ void DynamicCartPoseTermInfo::hatch(TrajOptProb& prob)
}
else if (term_type & TT_CNT)
{
prob.addConstraint(
std::make_shared<TrajOptConstraintFromErrFunc>(f, dfdx, prob.GetVarRow(timestep, 0, n_dof), coeff, sco::EQ, name));
prob.addConstraint(std::make_shared<TrajOptConstraintFromErrFunc>(
f, dfdx, prob.GetVarRow(timestep, 0, n_dof), coeff, sco::EQ, name));
}
else
{
Expand Down

0 comments on commit 89c1c82

Please sign in to comment.