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

[pre-commit.ci] pre-commit autoupdate #2448

Merged
merged 2 commits into from
Oct 8, 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
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,14 @@ ci:
autoupdate_schedule: quarterly
repos:
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v18.1.8
rev: v19.1.1
hooks:
- id: clang-format
types_or: []
types: [text]
files: \.(cpp|cxx|c|h|hpp|hxx|txx)$
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.6.0
rev: v5.0.0
hooks:
- id: check-added-large-files
- id: check-case-conflict
Expand All @@ -27,7 +27,7 @@ repos:
doc/doxygen-awesome.*
)$
- repo: https://github.com/astral-sh/ruff-pre-commit
rev: v0.6.2
rev: v0.6.9
hooks:
- id: ruff
- id: ruff-format
Expand Down
14 changes: 8 additions & 6 deletions bindings/python/algorithm/expose-com.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,21 +101,23 @@ namespace pinocchio

bp::def(
"computeTotalMass",
(Scalar(*)(const context::Model &))
& computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
(Scalar(*)(
const context::Model &))&computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model"), "Compute the total mass of the model and return it.");

bp::def(
"computeTotalMass",
(Scalar(*)(const context::Model &, context::Data &))
& computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
(Scalar(*)(
const context::Model &,
context::Data &))&computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model", "data"),
"Compute the total mass of the model, put it in data.mass[0] and return it.");

bp::def(
"computeSubtreeMasses",
(void (*)(const context::Model &, context::Data &))
& computeSubtreeMasses<Scalar, Options, JointCollectionDefaultTpl>,
(void (*)(
const context::Model &,
context::Data &))&computeSubtreeMasses<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model", "data"),
"Compute the mass of each kinematic subtree and store it in the vector data.mass.");

Expand Down
6 changes: 2 additions & 4 deletions bindings/python/algorithm/expose-frames.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -235,8 +235,7 @@ namespace pinocchio
"computeFrameJacobian",
(context::Data::Matrix6x(*)(
const context::Model &, context::Data &, const context::VectorXs &,
context::Data::FrameIndex, ReferenceFrame))
& compute_frame_jacobian_proxy,
context::Data::FrameIndex, ReferenceFrame))&compute_frame_jacobian_proxy,
bp::args("model", "data", "q", "frame_id", "reference_frame"),
"Computes the Jacobian of the frame given by its frame_id in the coordinate system "
"given by reference_frame.\n");
Expand All @@ -245,8 +244,7 @@ namespace pinocchio
"computeFrameJacobian",
(context::Data::Matrix6x(*)(
const context::Model &, context::Data &, const context::VectorXs &,
context::Data::FrameIndex))
& compute_frame_jacobian_proxy,
context::Data::FrameIndex))&compute_frame_jacobian_proxy,
bp::args("model", "data", "q", "frame_id"),
"Computes the Jacobian of the frame given by its frame_id.\n"
"The columns of the Jacobian are expressed in the coordinates system of the Frame itself.\n"
Expand Down
12 changes: 6 additions & 6 deletions bindings/python/algorithm/expose-kinematic-regressor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@ namespace pinocchio
"computeJointKinematicRegressor",
(context::Data::Matrix6x(*)(
const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame,
const context::SE3 &))
& computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
const context::
SE3 &))&computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model", "data", "joint_id", "reference_frame", "placement"),
"Computes the kinematic regressor that links the joint placements variations of the whole "
"kinematic tree to the placement variation of the frame rigidly attached to the joint and "
Expand All @@ -39,8 +39,8 @@ namespace pinocchio
bp::def(
"computeJointKinematicRegressor",
(context::Data::Matrix6x(*)(
const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame))
& computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
const context::Model &, const context::Data &, const JointIndex,
const ReferenceFrame))&computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model", "data", "joint_id", "reference_frame"),
"Computes the kinematic regressor that links the joint placement variations of the "
"whole kinematic tree to the placement variation of the joint given as input.\n\n"
Expand All @@ -54,8 +54,8 @@ namespace pinocchio
bp::def(
"computeFrameKinematicRegressor",
(context::Data::Matrix6x(*)(
const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame))
& computeFrameKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
const context::Model &, context::Data &, const FrameIndex,
const ReferenceFrame))&computeFrameKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
bp::args("model", "data", "frame_id", "reference_frame"),
"Computes the kinematic regressor that links the joint placement variations of the "
"whole kinematic tree to the placement variation of the frame given as input.\n\n"
Expand Down
20 changes: 10 additions & 10 deletions bindings/python/algorithm/expose-model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType>
bp::tuple buildReducedModel(
const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
Expand All @@ -57,8 +56,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType>
bp::tuple buildReducedModel(
const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
Expand Down Expand Up @@ -95,8 +93,9 @@ namespace pinocchio

bp::def(
"appendModel",
(Model(*)(const Model &, const Model &, const FrameIndex, const SE3 &))
& appendModel<double, 0, JointCollectionDefaultTpl>,
(Model(*)(
const Model &, const Model &, const FrameIndex,
const SE3 &))&appendModel<double, 0, JointCollectionDefaultTpl>,
bp::args("modelA", "modelB", "frame_in_modelA", "aMb"),
"Append a child model into a parent model, after a specific frame given by its index.\n\n"
"Parameters:\n"
Expand All @@ -121,8 +120,9 @@ namespace pinocchio
bp::def(
"buildReducedModel",
(Model(*)(
const Model &, const std::vector<JointIndex> &, const Eigen::MatrixBase<VectorXd> &))
& pinocchio::buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
const Model &, const std::vector<JointIndex> &,
const Eigen::MatrixBase<VectorXd> &))&pinocchio::
buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
bp::args("model", "list_of_joints_to_lock", "reference_configuration"),
"Build a reduce model from a given input model and a list of joint to lock.\n\n"
"Parameters:\n"
Expand All @@ -135,8 +135,8 @@ namespace pinocchio
"buildReducedModel",
(bp::tuple(*)(
const Model &, const GeometryModel &, const std::vector<JointIndex> &,
const Eigen::MatrixBase<VectorXd> &))
& buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
const Eigen::MatrixBase<
VectorXd> &))&buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
bp::args("model", "geom_model", "list_of_joints_to_lock", "reference_configuration"),
"Build a reduced model and a reduced geometry model from a given input model,"
"an input geometry model and a list of joints to lock.\n\n"
Expand Down
12 changes: 6 additions & 6 deletions bindings/python/collision/expose-broadphase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,14 @@ namespace pinocchio
typedef BroadPhaseManagerBase<BroadPhaseManager> BaseManager;

bp::def(
"computeCollisions", (bool (*)(BaseManager &, CollisionCallBackBase *)) & computeCollisions,
"computeCollisions", (bool (*)(BaseManager &, CollisionCallBackBase *))&computeCollisions,
(bp::arg("manager"), bp::arg("callback")),
"Determine if all collision pairs are effectively in collision or not.\n"
"This function assumes that updateGeometryPlacements and broadphase_manager.update() "
"have been called first.");

bp::def(
"computeCollisions", (bool (*)(BaseManager &, const bool)) & computeCollisions,
"computeCollisions", (bool (*)(BaseManager &, const bool))&computeCollisions,
(bp::arg("manager"), bp::arg("stop_at_first_collision") = false),
"Determine if all collision pairs are effectively in collision or not.\n"
"This function assumes that updateGeometryPlacements and broadphase_manager.update() "
Expand All @@ -48,8 +48,7 @@ namespace pinocchio
"computeCollisions",
(bool (*)(
const Model &, Data &, BaseManager &, const Eigen::MatrixBase<Eigen::VectorXd> &,
const bool))
& computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
const bool))&computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
(bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("q"),
bp::arg("stop_at_first_collision") = false),
"Compute the forward kinematics, update the geometry placements and run the "
Expand All @@ -59,8 +58,9 @@ namespace pinocchio
"computeCollisions",
(bool (*)(
const Model &, Data &, BaseManager &, CollisionCallBackBase *,
const Eigen::MatrixBase<Eigen::VectorXd> &))
& computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
const Eigen::MatrixBase<
Eigen::
VectorXd> &))&computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
(bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("callback"),
bp::arg("q")),
"Compute the forward kinematics, update the geometry placements and run the "
Expand Down
7 changes: 3 additions & 4 deletions bindings/python/collision/expose-collision.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType>
static std::size_t computeDistances_proxy(
const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
Expand Down Expand Up @@ -70,7 +69,7 @@ namespace pinocchio

bp::def(
"computeCollisions",
(bool (*)(const GeometryModel &, GeometryData &, const bool)) & computeCollisions,
(bool (*)(const GeometryModel &, GeometryData &, const bool))&computeCollisions,
(bp::arg("geometry_model"), bp::arg("geometry_data"),
bp::arg("stop_at_first_collision") = false),
"Determine if all collision pairs are effectively in collision or not.");
Expand All @@ -92,7 +91,7 @@ namespace pinocchio

bp::def(
"computeDistances",
(std::size_t(*)(const GeometryModel &, GeometryData &)) & computeDistances,
(std::size_t (*)(const GeometryModel &, GeometryData &))&computeDistances,
bp::args("geometry_model", "geometry_data"),
"Compute the distance between each collision pair for a given GeometryModel and "
"associated GeometryData.");
Expand Down
5 changes: 3 additions & 2 deletions bindings/python/math/expose-linalg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,9 @@ namespace pinocchio
#ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
bp::def(
"computeLargestEigenvector",
(context::VectorXs(*)(const context::MatrixXs &, const int, const context::Scalar))
& computeLargestEigenvector<context::MatrixXs>,
(context::VectorXs(*)(
const context::MatrixXs &, const int,
const context::Scalar))&computeLargestEigenvector<context::MatrixXs>,
(bp::arg("mat"), bp::arg("max_it") = 10, bp::arg("rel_tol") = 1e-8),
"Compute the lagest eigenvector of a given matrix according to a given eigenvector "
"estimate.");
Expand Down
3 changes: 1 addition & 2 deletions bindings/python/spatial/expose-explog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,7 @@ namespace pinocchio
" the tangent of SE(3) at Identity.");

bp::def(
"log6",
(context::Motion(*)(const context::SE3 &)) & log6<context::Scalar, context::Options>,
"log6", (context::Motion(*)(const context::SE3 &))&log6<context::Scalar, context::Options>,
bp::arg("M"),
"Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
" -> { v,w in se3, ||w|| < 2pi }.");
Expand Down
18 changes: 6 additions & 12 deletions include/pinocchio/algorithm/aba-derivatives.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2,
Expand Down Expand Up @@ -90,8 +89,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2,
Expand Down Expand Up @@ -134,8 +132,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2>
Expand Down Expand Up @@ -177,8 +174,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename ConfigVectorType,
typename TangentVectorType1,
typename TangentVectorType2>
Expand Down Expand Up @@ -216,8 +212,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename MatrixType1,
typename MatrixType2,
typename MatrixType3>
Expand Down Expand Up @@ -276,8 +271,7 @@ namespace pinocchio
template<
typename Scalar,
int Options,
template<typename, int>
class JointCollectionTpl,
template<typename, int> class JointCollectionTpl,
typename MatrixType1,
typename MatrixType2,
typename MatrixType3>
Expand Down
Loading
Loading