Namespaces | |
| context | |
| details | |
| helper | |
| internal | |
Typedefs | |
| typedef ContactCholeskyDecompositionTpl< context::Scalar, context::Options > | ContactCholeskyDecomposition |
| typedef Solver::PowerIterationAlgo | PowerIterationAlgo |
| typedef context::Scalar | Scalar |
| typedef ADMMContactSolverTpl< context::Scalar > | Solver |
| typedef Solver::SolverStats | SolverStats |
| template<class vector_type , bool NoProxy = false, bool EnableFromPythonListConverter = true, bool pickable = true> | |
| using | StdVectorPythonVisitor = eigenpy::StdVectorPythonVisitor< vector_type, NoProxy, EnableFromPythonListConverter, pickable > |
| typedef Eigen::Matrix< bool, Eigen::Dynamic, 1 > | VectorXb |
| typedef context::VectorXs | VectorXs |
Enumerations | |
| enum | { Options = context::Options } |
Functions | |
| template<typename BroadPhaseManager > | |
| void | _exposeBroadphaseAlgo () |
| 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 context::JointModelComposite & | addJoint_proxy (context::JointModelComposite &joint_composite, const context::JointModel &jmodel, const context::SE3 &joint_placement=context::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) |
| context::MatrixXs | bodyRegressor_proxy (const context::Motion &v, const context::Motion &a) |
| static void | buffer_copy (boost::asio::streambuf &dest, const boost::asio::streambuf &source) |
| GeometryModel | buildGeomFromMJCF (Model &model, const bp::object &filename, const GeometryType &type) |
| GeometryModel | buildGeomFromMJCF (Model &model, const bp::object &filename, const GeometryType &type, ::hpp::fcl::MeshLoaderPtr &meshLoader) |
| PINOCCHIO_PYTHON_PARSER_DLLAPI Model | buildModel (const std::string &filename, const std::string &var_name="model") |
| Load a model from a Python script. More... | |
| Model | buildModelFromMJCF (const bp::object &filename) |
| Model | buildModelFromMJCF (const bp::object &filename, const JointModel &root_joint) |
| bp::tuple | buildModelFromMJCF (const bp::object &filename, const JointModel &root_joint, const std::string &root_joint_name) |
| 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 (bool usingFF) |
| Model | buildSampleModelHumanoidRandom (bool usingFF, bool mimic) |
| Model | buildSampleModelManipulator (bool mimic) |
| static context::SE3::Vector3 | com_0_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, bool computeSubtreeComs=true) |
| static context::SE3::Vector3 | com_1_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, bool computeSubtreeComs=true) |
| static context::SE3::Vector3 | com_2_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a, bool computeSubtreeComs=true) |
| static const context::Data::Vector3 & | com_default_proxy (const context::Model &model, context::Data &data, bool computeSubtreeComs=true) |
| static const context::Data::Vector3 & | com_level_proxy (const context::Model &model, context::Data &data, KinematicLevel kinematic_level, bool computeSubtreeComs=true) |
| static context::Data::Matrix6x | compute_frame_jacobian_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, context::Data::FrameIndex frame_id) |
| static context::Data::Matrix6x | compute_frame_jacobian_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, context::Data::FrameIndex frame_id, ReferenceFrame reference_frame) |
| static context::Data::Matrix6x | compute_jacobian_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, JointIndex jointId) |
| bp::tuple | computeABADerivatives (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &tau) |
| bp::tuple | computeABADerivatives_fext (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &tau, const ForceAlignedVector &fext) |
| bp::tuple | computeABADerivatives_min (const context::Model &model, context::Data &data) |
| bp::tuple | computeABADerivatives_min_fext (const context::Model &model, context::Data &data, const ForceAlignedVector &fext) |
| static void | computeAllTerms_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v) |
| bp::tuple | computeCentroidalDynamicsDerivatives_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a) |
| template<typename BroadPhaseManager > | |
| VectorXb | computeCollisionsInParallel_1 (const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManager, double > &pool, const Eigen::MatrixBase< Eigen::MatrixXd > &q, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false) |
| template<typename BroadPhaseManager > | |
| std::vector< VectorXb > | computeCollisionsInParallel_2 (const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManager, double > &pool, const std::vector< Eigen::MatrixXd > &trajectories, const bool stopAtFirstCollisionInTrajectory=false) |
| static bool | computeCollisionsInParallel_full_proxy (const size_t num_threads, const Model &model, Data &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::VectorXd &q, const bool stopAtFirstCollision=false) |
| static VectorXb | computeCollisionsInParallel_pool_proxy (const int num_thread, GeometryPool &pool, const Eigen::MatrixXd &q, bool stopAtFirstCollisionInConfiguration=false, bool stopAtFirstCollisionInBatch=false) |
| static bool | computeCollisionsInParallel_proxy (const size_t num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false) |
| static context::VectorXs | computeComplementarityShift_wrapper (const context::CoulombFrictionConeVector &cones, const context::VectorXs &velocities) |
| static context::VectorXs | computeConeProjection_wrapper (const context::CoulombFrictionConeVector &cones, const context::VectorXs &forces) |
| bp::tuple | computeConstraintDynamicsDerivatives_proxy (const context::Model &model, context::Data &data, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const context::ProximalSettings &settings=context::ProximalSettings()) |
| static ConstRefVectorXs | computeContactImpulses_wrapper (const ModelTpl< Scalar, Options, JointCollectionDefaultTpl > &model, DataTpl< Scalar, Options, JointCollectionDefaultTpl > &data, const ConstRefVectorXs &c_ref, const context::RigidConstraintModelVector &contact_models, context::RigidConstraintDataVector &contact_datas, const context::CoulombFrictionConeVector &cones, const ConstRefVectorXs &R, const ConstRefVectorXs &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< ConstRefVectorXs > &lambda_guess=boost::none) |
| static const context::MatrixXs | computeDampedDelassusMatrixInverse_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const context::Scalar mu, const bool scaled=false) |
| static const context::MatrixXs | computeDelassusMatrix_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const context::Scalar mu=context::Scalar(0)) |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename ConfigVectorType > | |
| static std::size_t | computeDistances_proxy (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const GeometryModel &geom_model, GeometryData &geom_data, const Eigen::MatrixBase< ConfigVectorType > &q) |
| static context::VectorXs | computeDualConeProjection_wrapper (const context::CoulombFrictionConeVector &cones, const context::VectorXs &velocities) |
| context::Data::MatrixXs | computeGeneralizedGravityDerivatives (const context::Model &model, context::Data &data, const context::VectorXs &q) |
| static context::MatrixXs | computeKKTContactDynamicMatrixInverse_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::MatrixXs &J, const context::Scalar mu=context::Scalar(0)) |
| const context::Data::RowMatrixXs & | computeMinverse_min_proxy (const context::Model &model, context::Data &data) |
| const context::Data::RowMatrixXs & | computeMinverse_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q) |
| static context::Scalar | computePrimalFeasibility_wrapper (const context::CoulombFrictionConeVector &cones, const context::VectorXs &forces) |
| static context::Scalar | computeReprojectionError_wrapper (const context::CoulombFrictionConeVector &cones, const context::VectorXs &forces, const context::VectorXs &velocities) |
| bp::tuple | computeRNEADerivatives (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a) |
| bp::tuple | computeRNEADerivatives_fext (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a, const ForceAlignedVector &fext) |
| context::Data::MatrixXs | computeStaticTorqueDerivatives (const context::Model &model, context::Data &data, const context::VectorXs &q, const ForceAlignedVector &fext) |
| static const context::VectorXs | constraintDynamics_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &tau, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, context::ProximalSettings &prox_settings) |
| static const context::VectorXs | constraintDynamics_proxy_default (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &tau, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas) |
| static ConstRefVectorXs | contactInverseDynamics_wrapper (const ModelTpl< Scalar, Options, JointCollectionDefaultTpl > &model, DataTpl< Scalar, Options, JointCollectionDefaultTpl > &data, ConstRefVectorXs &q, ConstRefVectorXs &v, ConstRefVectorXs &a, Scalar dt, const context::RigidConstraintModelVector &contact_models, context::RigidConstraintDataVector &contact_datas, const context::CoulombFrictionConeVector &cones, ConstRefVectorXs &R, ConstRefVectorXs &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< ConstRefVectorXs > &lambda_guess=boost::none) |
| static context::MatrixXs | crba_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const Convention convention) |
| context::MatrixXs | dDifference_arg_proxy (const context::Model &model, const context::VectorXs &q1, const context::VectorXs &q2, const ArgumentPosition arg) |
| bp::tuple | dDifference_proxy (const context::Model &model, const context::VectorXs &q1, const context::VectorXs &q2) |
| template<typename T > | |
| py::object | default_arg (T t) |
| context::MatrixXs | dIntegrate_arg_proxy (const context::Model &model, const context::VectorXs &q, const context::VectorXs &v, const ArgumentPosition arg) |
| bp::tuple | dIntegrate_proxy (const context::Model &model, const context::VectorXs &q, const context::VectorXs &v) |
| context::MatrixXs | dIntegrateTransport_proxy (const context::Model &model, const context::VectorXs &q, const context::VectorXs &v, const context::MatrixXs &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 Vector3Like > | |
| Eigen::Matrix< typename Vector3Like::Scalar, 4, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | exp3_proxy_quat (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<typename Vector6Like > | |
| Eigen::Matrix< typename Vector6Like::Scalar, 7, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options > | exp6_proxy_quatvec (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_< JointDataHelicalUnaligned > & | expose_joint_data< JointDataHelicalUnaligned > (bp::class_< JointDataHelicalUnaligned > &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_< context::JointModelComposite > & | expose_joint_model< context::JointModelComposite > (bp::class_< context::JointModelComposite > &cl) |
| template<> | |
| bp::class_< context::JointModelHelicalUnaligned > & | expose_joint_model< context::JointModelHelicalUnaligned > (bp::class_< context::JointModelHelicalUnaligned > &cl) |
| template<> | |
| bp::class_< context::JointModelHX > & | expose_joint_model< context::JointModelHX > (bp::class_< context::JointModelHX > &cl) |
| template<> | |
| bp::class_< context::JointModelHY > & | expose_joint_model< context::JointModelHY > (bp::class_< context::JointModelHY > &cl) |
| template<> | |
| bp::class_< context::JointModelHZ > & | expose_joint_model< context::JointModelHZ > (bp::class_< context::JointModelHZ > &cl) |
| template<> | |
| bp::class_< context::JointModelMimic > & | expose_joint_model< context::JointModelMimic > (bp::class_< context::JointModelMimic > &cl) |
| template<> | |
| bp::class_< context::JointModelPrismaticUnaligned > & | expose_joint_model< context::JointModelPrismaticUnaligned > (bp::class_< context::JointModelPrismaticUnaligned > &cl) |
| template<> | |
| bp::class_< context::JointModelPX > & | expose_joint_model< context::JointModelPX > (bp::class_< context::JointModelPX > &cl) |
| template<> | |
| bp::class_< context::JointModelPY > & | expose_joint_model< context::JointModelPY > (bp::class_< context::JointModelPY > &cl) |
| template<> | |
| bp::class_< context::JointModelPZ > & | expose_joint_model< context::JointModelPZ > (bp::class_< context::JointModelPZ > &cl) |
| template<> | |
| bp::class_< context::JointModelRevoluteUnaligned > & | expose_joint_model< context::JointModelRevoluteUnaligned > (bp::class_< context::JointModelRevoluteUnaligned > &cl) |
| template<> | |
| bp::class_< context::JointModelRUBX > & | expose_joint_model< context::JointModelRUBX > (bp::class_< context::JointModelRUBX > &cl) |
| template<> | |
| bp::class_< context::JointModelRUBY > & | expose_joint_model< context::JointModelRUBY > (bp::class_< context::JointModelRUBY > &cl) |
| template<> | |
| bp::class_< context::JointModelRUBZ > & | expose_joint_model< context::JointModelRUBZ > (bp::class_< context::JointModelRUBZ > &cl) |
| template<> | |
| bp::class_< context::JointModelRX > & | expose_joint_model< context::JointModelRX > (bp::class_< context::JointModelRX > &cl) |
| template<> | |
| bp::class_< context::JointModelRY > & | expose_joint_model< context::JointModelRY > (bp::class_< context::JointModelRY > &cl) |
| template<> | |
| bp::class_< context::JointModelRZ > & | expose_joint_model< context::JointModelRZ > (bp::class_< context::JointModelRZ > &cl) |
| template<> | |
| bp::class_< context::JointModelUniversal > & | expose_joint_model< context::JointModelUniversal > (bp::class_< context::JointModelUniversal > &cl) |
| void | exposeABA () |
| void | exposeABADerivatives () |
| void | exposeADMMContactSolver () |
| void | exposeAlgorithms () |
| void | exposeBroadphase () |
| template<typename BroadPhaseManager > | |
| void | exposeBroadphaseAlgo () |
| void | exposeBroadphaseCallbacks () |
| template<typename BroadPhaseManager > | |
| void | exposeCase () |
| void | exposeCAT () |
| void | exposeCentroidal () |
| void | exposeCentroidalDerivatives () |
| void | exposeCholesky () |
| void | exposeClassicAcceleration () |
| void | exposeCollision () |
| void | exposeCOM () |
| void | exposeCones () |
| void | exposeConsoleBridge () |
| void | exposeConstraintDynamics () |
| void | exposeConstraintDynamicsDerivatives () |
| void | exposeContactDynamics () |
| void | exposeContactInverseDynamics () |
| void | exposeContactJacobian () |
| void | exposeContactSolvers () |
| void | exposeConversions () |
| void | exposeCRBA () |
| void | exposeData () |
| void | exposeDelassus () |
| void | exposeDependencies () |
| void | exposeEigenTypes () |
| void | exposeEnergy () |
| void | exposeExplog () |
| void | exposeExtras () |
| void | exposeFCL () |
| void | exposeForce () |
| void | exposeFrame () |
| void | exposeFramesAlgo () |
| void | exposeFramesDerivatives () |
| void | exposeGeometry () |
| void | exposeGeometryAlgo () |
| void | exposeImpulseDynamics () |
| void | exposeImpulseDynamicsDerivatives () |
| void | exposeInertia () |
| void | exposeJacobian () |
| void | exposeJoints () |
| void | exposeJointsAlgo () |
| void | exposeKinematicRegressor () |
| void | exposeKinematics () |
| void | exposeKinematicsDerivatives () |
| void | exposeLanczosDecomposition () |
| void | exposeLieGroups () |
| void | exposeLinalg () |
| void | exposeMJCFGeom () |
| void | exposeMJCFModel () |
| void | exposeMJCFParser () |
| void | exposeModel () |
| void | exposeModelAlgo () |
| void | exposeMotion () |
| void | exposeParallelABA () |
| void | exposeParallelAlgorithms () |
| void | exposeParallelBroadPhase () |
| void | exposeParallelCollision () |
| void | exposeParallelGeometry () |
| void | exposeParallelRNEA () |
| void | exposeParsers () |
| void | exposePGSContactSolver () |
| void | exposePool () |
| void | exposePoolCollision () |
| void | exposeReachableWorkspace () |
| void | exposeRegressor () |
| void | exposeRNEA () |
| void | exposeRNEADerivatives () |
| void | exposeRpy () |
| void | exposeSampleModels () |
| void | exposeSDFGeometry () |
| void | exposeSDFModel () |
| void | exposeSDFParser () |
| void | exposeSE3 () |
| void | exposeSerialization () |
| void | exposeSkew () |
| void | exposeSpecificTypeFeatures () |
| void | exposeSRDFParser () |
| void | exposeSymmetric3 () |
| void | exposeTridiagonalMatrix () |
| void | exposeURDFGeometry () |
| void | exposeURDFModel () |
| void | exposeURDFParser () |
| void | exposeVersion () |
| 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) |
| template<typename T , class Allocator > | |
| void | extract (const boost::python::list &list, std::vector< T, Allocator > &vec) |
| bp::tuple | findCommonAncestor_proxy (const context::Model &model, const JointIndex joint1_id, const JointIndex joint2_id) |
| static const context::VectorXs | forwardDynamics_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &tau, const context::MatrixXs &J, const context::VectorXs &gamma, const context::Scalar inv_damping=context::Scalar(0.0)) |
| static const context::VectorXs | forwardDynamics_proxy_no_q (const context::Model &model, context::Data &data, const context::VectorXs &tau, const context::MatrixXs &J, const context::VectorXs &gamma, const context::Scalar inv_damping=context::Scalar(0.0)) |
| static context::Data::Matrix6x | frame_jacobian_time_variation_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::Data::FrameIndex frame_id, const ReferenceFrame rf) |
| context::MatrixXs | frameBodyRegressor_proxy (const context::Model &model, context::Data &data, const FrameIndex frameId) |
| template<typename ReturnType > | |
| ReturnType & | from (py::handle model) |
| static context::Data::Motion | get_frame_acceleration_proxy1 (const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL) |
| static context::Data::Motion | get_frame_acceleration_proxy2 (const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL) |
| static context::Data::Motion | get_frame_classical_acceleration_proxy1 (const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL) |
| static context::Data::Motion | get_frame_classical_acceleration_proxy2 (const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL) |
| static context::Data::Matrix6x | get_frame_jacobian_proxy1 (const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL) |
| static context::Data::Matrix6x | get_frame_jacobian_proxy2 (const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL) |
| static context::Data::Matrix6x | get_frame_jacobian_time_variation_proxy (const context::Model &model, context::Data &data, context::Data::FrameIndex jointId, ReferenceFrame rf) |
| static context::Data::Motion | get_frame_velocity_proxy1 (const context::Model &model, context::Data &data, const context::Data::FrameIndex frame_id, ReferenceFrame rf=LOCAL) |
| static context::Data::Motion | get_frame_velocity_proxy2 (const context::Model &model, context::Data &data, const context::Data::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf=LOCAL) |
| static context::Data::Matrix6x | get_jacobian_proxy (const context::Model &model, context::Data &data, JointIndex jointId, ReferenceFrame rf) |
| static context::Data::Matrix3x | get_jacobian_subtree_com_proxy (const context::Model &model, context::Data &data, context::Model::JointIndex jointId) |
| static context::Data::Matrix6x | get_jacobian_time_variation_proxy (const context::Model &model, context::Data &data, JointIndex jointId, ReferenceFrame rf) |
| static context::Scalar | get_offset (context::JointModelMimic &jmodel) |
| static context::Scalar | get_scaling (context::JointModelMimic &jmodel) |
| bp::tuple | getCentroidalDynamicsDerivatives_proxy (const context::Model &model, context::Data &data) |
| context::Data::Matrix3x | getCoMVelocityDerivatives_proxy (const context::Model &model, context::Data &data) |
| static context::MatrixXs | getConstraintJacobian_proxy (const context::Model &model, const context::Data &data, const context::RigidConstraintModel &contact_model, context::RigidConstraintData &contact_data) |
| static context::MatrixXs | getConstraintsJacobian_proxy (const context::Model &model, const context::Data &data, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas) |
| std::string | getCurrentScopeName () |
| bp::tuple | getFrameAccelerationDerivatives_proxy1 (const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf) |
| bp::tuple | getFrameAccelerationDerivatives_proxy2 (const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf) |
| bp::tuple | getFrameVelocityDerivatives_proxy1 (const context::Model &model, context::Data &data, const context::Model::FrameIndex frame_id, ReferenceFrame rf) |
| bp::tuple | getFrameVelocityDerivatives_proxy2 (const context::Model &model, context::Data &data, const context::Model::JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf) |
| bp::tuple | getJointAccelerationDerivatives_proxy (const context::Model &model, context::Data &data, const JointIndex jointId, ReferenceFrame rf) |
| bp::tuple | getJointVelocityDerivatives_proxy (const context::Model &model, context::Data &data, const JointIndex jointId, ReferenceFrame rf) |
| static const context::MatrixXs | getKKTContactDynamicMatrixInverse_proxy (const context::Model &model, context::Data &data, const context::MatrixXs &J) |
| boost::python::object | getOrCreatePythonNamespace (const std::string &submodule_name) |
| Helper to create or simply return an existing namespace in Python. More... | |
| bp::tuple | getPointClassicAccelerationDerivatives_proxy (const context::Model &model, context::Data &data, const JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf) |
| bp::tuple | getPointVelocityDerivatives_proxy (const context::Model &model, context::Data &data, const JointIndex joint_id, const context::SE3 &placement, ReferenceFrame rf) |
| boost::python::object | getScalarType () |
| Hlog3 (M, v, res) | |
| static const context::VectorXs | impulseDynamics_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const context::Scalar r_coeff, const context::ProximalSettings &prox_settings) |
| static const context::VectorXs | impulseDynamics_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v_before, const context::MatrixXs &J, const context::Scalar r_coeff=context::Scalar(0.), const context::Scalar inv_damping=context::Scalar(0.)) |
| static const context::VectorXs | impulseDynamics_proxy_no_q (const context::Model &model, context::Data &data, const context::VectorXs &v_before, const context::MatrixXs &J, const context::Scalar r_coeff=context::Scalar(0.), const context::Scalar inv_damping=context::Scalar(0.)) |
| static void | impulseDynamicsDerivatives_proxy (const context::Model &model, context::Data &data, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const context::Scalar &r_coeff, const context::ProximalSettings &prox_settings) |
| static context::JointModelMimic * | init_proxy (const context::JointModel &jmodel, const context::Scalar &scaling, const context::Scalar &offset) |
| static context::JointModelComposite * | init_proxy1 (const context::JointModel &jmodel) |
| static context::JointModelComposite * | init_proxy2 (const context::JointModel &jmodel, const context::SE3 &joint_placement) |
| static context::Data::Matrix3x | jacobian_subtree_com_kinematics_proxy (const context::Model &model, context::Data &data, const context::VectorXs &q, context::Model::JointIndex jointId) |
| static context::Data::Matrix3x | jacobian_subtree_com_proxy (const context::Model &model, context::Data &data, context::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) |
| context::MatrixXs | jointBodyRegressor_proxy (const context::Model &model, context::Data &data, const JointIndex jointId) |
| void | loadReferenceConfigurations (Model &model, const bp::object &filename, const bool verbose=false) |
| void | loadReferenceConfigurationsFromXML (Model &model, const std::string &xmlStream, const bool verbose=false) |
| bool | loadRotorParameters (Model &model, const bp::object &filename, const bool verbose=false) |
| template<typename Matrix3Like > | |
| Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3_proxy (const Matrix3Like &R) |
| template<typename Matrix3Like , typename Matrix1Like > | |
| Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3_proxy (const Matrix3Like &R, Eigen::Ref< Matrix1Like > theta) |
| template<typename QuaternionLike > | |
| Eigen::Matrix< typename QuaternionLike::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(typename QuaternionLike::Vector3)::Options > | log3_proxy (const QuaternionLike &quat) |
| template<typename Matrix3Like , typename Scalar > | |
| Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | log3_proxy_fix (const Matrix3Like &R, Scalar &theta) |
| template<typename Vector4Like > | |
| Eigen::Matrix< typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options > | log3_proxy_quatvec (const Vector4Like &v) |
| template<typename Vector4Like , typename Matrix1Like > | |
| Eigen::Matrix< typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options > | log3_proxy_quatvec (const Vector4Like &v, Eigen::Ref< Matrix1Like > theta) |
| template<typename Vector4Like , typename _Scalar > | |
| Eigen::Matrix< typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options > | log3_proxy_quatvec_fix (const Vector4Like &v, _Scalar &theta) |
| template<typename Matrix4Like > | |
| MotionTpl< typename Matrix4Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix4Like)::Options > | log6_proxy (const Matrix4Like &homegenous_matrix) |
| template<typename Vector7Like > | |
| MotionTpl< typename Vector7Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector7Like)::Options > | log6_proxy_quatvec (const Vector7Like &q) |
| 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 (const Eigen::PlainObjectBase< Matrix > &mat) |
| template<typename Matrix > | |
| void | make_symmetric (const Eigen::MatrixBase< Matrix > &mat, const int mode=Eigen::Upper) |
| template<typename LgType > | |
| CartesianProductOperationVariantTpl< context::Scalar, context::Options, LieGroupCollectionDefaultTpl > | makeLieGroup () |
| CartesianProductOperationVariantTpl< context::Scalar, context::Options, LieGroupCollectionDefaultTpl > | makeRn (int n) |
| static context::VectorXs | normalize_proxy (const context::Model &model, const context::VectorXs &config) |
| std::string | path (const bp::object &path) |
| python pathlib.Path | str -> C++ std::string More... | |
| std::vector< std::string > | pathList (const bp::object &path_list) |
| python typing.List[pathlib.Path] | typing.List[str] -> C++ std::vector<std::string> More... | |
| typedef | PINOCCHIO_ALIGNED_STD_VECTOR (context::Force) ForceAlignedVector |
| template<typename Matrix > | |
| PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix) make_copy(const Eigen | |
| template<typename Matrix3Like , typename Vector3Like > | |
| PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3Like) Hlog3_proxy(const Matrix3Like &M | |
| template<typename Matrix3Like > | |
| PINOCCHIO_EIGEN_PLAIN_TYPE (Matrix3Like) Jlog3_proxy(const Matrix3Like &M) | |
| template<typename MatrixType > | |
| PINOCCHIO_EIGEN_PLAIN_TYPE (MatrixType) inv(const Eigen | |
| typedef | PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR (context::RigidConstraintData) RigidConstraintDataVector |
| typedef | PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR (context::RigidConstraintModel) RigidConstraintModelVector |
| static boost::asio::streambuf & | prepare_proxy (boost::asio::streambuf &self, const std::size_t n) |
| static context::VectorXs | randomConfiguration_proxy (const context::Model &model) |
| static context::Data::MatrixXs | reachableWorkspace_ (const context::Model &model, const context::VectorXs &q0, const double time_horizon, const int frame_id, const int n_samples=5, const int facet_dims=3) |
| bp::tuple | reachableWorkspaceHull_ (const context::Model &model, const context::VectorXs &q0, const double time_horizon, const int frame_id, const int n_samples=5, const int facet_dims=3) |
| template<typename T > | |
| bool | register_symbolic_link_to_registered_type () |
| void | removeCollisionPairs (const Model &model, GeometryModel &geom_model, const bp::object &filename, const bool verbose=false) |
| 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) |
| context::Matrix3s | rotate (const std::string &axis, const context::Scalar ang) |
| template<typename T > | |
| std::string | sanitizedClassname () |
| 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) |
| static PyObject * | tobytes (boost::asio::streambuf &self) |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
| ModelTpl< Scalar, Options, JointCollectionTpl > | transformJointIntoMimic_proxy (const ModelTpl< Scalar, Options, JointCollectionTpl > &input_model, const JointIndex &index_mimicked, const JointIndex &index_mimicking, const Scalar &scaling, const Scalar &offset) |
| template<typename Matrix3 > | |
| Eigen::Matrix< typename Matrix3::Scalar, 3, 1, Matrix3::Options > | unSkew (const Matrix3 &mat) |
| static PyObject * | view (boost::asio::streambuf &self) |
Variables | |
| const typedef Eigen::Ref< const VectorXs > | ConstRefVectorXs |
| ReturnType | res |
| const Vector3Like & | v |
| typedef ContactCholeskyDecompositionTpl<context::Scalar, context::Options> pinocchio::python::ContactCholeskyDecomposition |
Definition at line 33 of file admm-solver.cpp.
| typedef Solver::PowerIterationAlgo pinocchio::python::PowerIterationAlgo |
Definition at line 27 of file admm-solver.cpp.
Definition at line 29 of file admm-solver.cpp.
Definition at line 26 of file admm-solver.cpp.
| typedef Solver::SolverStats pinocchio::python::SolverStats |
Definition at line 28 of file admm-solver.cpp.
| using pinocchio::python::StdVectorPythonVisitor = typedef eigenpy:: StdVectorPythonVisitor<vector_type, NoProxy, EnableFromPythonListConverter, pickable> |
Definition at line 47 of file std-vector.hpp.
| typedef Eigen::Matrix< bool, Eigen::Dynamic, 1 > pinocchio::python::VectorXb |
Definition at line 28 of file bindings/python/collision/parallel/broadphase.cpp.
| typedef context::VectorXs pinocchio::python::VectorXs |
Definition at line 30 of file admm-solver.cpp.
| anonymous enum |
| Enumerator | |
|---|---|
| Options | |
Definition at line 22 of file expose-contact-inverse-dynamics.cpp.
| void pinocchio::python::_exposeBroadphaseAlgo | ( | ) |
Definition at line 27 of file expose-broadphase.cpp.
|
static |
Definition at line 26 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 294 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 17 of file algorithm/expose-model.cpp.
| context::MatrixXs pinocchio::python::bodyRegressor_proxy | ( | const context::Motion & | v, |
| const context::Motion & | a | ||
| ) |
Definition at line 15 of file expose-regressor.cpp.
|
static |
Definition at line 16 of file bindings/python/serialization/serialization.cpp.
| GeometryModel pinocchio::python::buildGeomFromMJCF | ( | Model & | model, |
| const bp::object & | filename, | ||
| const GeometryType & | type | ||
| ) |
Definition at line 19 of file bindings/python/parsers/mjcf/geometry.cpp.
| GeometryModel pinocchio::python::buildGeomFromMJCF | ( | Model & | model, |
| const bp::object & | filename, | ||
| const GeometryType & | type, | ||
| ::hpp::fcl::MeshLoaderPtr & | meshLoader | ||
| ) |
Definition at line 26 of file bindings/python/parsers/mjcf/geometry.cpp.
| 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 inconsistency in the Python code.
\input filename The full path to the model file. \input var_name Name of the Python variable which contains the model in the script.
Definition at line 23 of file src/parsers/python/model.cpp.
| Model pinocchio::python::buildModelFromMJCF | ( | const bp::object & | filename | ) |
Definition at line 18 of file bindings/python/parsers/mjcf/model.cpp.
| Model pinocchio::python::buildModelFromMJCF | ( | const bp::object & | filename, |
| const JointModel & | root_joint | ||
| ) |
Definition at line 25 of file bindings/python/parsers/mjcf/model.cpp.
| bp::tuple pinocchio::python::buildModelFromMJCF | ( | const bp::object & | filename, |
| const JointModel & | root_joint, | ||
| const std::string & | root_joint_name | ||
| ) |
Definition at line 32 of file bindings/python/parsers/mjcf/model.cpp.
| 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 39 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 61 of file algorithm/expose-model.cpp.
| Model pinocchio::python::buildSampleModelHumanoid | ( | bool | usingFF | ) |
Definition at line 38 of file bindings/python/multibody/sample-models.cpp.
| Model pinocchio::python::buildSampleModelHumanoidRandom | ( | bool | usingFF, |
| bool | mimic | ||
| ) |
Definition at line 15 of file bindings/python/multibody/sample-models.cpp.
| Model pinocchio::python::buildSampleModelManipulator | ( | bool | mimic | ) |
Definition at line 22 of file bindings/python/multibody/sample-models.cpp.
|
static |
Definition at line 17 of file expose-com.cpp.
|
static |
Definition at line 26 of file expose-com.cpp.
|
static |
Definition at line 36 of file expose-com.cpp.
|
static |
Definition at line 56 of file expose-com.cpp.
|
static |
Definition at line 47 of file expose-com.cpp.
|
static |
Definition at line 96 of file expose-frames.cpp.
|
static |
Definition at line 109 of file expose-frames.cpp.
|
static |
Definition at line 13 of file expose-jacobian.cpp.
| bp::tuple pinocchio::python::computeABADerivatives | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::VectorXs & | tau | ||
| ) |
Definition at line 21 of file expose-aba-derivatives.cpp.
| bp::tuple pinocchio::python::computeABADerivatives_fext | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::VectorXs & | tau, | ||
| const ForceAlignedVector & | fext | ||
| ) |
Definition at line 33 of file expose-aba-derivatives.cpp.
| bp::tuple pinocchio::python::computeABADerivatives_min | ( | const context::Model & | model, |
| context::Data & | data | ||
| ) |
Definition at line 46 of file expose-aba-derivatives.cpp.
| bp::tuple pinocchio::python::computeABADerivatives_min_fext | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const ForceAlignedVector & | fext | ||
| ) |
Definition at line 53 of file expose-aba-derivatives.cpp.
|
static |
Definition at line 13 of file expose-cat.cpp.
| bp::tuple pinocchio::python::computeCentroidalDynamicsDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::VectorXs & | a | ||
| ) |
Definition at line 16 of file expose-centroidal-derivatives.cpp.
| VectorXb pinocchio::python::computeCollisionsInParallel_1 | ( | const size_t | num_threads, |
| BroadPhaseManagerPoolBase< BroadPhaseManager, double > & | pool, | ||
| const Eigen::MatrixBase< Eigen::MatrixXd > & | q, | ||
| const bool | stopAtFirstCollisionInConfiguration = false, |
||
| const bool | stopAtFirstCollisionInBatch = false |
||
| ) |
Definition at line 31 of file bindings/python/collision/parallel/broadphase.cpp.
| std::vector<VectorXb> pinocchio::python::computeCollisionsInParallel_2 | ( | const size_t | num_threads, |
| BroadPhaseManagerPoolBase< BroadPhaseManager, double > & | pool, | ||
| const std::vector< Eigen::MatrixXd > & | trajectories, | ||
| const bool | stopAtFirstCollisionInTrajectory = false |
||
| ) |
Definition at line 46 of file bindings/python/collision/parallel/broadphase.cpp.
|
static |
Definition at line 29 of file bindings/python/collision/parallel/geometry.cpp.
|
static |
Definition at line 42 of file bindings/python/collision/parallel/geometry.cpp.
|
static |
Definition at line 20 of file bindings/python/collision/parallel/geometry.cpp.
|
static |
Definition at line 98 of file admm-solver.cpp.
|
static |
Definition at line 68 of file admm-solver.cpp.
| bp::tuple pinocchio::python::computeConstraintDynamicsDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const RigidConstraintModelVector & | contact_models, | ||
| RigidConstraintDataVector & | contact_datas, | ||
| const context::ProximalSettings & | settings = context::ProximalSettings() |
||
| ) |
Definition at line 23 of file expose-constrained-dynamics-derivatives.cpp.
|
static |
Definition at line 27 of file expose-contact-inverse-dynamics.cpp.
|
static |
Definition at line 39 of file expose-delassus.cpp.
|
static |
Definition at line 24 of file expose-delassus.cpp.
|
static |
Definition at line 25 of file expose-collision.cpp.
|
static |
Definition at line 76 of file admm-solver.cpp.
| context::Data::MatrixXs pinocchio::python::computeGeneralizedGravityDerivatives | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q | ||
| ) |
Definition at line 18 of file expose-rnea-derivatives.cpp.
|
static |
Definition at line 78 of file expose-contact-dynamics.cpp.
| const context::Data::RowMatrixXs& pinocchio::python::computeMinverse_min_proxy | ( | const context::Model & | model, |
| context::Data & | data | ||
| ) |
Definition at line 26 of file expose-aba.cpp.
| const context::Data::RowMatrixXs& pinocchio::python::computeMinverse_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q | ||
| ) |
Definition at line 17 of file expose-aba.cpp.
|
static |
Definition at line 84 of file admm-solver.cpp.
|
static |
Definition at line 90 of file admm-solver.cpp.
| bp::tuple pinocchio::python::computeRNEADerivatives | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::VectorXs & | a | ||
| ) |
Definition at line 39 of file expose-rnea-derivatives.cpp.
| bp::tuple pinocchio::python::computeRNEADerivatives_fext | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::VectorXs & | a, | ||
| const ForceAlignedVector & | fext | ||
| ) |
Definition at line 51 of file expose-rnea-derivatives.cpp.
| context::Data::MatrixXs pinocchio::python::computeStaticTorqueDerivatives | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::VectorXs & | q, | ||
| const ForceAlignedVector & | fext | ||
| ) |
Definition at line 27 of file expose-rnea-derivatives.cpp.
|
static |
Definition at line 28 of file expose-constrained-dynamics.cpp.
|
static |
Definition at line 42 of file expose-constrained-dynamics.cpp.
|
static |
Definition at line 44 of file expose-contact-inverse-dynamics.cpp.
|
static |
Definition at line 14 of file expose-crba.cpp.
| context::MatrixXs pinocchio::python::dDifference_arg_proxy | ( | const context::Model & | model, |
| const context::VectorXs & | q1, | ||
| const context::VectorXs & | q2, | ||
| const ArgumentPosition | arg | ||
| ) |
Definition at line 76 of file algorithm/expose-joints.cpp.
| bp::tuple pinocchio::python::dDifference_proxy | ( | const context::Model & | model, |
| const context::VectorXs & | q1, | ||
| const context::VectorXs & | q2 | ||
| ) |
Definition at line 64 of file algorithm/expose-joints.cpp.
| py::object pinocchio::python::default_arg | ( | T | t | ) |
Definition at line 193 of file pybind11.hpp.
| context::MatrixXs pinocchio::python::dIntegrate_arg_proxy | ( | const context::Model & | model, |
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const ArgumentPosition | arg | ||
| ) |
Definition at line 38 of file algorithm/expose-joints.cpp.
| bp::tuple pinocchio::python::dIntegrate_proxy | ( | const context::Model & | model, |
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v | ||
| ) |
Definition at line 26 of file algorithm/expose-joints.cpp.
| context::MatrixXs pinocchio::python::dIntegrateTransport_proxy | ( | const context::Model & | model, |
| const context::VectorXs & | q, | ||
| const context::VectorXs & | v, | ||
| const context::MatrixXs & | Jin, | ||
| const ArgumentPosition | arg | ||
| ) |
Definition at line 51 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 19 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Vector3Like::Scalar, 4, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::python::exp3_proxy_quat | ( | const Vector3Like & | v | ) |
Definition at line 27 of file bindings/python/spatial/explog.hpp.
| SE3Tpl<Scalar, Options> pinocchio::python::exp6_proxy | ( | const MotionTpl< Scalar, Options > & | v | ) |
Definition at line 74 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 81 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Vector6Like::Scalar, 7, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector6Like)::Options> pinocchio::python::exp6_proxy_quatvec | ( | const Vector6Like & | vec6 | ) |
Definition at line 89 of file bindings/python/spatial/explog.hpp.
|
inline |
Definition at line 16 of file joints-datas.hpp.
|
inline |
Definition at line 64 of file joints-datas.hpp.
|
inline |
Definition at line 42 of file joints-datas.hpp.
|
inline |
Definition at line 50 of file joints-datas.hpp.
|
inline |
Definition at line 33 of file joints-datas.hpp.
|
inline |
Definition at line 24 of file joints-datas.hpp.
|
inline |
Definition at line 57 of file joints-datas.hpp.
| bp::class_<T>& pinocchio::python::expose_joint_model | ( | bp::class_< T > & | cl | ) |
Definition at line 25 of file joints-models.hpp.
| bp::class_<context::JointModelComposite>& pinocchio::python::expose_joint_model< context::JointModelComposite > | ( | bp::class_< context::JointModelComposite > & | cl | ) |
Definition at line 334 of file joints-models.hpp.
| bp::class_<context::JointModelHelicalUnaligned>& pinocchio::python::expose_joint_model< context::JointModelHelicalUnaligned > | ( | bp::class_< context::JointModelHelicalUnaligned > & | cl | ) |
Definition at line 180 of file joints-models.hpp.
| bp::class_<context::JointModelHX>& pinocchio::python::expose_joint_model< context::JointModelHX > | ( | bp::class_< context::JointModelHX > & | cl | ) |
Definition at line 201 of file joints-models.hpp.
| bp::class_<context::JointModelHY>& pinocchio::python::expose_joint_model< context::JointModelHY > | ( | bp::class_< context::JointModelHY > & | cl | ) |
Definition at line 218 of file joints-models.hpp.
| bp::class_<context::JointModelHZ>& pinocchio::python::expose_joint_model< context::JointModelHZ > | ( | bp::class_< context::JointModelHZ > & | cl | ) |
Definition at line 235 of file joints-models.hpp.
| bp::class_<context::JointModelMimic>& pinocchio::python::expose_joint_model< context::JointModelMimic > | ( | bp::class_< context::JointModelMimic > & | cl | ) |
Definition at line 407 of file joints-models.hpp.
| bp::class_<context::JointModelPrismaticUnaligned>& pinocchio::python::expose_joint_model< context::JointModelPrismaticUnaligned > | ( | bp::class_< context::JointModelPrismaticUnaligned > & | cl | ) |
Definition at line 162 of file joints-models.hpp.
| bp::class_<context::JointModelPX>& pinocchio::python::expose_joint_model< context::JointModelPX > | ( | bp::class_< context::JointModelPX > & | cl | ) |
Definition at line 125 of file joints-models.hpp.
| bp::class_<context::JointModelPY>& pinocchio::python::expose_joint_model< context::JointModelPY > | ( | bp::class_< context::JointModelPY > & | cl | ) |
Definition at line 137 of file joints-models.hpp.
| bp::class_<context::JointModelPZ>& pinocchio::python::expose_joint_model< context::JointModelPZ > | ( | bp::class_< context::JointModelPZ > & | cl | ) |
Definition at line 149 of file joints-models.hpp.
| bp::class_<context::JointModelRevoluteUnaligned>& pinocchio::python::expose_joint_model< context::JointModelRevoluteUnaligned > | ( | bp::class_< context::JointModelRevoluteUnaligned > & | cl | ) |
Definition at line 70 of file joints-models.hpp.
| bp::class_<context::JointModelRUBX>& pinocchio::python::expose_joint_model< context::JointModelRUBX > | ( | bp::class_< context::JointModelRUBX > & | cl | ) |
Definition at line 88 of file joints-models.hpp.
| bp::class_<context::JointModelRUBY>& pinocchio::python::expose_joint_model< context::JointModelRUBY > | ( | bp::class_< context::JointModelRUBY > & | cl | ) |
Definition at line 100 of file joints-models.hpp.
| bp::class_<context::JointModelRUBZ>& pinocchio::python::expose_joint_model< context::JointModelRUBZ > | ( | bp::class_< context::JointModelRUBZ > & | cl | ) |
Definition at line 112 of file joints-models.hpp.
| bp::class_<context::JointModelRX>& pinocchio::python::expose_joint_model< context::JointModelRX > | ( | bp::class_< context::JointModelRX > & | cl | ) |
Definition at line 33 of file joints-models.hpp.
| bp::class_<context::JointModelRY>& pinocchio::python::expose_joint_model< context::JointModelRY > | ( | bp::class_< context::JointModelRY > & | cl | ) |
Definition at line 45 of file joints-models.hpp.
| bp::class_<context::JointModelRZ>& pinocchio::python::expose_joint_model< context::JointModelRZ > | ( | bp::class_< context::JointModelRZ > & | cl | ) |
Definition at line 57 of file joints-models.hpp.
| bp::class_<context::JointModelUniversal>& pinocchio::python::expose_joint_model< context::JointModelUniversal > | ( | bp::class_< context::JointModelUniversal > & | cl | ) |
Definition at line 253 of file joints-models.hpp.
| void pinocchio::python::exposeABA | ( | ) |
Definition at line 33 of file expose-aba.cpp.
| void pinocchio::python::exposeABADerivatives | ( | ) |
Definition at line 61 of file expose-aba-derivatives.cpp.
| void pinocchio::python::exposeADMMContactSolver | ( | ) |
Definition at line 107 of file admm-solver.cpp.
| void pinocchio::python::exposeAlgorithms | ( | ) |
Definition at line 12 of file expose-algorithms.cpp.
| void pinocchio::python::exposeBroadphase | ( | ) |
Definition at line 80 of file expose-broadphase.cpp.
| void pinocchio::python::exposeBroadphaseAlgo | ( | ) |
Definition at line 71 of file expose-broadphase.cpp.
| void pinocchio::python::exposeBroadphaseCallbacks | ( | ) |
Definition at line 70 of file expose-broadphase-callbacks.cpp.
| void pinocchio::python::exposeCase | ( | ) |
Definition at line 63 of file bindings/python/collision/parallel/broadphase.cpp.
| void pinocchio::python::exposeCAT | ( | ) |
Definition at line 25 of file expose-cat.cpp.
| void pinocchio::python::exposeCentroidal | ( | ) |
Definition at line 14 of file expose-centroidal.cpp.
| void pinocchio::python::exposeCentroidalDerivatives | ( | ) |
Definition at line 50 of file expose-centroidal-derivatives.cpp.
| void pinocchio::python::exposeCholesky | ( | ) |
Definition at line 16 of file expose-cholesky.cpp.
| void pinocchio::python::exposeClassicAcceleration | ( | ) |
Definition at line 14 of file bindings/python/spatial/classic-acceleration.hpp.
| void pinocchio::python::exposeCollision | ( | ) |
Definition at line 35 of file expose-collision.cpp.
| void pinocchio::python::exposeCOM | ( | ) |
Definition at line 95 of file expose-com.cpp.
| void pinocchio::python::exposeCones | ( | ) |
Definition at line 17 of file expose-cones.cpp.
| void pinocchio::python::exposeConsoleBridge | ( | ) |
Definition at line 17 of file console-bridge.cpp.
| void pinocchio::python::exposeConstraintDynamics | ( | ) |
Definition at line 54 of file expose-constrained-dynamics.cpp.
| void pinocchio::python::exposeConstraintDynamicsDerivatives | ( | ) |
Definition at line 39 of file expose-constrained-dynamics-derivatives.cpp.
| void pinocchio::python::exposeContactDynamics | ( | ) |
Definition at line 103 of file expose-contact-dynamics.cpp.
| void pinocchio::python::exposeContactInverseDynamics | ( | ) |
Definition at line 65 of file expose-contact-inverse-dynamics.cpp.
| void pinocchio::python::exposeContactJacobian | ( | ) |
Definition at line 48 of file expose-contact-jacobian.cpp.
| void pinocchio::python::exposeContactSolvers | ( | ) |
Definition at line 16 of file expose-contact-solvers.cpp.
| void pinocchio::python::exposeConversions | ( | ) |
Definition at line 122 of file conversions.cpp.
| void pinocchio::python::exposeCRBA | ( | ) |
Definition at line 26 of file expose-crba.cpp.
| void pinocchio::python::exposeData | ( | ) |
Definition at line 13 of file expose-data.cpp.
| void pinocchio::python::exposeDelassus | ( | ) |
Definition at line 56 of file expose-delassus.cpp.
| void pinocchio::python::exposeDependencies | ( | ) |
Definition at line 14 of file dependencies.cpp.
| void pinocchio::python::exposeEigenTypes | ( | ) |
Definition at line 55 of file expose-eigen-types.cpp.
| void pinocchio::python::exposeEnergy | ( | ) |
Definition at line 15 of file expose-energy.cpp.
| void pinocchio::python::exposeExplog | ( | ) |
Definition at line 17 of file expose-explog.cpp.
| void pinocchio::python::exposeExtras | ( | ) |
Definition at line 12 of file expose-extras.cpp.
| void pinocchio::python::exposeFCL | ( | ) |
Definition at line 19 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 150 of file expose-frames.cpp.
| void pinocchio::python::exposeFramesDerivatives | ( | ) |
Definition at line 91 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::exposeImpulseDynamics | ( | ) |
Definition at line 39 of file expose-impulse-dynamics.cpp.
| void pinocchio::python::exposeImpulseDynamicsDerivatives | ( | ) |
Definition at line 36 of file expose-impulse-dynamics-derivatives.cpp.
| void pinocchio::python::exposeInertia | ( | ) |
Definition at line 18 of file expose-inertia.cpp.
| void pinocchio::python::exposeJacobian | ( | ) |
Definition at line 46 of file expose-jacobian.cpp.
| void pinocchio::python::exposeJoints | ( | ) |
Definition at line 18 of file multibody/joint/expose-joints.cpp.
| void pinocchio::python::exposeJointsAlgo | ( | ) |
Definition at line 89 of file algorithm/expose-joints.cpp.
| void pinocchio::python::exposeKinematicRegressor | ( | ) |
Definition at line 14 of file expose-kinematic-regressor.cpp.
| void pinocchio::python::exposeKinematics | ( | ) |
Definition at line 13 of file expose-kinematics.cpp.
| void pinocchio::python::exposeKinematicsDerivatives | ( | ) |
Definition at line 100 of file expose-kinematics-derivatives.cpp.
| void pinocchio::python::exposeLanczosDecomposition | ( | ) |
Definition at line 14 of file expose-lanczos-decomposition.cpp.
| void pinocchio::python::exposeLieGroups | ( | ) |
Definition at line 41 of file expose-liegroups.cpp.
| void pinocchio::python::exposeLinalg | ( | ) |
Definition at line 25 of file expose-linalg.cpp.
| void pinocchio::python::exposeMJCFGeom | ( | ) |
Definition at line 37 of file bindings/python/parsers/mjcf/geometry.cpp.
| void pinocchio::python::exposeMJCFModel | ( | ) |
Definition at line 44 of file bindings/python/parsers/mjcf/model.cpp.
|
inline |
Definition at line 15 of file bindings/python/parsers/mjcf.hpp.
| void pinocchio::python::exposeModel | ( | ) |
Definition at line 13 of file multibody/expose-model.cpp.
| void pinocchio::python::exposeModelAlgo | ( | ) |
Definition at line 102 of file algorithm/expose-model.cpp.
| void pinocchio::python::exposeMotion | ( | ) |
Definition at line 19 of file expose-motion.cpp.
| void pinocchio::python::exposeParallelABA | ( | ) |
Definition at line 38 of file bindings/python/algorithm/parallel/aba.cpp.
| void pinocchio::python::exposeParallelAlgorithms | ( | ) |
Definition at line 17 of file algorithm/parallel/expose-parallel.cpp.
| void pinocchio::python::exposeParallelBroadPhase | ( | ) |
Definition at line 94 of file bindings/python/collision/parallel/broadphase.cpp.
| void pinocchio::python::exposeParallelCollision | ( | ) |
Definition at line 17 of file collision/parallel/expose-parallel.cpp.
| void pinocchio::python::exposeParallelGeometry | ( | ) |
Definition at line 55 of file bindings/python/collision/parallel/geometry.cpp.
| void pinocchio::python::exposeParallelRNEA | ( | ) |
Definition at line 38 of file bindings/python/algorithm/parallel/rnea.cpp.
| void pinocchio::python::exposeParsers | ( | ) |
Definition at line 15 of file expose-parsers.cpp.
| void pinocchio::python::exposePGSContactSolver | ( | ) |
Definition at line 34 of file pgs-solver.cpp.
| void pinocchio::python::exposePool | ( | ) |
Definition at line 13 of file multibody/pool/expose-pool.cpp.
| void pinocchio::python::exposePoolCollision | ( | ) |
Definition at line 25 of file collision/pool/expose-pool.cpp.
| void pinocchio::python::exposeReachableWorkspace | ( | ) |
Definition at line 95 of file expose-reachable-workspace.cpp.
| void pinocchio::python::exposeRegressor | ( | ) |
Definition at line 32 of file expose-regressor.cpp.
| void pinocchio::python::exposeRNEA | ( | ) |
Definition at line 13 of file expose-rnea.cpp.
| void pinocchio::python::exposeRNEADerivatives | ( | ) |
Definition at line 64 of file expose-rnea-derivatives.cpp.
| void pinocchio::python::exposeRpy | ( | ) |
Definition at line 41 of file expose-rpy.cpp.
| void pinocchio::python::exposeSampleModels | ( | ) |
Definition at line 54 of file bindings/python/multibody/sample-models.cpp.
| void pinocchio::python::exposeSDFGeometry | ( | ) |
Definition at line 175 of file bindings/python/parsers/sdf/geometry.cpp.
| void pinocchio::python::exposeSDFModel | ( | ) |
Definition at line 63 of file bindings/python/parsers/sdf/model.cpp.
|
inline |
Definition at line 15 of file bindings/python/parsers/sdf.hpp.
| void pinocchio::python::exposeSE3 | ( | ) |
Definition at line 18 of file expose-SE3.cpp.
| void pinocchio::python::exposeSerialization | ( | ) |
Definition at line 43 of file bindings/python/serialization/serialization.cpp.
| void pinocchio::python::exposeSkew | ( | ) |
Definition at line 41 of file expose-skew.cpp.
|
inline |
Definition at line 14 of file boost_number.cpp.
| void pinocchio::python::exposeSRDFParser | ( | ) |
Definition at line 45 of file bindings/python/parsers/srdf.cpp.
| void pinocchio::python::exposeSymmetric3 | ( | ) |
Definition at line 18 of file expose-symmetric3.cpp.
| void pinocchio::python::exposeTridiagonalMatrix | ( | ) |
Definition at line 14 of file expose-tridiagonal-matrix.cpp.
| void pinocchio::python::exposeURDFGeometry | ( | ) |
Definition at line 210 of file bindings/python/parsers/urdf/geometry.cpp.
| void pinocchio::python::exposeURDFModel | ( | ) |
Definition at line 128 of file bindings/python/parsers/urdf/model.cpp.
|
inline |
Definition at line 16 of file bindings/python/parsers/urdf.hpp.
| void pinocchio::python::exposeVersion | ( | ) |
Definition at line 18 of file bindings/python/utils/version.cpp.
| 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 | ) |
| void pinocchio::python::extract | ( | const boost::python::list & | list, |
| std::vector< T, Allocator > & | vec | ||
| ) |
| bp::tuple pinocchio::python::findCommonAncestor_proxy | ( | const context::Model & | model, |
| const JointIndex | joint1_id, | ||
| const JointIndex | joint2_id | ||
| ) |
Definition at line 77 of file algorithm/expose-model.cpp.
|
static |
Definition at line 15 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 32 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 136 of file expose-frames.cpp.
| context::MatrixXs pinocchio::python::frameBodyRegressor_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const FrameIndex | frameId | ||
| ) |
Definition at line 26 of file expose-regressor.cpp.
|
inline |
Definition at line 70 of file pybind11.hpp.
|
static |
Definition at line 58 of file expose-frames.cpp.
|
static |
Definition at line 67 of file expose-frames.cpp.
|
static |
Definition at line 77 of file expose-frames.cpp.
|
static |
Definition at line 86 of file expose-frames.cpp.
|
static |
Definition at line 13 of file expose-frames.cpp.
|
static |
Definition at line 26 of file expose-frames.cpp.
|
static |
Definition at line 123 of file expose-frames.cpp.
|
static |
Definition at line 39 of file expose-frames.cpp.
|
static |
Definition at line 48 of file expose-frames.cpp.
|
static |
Definition at line 26 of file expose-jacobian.cpp.
|
static |
Definition at line 85 of file expose-com.cpp.
|
static |
Definition at line 36 of file expose-jacobian.cpp.
|
static |
Definition at line 400 of file joints-models.hpp.
|
static |
Definition at line 395 of file joints-models.hpp.
| bp::tuple pinocchio::python::getCentroidalDynamicsDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data | ||
| ) |
Definition at line 36 of file expose-centroidal-derivatives.cpp.
| context::Data::Matrix3x pinocchio::python::getCoMVelocityDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data | ||
| ) |
Definition at line 92 of file expose-kinematics-derivatives.cpp.
|
static |
Definition at line 23 of file expose-contact-jacobian.cpp.
|
static |
Definition at line 35 of file expose-contact-jacobian.cpp.
|
inline |
| bp::tuple pinocchio::python::getFrameAccelerationDerivatives_proxy1 | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::Model::FrameIndex | frame_id, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 51 of file expose-frames-derivatives.cpp.
| bp::tuple pinocchio::python::getFrameAccelerationDerivatives_proxy2 | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::Model::JointIndex | joint_id, | ||
| const context::SE3 & | placement, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 70 of file expose-frames-derivatives.cpp.
| bp::tuple pinocchio::python::getFrameVelocityDerivatives_proxy1 | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::Model::FrameIndex | frame_id, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 18 of file expose-frames-derivatives.cpp.
| bp::tuple pinocchio::python::getFrameVelocityDerivatives_proxy2 | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const context::Model::JointIndex | joint_id, | ||
| const context::SE3 & | placement, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 34 of file expose-frames-derivatives.cpp.
| bp::tuple pinocchio::python::getJointAccelerationDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const JointIndex | jointId, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 51 of file expose-kinematics-derivatives.cpp.
| bp::tuple pinocchio::python::getJointVelocityDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const JointIndex | jointId, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 18 of file expose-kinematics-derivatives.cpp.
|
static |
Definition at line 90 of file expose-contact-dynamics.cpp.
|
inline |
Helper to create or simply return an existing namespace in Python.
| [in] | submodule_name | name of the submodule |
Definition at line 34 of file namespace.hpp.
| bp::tuple pinocchio::python::getPointClassicAccelerationDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const JointIndex | joint_id, | ||
| const context::SE3 & | placement, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 70 of file expose-kinematics-derivatives.cpp.
| bp::tuple pinocchio::python::getPointVelocityDerivatives_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const JointIndex | joint_id, | ||
| const context::SE3 & | placement, | ||
| ReferenceFrame | rf | ||
| ) |
Definition at line 34 of file expose-kinematics-derivatives.cpp.
|
inline |
Definition at line 19 of file boost_number.cpp.
|
static |
Definition at line 24 of file expose-impulse-dynamics.cpp.
|
static |
Definition at line 47 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 63 of file expose-contact-dynamics.cpp.
|
static |
Definition at line 23 of file expose-impulse-dynamics-derivatives.cpp.
|
static |
Definition at line 387 of file joints-models.hpp.
|
static |
Definition at line 320 of file joints-models.hpp.
|
static |
Definition at line 327 of file joints-models.hpp.
|
static |
Definition at line 62 of file expose-com.cpp.
|
static |
Definition at line 75 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 44 of file bindings/python/spatial/explog.hpp.
| MotionTpl<Scalar, Options>::Matrix6 pinocchio::python::Jexp6_proxy | ( | const MotionTpl< Scalar, Options > & | v | ) |
Definition at line 105 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 116 of file bindings/python/spatial/explog.hpp.
| SE3Tpl<Scalar, Options>::Matrix6 pinocchio::python::Jlog6_proxy | ( | const SE3Tpl< Scalar, Options > & | M | ) |
Definition at line 96 of file bindings/python/spatial/explog.hpp.
| context::MatrixXs pinocchio::python::jointBodyRegressor_proxy | ( | const context::Model & | model, |
| context::Data & | data, | ||
| const JointIndex | jointId | ||
| ) |
Definition at line 20 of file expose-regressor.cpp.
| void pinocchio::python::loadReferenceConfigurations | ( | Model & | model, |
| const bp::object & | filename, | ||
| const bool | verbose = false |
||
| ) |
Definition at line 27 of file bindings/python/parsers/srdf.cpp.
| void pinocchio::python::loadReferenceConfigurationsFromXML | ( | Model & | model, |
| const std::string & | xmlStream, | ||
| const bool | verbose = false |
||
| ) |
Definition at line 33 of file bindings/python/parsers/srdf.cpp.
| bool pinocchio::python::loadRotorParameters | ( | Model & | model, |
| const bp::object & | filename, | ||
| const bool | verbose = false |
||
| ) |
Definition at line 40 of file bindings/python/parsers/srdf.cpp.
| Eigen:: Matrix<typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::python::log3_proxy | ( | const Matrix3Like & | R | ) |
Definition at line 129 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::python::log3_proxy | ( | const Matrix3Like & | R, |
| Eigen::Ref< Matrix1Like > | theta | ||
| ) |
Definition at line 137 of file bindings/python/spatial/explog.hpp.
| Eigen::Matrix< typename QuaternionLike::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(typename QuaternionLike::Vector3)::Options> pinocchio::python::log3_proxy | ( | const QuaternionLike & | quat | ) |
Definition at line 156 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::python::log3_proxy_fix | ( | const Matrix3Like & | R, |
| Scalar & | theta | ||
| ) |
Definition at line 145 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options> pinocchio::python::log3_proxy_quatvec | ( | const Vector4Like & | v | ) |
Definition at line 164 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options> pinocchio::python::log3_proxy_quatvec | ( | const Vector4Like & | v, |
| Eigen::Ref< Matrix1Like > | theta | ||
| ) |
Definition at line 180 of file bindings/python/spatial/explog.hpp.
| Eigen:: Matrix<typename Vector4Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector4Like)::Options> pinocchio::python::log3_proxy_quatvec_fix | ( | const Vector4Like & | v, |
| _Scalar & | theta | ||
| ) |
Definition at line 197 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 213 of file bindings/python/spatial/explog.hpp.
| MotionTpl<typename Vector7Like::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector7Like)::Options> pinocchio::python::log6_proxy_quatvec | ( | const Vector7Like & | q | ) |
Definition at line 220 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 185 of file pybind11.hpp.
| Eigen::Ref<Matrix> pinocchio::python::make_ref | ( | const Eigen::PlainObjectBase< Matrix > & | mat | ) |
Definition at line 17 of file bindings/python/utils/eigen.hpp.
| void pinocchio::python::make_symmetric | ( | const Eigen::MatrixBase< Matrix > & | mat, |
| const int | mode = Eigen::Upper |
||
| ) |
Definition at line 24 of file bindings/python/utils/eigen.hpp.
| CartesianProductOperationVariantTpl< context::Scalar, context::Options, LieGroupCollectionDefaultTpl> pinocchio::python::makeLieGroup | ( | ) |
Definition at line 23 of file expose-liegroups.cpp.
| CartesianProductOperationVariantTpl< context::Scalar, context::Options, LieGroupCollectionDefaultTpl> pinocchio::python::makeRn | ( | int | n | ) |
Definition at line 33 of file expose-liegroups.cpp.
|
static |
Definition at line 14 of file algorithm/expose-joints.cpp.
| std::string pinocchio::python::path | ( | const bp::object & | path | ) |
| std::vector< std::string > pinocchio::python::pathList | ( | const bp::object & | path_list | ) |
| typedef pinocchio::python::PINOCCHIO_ALIGNED_STD_VECTOR | ( | context::Force | ) |
| pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix | ) | const |
Definition at line 39 of file bindings/python/utils/eigen.hpp.
| pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix3Like | ) | const & |
| pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Matrix3Like | ) | const & |
Definition at line 55 of file bindings/python/spatial/explog.hpp.
| pinocchio::python::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | MatrixType | ) | const |
Definition at line 18 of file expose-linalg.cpp.
| typedef pinocchio::python::PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR | ( | context::RigidConstraintData | ) |
| typedef pinocchio::python::PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR | ( | context::RigidConstraintModel | ) |
|
static |
Definition at line 24 of file bindings/python/serialization/serialization.cpp.
|
static |
Definition at line 21 of file algorithm/expose-joints.cpp.
|
static |
Definition at line 35 of file expose-reachable-workspace.cpp.
| bp::tuple pinocchio::python::reachableWorkspaceHull_ | ( | const context::Model & | model, |
| const context::VectorXs & | q0, | ||
| const double | time_horizon, | ||
| const int | frame_id, | ||
| const int | n_samples = 5, |
||
| const int | facet_dims = 3 |
||
| ) |
Definition at line 18 of file expose-reachable-workspace.cpp.
|
inline |
Definition at line 16 of file registration.hpp.
| void pinocchio::python::removeCollisionPairs | ( | const Model & | model, |
| GeometryModel & | geom_model, | ||
| const bp::object & | filename, | ||
| const bool | verbose = false |
||
| ) |
Definition at line 18 of file bindings/python/parsers/srdf.cpp.
|
static |
Definition at line 26 of file bindings/python/algorithm/parallel/rnea.cpp.
|
static |
Definition at line 15 of file bindings/python/algorithm/parallel/rnea.cpp.
| context::Matrix3s pinocchio::python::rotate | ( | const std::string & | axis, |
| const context::Scalar | ang | ||
| ) |
Definition at line 15 of file expose-rpy.cpp.
| std::string pinocchio::python::sanitizedClassname | ( | ) |
Definition at line 24 of file joints-variant.hpp.
| 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 19 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 28 of file expose-skew.cpp.
|
inline |
Definition at line 52 of file pybind11.hpp.
|
inline |
Definition at line 60 of file pybind11.hpp.
|
static |
Definition at line 38 of file bindings/python/serialization/serialization.cpp.
| ModelTpl<Scalar, Options, JointCollectionTpl> pinocchio::python::transformJointIntoMimic_proxy | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | input_model, |
| const JointIndex & | index_mimicked, | ||
| const JointIndex & | index_mimicking, | ||
| const Scalar & | scaling, | ||
| const Scalar & | offset | ||
| ) |
Definition at line 87 of file algorithm/expose-model.cpp.
| Eigen::Matrix<typename Matrix3::Scalar, 3, 1, Matrix3::Options> pinocchio::python::unSkew | ( | const Matrix3 & | mat | ) |
Definition at line 36 of file expose-skew.cpp.
|
static |
Definition at line 30 of file bindings/python/serialization/serialization.cpp.
| const typedef Eigen::Ref< const VectorXs > pinocchio::python::ConstRefVectorXs |
Definition at line 31 of file admm-solver.cpp.
| return pinocchio::python::res |
Definition at line 68 of file bindings/python/spatial/explog.hpp.
| const Vector3Like& pinocchio::python::v |
Definition at line 66 of file bindings/python/spatial/explog.hpp.