#include <model.hpp>
Public Types | |
typedef Model::Data | Data |
typedef Model::Force | Force |
typedef Model::Frame | Frame |
typedef Model::FrameIndex | FrameIndex |
typedef Model::Index | Index |
typedef Model::IndexVector | IndexVector |
typedef Model::Inertia | Inertia |
typedef Model::JointIndex | JointIndex |
typedef Model::JointModel | JointModel |
typedef JointModel::JointModelVariant | JointModelVariant |
typedef Model::Motion | Motion |
typedef Model::Scalar | Scalar |
typedef Model::SE3 | SE3 |
typedef Model::VectorXs | VectorXs |
Public Member Functions | |
template<class PyClass > | |
void | visit (PyClass &cl) const |
Static Public Member Functions | |
static JointIndex | addJoint0 (Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name) |
static JointIndex | addJoint1 (Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config) |
static JointIndex | addJoint2 (Model &model, JointIndex parent_id, const JointModel &jmodel, const SE3 &joint_placement, const std::string &joint_name, const VectorXs &max_effort, const VectorXs &max_velocity, const VectorXs &min_config, const VectorXs &max_config, const VectorXs &friction, const VectorXs &damping) |
static Data | createData (const Model &model) |
static void | expose () |
template<typename T > | |
static Index | index (std::vector< T > const &x, typename std::vector< T >::value_type const &v) |
Provide equivalent to python list index function for vectors. More... | |
Definition at line 41 of file bindings/python/multibody/model.hpp.
typedef Model::Data pinocchio::python::ModelPythonVisitor< Model >::Data |
Definition at line 59 of file bindings/python/multibody/model.hpp.
typedef Model::Force pinocchio::python::ModelPythonVisitor< Model >::Force |
Definition at line 55 of file bindings/python/multibody/model.hpp.
typedef Model::Frame pinocchio::python::ModelPythonVisitor< Model >::Frame |
Definition at line 56 of file bindings/python/multibody/model.hpp.
typedef Model::FrameIndex pinocchio::python::ModelPythonVisitor< Model >::FrameIndex |
Definition at line 50 of file bindings/python/multibody/model.hpp.
typedef Model::Index pinocchio::python::ModelPythonVisitor< Model >::Index |
Definition at line 46 of file bindings/python/multibody/model.hpp.
typedef Model::IndexVector pinocchio::python::ModelPythonVisitor< Model >::IndexVector |
Definition at line 51 of file bindings/python/multibody/model.hpp.
typedef Model::Inertia pinocchio::python::ModelPythonVisitor< Model >::Inertia |
Definition at line 57 of file bindings/python/multibody/model.hpp.
typedef Model::JointIndex pinocchio::python::ModelPythonVisitor< Model >::JointIndex |
Definition at line 47 of file bindings/python/multibody/model.hpp.
typedef Model::JointModel pinocchio::python::ModelPythonVisitor< Model >::JointModel |
Definition at line 48 of file bindings/python/multibody/model.hpp.
typedef JointModel::JointModelVariant pinocchio::python::ModelPythonVisitor< Model >::JointModelVariant |
Definition at line 49 of file bindings/python/multibody/model.hpp.
typedef Model::Motion pinocchio::python::ModelPythonVisitor< Model >::Motion |
Definition at line 54 of file bindings/python/multibody/model.hpp.
typedef Model::Scalar pinocchio::python::ModelPythonVisitor< Model >::Scalar |
Definition at line 44 of file bindings/python/multibody/model.hpp.
typedef Model::SE3 pinocchio::python::ModelPythonVisitor< Model >::SE3 |
Definition at line 53 of file bindings/python/multibody/model.hpp.
typedef Model::VectorXs pinocchio::python::ModelPythonVisitor< Model >::VectorXs |
Definition at line 61 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Definition at line 237 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Definition at line 247 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Definition at line 263 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Definition at line 281 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Definition at line 311 of file bindings/python/multibody/model.hpp.
|
inlinestatic |
Provide equivalent to python list index function for vectors.
[in] | x | The input vector. |
[in] | v | The value of to look for in the vector. |
Definition at line 297 of file bindings/python/multibody/model.hpp.
|
inline |
Definition at line 66 of file bindings/python/multibody/model.hpp.