5 #include "pinocchio/algorithm/parallel/rnea.hpp" 6 #include "pinocchio/algorithm/parallel/aba.hpp" 7 #include "pinocchio/algorithm/joint-configuration.hpp" 8 #include "pinocchio/parsers/sample-models.hpp" 10 #ifdef PINOCCHIO_WITH_HPP_FCL 11 #include "pinocchio/algorithm/parallel/geometry.hpp" 14 #include "pinocchio/parsers/urdf.hpp" 15 #include "pinocchio/parsers/srdf.hpp" 16 #include "pinocchio/parsers/sample-models.hpp" 20 #include "pinocchio/utils/timer.hpp" 23 int main(
int ,
const char ** )
25 using namespace Eigen;
28 typedef Eigen::Matrix<bool,Eigen::Dynamic,1>
VectorXb;
37 std::cout <<
"(the time score in debug mode is not relevant) " << std::endl;
41 const int NUM_THREADS = omp_get_max_threads();
48 std::cout <<
"nq = " << model.
nq << std::endl;
49 std::cout <<
"nv = " << model.
nv << std::endl;
50 std::cout <<
"name = " << model.
name << std::endl;
52 #ifdef PINOCCHIO_WITH_HPP_FCL 54 hpp::fcl::MeshLoaderPtr mesh_loader = make_shared<hpp::fcl::CachedMeshLoader>();
56 std::vector<std::string> package_paths(1,package_path);
65 int num_active_collision_pairs = 0;
69 num_active_collision_pairs++;
71 std::cout <<
"active collision pairs = " << num_active_collision_pairs << std::endl;
75 std::cout <<
"--" << std::endl;
76 std::cout <<
"NUM_THREADS: " << NUM_THREADS << std::endl;
77 std::cout <<
"BATCH_SIZE: " << BATCH_SIZE << std::endl;
78 std::cout <<
"--" << std::endl;
81 const VectorXd qmax = Eigen::VectorXd::Ones(model.
nq);
83 MatrixXd
qs(model.
nq,BATCH_SIZE);
84 MatrixXd vs(model.
nv,BATCH_SIZE);
85 MatrixXd as(model.
nv,BATCH_SIZE);
86 MatrixXd taus(model.
nv,BATCH_SIZE);
87 MatrixXd
res(model.
nv,BATCH_SIZE);
90 for(
size_t i=0;
i < NBT; ++
i)
98 vs.col(
i) = Eigen::VectorXd::Random(model.
nv);
99 as.col(
i) = Eigen::VectorXd::Random(model.
nv);
100 taus.col(
i) = Eigen::VectorXd::Random(model.
nv);
109 res.col(
i) =
rnea(model,data,qs.col(
i),vs.col(
i),as.col(
i));
111 std::cout <<
"mean RNEA = \t\t\t\t"; timer.
toc(std::cout,NBT*BATCH_SIZE);
121 std::stringstream ss;
122 ss <<
"mean RNEA pool (";
124 ss <<
" threads) = \t\t";
125 ss << elapsed <<
" us" << std::endl;
126 std::cout << ss.str();
129 std::cout <<
"--" << std::endl;
135 res.col(
i) =
aba(model,data,qs.col(
i),vs.col(
i),taus.col(
i));
137 std::cout <<
"mean ABA = \t\t\t\t"; timer.
toc(std::cout,NBT*BATCH_SIZE);
147 std::stringstream ss;
148 ss <<
"mean ABA pool (";
150 ss <<
" threads) = \t\t";
151 ss << elapsed <<
" us" << std::endl;
152 std::cout << ss.str();
155 #ifdef PINOCCHIO_WITH_HPP_FCL 156 std::cout <<
"--" << std::endl;
157 const int NBT_COLLISION =
math::max(NBT,1);
159 SMOOTH((
size_t)NBT_COLLISION)
163 std::cout <<
"non parallel collision = \t\t\t"; timer.
toc(std::cout,NBT_COLLISION);
168 SMOOTH((
size_t)NBT_COLLISION)
172 double elapsed = timer.
toc()/(NBT_COLLISION);
173 std::stringstream ss;
174 ss <<
"parallel collision (";
176 ss <<
" threads) = \t\t";
177 ss << elapsed <<
" us" << std::endl;
178 std::cout << ss.str();
181 std::cout <<
"--" << std::endl;
182 GeometryPool geometry_pool(model,geometry_model,NUM_THREADS);
183 VectorXb collision_res(BATCH_SIZE);
184 collision_res.fill(
false);
187 SMOOTH((
size_t)(NBT_COLLISION/BATCH_SIZE))
192 std::cout <<
"non parallel collision = \t\t\t"; timer.
toc(std::cout,NBT_COLLISION);
197 SMOOTH((
size_t)(NBT_COLLISION/BATCH_SIZE))
201 double elapsed = timer.
toc()/(NBT_COLLISION);
202 std::stringstream ss;
203 ss <<
"pool parallel collision (";
205 ss <<
" threads) = \t\t";
206 ss << elapsed <<
" us" << std::endl;
207 std::cout << ss.str();
211 std::cout <<
"--" << std::endl;
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)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
int main(int, const char **)
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...
void rnea(const int 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...
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
std::vector< bool > activeCollisionPairs
Vector of 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.
#define PINOCCHIO_MODEL_DIR
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
std::string name
Model name;.
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
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 ...
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
void addAllCollisionPairs()
Add all possible collision pairs.
Main pinocchio namespace.
int nv
Dimension of the velocity vector space.
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
int nq
Dimension of the configuration vector representation.