Go to the documentation of this file.
5 #define BOOST_FUSION_INVOKE_MAX_ARITY 10
14 #include "pinocchio/tools/timer.hpp"
17 #include <boost/test/unit_test.hpp>
18 #include <boost/utility/binary.hpp>
26 std::cout <<
"Test()" << std::endl;
31 std::cout <<
"Test(int)" << std::endl;
36 std::cout <<
"Test(clone)" << std::endl;
45 return static_cast<D &
>(*this);
49 return static_cast<const D &
>(*this);
54 static_cast<D *
>(
this)->
f();
58 return static_cast<D *
>(
this)->
g();
60 int h(
const double & x)
62 return static_cast<D *
>(
this)->
h(
x);
64 int hh(
const double & x,
const int & y,
const Eigen::MatrixXd & z,
const TestObj &
a)
66 return static_cast<D *
>(
this)->
hh(
x,
y, z,
a);
74 std::cout <<
"f()" << std::endl;
78 std::cout <<
"g()" << std::endl;
81 int h(
const double & x)
83 std::cout <<
"h(" <<
x <<
")" << std::endl;
86 int hh(
const double & x,
const int & y,
const Eigen::MatrixXd & z,
const TestObj &)
88 std::cout <<
"hh(" <<
x <<
"," <<
y <<
"," << z <<
",a)" << std::endl;
97 std::cout <<
"f()" << std::endl;
101 std::cout <<
"g()" << std::endl;
104 int h(
const double & x)
106 std::cout <<
"h(" <<
x <<
")" << std::endl;
109 int hh(
const double & x,
const int & y,
const Eigen::MatrixXd & z,
const TestObj &)
111 std::cout <<
"hh(" <<
x <<
"," <<
y <<
"," << z <<
",a)" << std::endl;
131 #include <boost/variant.hpp>
134 #include <boost/fusion/include/sequence.hpp>
135 #include <boost/fusion/include/make_vector.hpp>
136 #include <boost/fusion/include/next.hpp>
137 #include <boost/fusion/include/invoke.hpp>
138 #include <boost/fusion/view/joint_view.hpp>
139 #include <boost/fusion/include/joint_view.hpp>
140 #include <boost/fusion/algorithm.hpp>
141 #include <boost/fusion/container.hpp>
145 struct Launcher :
public boost::static_visitor<int>
151 const Eigen::MatrixXd &,
152 const Eigen::MatrixXd &,
153 const Eigen::MatrixXd &,
166 return bf::invoke(&Launcher::algo<D>, bf::push_front(
args, boost::ref(dref)));
179 const Eigen::MatrixXd & z,
180 const Eigen::MatrixXd &,
181 const Eigen::MatrixXd &,
184 return crtp.
hh(
x,
y, z,
a);
192 template<
typename T,
typename V>
195 return push_front(
v,
t);
198 template<
typename T1,
typename T2,
typename V>
203 return push_front(push_front(
v,
t2), t1);
214 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
228 1.0, 1, Eigen::MatrixXd::Zero(3, 3), Eigen::MatrixXd::Zero(3, 3),
229 Eigen::MatrixXd::Zero(3, 3),
TestObj(1)));
233 bf::vector<int &> arg = bf::make_vector(boost::ref(j));
235 bf::vector<double &, int &> arg1 =
bf::append(boost::ref(k), arg);
236 bf::vector<int &, double &, int &> arg11 =
bf::append(boost::ref(
i), arg1);
238 bf::vector<int &, double &, int &> arg2 =
bf::append2(boost::ref(
i), boost::ref(k), arg);
242 BOOST_AUTO_TEST_SUITE_END()
result_of::push_front< typename result_of::push_front< V const, T2 >::type const, T1 >::type append2(T1 const &t1, T2 const &t2, V const &v)
BOOST_AUTO_TEST_CASE(test_fusion)
bf::vector< const double &, const int &, const Eigen::MatrixXd &, const Eigen::MatrixXd &, const Eigen::MatrixXd &, const TestObj & > Args
int hh(const double &x, const int &y, const Eigen::MatrixXd &z, const TestObj &a)
static int run(CRTPVariant &crtp, Args args)
virtual CollisionGeometry * clone() const=0
static int algo(CRTPBase< D > &crtp, const double &x, const int &y, const Eigen::MatrixXd &z, const Eigen::MatrixXd &, const Eigen::MatrixXd &, const TestObj &a)
TestObj(const TestObj &clone)
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
int hh(const double &x, const int &y, const Eigen::MatrixXd &z, const TestObj &)
const D & derived() const
int hh(const double &x, const int &y, const Eigen::MatrixXd &z, const TestObj &)
boost::variant< CRTPDerived, CRTPDerived2 > CRTPVariant
int operator()(CRTPBase< D > &dref) const
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:42:57