Go to the documentation of this file.
   12 #ifdef PINOCCHIO_WITH_HPP_FCL 
   32 #include <benchmark/benchmark.h> 
   36 typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> 
VectorXb;
 
   40   void SetUp(benchmark::State & st)
 
   43     const auto NUM_THREADS = st.range(1);
 
   48     const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(
model.
nq);
 
   63     pool = std::make_unique<pinocchio::ModelPool>(
model, 
static_cast<size_t>(NUM_THREADS));
 
   77   std::unique_ptr<pinocchio::ModelPool> 
pool;
 
   85       + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
 
   92     std::cout << 
"nq = " << 
MODEL.
nq << std::endl;
 
   93     std::cout << 
"nv = " << 
MODEL.
nv << std::endl;
 
   94     std::cout << 
"name = " << 
MODEL.
name << std::endl;
 
   95     std::cout << 
"--" << std::endl;
 
  103   b->MinWarmUpTime(3.)->ArgsProduct({{256}, {1}})->ArgNames({
"BATCH_SIZE", 
"NUM_THREADS"});
 
  109     ->ArgsProduct({{256}, benchmark::CreateRange(1, omp_get_max_threads(), 2)})
 
  110     ->ArgNames({
"BATCH_SIZE", 
"NUM_THREADS"})
 
  119   const Eigen::MatrixXd::ColXpr & q,
 
  120   const Eigen::MatrixXd::ColXpr & 
v,
 
  121   const Eigen::MatrixXd::ColXpr & 
a,
 
  122   const Eigen::MatrixXd::ColXpr & 
r)
 
  144   const Eigen::MatrixXd & 
qs,
 
  145   const Eigen::MatrixXd & vs,
 
  146   const Eigen::MatrixXd & as,
 
  147   const Eigen::MatrixXd & res)
 
  153   const auto NUM_THREADS = st.range(1);
 
  166   const Eigen::MatrixXd::ColXpr & q,
 
  167   const Eigen::MatrixXd::ColXpr & 
v,
 
  168   const Eigen::MatrixXd::ColXpr & taus,
 
  169   const Eigen::MatrixXd::ColXpr & 
r)
 
  192   const Eigen::MatrixXd & 
qs,
 
  193   const Eigen::MatrixXd & vs,
 
  194   const Eigen::MatrixXd & taus,
 
  195   const Eigen::MatrixXd & res)
 
  201   const auto NUM_THREADS = st.range(1);
 
  209 #ifdef PINOCCHIO_WITH_HPP_FCL 
  213   void SetUp(benchmark::State & st)
 
  220     const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(
model.
nq);
 
  224   void TearDown(benchmark::State & st)
 
  241       + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
 
  245       PINOCCHIO_MODEL_DIR + std::string(
"/example-robot-data/robots/talos_data/srdf/talos.srdf");
 
  246     std::vector<std::string> package_paths(1, package_path);
 
  255     int num_active_collision_pairs = 0;
 
  259         num_active_collision_pairs++;
 
  261     std::cout << 
"active collision pairs = " << num_active_collision_pairs << std::endl;
 
  262     std::cout << 
"---" << std::endl;
 
  274   const Eigen::VectorXd & q)
 
  282     computeCollisionsCall(
model, 
data, geometry_model, geometry_data, q);
 
  295   const Eigen::VectorXd & q)
 
  302   const auto NUM_THREADS = st.range(1);
 
  305     computeCollisionsInParallelCall(
 
  306       static_cast<size_t>(NUM_THREADS), 
model, 
data, geometry_model, geometry_data, q);
 
  319   const Eigen::MatrixXd::ColXpr & q)
 
  330       computeCollisionsBatchCall(
model, 
data, geometry_model, geometry_data, 
qs.col(
i));
 
  346   const auto NUM_THREADS = st.range(1);
 
  350   collision_res.fill(
false);
 
  353     computeCollisionsBatchInParallelCall(
 
  354       static_cast<size_t>(NUM_THREADS), geometry_pool, 
qs, collision_res);
 
  365   const Eigen::MatrixXd & 
qs,
 
  371   benchmark::State & st)
 
  374   const auto NUM_THREADS = st.range(1);
 
  377     model, geometry_model, 
static_cast<size_t>(NUM_THREADS));
 
  379   collision_res.fill(
false);
 
  382     computeCollisionsBatchInParallelWithBroadPhaseCall(
 
  383       static_cast<size_t>(NUM_THREADS), 
pool, 
qs, collision_res);
 
  394   const Eigen::MatrixXd & 
qs,
 
  400   benchmark::State & st)
 
  403   const auto NUM_THREADS = st.range(1);
 
  406     model, geometry_model, 
static_cast<size_t>(NUM_THREADS));
 
  408   collision_res.fill(
false);
 
  411     computeCollisionsBatchInParallelWithTreeBroadPhaseCall(
 
  412       static_cast<size_t>(NUM_THREADS), 
pool, 
qs, collision_res);
 
  418 #endif // #ifdef PINOCCHIO_WITH_HPP_FCL 
  420 #ifdef PINOCCHIO_WITH_HPP_FCL 
  
#define PINOCCHIO_DONT_INLINE
Function attribute to forbid inlining. This is a compiler hint that can be not respected.
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
pinocchio::GeometryData geometry_data
static pinocchio::Model MODEL
static void MonoThreadCustomArguments(benchmark::internal::Benchmark *b)
BENCHMARK_REGISTER_F(ParallelFixture, RNEA) -> Apply(MonoThreadCustomArguments)
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
static PINOCCHIO_DONT_INLINE void abaInParallelCall(size_t num_threads, pinocchio::ModelPool &pool, const Eigen::MatrixXd &qs, const Eigen::MatrixXd &vs, const Eigen::MatrixXd &taus, const Eigen::MatrixXd &res)
void SetUp(benchmark::State &st)
pinocchio::GeometryModel geometry_model
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
std::string name
Model name.
void addAllCollisionPairs()
Add all possible collision pairs.
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
void abaInParallel(const size_t num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &tau, const Eigen::MatrixBase< TangentVectorPool3 > &a)
A parallel version of the Articulated Body algorithm. It computes the forward dynamics,...
void SetUp(benchmark::State &)
static PINOCCHIO_DONT_INLINE void rneaInParallelCall(size_t num_threads, pinocchio::ModelPool &pool, const Eigen::MatrixXd &qs, const Eigen::MatrixXd &vs, const Eigen::MatrixXd &as, const Eigen::MatrixXd &res)
std::shared_ptr< MeshLoader > MeshLoaderPtr
DataTpl< context::Scalar, context::Options > Data
BENCHMARK_DEFINE_F(ParallelFixture, RNEA)(benchmark
PINOCCHIO_BENCHMARK_MAIN_WITH_SETUP(ParallelFixture::GlobalSetUp)
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
void rneaInParallel(const size_t num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
static PINOCCHIO_DONT_INLINE void rneaCall(const pinocchio::Model &model, pinocchio::Data &data, const Eigen::MatrixXd::ColXpr &q, const Eigen::MatrixXd::ColXpr &v, const Eigen::MatrixXd::ColXpr &a, const Eigen::MatrixXd::ColXpr &r)
int nv
Dimension of the velocity vector space.
void computeCollisionsInParallel(const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false)
std::unique_ptr< pinocchio::ModelPool > pool
void TearDown(benchmark::State &)
void TearDown(benchmark::State &)
static pinocchio::Model MODEL
static void GlobalSetUp(const ExtraArgs &)
static void MultiThreadCustomArguments(benchmark::internal::Benchmark *b)
static PINOCCHIO_DONT_INLINE void abaCall(const pinocchio::Model &model, pinocchio::Data &data, const Eigen::MatrixXd::ColXpr &q, const Eigen::MatrixXd::ColXpr &v, const Eigen::MatrixXd::ColXpr &taus, const Eigen::MatrixXd::ColXpr &r)
int nq
Dimension of the configuration vector representation.
static void GlobalSetUp(const ExtraArgs &)
#define PINOCCHIO_MODEL_DIR
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geom_model, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false, const bool mimic=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
static pinocchio::GeometryModel GEOMETRY_MODEL
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:22