Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/).
- Add parsing of equality/connect tag for closed-loop chains for MJCF format ([#2413](https://github.com/stack-of-tasks/pinocchio/pull/2413))
- Add compatibility with NumPy 2 `__array__` API ([#2436](https://github.com/stack-of-tasks/pinocchio/pull/2436))
- Added argument to let users decide of root joint name when parsing models (urdf, mjcf, sdf) ([#2402](https://github.com/stack-of-tasks/pinocchio/pull/2402))
- Allow use of `pathlib.Path | str` for paths in python bindings ([#2431](https://github.com/stack-of-tasks/pinocchio/pull/2431))

### Fixed
- Fix linkage of Boost.Serialization on Windows ([#2400](https://github.com/stack-of-tasks/pinocchio/pull/2400))
Expand Down
13 changes: 7 additions & 6 deletions bindings/python/parsers/mjcf/geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "pinocchio/parsers/mjcf.hpp"
#include "pinocchio/bindings/python/parsers/mjcf.hpp"
#include "pinocchio/bindings/python/utils/path.hpp"

#include <boost/python.hpp>

Expand All @@ -15,29 +16,29 @@ namespace pinocchio
namespace bp = boost::python;

GeometryModel
buildGeomFromMJCF(Model & model, const std::string & filename, const GeometryType & type)
buildGeomFromMJCF(Model & model, const bp::object & filename, const GeometryType & type)
{
GeometryModel geometry_model;
::pinocchio::mjcf::buildGeom(model, filename, type, geometry_model);
::pinocchio::mjcf::buildGeom(model, path(filename), type, geometry_model);
return geometry_model;
}

GeometryModel buildGeomFromMJCF(
Model & model,
const std::string & filename,
const bp::object & filename,
const GeometryType & type,
::hpp::fcl::MeshLoaderPtr & meshLoader)
{
GeometryModel geometry_model;
::pinocchio::mjcf::buildGeom(model, filename, type, geometry_model, meshLoader);
::pinocchio::mjcf::buildGeom(model, path(filename), type, geometry_model, meshLoader);
return geometry_model;
}

void exposeMJCFGeom()
{
bp::def(
"buildGeomFromMJCF",
static_cast<GeometryModel (*)(Model &, const std::string &, const GeometryType &)>(
static_cast<GeometryModel (*)(Model &, const bp::object &, const GeometryType &)>(
pinocchio::python::buildGeomFromMJCF),
bp::args("model", "mjcf_filename", "geom_type"),
"Parse the Mjcf file given as input looking for the geometry of the given input model and\n"
Expand All @@ -52,7 +53,7 @@ namespace pinocchio
bp::def(
"buildGeomFromMJCF",
static_cast<GeometryModel (*)(
Model &, const std::string &, const GeometryType &, ::hpp::fcl::MeshLoaderPtr &)>(
Model &, const bp::object &, const GeometryType &, ::hpp::fcl::MeshLoaderPtr &)>(
pinocchio::python::buildGeomFromMJCF),
bp::args("model", "mjcf_filename", "geom_type", "mesh_loader"),
"Parse the Mjcf file given as input looking for the geometry of the given input model and\n"
Expand Down
20 changes: 11 additions & 9 deletions bindings/python/parsers/mjcf/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include "pinocchio/parsers/mjcf.hpp"
#include "pinocchio/bindings/python/parsers/mjcf.hpp"
#include "pinocchio/bindings/python/utils/path.hpp"

#include <boost/python.hpp>

Expand All @@ -14,49 +15,50 @@ namespace pinocchio

namespace bp = boost::python;

Model buildModelFromMJCF(const std::string & filename)
Model buildModelFromMJCF(const bp::object & filename)
{
Model model;
::pinocchio::mjcf::buildModel(filename, model);
::pinocchio::mjcf::buildModel(path(filename), model);
return model;
}

Model buildModelFromMJCF(const std::string & filename, const JointModel & root_joint)
Model buildModelFromMJCF(const bp::object & filename, const JointModel & root_joint)
{
Model model;
::pinocchio::mjcf::buildModel(filename, root_joint, model);
::pinocchio::mjcf::buildModel(path(filename), root_joint, model);
return model;
}

bp::tuple buildModelFromMJCF(
const std::string & filename,
const bp::object & filename,
const JointModel & root_joint,
const std::string & root_joint_name)
{
Model model;
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models;
::pinocchio::mjcf::buildModel(filename, root_joint, root_joint_name, model, contact_models);
::pinocchio::mjcf::buildModel(
path(filename), root_joint, root_joint_name, model, contact_models);
return bp::make_tuple(model, contact_models);
}

void exposeMJCFModel()
{
bp::def(
"buildModelFromMJCF",
static_cast<Model (*)(const std::string &)>(pinocchio::python::buildModelFromMJCF),
static_cast<Model (*)(const bp::object &)>(pinocchio::python::buildModelFromMJCF),
bp::args("mjcf_filename"),
"Parse the MJCF file given in input and return a pinocchio Model.");

bp::def(
"buildModelFromMJCF",
static_cast<Model (*)(const std::string &, const JointModel &)>(
static_cast<Model (*)(const bp::object &, const JointModel &)>(
pinocchio::python::buildModelFromMJCF),
bp::args("mjcf_filename", "root_joint"),
"Parse the MJCF file and return a pinocchio Model with the given root Joint.");

bp::def(
"buildModelFromMJCF",
static_cast<bp::tuple (*)(const std::string &, const JointModel &, const std::string &)>(
static_cast<bp::tuple (*)(const bp::object &, const JointModel &, const std::string &)>(
pinocchio::python::buildModelFromMJCF),
bp::args("mjcf_filename", "root_joint", "root_joint_name"),
"Parse the MJCF file and return a pinocchio Model with the given root Joint and its "
Expand Down
Loading