@@ -62,7 +62,7 @@ void runKinematicsTest(const Model & model, Data & data)
6262 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
6363 const Eigen::VectorXd a = Eigen::VectorXd::Random (model.nv );
6464
65- [&]() [[clang::nonallocating ]] {
65+ [&]() noexcept [[clang::nonblocking ]] {
6666 // Forward kinematics (position only)
6767 forwardKinematics (model, data, q);
6868
@@ -82,7 +82,7 @@ void runJacobianTest(const Model & model, Data & data)
8282 const Eigen::VectorXd q = randomConfiguration (model);
8383 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
8484
85- [&]() [[clang::nonallocating ]] {
85+ [&]() noexcept [[clang::nonblocking ]] {
8686 // Compute joint Jacobians
8787 computeJointJacobians (model, data, q);
8888 }();
@@ -91,7 +91,7 @@ void runJacobianTest(const Model & model, Data & data)
9191 const Data::Matrix6x J = Data::Matrix6x::Zero (6 , model.nv );
9292 const JointIndex joint_id = static_cast <JointIndex>(model.njoints - 1 );
9393
94- [&]() [[clang::nonallocating ]] {
94+ [&]() noexcept [[clang::nonblocking ]] {
9595 getJointJacobian (model, data, joint_id, LOCAL, J);
9696 getJointJacobian (model, data, joint_id, WORLD, J);
9797 getJointJacobian (model, data, joint_id, LOCAL_WORLD_ALIGNED, J);
@@ -106,7 +106,7 @@ void runNonLinearEffectsTest(const Model & model, Data & data)
106106 const Eigen::VectorXd q = randomConfiguration (model);
107107 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
108108
109- [&]() [[clang::nonallocating ]] {
109+ [&]() noexcept [[clang::nonblocking ]] {
110110 // Non-linear effects
111111 nonLinearEffects (model, data, q, v);
112112 }();
@@ -118,7 +118,7 @@ void runRNEATest(const Model & model, Data & data)
118118 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
119119 const Eigen::VectorXd a = Eigen::VectorXd::Random (model.nv );
120120
121- [&]() [[clang::nonallocating ]] {
121+ [&]() noexcept [[clang::nonblocking ]] {
122122 // RNEA (Recursive Newton-Euler Algorithm)
123123 rnea (model, data, q, v, a);
124124 }();
@@ -128,7 +128,7 @@ void runCRBATest(const Model & model, Data & data)
128128{
129129 const Eigen::VectorXd q = randomConfiguration (model);
130130
131- [&]() [[clang::nonallocating ]] {
131+ [&]() noexcept [[clang::nonblocking ]] {
132132 // CRBA (Composite Rigid Body Algorithm)
133133 crba (model, data, q);
134134 crba (model, data, q, Convention::WORLD);
@@ -142,7 +142,7 @@ void runABATest(const Model & model, Data & data)
142142 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
143143 const Eigen::VectorXd tau = Eigen::VectorXd::Random (model.nv );
144144
145- [&]() [[clang::nonallocating ]] {
145+ [&]() noexcept [[clang::nonblocking ]] {
146146 // ABA (Articulated Body Algorithm)
147147 aba (model, data, q, v, tau);
148148 }();
@@ -155,7 +155,7 @@ void runDerivativesTest(const Model & model, Data & data)
155155 const Eigen::VectorXd a = Eigen::VectorXd::Random (model.nv );
156156 const Eigen::VectorXd tau = Eigen::VectorXd::Random (model.nv );
157157
158- [&]() [[clang::nonallocating ]] {
158+ [&]() noexcept [[clang::nonblocking ]] {
159159 // Compute forward kinematics derivatives
160160 computeForwardKinematicsDerivatives (model, data, q, v, a);
161161 }();
@@ -165,7 +165,7 @@ void runDerivativesTest(const Model & model, Data & data)
165165 const Data::MatrixXs rnea_partial_dv = Data::MatrixXs::Zero (model.nv , model.nv );
166166 const Data::MatrixXs rnea_partial_da = Data::MatrixXs::Zero (model.nv , model.nv );
167167
168- [&]() [[clang::nonallocating ]] {
168+ [&]() noexcept [[clang::nonblocking ]] {
169169 computeRNEADerivatives (model, data, q, v, a, rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
170170 }();
171171
@@ -174,7 +174,7 @@ void runDerivativesTest(const Model & model, Data & data)
174174 const Data::MatrixXs aba_partial_dv = Data::MatrixXs::Zero (model.nv , model.nv );
175175 const Data::MatrixXs aba_partial_dtau = Data::MatrixXs::Zero (model.nv , model.nv );
176176
177- [&]() [[clang::nonallocating ]] {
177+ [&]() noexcept [[clang::nonblocking ]] {
178178 computeABADerivatives (model, data, q, v, tau, aba_partial_dq, aba_partial_dv, aba_partial_dtau);
179179 }();
180180}
@@ -185,7 +185,7 @@ void runCenterOfMassTest(const Model & model, Data & data)
185185 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
186186 const Eigen::VectorXd a = Eigen::VectorXd::Random (model.nv );
187187
188- [&]() [[clang::nonallocating ]] {
188+ [&]() noexcept [[clang::nonblocking ]] {
189189 // Compute center of mass position
190190 centerOfMass (model, data, q);
191191
@@ -206,7 +206,7 @@ void runCenterOfMassDerivativesTest(const Model & model, Data & data)
206206 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
207207 Data::Matrix3x vcom_partial_dq = Data::Matrix3x::Zero (3 , model.nv );
208208
209- [&]() [[clang::nonallocating ]] {
209+ [&]() noexcept [[clang::nonblocking ]] {
210210 // Center of mass derivatives
211211 getCenterOfMassVelocityDerivatives (model, data, vcom_partial_dq);
212212 }();
@@ -222,7 +222,7 @@ void runCentroidalDynamicsTest(const Model & model, Data & data)
222222 Data::Matrix6x dhdot_dv = Data::Matrix6x::Zero (6 , model.nv );
223223 Data::Matrix6x dhdot_da = Data::Matrix6x::Zero (6 , model.nv );
224224
225- [&]() [[clang::nonallocating ]] {
225+ [&]() noexcept [[clang::nonblocking ]] {
226226 // Compute centroidal momentum
227227 computeCentroidalMomentum (model, data, q, v);
228228
@@ -241,7 +241,7 @@ void runFrameAlgorithmsTest(const Model & model, Data & data)
241241{
242242 const Eigen::VectorXd q = randomConfiguration (model);
243243
244- [&]() [[clang::nonallocating ]] {
244+ [&]() noexcept [[clang::nonblocking ]] {
245245 // Update frame placements
246246 updateFramePlacements (model, data);
247247
@@ -258,7 +258,7 @@ void runFrameAlgorithmsTest(const Model & model, Data & data)
258258
259259 for (FrameIndex frame_idx = 0 ; frame_idx < static_cast <FrameIndex>(model.nframes ); ++frame_idx)
260260 {
261- [&]() [[clang::nonallocating ]] {
261+ [&]() noexcept [[clang::nonblocking ]] {
262262 getFrameJacobian (model, data, frame_idx, LOCAL, frame_J);
263263 getFrameJacobian (model, data, frame_idx, WORLD, frame_J);
264264 getFrameJacobian (model, data, frame_idx, LOCAL_WORLD_ALIGNED, frame_J);
@@ -289,7 +289,7 @@ void runFrameAlgorithmsTest(const Model & model, Data & data)
289289 // Frame derivatives
290290 if (!hasMimicJoints (model))
291291 {
292- [&]() [[clang::nonallocating ]] {
292+ [&]() noexcept [[clang::nonblocking ]] {
293293 getFrameVelocityDerivatives (model, data, frame_idx, LOCAL, v_partial_dq, v_partial_dv);
294294 getFrameAccelerationDerivatives (
295295 model, data, frame_idx, LOCAL, v_partial_dq, a_partial_dq, a_partial_dv, a_partial_da);
@@ -303,15 +303,15 @@ void runComputeAllTermsTest(const Model & model, Data & data)
303303 const Eigen::VectorXd q = randomConfiguration (model);
304304 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
305305
306- [&]() [[clang::nonallocating ]] { computeAllTerms (model, data, q, v); }();
306+ [&]() noexcept [[clang::nonblocking ]] { computeAllTerms (model, data, q, v); }();
307307}
308308
309309void runEnergyTest (const Model & model, Data & data)
310310{
311311 const Eigen::VectorXd q = randomConfiguration (model);
312312 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
313313
314- [&]() [[clang::nonallocating ]] {
314+ [&]() noexcept [[clang::nonblocking ]] {
315315 // Compute kinetic energy
316316 computeKineticEnergy (model, data, q, v);
317317
@@ -324,7 +324,7 @@ void runComputeGeneralizedGravityTest(const Model & model, Data & data)
324324{
325325 const Eigen::VectorXd q = randomConfiguration (model);
326326
327- [&]() [[clang::nonallocating ]] {
327+ [&]() noexcept [[clang::nonblocking ]] {
328328 // Compute generalized gravity
329329 computeGeneralizedGravity (model, data, q);
330330 }();
@@ -334,14 +334,14 @@ void runCholeskyTest(const Model & model, Data & data)
334334{
335335 Eigen::VectorXd v_chol = Eigen::VectorXd::Random (model.nv );
336336
337- [&]() [[clang::nonallocating ]] {
337+ [&]() noexcept [[clang::nonblocking ]] {
338338 cholesky::decompose (model, data);
339339 cholesky::solve (model, data, v_chol);
340340 }();
341341
342342 Data::MatrixXs M_inv = Data::MatrixXs::Zero (model.nv , model.nv );
343343
344- [&]() [[clang::nonallocating ]] {
344+ [&]() noexcept [[clang::nonblocking ]] {
345345 // Compute inverse of mass matrix using Cholesky
346346 cholesky::computeMinv (model, data, M_inv);
347347 }();
@@ -356,7 +356,7 @@ void runJointConfigurationOperationsTest(const Model & model)
356356 Eigen::VectorXd q_integrated (model.nq );
357357 Eigen::VectorXd q_interp (model.nq );
358358
359- [&]() [[clang::nonallocating ]] {
359+ [&]() noexcept [[clang::nonblocking ]] {
360360 normalize (model, q);
361361 difference (model, q, q_neutral, dq);
362362 integrate (model, q, v, q_integrated);
@@ -373,7 +373,7 @@ void runJointTorqueRegressorTest(const Model & model, Data & data)
373373 const Eigen::VectorXd v = Eigen::VectorXd::Random (model.nv );
374374 const Eigen::VectorXd a = Eigen::VectorXd::Random (model.nv );
375375
376- [&]() [[clang::nonallocating ]] {
376+ [&]() noexcept [[clang::nonblocking ]] {
377377 // Compute joint torque regressor
378378 computeJointTorqueRegressor (model, data, q, v, a);
379379 }();
@@ -401,7 +401,7 @@ void runContactDynamicsTest(const Model & model, Data & data)
401401 // Initialize contact data
402402 initConstraintDynamics (model, data, contact_models);
403403
404- [&]() [[clang::nonallocating ]] {
404+ [&]() noexcept [[clang::nonblocking ]] {
405405 // Constrained forward dynamics
406406 constraintDynamics (model, data, q, v, tau, contact_models, contact_data);
407407 }();
@@ -410,7 +410,7 @@ void runContactDynamicsTest(const Model & model, Data & data)
410410 ContactCholeskyDecomposition contact_chol;
411411 contact_chol.allocate (model, contact_models);
412412
413- [&]() [[clang::nonallocating ]] {
413+ [&]() noexcept [[clang::nonblocking ]] {
414414 crba (model, data, q, Convention::WORLD);
415415 contact_chol.compute (model, data, contact_models, contact_data);
416416 }();
@@ -424,7 +424,7 @@ void runContactDynamicsTest(const Model & model, Data & data)
424424 Data::MatrixXs lambda_dv = Data::MatrixXs::Zero (constraint_dim, model.nv );
425425 Data::MatrixXs lambda_dtau = Data::MatrixXs::Zero (constraint_dim, model.nv );
426426
427- [&]() [[clang::nonallocating ]] {
427+ [&]() noexcept [[clang::nonblocking ]] {
428428 computeConstraintDynamicsDerivatives (
429429 model, data, contact_models, contact_data, ddq_dq, ddq_dv, ddq_dtau, lambda_dq, lambda_dv,
430430 lambda_dtau);
@@ -435,7 +435,7 @@ void runContactDynamicsTest(const Model & model, Data & data)
435435 const double r_coeff = 0.0 ;
436436 ProximalSettings prox_settings (1e-12 , 0 ., 1 );
437437
438- [&]() [[clang::nonallocating ]] {
438+ [&]() noexcept [[clang::nonblocking ]] {
439439 impulseDynamics (
440440 model, data, q, v_before, contact_models, contact_data, r_coeff, prox_settings);
441441 }();
@@ -446,7 +446,7 @@ void runContactDynamicsTest(const Model & model, Data & data)
446446 Data::MatrixXs impulse_dq = Data::MatrixXs::Zero (constraint_dim, model.nv );
447447 Data::MatrixXs impulse_dv = Data::MatrixXs::Zero (constraint_dim, model.nv );
448448
449- [&]() [[clang::nonallocating ]] {
449+ [&]() noexcept [[clang::nonblocking ]] {
450450 computeImpulseDynamicsDerivatives (
451451 model, data, contact_models, contact_data, r_coeff, prox_settings);
452452 }();
@@ -561,7 +561,7 @@ BOOST_AUTO_TEST_CASE(dynamic_allocations_humanoid_composite)
561561
562562BOOST_AUTO_TEST_CASE (dynamic_allocations_spatial_operations)
563563{
564- [&]() [[clang::nonallocating ]] {
564+ [&]() noexcept [[clang::nonblocking ]] {
565565 // Classic acceleration
566566 SE3 M = SE3::Random ();
567567 Motion v_spatial = Motion::Random ();
0 commit comments