Skip to content

Commit dcb4346

Browse files
[pre-commit.ci] auto fixes from pre-commit.com hooks
for more information, see https://pre-commit.ci
1 parent ae408b9 commit dcb4346

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

51 files changed

+667
-567
lines changed

bindings/python/algorithm/expose-com.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,13 @@ namespace pinocchio
103103

104104
bp::def(
105105
"computeTotalMass",
106-
(Scalar(*)(
106+
(Scalar (*)(
107107
const context::Model &))&computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
108108
bp::args("model"), "Compute the total mass of the model and return it.");
109109

110110
bp::def(
111111
"computeTotalMass",
112-
(Scalar(*)(
112+
(Scalar (*)(
113113
const context::Model &,
114114
context::Data &))&computeTotalMass<Scalar, Options, JointCollectionDefaultTpl>,
115115
bp::args("model", "data"),

bindings/python/algorithm/expose-frames.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -233,7 +233,7 @@ namespace pinocchio
233233

234234
bp::def(
235235
"computeFrameJacobian",
236-
(context::Data::Matrix6x(*)(
236+
(context::Data::Matrix6x (*)(
237237
const context::Model &, context::Data &, const context::VectorXs &,
238238
context::Data::FrameIndex, ReferenceFrame))&compute_frame_jacobian_proxy,
239239
bp::args("model", "data", "q", "frame_id", "reference_frame"),
@@ -242,7 +242,7 @@ namespace pinocchio
242242

243243
bp::def(
244244
"computeFrameJacobian",
245-
(context::Data::Matrix6x(*)(
245+
(context::Data::Matrix6x (*)(
246246
const context::Model &, context::Data &, const context::VectorXs &,
247247
context::Data::FrameIndex))&compute_frame_jacobian_proxy,
248248
bp::args("model", "data", "q", "frame_id"),

bindings/python/algorithm/expose-kinematic-regressor.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ namespace pinocchio
2121

2222
bp::def(
2323
"computeJointKinematicRegressor",
24-
(context::Data::Matrix6x(*)(
24+
(context::Data::Matrix6x (*)(
2525
const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame,
2626
const context::
2727
SE3 &))&computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
@@ -40,7 +40,7 @@ namespace pinocchio
4040

4141
bp::def(
4242
"computeJointKinematicRegressor",
43-
(context::Data::Matrix6x(*)(
43+
(context::Data::Matrix6x (*)(
4444
const context::Model &, const context::Data &, const JointIndex,
4545
const ReferenceFrame))&computeJointKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
4646
bp::args("model", "data", "joint_id", "reference_frame"),
@@ -56,7 +56,7 @@ namespace pinocchio
5656

5757
bp::def(
5858
"computeFrameKinematicRegressor",
59-
(context::Data::Matrix6x(*)(
59+
(context::Data::Matrix6x (*)(
6060
const context::Model &, context::Data &, const FrameIndex,
6161
const ReferenceFrame))&computeFrameKinematicRegressor<Scalar, Options, JointCollectionDefaultTpl>,
6262
bp::args("model", "data", "frame_id", "reference_frame"),

bindings/python/algorithm/expose-model.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -109,7 +109,7 @@ namespace pinocchio
109109

110110
bp::def(
111111
"appendModel",
112-
(Model(*)(
112+
(Model (*)(
113113
const Model &, const Model &, const FrameIndex,
114114
const SE3 &))&appendModel<double, 0, JointCollectionDefaultTpl>,
115115
bp::args("modelA", "modelB", "frame_in_modelA", "aMb"),
@@ -135,7 +135,7 @@ namespace pinocchio
135135

136136
bp::def(
137137
"buildReducedModel",
138-
(Model(*)(
138+
(Model (*)(
139139
const Model &, const std::vector<JointIndex> &,
140140
const Eigen::MatrixBase<VectorXd> &))&pinocchio::
141141
buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
@@ -149,7 +149,7 @@ namespace pinocchio
149149

150150
bp::def(
151151
"buildReducedModel",
152-
(bp::tuple(*)(
152+
(bp::tuple (*)(
153153
const Model &, const GeometryModel &, const std::vector<JointIndex> &,
154154
const Eigen::MatrixBase<
155155
VectorXd> &))&buildReducedModel<double, 0, JointCollectionDefaultTpl, VectorXd>,
@@ -165,7 +165,7 @@ namespace pinocchio
165165

166166
bp::def(
167167
"buildReducedModel",
168-
(bp::tuple(*)(
168+
(bp::tuple (*)(
169169
const Model &,
170170
const std::vector<GeometryModel, Eigen::aligned_allocator<GeometryModel>> &,
171171
const std::vector<JointIndex> &, const Eigen::MatrixBase<VectorXd> &))

bindings/python/collision/expose-broadphase-callbacks.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,10 +73,11 @@ namespace pinocchio
7373

7474
bp::class_<CollisionCallBackDefault, bp::bases<CollisionCallBackBase>>(
7575
"CollisionCallBackDefault", bp::no_init)
76-
.def(bp::init<const GeometryModel &, GeometryData &, bp::optional<bool>>(
77-
bp::args("self", "geometry_model", "geometry_data", "stopAtFirstCollision"),
78-
"Default constructor from a given GeometryModel and a GeometryData")
79-
[bp::with_custodian_and_ward<1, 2>(), bp::with_custodian_and_ward<1, 3>()])
76+
.def(
77+
bp::init<const GeometryModel &, GeometryData &, bp::optional<bool>>(
78+
bp::args("self", "geometry_model", "geometry_data", "stopAtFirstCollision"),
79+
"Default constructor from a given GeometryModel and a GeometryData")
80+
[bp::with_custodian_and_ward<1, 2>(), bp::with_custodian_and_ward<1, 3>()])
8081

8182
.def_readwrite(
8283
"stopAtFirstCollision", &CollisionCallBackDefault::stopAtFirstCollision,

bindings/python/math/expose-linalg.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ namespace pinocchio
3333
#ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
3434
bp::def(
3535
"computeLargestEigenvector",
36-
(context::VectorXs(*)(
36+
(context::VectorXs (*)(
3737
const context::MatrixXs &, const int,
3838
const context::Scalar))&computeLargestEigenvector<context::MatrixXs>,
3939
(bp::arg("mat"), bp::arg("max_it") = 10, bp::arg("rel_tol") = 1e-8),

bindings/python/module.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -49,12 +49,15 @@ BOOST_PYTHON_MODULE(PINOCCHIO_PYTHON_MODULE_NAME)
4949

5050
bp::scope().attr("ScalarType") = getScalarType();
5151

52-
bp::scope().attr("XAxis") = bp::object(bp::handle<>(
53-
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::XAxis::vector<context::Scalar>())));
54-
bp::scope().attr("YAxis") = bp::object(bp::handle<>(
55-
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::YAxis::vector<context::Scalar>())));
56-
bp::scope().attr("ZAxis") = bp::object(bp::handle<>(
57-
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::ZAxis::vector<context::Scalar>())));
52+
bp::scope().attr("XAxis") = bp::object(
53+
bp::handle<>(
54+
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::XAxis::vector<context::Scalar>())));
55+
bp::scope().attr("YAxis") = bp::object(
56+
bp::handle<>(
57+
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::YAxis::vector<context::Scalar>())));
58+
bp::scope().attr("ZAxis") = bp::object(
59+
bp::handle<>(
60+
eigenpy::EigenToPy<context::Vector3s>::convert(pinocchio::ZAxis::vector<context::Scalar>())));
5861

5962
if (!register_symbolic_link_to_registered_type<::pinocchio::ReferenceFrame>())
6063
{

bindings/python/spatial/expose-explog.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ namespace pinocchio
113113
" the tangent of SE(3) at Identity.");
114114

115115
bp::def(
116-
"log6", (context::Motion(*)(const context::SE3 &))&log6<context::Scalar, context::Options>,
116+
"log6", (context::Motion (*)(const context::SE3 &))&log6<context::Scalar, context::Options>,
117117
bp::arg("M"),
118118
"Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
119119
" -> { v,w in se3, ||w|| < 2pi }.");

examples/display-shapes.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,8 +49,7 @@
4949
viz.loadViewerModel("shapes")
5050
except AttributeError as error:
5151
print(
52-
"Error while loading the viewer model. "
53-
"It seems you should start gepetto-viewer"
52+
"Error while loading the viewer model. It seems you should start gepetto-viewer"
5453
)
5554
print(error)
5655
sys.exit(0)

examples/gepetto-viewer.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,7 @@
3636
viz.loadViewerModel("pinocchio")
3737
except AttributeError as err:
3838
print(
39-
"Error while loading the viewer model. "
40-
"It seems you should start gepetto-viewer"
39+
"Error while loading the viewer model. It seems you should start gepetto-viewer"
4140
)
4241
print(err)
4342
sys.exit(0)

0 commit comments

Comments
 (0)