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)
36 .add_property(
"nq", &
get_nq)
37 .add_property(
"nv", &
get_nv)
41 "Return vector of boolean if joint has configuration limits.")
44 "Return vector of boolean if joint has configuration limits in tangent space.")
45 .def(
"setIndexes", &
setIndexes0, bp::args(
"self",
"joint_id",
"idx_q",
"idx_v"))
48 bp::args(
"self",
"joint_id",
"idx_q",
"idx_v",
"idx_vExtended"))
49 .def(
"classname", &JointModelDerived::classname)
50 .staticmethod(
"classname")
51 .def(
"calc", &
calc0, bp::args(
"self",
"jdata",
"q"))
52 .def(
"calc", &
calc1, bp::args(
"self",
"jdata",
"q",
"v"))
55 "Create data associated to the joint model.")
57 "hasSameIndexes", &JointModelDerived::template hasSameIndexes<JointModelDerived>,
58 bp::args(
"self",
"other"),
"Check if this has same indexes than other.")
61 "Returns string indicating the joint type (class name):"
62 "\n\t- JointModelR[*]: Revolute Joint, with rotation axis [*] ∈ [X,Y,Z]"
63 "\n\t- JointModelRevoluteUnaligned: Revolute Joint, with rotation axis not aligned "
65 "\n\t- JointModelRUB[*]: Unbounded revolute Joint (without position limits), with "
66 "rotation axis [*] ∈ [X,Y,Z]"
67 "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with "
68 "rotation axis not aligned with X, Y, nor Z"
69 "\n\t- JointModelP[*]: Prismatic Joint, with rotation axis [*] ∈ [X,Y,Z]"
70 "\n\t- JointModelPlanar: Planar joint"
71 "\n\t- JointModelPrismaticUnaligned: Prismatic joint, with translation axis not "
72 "aligned with X, Y, nor Z"
73 "\n\t- JointModelSphericalZYX: Spherical joint (3D rotation)"
74 "\n\t- JointModelTranslation: Translation joint (3D translation)"
75 "\n\t- JointModelFreeFlyer: Joint enabling 3D rotation and translations.")
77 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
78 .def(bp::self == bp::self)
79 .def(bp::self != bp::self)
88 static int get_idx_q(
const JointModelDerived &
self)
92 static int get_idx_v(
const JointModelDerived &
self)
98 return self.idx_vExtended();
100 static int get_nq(
const JointModelDerived &
self)
104 static int get_nv(
const JointModelDerived &
self)
110 return self.nvExtended();
119 const JointModelDerived &
self,
124 self.calc(jdata,
q,
v);
134 JointModelDerived &
self,
144 template<
class Jo
intDataDerived>
146 :
public boost::python::def_visitor<JointDataBasePythonVisitor<JointDataDerived>>
149 template<
class PyClass>
156 .add_property(
"S", &
get_S)
157 .add_property(
"M", &
get_M)
158 .add_property(
"v", &
get_v)
159 .add_property(
"c", &
get_c)
160 .add_property(
"U", &
get_U)
165 #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS
166 .def(bp::self == bp::self)
167 .def(bp::self != bp::self)
172 static typename JointDataDerived::ConfigVector_t
get_joint_q(
const JointDataDerived &
self)
174 return self.joint_q_accessor();
176 static typename JointDataDerived::TangentVector_t
get_joint_v(
const JointDataDerived &
self)
178 return self.joint_v_accessor();
182 static typename JointDataDerived::Constraint_t::DenseBase
get_S(
const JointDataDerived &
self)
184 return self.S_accessor().matrix();
186 static typename JointDataDerived::Transformation_t
get_M(
const JointDataDerived &
self)
188 return self.M_accessor();
190 static typename JointDataDerived::Motion_t
get_v(
const JointDataDerived &
self)
192 return self.v_accessor();
194 static typename JointDataDerived::Bias_t
get_c(
const JointDataDerived &
self)
196 return self.c_accessor();
198 static typename JointDataDerived::U_t
get_U(
const JointDataDerived &
self)
200 return self.U_accessor();
202 static typename JointDataDerived::D_t
get_Dinv(
const JointDataDerived &
self)
204 return self.Dinv_accessor();
206 static typename JointDataDerived::UD_t
get_UDinv(
const JointDataDerived &
self)
208 return self.UDinv_accessor();
219 #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)
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
void visit(PyClass &cl) const
static void calc1(const JointModelDerived &self, JointDataDerived &jdata, const context::VectorXs &q, const context::VectorXs &v)
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the model tangent space correspond...
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 int get_nvExtended(const JointModelDerived &self)
context::VectorXs VectorXs
static JointIndex get_id(const JointModelDerived &self)
static void setIndexes1(JointModelDerived &self, const int &id, const int &idx_q, const int &idx_v, const int &idx_vExtended)
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...
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)
static JointDataDerived::Bias_t get_c(const JointDataDerived &self)
static int get_idx_vExtended(const JointModelDerived &self)
void visit(PyClass &cl) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
int idx_vExtended(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdvExtendedVisitor to get the index in the model extended tangent ...
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)
static void setIndexes0(JointModelDerived &self, const int &id, const int &idx_q, const int &idx_v)
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Thu Apr 10 2025 02:42:19