Go to the documentation of this file.
5 #ifndef __pinocchio_python_multibody_joint_joint_base_hpp__
6 #define __pinocchio_python_multibody_joint_joint_base_hpp__
8 #include <boost/python.hpp>
20 template<
class Jo
intModelDerived>
22 :
public boost::python::def_visitor<JointModelBasePythonVisitor<JointModelDerived>>
27 template<
class PyClass>
30 cl.def(bp::init<>(bp::arg(
"self")))
32 .add_property(
"id", &
get_id)
35 .add_property(
"nq", &
get_nq)
36 .add_property(
"nv", &
get_nv)
39 "Return vector of boolean if joint has configuration limits.")
42 "Return vector of boolean if joint has configuration limits in tangent space.")
45 bp::args(
"self",
"joint_id",
"idx_q",
"idx_v"))
46 .def(
"classname", &JointModelDerived::classname)
47 .staticmethod(
"classname")
48 .def(
"calc", &
calc0, bp::args(
"self",
"jdata",
"q"))
49 .def(
"calc", &
calc1, bp::args(
"self",
"jdata",
"q",
"v"))
52 "Create data associated to the joint model.")
54 "hasSameIndexes", &JointModelDerived::template hasSameIndexes<JointModelDerived>,
55 bp::args(
"self",
"other"),
"Check if this has same indexes than other.")
58 "Returns string indicating the joint type (class name):"
59 "\n\t- JointModelR[*]: Revolute Joint, with rotation axis [*] ∈ [X,Y,Z]"
60 "\n\t- JointModelRevoluteUnaligned: Revolute Joint, with rotation axis not aligned "
62 "\n\t- JointModelRUB[*]: Unbounded revolute Joint (without position limits), with "
63 "rotation axis [*] ∈ [X,Y,Z]"
64 "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with "
65 "rotation axis not aligned with X, Y, nor Z"
66 "\n\t- JointModelP[*]: Prismatic Joint, with rotation axis [*] ∈ [X,Y,Z]"
67 "\n\t- JointModelPlanar: Planar joint"
68 "\n\t- JointModelPrismaticUnaligned: Prismatic joint, with translation axis not "
69 "aligned with X, Y, nor Z"
70 "\n\t- JointModelSphericalZYX: Spherical joint (3D rotation)"
71 "\n\t- JointModelTranslation: Translation joint (3D translation)"
72 "\n\t- JointModelFreeFlyer: Joint enabling 3D rotation and translations.")
74 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
75 .def(bp::self == bp::self)
76 .def(bp::self != bp::self)
85 static int get_idx_q(
const JointModelDerived &
self)
89 static int get_idx_v(
const JointModelDerived &
self)
93 static int get_nq(
const JointModelDerived &
self)
97 static int get_nv(
const JointModelDerived &
self)
107 const JointModelDerived &
self,
112 self.calc(jdata,
q,
v);
116 template<
class Jo
intDataDerived>
118 :
public boost::python::def_visitor<JointDataBasePythonVisitor<JointDataDerived>>
121 template<
class PyClass>
128 .add_property(
"S", &
get_S)
129 .add_property(
"M", &
get_M)
130 .add_property(
"v", &
get_v)
131 .add_property(
"c", &
get_c)
132 .add_property(
"U", &
get_U)
137 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
138 .def(bp::self == bp::self)
139 .def(bp::self != bp::self)
144 static typename JointDataDerived::ConfigVector_t
get_joint_q(
const JointDataDerived &
self)
146 return self.joint_q_accessor();
148 static typename JointDataDerived::TangentVector_t
get_joint_v(
const JointDataDerived &
self)
150 return self.joint_v_accessor();
154 static typename JointDataDerived::Constraint_t::DenseBase
get_S(
const JointDataDerived &
self)
156 return self.S_accessor().matrix();
158 static typename JointDataDerived::Transformation_t
get_M(
const JointDataDerived &
self)
160 return self.M_accessor();
162 static typename JointDataDerived::Motion_t
get_v(
const JointDataDerived &
self)
164 return self.v_accessor();
166 static typename JointDataDerived::Bias_t
get_c(
const JointDataDerived &
self)
168 return self.c_accessor();
170 static typename JointDataDerived::U_t
get_U(
const JointDataDerived &
self)
172 return self.U_accessor();
174 static typename JointDataDerived::D_t
get_Dinv(
const JointDataDerived &
self)
176 return self.Dinv_accessor();
178 static typename JointDataDerived::UD_t
get_UDinv(
const JointDataDerived &
self)
180 return self.UDinv_accessor();
191 #endif // ifndef __pinocchio_python_multibody_joint_joint_base_hpp__
static int get_idx_q(const JointModelDerived &self)
JointModelDerived::JointDataDerived JointDataDerived
static JointDataDerived::Transformation_t get_M(const JointDataDerived &self)
static JointDataDerived::U_t get_U(const JointDataDerived &self)
void visit(PyClass &cl) const
static void calc1(const JointModelDerived &self, JointDataDerived &jdata, const context::VectorXs &q, const context::VectorXs &v)
static int get_idx_v(const JointModelDerived &self)
static JointDataDerived::TangentVector_t get_joint_v(const JointDataDerived &self)
static JointDataDerived::UD_t get_UDinv(const JointDataDerived &self)
static JointIndex get_id(const JointModelDerived &self)
static JointDataDerived::Motion_t get_v(const JointDataDerived &self)
const std::vector< bool > hasConfigurationLimitInTangent(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limit...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
static JointDataDerived::D_t get_Dinv(const JointDataDerived &self)
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model.
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
const std::vector< bool > hasConfigurationLimit(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitVisitor to get the configurations limits.
static JointDataDerived::ConfigVector_t get_joint_q(const JointDataDerived &self)
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
static JointDataDerived::Bias_t get_c(const JointDataDerived &self)
void visit(PyClass &cl) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
static JointDataDerived::Constraint_t::DenseBase get_S(const JointDataDerived &self)
static int get_nv(const JointModelDerived &self)
static void calc0(const JointModelDerived &self, JointDataDerived &jdata, const context::VectorXs &q)
static int get_nq(const JointModelDerived &self)
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:30