Namespaces | |
details | |
internal | |
Typedefs | |
typedef Eigen::Map< const SE3::Quaternion > | QuatConstMap |
typedef Eigen::Map< SE3::Quaternion > | QuatMap |
typedef SE3::Scalar | Scalar |
typedef Eigen::Matrix< Scalar, 7, 1 > | Vector7d |
typedef Eigen::Matrix< bool, Eigen::Dynamic, 1 > | VectorXb |
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > | VectorXd |
Functions | |
static Eigen::MatrixXd | aba_proxy (const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &tau) |
static void | aba_proxy_res (const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &tau, Eigen::Ref< Eigen::MatrixXd > a) |
static JointModelComposite & | addJoint_proxy (JointModelComposite &joint_composite, const JointModel &jmodel, const SE3 &joint_placement=SE3::Identity()) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
bp::tuple | appendModel_proxy (const ModelTpl< Scalar, Options, JointCollectionTpl > &modelA, const ModelTpl< Scalar, Options, JointCollectionTpl > &modelB, const GeometryModel &geomModelA, const GeometryModel &geomModelB, const FrameIndex frameInModelA, const SE3Tpl< Scalar, Options > &aMb) |
Eigen::MatrixXd | bodyRegressor_proxy (const Motion &v, const Motion &a) |
BOOST_PYTHON_FUNCTION_OVERLOADS (removeCollisionPairs_overload, srdf::removeCollisionPairs, 3, 4) BOOST_PYTHON_FUNCTION_OVERLOADS(removeCollisionPairsFromXML_overload | |
BOOST_PYTHON_FUNCTION_OVERLOADS (loadReferenceConfigurations_overload, srdf::loadReferenceConfigurations, 2, 3) void loadReferenceConfigurationsFromXML(Model &model | |
BOOST_PYTHON_FUNCTION_OVERLOADS (computeKKTContactDynamicMatrixInverse_overload, computeKKTContactDynamicMatrixInverse_proxy, 4, 5) static const Eigen | |
static void | buffer_copy (boost::asio::streambuf &dest, const boost::asio::streambuf &source) |
Model | buildModel (const std::string &filename, const std::string &var_name="model") |
Load a model from a Python script. More... | |
PINOCCHIO_DEPRECATED Model | buildModel (const std::string &filename, const std::string &var_name, const bool) |
Load a model from a Python script. More... | |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bp::tuple | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const GeometryModel &geom_model, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration) |
template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
bp::tuple | buildReducedModel (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::vector< GeometryModel, Eigen::aligned_allocator< GeometryModel > > &list_of_geom_models, const std::vector< JointIndex > &list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration) |
Model | buildSampleModelHumanoid () |
Model | buildSampleModelHumanoid (bool usingFF) |
Model | buildSampleModelHumanoidRandom () |
Model | buildSampleModelHumanoidRandom (bool usingFF) |
Model | buildSampleModelManipulator () |
static SE3::Vector3 | com_0_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, bool computeSubtreeComs=true) |
static SE3::Vector3 | com_1_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, bool computeSubtreeComs=true) |
static SE3::Vector3 | com_2_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, bool computeSubtreeComs=true) |
static const Data::Vector3 & | com_default_proxy (const Model &model, Data &data, bool computeSubtreeComs=true) |
static const Data::Vector3 & | com_level_proxy (const Model &model, Data &data, KinematicLevel kinematic_level, bool computeSubtreeComs=true) |
static void | com_level_proxy_deprecated_signature (const Model &model, Data &data, int kinematic_level, bool computeSubtreeComs=true) |
static Data::Matrix6x | compute_frame_jacobian_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, Model::FrameIndex frame_id) |
static Data::Matrix6x | compute_frame_jacobian_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, Model::FrameIndex frame_id, ReferenceFrame reference_frame) |
static Data::Matrix6x | compute_jacobian_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, Model::JointIndex jointId) |
bp::tuple | computeABADerivatives_fext (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau, const ForceAlignedVector &fext) |
bp::tuple | computeABADerivativesDefault (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau) |
static void | computeAllTerms_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v) |
bp::tuple | computeCentroidalDynamicsDerivatives_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a) |
static bool | computeCollisions_full_proxy (const int num_threads, const Model &model, Data &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::VectorXd &q, const bool stopAtFirstCollision=false) |
static VectorXb | computeCollisions_pool_proxy (const int num_thread, GeometryPool &pool, const Eigen::MatrixXd &q, bool stop_at_first_collision=false) |
static void | computeCollisions_pool_proxy_res (const int num_thread, GeometryPool &pool, const Eigen::MatrixXd &q, Eigen::Ref< VectorXb > res, bool stop_at_first_collision=false) |
static bool | computeCollisions_proxy (const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false) |
Data::MatrixXs | computeGeneralizedGravityDerivatives (const Model &model, Data &data, const Eigen::VectorXd &q) |
static Eigen::MatrixXd | computeKKTContactDynamicMatrixInverse_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::MatrixXd &J, const double mu=0) |
const Data::RowMatrixXs & | computeMinverse_proxy (const Model &model, Data &data, const Eigen::VectorXd &q) |
bp::tuple | computeRNEADerivatives (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a) |
bp::tuple | computeRNEADerivatives_fext (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &a, const ForceAlignedVector &fext) |
Data::MatrixXs | computeStaticTorqueDerivatives (const Model &model, Data &data, const Eigen::VectorXd &q, const ForceAlignedVector &fext) |
static Eigen::MatrixXd | crba_proxy (const Model &model, Data &data, const Eigen::VectorXd &q) |
Eigen::MatrixXd | dDifference_arg_proxy (const Model &model, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, const ArgumentPosition arg) |
bp::tuple | dDifference_proxy (const Model &model, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) |
template<typename T > | |
py::object | default_arg (T t) |
Eigen::MatrixXd | dIntegrate_arg_proxy (const Model &model, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const ArgumentPosition arg) |
bp::tuple | dIntegrate_proxy (const Model &model, const Eigen::VectorXd &q, const Eigen::VectorXd &v) |
Eigen::MatrixXd | dIntegrateTransport_proxy (const Model &model, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::MatrixXd &Jin, const ArgumentPosition arg) |
template<typename Vector3Like > | |
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | exp3_proxy (const Vector3Like &v) |
template<typename Scalar , int Options> | |
SE3Tpl< Scalar, Options > | exp6_proxy (const MotionTpl< Scalar, Options > &v) |
template<typename Vector6Like > | |
SE3Tpl< typename Vector6Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | exp6_proxy (const Vector6Like &vec6) |
template<class T > | |
bp::class_< T > & | expose_joint_data (bp::class_< T > &cl) |
template<> | |
bp::class_< JointDataComposite > & | expose_joint_data< JointDataComposite > (bp::class_< JointDataComposite > &cl) |
template<> | |
bp::class_< JointDataPlanar > & | expose_joint_data< JointDataPlanar > (bp::class_< JointDataPlanar > &cl) |
template<> | |
bp::class_< JointDataPrismaticUnaligned > & | expose_joint_data< JointDataPrismaticUnaligned > (bp::class_< JointDataPrismaticUnaligned > &cl) |
template<> | |
bp::class_< JointDataRevoluteUnaligned > & | expose_joint_data< JointDataRevoluteUnaligned > (bp::class_< JointDataRevoluteUnaligned > &cl) |
template<> | |
bp::class_< JointDataSphericalZYX > & | expose_joint_data< JointDataSphericalZYX > (bp::class_< JointDataSphericalZYX > &cl) |
template<class T > | |
bp::class_< T > & | expose_joint_model (bp::class_< T > &cl) |
template<> | |
bp::class_< JointModelComposite > & | expose_joint_model< JointModelComposite > (bp::class_< JointModelComposite > &cl) |
template<> | |
bp::class_< JointModelPrismaticUnaligned > & | expose_joint_model< JointModelPrismaticUnaligned > (bp::class_< JointModelPrismaticUnaligned > &cl) |
template<> | |
bp::class_< JointModelRevoluteUnaligned > & | expose_joint_model< JointModelRevoluteUnaligned > (bp::class_< JointModelRevoluteUnaligned > &cl) |
void | exposeABA () |
void | exposeABADerivatives () |
void | exposeAlgorithms () |
void | exposeCAT () |
void | exposeCentroidal () |
void | exposeCentroidalDerivatives () |
void | exposeCholesky () |
void | exposeCOM () |
void | exposeConversions () |
void | exposeCRBA () |
void | exposeData () |
void | exposeDependencies () |
void | exposeDynamics () |
void | exposeEnergy () |
void | exposeExplog () |
void | exposeFCL () |
void | exposeForce () |
void | exposeFrame () |
void | exposeFramesAlgo () |
void | exposeFramesDerivatives () |
void | exposeGeometry () |
void | exposeGeometryAlgo () |
void | exposeInertia () |
void | exposeJacobian () |
void | exposeJoints () |
void | exposeJointsAlgo () |
void | exposeKinematicRegressor () |
void | exposeKinematics () |
void | exposeKinematicsDerivatives () |
void | exposeLieGroups () |
void | exposeModel () |
void | exposeModelAlgo () |
void | exposeMotion () |
void | exposeParallelABA () |
void | exposeParallelAlgorithms () |
void | exposeParallelGeometry () |
void | exposeParallelRNEA () |
void | exposeParsers () |
void | exposePool () |
void | exposeRegressor () |
void | exposeRNEA () |
void | exposeRNEADerivatives () |
void | exposeRpy () |
void | exposeSampleModels () |
void | exposeSE3 () |
void | exposeSerialization () |
void | exposeSkew () |
void | exposeSRDFParser () |
void | exposeURDFGeometry () |
void | exposeURDFModel () |
void | exposeURDFParser () |
void | exposeVersion () |
template<typename T , class Allocator > | |
void | extract (const boost::python::list &list, std::vector< T, Allocator > &vec) |
template<typename T > | |
std::vector< T, std::allocator< T > > | extract (const boost::python::list &list) |
template<typename T , class Allocator > | |
std::vector< T, Allocator > | extract (const boost::python::list &list) |
static const Eigen::VectorXd | forwardDynamics_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau, const Eigen::MatrixXd &J, const Eigen::VectorXd &gamma, const double inv_damping=0.0) |
static const Eigen::VectorXd | forwardDynamics_proxy_no_q (const Model &model, Data &data, const Eigen::VectorXd &tau, const Eigen::MatrixXd &J, const Eigen::VectorXd &gamma, const double inv_damping=0.0) |
static Data::Matrix6x | frame_jacobian_time_variation_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Model::FrameIndex frame_id, const ReferenceFrame rf) |
Eigen::MatrixXd | frameBodyRegressor_proxy (const Model &model, Data &data, const FrameIndex frameId) |
template<typename ReturnType > | |
ReturnType & | from (py::handle model) |
static Data::Matrix6x | get_frame_jacobian_proxy (const Model &model, Data &data, const Model::FrameIndex frame_id, ReferenceFrame rf) |
static Data::Matrix6x | get_frame_jacobian_time_variation_proxy (const Model &model, Data &data, Model::FrameIndex jointId, ReferenceFrame rf) |
static Data::Matrix6x | get_jacobian_proxy (const Model &model, Data &data, Model::JointIndex jointId, ReferenceFrame rf) |
static Data::Matrix3x | get_jacobian_subtree_com_proxy (const Model &model, Data &data, Model::JointIndex jointId) |
static Data::Matrix6x | get_jacobian_time_variation_proxy (const Model &model, Data &data, Model::JointIndex jointId, ReferenceFrame rf) |
bp::tuple | getCentroidalDynamicsDerivatives_proxy (const Model &model, Data &data) |
Data::Matrix3x | getCoMVelocityDerivatives_proxy (const Model &model, Data &data) |
bp::tuple | getFrameAccelerationDerivatives_proxy (const Model &model, Data &data, const Model::FrameIndex frame_id, ReferenceFrame rf) |
bp::tuple | getFrameVelocityDerivatives_proxy (const Model &model, Data &data, const Model::FrameIndex frame_id, ReferenceFrame rf) |
bp::tuple | getJointAccelerationDerivatives_proxy (const Model &model, Data &data, const Model::JointIndex jointId, ReferenceFrame rf) |
bp::tuple | getJointVelocityDerivatives_proxy (const Model &model, Data &data, const Model::JointIndex jointId, ReferenceFrame rf) |
boost::python::object | getOrCreatePythonNamespace (const std::string &submodule_name) |
Helper to create or simply return an existing namespace in Python. More... | |
Hlog3 (M, v, res) | |
static const Eigen::VectorXd | impulseDynamics_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v_before, const Eigen::MatrixXd &J, const double r_coeff=0., const double inv_damping=0.) |
static const Eigen::VectorXd | impulseDynamics_proxy_no_q (const Model &model, Data &data, const Eigen::VectorXd &v_before, const Eigen::MatrixXd &J, const double r_coeff=0., const double inv_damping=0.) |
static JointModelComposite * | init_proxy1 (const JointModel &jmodel) |
static JointModelComposite * | init_proxy2 (const JointModel &jmodel, const SE3 &joint_placement) |
static Data::Matrix3x | jacobian_subtree_com_kinematics_proxy (const Model &model, Data &data, const Eigen::VectorXd &q, Model::JointIndex jointId) |
static Data::Matrix3x | jacobian_subtree_com_proxy (const Model &model, Data &data, Model::JointIndex jointId) |
template<typename Vector3Like > | |
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | Jexp3_proxy (const Vector3Like &v) |
template<typename Scalar , int Options> | |
MotionTpl< Scalar, Options >::Matrix6 | Jexp6_proxy (const MotionTpl< Scalar, Options > &v) |
template<typename Vector6Like > | |
Eigen::Matrix< typename Vector6Like::Scalar, 6, 6, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | Jexp6_proxy (const Vector6Like &vec6) |
template<typename Scalar , int Options> | |
SE3Tpl< Scalar, Options >::Matrix6 | Jlog6_proxy (const SE3Tpl< Scalar, Options > &M) |
Eigen::MatrixXd | jointBodyRegressor_proxy (const Model &model, Data &data, const JointIndex jointId) |
template<typename Matrix3Like > | |
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3_proxy (const Matrix3Like &R) |
template<typename Matrix4Like > | |
MotionTpl< typename Matrix4Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix4Like)::Options > | log6_proxy (const Matrix4Like &homegenous_matrix) |
template<typename R , typename... Args> | |
internal::function_wrapper< R(*)(Args...)> | make_pybind11_function (R(*func)(Args...)) |
Creates a function wrapper. More... | |
template<typename Matrix > | |
Eigen::Ref< Matrix > | make_ref (Eigen::PlainObjectBase< Matrix > &mat) |
template<typename Matrix > | |
void | make_symmetric (Eigen::MatrixBase< Matrix > &mat) |
template<typename LgType > | |
CartesianProductOperationVariantTpl< double, 0, LieGroupCollectionDefaultTpl > | makeLieGroup () |
CartesianProductOperationVariantTpl< double, 0, LieGroupCollectionDefaultTpl > | makeRn (int n) |
static Eigen::VectorXd | normalize_proxy (const Model &model, const Eigen::VectorXd &config) |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (Force) ForceAlignedVector |
template<typename Matrix > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix) make_copy(const Eigen | |
template<typename Matrix3Like > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3Like) Jlog3_proxy(const Matrix3Like &M) | |
template<typename Matrix3Like , typename Vector3Like > | |
PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3Like) Hlog3_proxy(const Matrix3Like &M | |
static boost::asio::streambuf & | prepare_proxy (boost::asio::streambuf &self, const std::size_t n) |
static Eigen::VectorXd | randomConfiguration_proxy (const Model &model) |
template<typename T > | |
bool | register_symbolic_link_to_registered_type () |
static Eigen::MatrixXd | rnea_proxy (const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &a) |
static void | rnea_proxy_res (const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &a, Eigen::Ref< Eigen::MatrixXd > tau) |
Eigen::Matrix3d | rotate (const std::string &axis, const double ang) |
template<typename T > | |
std::string | sanitizedClassname () |
VectorXd | SE3ToXYZQUAT (const SE3 &M) |
bp::tuple | SE3ToXYZQUATtuple (const SE3 &M) |
template<typename T > | |
void | serialize () |
template<typename Vector3 > | |
Eigen::Matrix< typename Vector3::Scalar, 3, 3, Vector3::Options > | skew (const Vector3 &v) |
template<typename Vector3 > | |
Eigen::Matrix< typename Vector3::Scalar, 3, 3, Vector3::Options > | skewSquare (const Vector3 &u, const Vector3 &v) |
template<typename T > | |
py::object | to (T &t) |
template<typename T > | |
py::object | to (T *t) |
template<typename Matrix3 > | |
Eigen::Matrix< typename Matrix3::Scalar, 3, 1, Matrix3::Options > | unSkew (const Matrix3 &mat) |
template<typename TupleOrList > | |
SE3 | XYZQUATToSE3_bp (const TupleOrList &v) |
template<typename Vector7Like > | |
SE3 | XYZQUATToSE3_ei (const Vector7Like &v) |
Variables | |
ReturnType | res |
const Vector3Like & | v |
const std::string & | xmlStream |
typedef Eigen::Map<const SE3::Quaternion> pinocchio::python::QuatConstMap |
Definition at line 17 of file conversions.cpp.
typedef Eigen::Map< SE3::Quaternion> pinocchio::python::QuatMap |
Definition at line 16 of file conversions.cpp.
typedef SE3::Scalar pinocchio::python::Scalar |
Definition at line 13 of file conversions.cpp.
typedef Eigen::Matrix<Scalar, 7,1> pinocchio::python::Vector7d |
Definition at line 15 of file conversions.cpp.
typedef Eigen::Matrix<bool,Eigen::Dynamic,1> pinocchio::python::VectorXb |
Definition at line 16 of file bindings/python/algorithm/parallel/geometry.cpp.
typedef Eigen::Matrix<Scalar, Eigen::Dynamic,1> pinocchio::python::VectorXd |
Definition at line 14 of file conversions.cpp.
|
static |
Definition at line 22 of file bindings/python/algorithm/parallel/aba.cpp.
|
static |
Definition at line 15 of file bindings/python/algorithm/parallel/aba.cpp.
|
static |
Definition at line 78 of file joints-models.hpp.
bp::tuple pinocchio::python::appendModel_proxy | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelA, |
const ModelTpl< Scalar, Options, JointCollectionTpl > & | modelB, | ||
const GeometryModel & | geomModelA, | ||
const GeometryModel & | geomModelB, | ||
const FrameIndex | frameInModelA, | ||
const SE3Tpl< Scalar, Options > & | aMb | ||
) |
Definition at line 18 of file algorithm/expose-model.cpp.
Definition at line 13 of file expose-regressor.cpp.
pinocchio::python::BOOST_PYTHON_FUNCTION_OVERLOADS | ( | removeCollisionPairs_overload | , |
srdf::removeCollisionPairs | , | ||
3 | , | ||
4 | |||
) |
pinocchio::python::BOOST_PYTHON_FUNCTION_OVERLOADS | ( | loadReferenceConfigurations_overload | , |
srdf::loadReferenceConfigurations | , | ||
2 | , | ||
3 | |||
) | & |
pinocchio::python::BOOST_PYTHON_FUNCTION_OVERLOADS | ( | computeKKTContactDynamicMatrixInverse_overload | , |
computeKKTContactDynamicMatrixInverse_proxy | , | ||
4 | , | ||
5 | |||
) | const |
Definition at line 75 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 16 of file bindings/python/serialization/serialization.cpp.
PINOCCHIO_PYWRAP_DLLAPI Model pinocchio::python::buildModel | ( | const std::string & | filename, |
const std::string & | var_name = "model" |
||
) |
Load a model from a Python script.
This function raises a Python error in case of incistency in the Python code.
filename The full path to the model file. var_name Name of the Python variable which contains the model in the script.
Definition at line 23 of file bindings/python/parsers/python/model.cpp.
PINOCCHIO_DEPRECATED Model pinocchio::python::buildModel | ( | const std::string & | filename, |
const std::string & | var_name, | ||
const bool | |||
) |
Load a model from a Python script.
This function raises a Python error in case of incistency in the Python code.
filename The full path to the model file. var_name Name of the Python variable which contains the model in the script.
Definition at line 44 of file python.hpp.
bp::tuple pinocchio::python::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const GeometryModel & | geom_model, | ||
const std::vector< JointIndex > & | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration | ||
) |
Definition at line 36 of file algorithm/expose-model.cpp.
bp::tuple pinocchio::python::buildReducedModel | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, |
const std::vector< GeometryModel, Eigen::aligned_allocator< GeometryModel > > & | list_of_geom_models, | ||
const std::vector< JointIndex > & | list_of_joints_to_lock, | ||
const Eigen::MatrixBase< ConfigVectorType > & | reference_configuration | ||
) |
Definition at line 53 of file algorithm/expose-model.cpp.
Model pinocchio::python::buildSampleModelHumanoid | ( | ) |
Definition at line 45 of file bindings/python/parsers/sample-models.cpp.
Model pinocchio::python::buildSampleModelHumanoid | ( | bool | usingFF | ) |
Definition at line 52 of file bindings/python/parsers/sample-models.cpp.
Model pinocchio::python::buildSampleModelHumanoidRandom | ( | ) |
Definition at line 15 of file bindings/python/parsers/sample-models.cpp.
Model pinocchio::python::buildSampleModelHumanoidRandom | ( | bool | usingFF | ) |
Definition at line 22 of file bindings/python/parsers/sample-models.cpp.
Model pinocchio::python::buildSampleModelManipulator | ( | ) |
Definition at line 29 of file bindings/python/parsers/sample-models.cpp.
|
static |
Definition at line 21 of file expose-com.cpp.
|
static |
Definition at line 30 of file expose-com.cpp.
|
static |
Definition at line 40 of file expose-com.cpp.
|
static |
Definition at line 69 of file expose-com.cpp.
|
static |
Definition at line 51 of file expose-com.cpp.
|
static |
Definition at line 60 of file expose-com.cpp.
|
static |
Definition at line 24 of file expose-frames.cpp.
|
static |
Definition at line 35 of file expose-frames.cpp.
|
static |
Definition at line 14 of file expose-jacobian.cpp.
bp::tuple pinocchio::python::computeABADerivatives_fext | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::VectorXd & | tau, | ||
const ForceAlignedVector & | fext | ||
) |
Definition at line 31 of file expose-aba-derivatives.cpp.
bp::tuple pinocchio::python::computeABADerivativesDefault | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::VectorXd & | tau | ||
) |
Definition at line 17 of file expose-aba-derivatives.cpp.
|
static |
Definition at line 12 of file expose-cat.cpp.
bp::tuple pinocchio::python::computeCentroidalDynamicsDerivatives_proxy | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::VectorXd & | a | ||
) |
Definition at line 15 of file expose-centroidal-derivatives.cpp.
|
static |
Definition at line 26 of file bindings/python/algorithm/parallel/geometry.cpp.
|
static |
Definition at line 44 of file bindings/python/algorithm/parallel/geometry.cpp.
|
static |
Definition at line 37 of file bindings/python/algorithm/parallel/geometry.cpp.
|
static |
Definition at line 18 of file bindings/python/algorithm/parallel/geometry.cpp.
Data::MatrixXs pinocchio::python::computeGeneralizedGravityDerivatives | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q | ||
) |
Definition at line 17 of file expose-rnea-derivatives.cpp.
|
static |
Definition at line 64 of file expose-contact-dynamics.cpp.
const Data::RowMatrixXs& pinocchio::python::computeMinverse_proxy | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q | ||
) |
Definition at line 15 of file expose-aba.cpp.
bp::tuple pinocchio::python::computeRNEADerivatives | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::VectorXd & | a | ||
) |
Definition at line 36 of file expose-rnea-derivatives.cpp.
bp::tuple pinocchio::python::computeRNEADerivatives_fext | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::VectorXd & | a, | ||
const ForceAlignedVector & | fext | ||
) |
Definition at line 48 of file expose-rnea-derivatives.cpp.
Data::MatrixXs pinocchio::python::computeStaticTorqueDerivatives | ( | const Model & | model, |
Data & | data, | ||
const Eigen::VectorXd & | q, | ||
const ForceAlignedVector & | fext | ||
) |
Definition at line 26 of file expose-rnea-derivatives.cpp.
|
static |
Definition at line 12 of file expose-crba.cpp.
Eigen::MatrixXd pinocchio::python::dDifference_arg_proxy | ( | const Model & | model, |
const Eigen::VectorXd & | q1, | ||
const Eigen::VectorXd & | q2, | ||
const ArgumentPosition | arg | ||
) |
Definition at line 78 of file algorithm/expose-joints.cpp.
bp::tuple pinocchio::python::dDifference_proxy | ( | const Model & | model, |
const Eigen::VectorXd & | q1, | ||
const Eigen::VectorXd & | q2 | ||
) |
Definition at line 65 of file algorithm/expose-joints.cpp.
py::object pinocchio::python::default_arg | ( | T | t | ) |
Definition at line 169 of file pybind11.hpp.
Eigen::MatrixXd pinocchio::python::dIntegrate_arg_proxy | ( | const Model & | model, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const ArgumentPosition | arg | ||
) |
Definition at line 41 of file algorithm/expose-joints.cpp.
bp::tuple pinocchio::python::dIntegrate_proxy | ( | const Model & | model, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v | ||
) |
Definition at line 28 of file algorithm/expose-joints.cpp.
Eigen::MatrixXd pinocchio::python::dIntegrateTransport_proxy | ( | const Model & | model, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const Eigen::MatrixXd & | Jin, | ||
const ArgumentPosition | arg | ||
) |
Definition at line 53 of file algorithm/expose-joints.cpp.
Eigen::Matrix<typename Vector3Like::Scalar,3,3,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::python::exp3_proxy | ( | const Vector3Like & | v | ) |
Definition at line 18 of file bindings/python/spatial/explog.hpp.
SE3Tpl<Scalar,Options> pinocchio::python::exp6_proxy | ( | const MotionTpl< Scalar, Options > & | v | ) |
Definition at line 51 of file bindings/python/spatial/explog.hpp.
SE3Tpl<typename Vector6Like::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options> pinocchio::python::exp6_proxy | ( | const Vector6Like & | vec6 | ) |
Definition at line 58 of file bindings/python/spatial/explog.hpp.
|
inline |
Definition at line 18 of file joints-datas.hpp.
|
inline |
Definition at line 59 of file joints-datas.hpp.
|
inline |
Definition at line 42 of file joints-datas.hpp.
|
inline |
Definition at line 34 of file joints-datas.hpp.
|
inline |
Definition at line 25 of file joints-datas.hpp.
|
inline |
Definition at line 51 of file joints-datas.hpp.
|
inline |
Definition at line 25 of file joints-models.hpp.
bp::class_<JointModelComposite>& pinocchio::python::expose_joint_model< JointModelComposite > | ( | bp::class_< JointModelComposite > & | cl | ) |
Definition at line 117 of file joints-models.hpp.
|
inline |
Definition at line 46 of file joints-models.hpp.
|
inline |
Definition at line 32 of file joints-models.hpp.
void pinocchio::python::exposeABA | ( | ) |
Definition at line 22 of file expose-aba.cpp.
void pinocchio::python::exposeABADerivatives | ( | ) |
Definition at line 44 of file expose-aba-derivatives.cpp.
void pinocchio::python::exposeAlgorithms | ( | ) |
Definition at line 12 of file expose-algorithms.cpp.
void pinocchio::python::exposeCAT | ( | ) |
Definition at line 23 of file expose-cat.cpp.
void pinocchio::python::exposeCentroidal | ( | ) |
Definition at line 13 of file expose-centroidal.cpp.
void pinocchio::python::exposeCentroidalDerivatives | ( | ) |
Definition at line 47 of file expose-centroidal-derivatives.cpp.
void pinocchio::python::exposeCholesky | ( | ) |
Definition at line 14 of file expose-cholesky.cpp.
void pinocchio::python::exposeCOM | ( | ) |
Definition at line 121 of file expose-com.cpp.
void pinocchio::python::exposeConversions | ( | ) |
Definition at line 59 of file conversions.cpp.
void pinocchio::python::exposeCRBA | ( | ) |
Definition at line 23 of file expose-crba.cpp.
void pinocchio::python::exposeData | ( | ) |
Definition at line 13 of file expose-data.cpp.
void pinocchio::python::exposeDependencies | ( | ) |
Definition at line 14 of file dependencies.cpp.
void pinocchio::python::exposeDynamics | ( | ) |
Definition at line 87 of file expose-contact-dynamics.cpp.
void pinocchio::python::exposeEnergy | ( | ) |
Definition at line 13 of file expose-energy.cpp.
void pinocchio::python::exposeExplog | ( | ) |
Definition at line 15 of file expose-explog.cpp.
void pinocchio::python::exposeFCL | ( | ) |
Definition at line 18 of file expose-fcl.cpp.
void pinocchio::python::exposeForce | ( | ) |
Definition at line 18 of file expose-force.cpp.
void pinocchio::python::exposeFrame | ( | ) |
Definition at line 18 of file expose-frame.cpp.
void pinocchio::python::exposeFramesAlgo | ( | ) |
Definition at line 75 of file expose-frames.cpp.
void pinocchio::python::exposeFramesDerivatives | ( | ) |
Definition at line 51 of file expose-frames-derivatives.cpp.
void pinocchio::python::exposeGeometry | ( | ) |
Definition at line 16 of file multibody/expose-geometry.cpp.
void pinocchio::python::exposeGeometryAlgo | ( | ) |
Definition at line 13 of file algorithm/expose-geometry.cpp.
void pinocchio::python::exposeInertia | ( | ) |
Definition at line 18 of file expose-inertia.cpp.
void pinocchio::python::exposeJacobian | ( | ) |
Definition at line 49 of file expose-jacobian.cpp.
void pinocchio::python::exposeJoints | ( | ) |
Definition at line 17 of file multibody/joint/expose-joints.cpp.
void pinocchio::python::exposeJointsAlgo | ( | ) |
Definition at line 90 of file algorithm/expose-joints.cpp.
void pinocchio::python::exposeKinematicRegressor | ( | ) |
Definition at line 13 of file expose-kinematic-regressor.cpp.
void pinocchio::python::exposeKinematics | ( | ) |
Definition at line 17 of file expose-kinematics.cpp.
void pinocchio::python::exposeKinematicsDerivatives | ( | ) |
Definition at line 62 of file expose-kinematics-derivatives.cpp.
void pinocchio::python::exposeLieGroups | ( | ) |
Definition at line 34 of file expose-liegroups.cpp.
void pinocchio::python::exposeModel | ( | ) |
Definition at line 13 of file multibody/expose-model.cpp.
void pinocchio::python::exposeModelAlgo | ( | ) |
Definition at line 67 of file algorithm/expose-model.cpp.
void pinocchio::python::exposeMotion | ( | ) |
Definition at line 18 of file expose-motion.cpp.
void pinocchio::python::exposeParallelABA | ( | ) |
Definition at line 30 of file bindings/python/algorithm/parallel/aba.cpp.
void pinocchio::python::exposeParallelAlgorithms | ( | ) |
Definition at line 18 of file expose-parallel.cpp.
void pinocchio::python::exposeParallelGeometry | ( | ) |
Definition at line 58 of file bindings/python/algorithm/parallel/geometry.cpp.
void pinocchio::python::exposeParallelRNEA | ( | ) |
Definition at line 30 of file bindings/python/algorithm/parallel/rnea.cpp.
void pinocchio::python::exposeParsers | ( | ) |
Definition at line 14 of file expose-parsers.cpp.
void pinocchio::python::exposePool | ( | ) |
Definition at line 17 of file expose-pool.cpp.
void pinocchio::python::exposeRegressor | ( | ) |
Definition at line 28 of file expose-regressor.cpp.
void pinocchio::python::exposeRNEA | ( | ) |
Definition at line 14 of file expose-rnea.cpp.
void pinocchio::python::exposeRNEADerivatives | ( | ) |
Definition at line 61 of file expose-rnea-derivatives.cpp.
void pinocchio::python::exposeRpy | ( | ) |
Definition at line 37 of file expose-rpy.cpp.
void pinocchio::python::exposeSampleModels | ( | ) |
Definition at line 68 of file bindings/python/parsers/sample-models.cpp.
void pinocchio::python::exposeSE3 | ( | ) |
Definition at line 18 of file expose-SE3.cpp.
void pinocchio::python::exposeSerialization | ( | ) |
Definition at line 28 of file bindings/python/serialization/serialization.cpp.
void pinocchio::python::exposeSkew | ( | ) |
Definition at line 37 of file expose-skew.cpp.
void pinocchio::python::exposeSRDFParser | ( | ) |
void pinocchio::python::exposeURDFGeometry | ( | ) |
Definition at line 179 of file bindings/python/parsers/urdf/geometry.cpp.
void pinocchio::python::exposeURDFModel | ( | ) |
Definition at line 79 of file bindings/python/parsers/urdf/model.cpp.
|
inline |
Definition at line 15 of file bindings/python/parsers/urdf.hpp.
void pinocchio::python::exposeVersion | ( | ) |
Definition at line 20 of file bindings/python/utils/version.cpp.
void pinocchio::python::extract | ( | const boost::python::list & | list, |
std::vector< T, Allocator > & | vec | ||
) |
std::vector<T,std::allocator<T> > pinocchio::python::extract | ( | const boost::python::list & | list | ) |
std::vector<T,Allocator> pinocchio::python::extract | ( | const boost::python::list & | list | ) |
|
static |
Definition at line 13 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 27 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 58 of file expose-frames.cpp.
Eigen::MatrixXd pinocchio::python::frameBodyRegressor_proxy | ( | const Model & | model, |
Data & | data, | ||
const FrameIndex | frameId | ||
) |
Definition at line 23 of file expose-regressor.cpp.
|
inline |
Definition at line 66 of file pybind11.hpp.
|
static |
Definition at line 13 of file expose-frames.cpp.
|
static |
Definition at line 47 of file expose-frames.cpp.
|
static |
Definition at line 26 of file expose-jacobian.cpp.
|
static |
Definition at line 100 of file expose-com.cpp.
|
static |
Definition at line 38 of file expose-jacobian.cpp.
bp::tuple pinocchio::python::getCentroidalDynamicsDerivatives_proxy | ( | const Model & | model, |
Data & | data | ||
) |
Definition at line 33 of file expose-centroidal-derivatives.cpp.
Data::Matrix3x pinocchio::python::getCoMVelocityDerivatives_proxy | ( | const Model & | model, |
Data & | data | ||
) |
Definition at line 52 of file expose-kinematics-derivatives.cpp.
bp::tuple pinocchio::python::getFrameAccelerationDerivatives_proxy | ( | const Model & | model, |
Data & | data, | ||
const Model::FrameIndex | frame_id, | ||
ReferenceFrame | rf | ||
) |
Definition at line 32 of file expose-frames-derivatives.cpp.
bp::tuple pinocchio::python::getFrameVelocityDerivatives_proxy | ( | const Model & | model, |
Data & | data, | ||
const Model::FrameIndex | frame_id, | ||
ReferenceFrame | rf | ||
) |
Definition at line 16 of file expose-frames-derivatives.cpp.
bp::tuple pinocchio::python::getJointAccelerationDerivatives_proxy | ( | const Model & | model, |
Data & | data, | ||
const Model::JointIndex | jointId, | ||
ReferenceFrame | rf | ||
) |
Definition at line 33 of file expose-kinematics-derivatives.cpp.
bp::tuple pinocchio::python::getJointVelocityDerivatives_proxy | ( | const Model & | model, |
Data & | data, | ||
const Model::JointIndex | jointId, | ||
ReferenceFrame | rf | ||
) |
Definition at line 17 of file expose-kinematics-derivatives.cpp.
|
inline |
Helper to create or simply return an existing namespace in Python.
[in] | submodule_name | name of the submodule |
Definition at line 22 of file namespace.hpp.
|
static |
Definition at line 39 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 52 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 103 of file joints-models.hpp.
|
static |
Definition at line 109 of file joints-models.hpp.
|
static |
Definition at line 77 of file expose-com.cpp.
|
static |
Definition at line 89 of file expose-com.cpp.
Eigen::Matrix<typename Vector3Like::Scalar,3,3,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::python::Jexp3_proxy | ( | const Vector3Like & | v | ) |
Definition at line 25 of file bindings/python/spatial/explog.hpp.
MotionTpl<Scalar,Options>::Matrix6 pinocchio::python::Jexp6_proxy | ( | const MotionTpl< Scalar, Options > & | v | ) |
Definition at line 73 of file bindings/python/spatial/explog.hpp.
Eigen::Matrix<typename Vector6Like::Scalar,6,6,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options> pinocchio::python::Jexp6_proxy | ( | const Vector6Like & | vec6 | ) |
Definition at line 82 of file bindings/python/spatial/explog.hpp.
SE3Tpl<Scalar,Options>::Matrix6 pinocchio::python::Jlog6_proxy | ( | const SE3Tpl< Scalar, Options > & | M | ) |
Definition at line 64 of file bindings/python/spatial/explog.hpp.
Eigen::MatrixXd pinocchio::python::jointBodyRegressor_proxy | ( | const Model & | model, |
Data & | data, | ||
const JointIndex | jointId | ||
) |
Definition at line 18 of file expose-regressor.cpp.
Eigen::Matrix<typename Matrix3Like::Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::python::log3_proxy | ( | const Matrix3Like & | R | ) |
Definition at line 93 of file bindings/python/spatial/explog.hpp.
MotionTpl<typename Matrix4Like::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix4Like)::Options> pinocchio::python::log6_proxy | ( | const Matrix4Like & | homegenous_matrix | ) |
Definition at line 100 of file bindings/python/spatial/explog.hpp.
internal::function_wrapper<R (*)(Args...)> pinocchio::python::make_pybind11_function | ( | R(*)(Args...) | func | ) |
Creates a function wrapper.
Using function wrapper has the advantage of being copy-less when possible but the disadvantage of requiring to wrap the exposed function.
The wrapper does:
Definition at line 161 of file pybind11.hpp.
Eigen::Ref<Matrix> pinocchio::python::make_ref | ( | Eigen::PlainObjectBase< Matrix > & | mat | ) |
Definition at line 17 of file bindings/python/utils/eigen.hpp.
void pinocchio::python::make_symmetric | ( | Eigen::MatrixBase< Matrix > & | mat | ) |
Definition at line 24 of file bindings/python/utils/eigen.hpp.
CartesianProductOperationVariantTpl<double,0,LieGroupCollectionDefaultTpl> pinocchio::python::makeLieGroup | ( | ) |
Definition at line 20 of file expose-liegroups.cpp.
CartesianProductOperationVariantTpl<double,0,LieGroupCollectionDefaultTpl> pinocchio::python::makeRn | ( | int | n | ) |
Definition at line 26 of file expose-liegroups.cpp.
|
static |
Definition at line 15 of file algorithm/expose-joints.cpp.
typedef pinocchio::python::PINOCCHIO_ALIGNED_STD_VECTOR | ( | Force | ) |
pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix | ) | const |
Definition at line 31 of file bindings/python/utils/eigen.hpp.
pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix3Like | ) | const & |
Definition at line 33 of file bindings/python/spatial/explog.hpp.
pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix3Like | ) | const & |
|
static |
Definition at line 23 of file bindings/python/serialization/serialization.cpp.
|
static |
Definition at line 23 of file algorithm/expose-joints.cpp.
|
inline |
Definition at line 19 of file registration.hpp.
|
static |
Definition at line 22 of file bindings/python/algorithm/parallel/rnea.cpp.
|
static |
Definition at line 15 of file bindings/python/algorithm/parallel/rnea.cpp.
Eigen::Matrix3d pinocchio::python::rotate | ( | const std::string & | axis, |
const double | ang | ||
) |
Definition at line 19 of file expose-rpy.cpp.
std::string pinocchio::python::sanitizedClassname | ( | ) |
Definition at line 24 of file joints-variant.hpp.
Definition at line 19 of file conversions.cpp.
bp::tuple pinocchio::python::SE3ToXYZQUATtuple | ( | const SE3 & | M | ) |
Definition at line 27 of file conversions.cpp.
void pinocchio::python::serialize | ( | ) |
Definition at line 21 of file serialization.hpp.
Eigen::Matrix<typename Vector3::Scalar,3,3,Vector3::Options> pinocchio::python::skew | ( | const Vector3 & | v | ) |
Definition at line 18 of file expose-skew.cpp.
Eigen::Matrix<typename Vector3::Scalar,3,3,Vector3::Options> pinocchio::python::skewSquare | ( | const Vector3 & | u, |
const Vector3 & | v | ||
) |
Definition at line 25 of file expose-skew.cpp.
|
inline |
Definition at line 50 of file pybind11.hpp.
|
inline |
Definition at line 57 of file pybind11.hpp.
Eigen::Matrix<typename Matrix3::Scalar,3,1,Matrix3::Options> pinocchio::python::unSkew | ( | const Matrix3 & | mat | ) |
Definition at line 32 of file expose-skew.cpp.
SE3 pinocchio::python::XYZQUATToSE3_bp | ( | const TupleOrList & | v | ) |
Definition at line 36 of file conversions.cpp.
SE3 pinocchio::python::XYZQUATToSE3_ei | ( | const Vector7Like & | v | ) |
Definition at line 52 of file conversions.cpp.
return pinocchio::python::res |
Definition at line 46 of file bindings/python/spatial/explog.hpp.
const Vector3Like& pinocchio::python::v |
Definition at line 44 of file bindings/python/spatial/explog.hpp.
const std::string& pinocchio::python::xmlStream |
Definition at line 30 of file bindings/python/parsers/srdf.cpp.