Skip to content
Open
Show file tree
Hide file tree
Changes from 1 commit
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 bindings/pydairlib/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ pybind_py_library(
cc_deps = [
"//multibody:multipose_visualizer",
"//multibody:utils",
"//multibody:visualization_utils",
"@drake//:drake_shared_library",
],
cc_so_name = "multibody",
Expand Down
20 changes: 17 additions & 3 deletions bindings/pydairlib/multibody/multibody_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

#include "multibody/multibody_utils.h"
#include "multibody/multipose_visualizer.h"
#include "multibody/visualization_utils.h"

namespace py = pybind11;

Expand All @@ -22,12 +23,18 @@ PYBIND11_MODULE(multibody, m) {
.def(py::init<std::string, int, std::string>())
.def(py::init<std::string, int, double, std::string>())
.def(py::init<std::string, int, Eigen::VectorXd, std::string>())
.def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses"));
.def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses"))
.def("GetMeshcat", &MultiposeVisualizer::GetMeshcat);

m.def("ConnectTrajectoryVisualizer",
&dairlib::multibody::ConnectTrajectoryVisualizer, py::arg("plant"),
py::arg("builder"), py::arg("scene_graph"), py::arg("trajectory"));

m.def("MakeNameToPositionsMap",
&dairlib::multibody::MakeNameToPositionsMap<double>, py::arg("plant"))
py::overload_cast<const drake::multibody::MultibodyPlant<double>&>(&dairlib::multibody::MakeNameToPositionsMap<double>),
py::arg("plant"))
.def("MakeNameToVelocitiesMap",
&dairlib::multibody::MakeNameToVelocitiesMap<double>,
py::overload_cast<const drake::multibody::MultibodyPlant<double>&>(&dairlib::multibody::MakeNameToVelocitiesMap<double>),
py::arg("plant"))
.def("MakeNameToActuatorsMap",
&dairlib::multibody::MakeNameToActuatorsMap<double>,
Expand All @@ -38,10 +45,17 @@ PYBIND11_MODULE(multibody, m) {
.def("CreateActuatorNameVectorFromMap",
&dairlib::multibody::CreateActuatorNameVectorFromMap<double>,
py::arg("plant"))
.def("CreateWithSpringsToWithoutSpringsMapPos",
&dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos<double>,
py::arg("plant_w_spr"), py::arg("plant_wo_spr"))
.def("CreateWithSpringsToWithoutSpringsMapVel",
&dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel<double>,
py::arg("plant_w_spr"), py::arg("plant_wo_spr"))
.def("AddFlatTerrain", &dairlib::multibody::AddFlatTerrain<double>,
py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"),
py::arg("mu_kinetic"),
py::arg("normal_W") = Eigen::Vector3d(0, 0, 1),
py::arg("stiffness") = 0, py::arg("dissipation_rate") = 0,
py::arg("show_ground") = 1);
}

Expand Down
35 changes: 27 additions & 8 deletions bindings/pydairlib/systems/robot_lcm_systems_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
#include "drake/multibody/plant/multibody_plant.h"

namespace py = pybind11;
using py_rvp = py::return_value_policy;

namespace dairlib {
namespace pydairlib {
Expand All @@ -18,32 +17,52 @@ PYBIND11_MODULE(robot_lcm_systems, m) {

using drake::multibody::MultibodyPlant;
using systems::RobotOutputSender;
using py_rvp = py::return_value_policy;

py::class_<systems::RobotOutputReceiver, drake::systems::LeafSystem<double>>(
m, "RobotOutputReceiver")
.def(py::init<const MultibodyPlant<double>&>());
.def(py::init<const MultibodyPlant<double>&>())
.def(py::init<const MultibodyPlant<double>&,
drake::multibody::ModelInstanceIndex>());
py::class_<systems::RobotInputReceiver, drake::systems::LeafSystem<double>>(
m, "RobotInputReceiver")
.def(py::init<const MultibodyPlant<double>&>());
py::class_<RobotOutputSender, drake::systems::LeafSystem<double>>(
m, "RobotOutputSender")
.def(py::init<const MultibodyPlant<double>&, bool>())
.def(py::init<const MultibodyPlant<double>&, bool, bool>())
.def(py::init<const MultibodyPlant<double>&,
drake::multibody::ModelInstanceIndex,
bool, bool>())
.def("get_input_port_state", &RobotOutputSender::get_input_port_state,
py_rvp::reference_internal)
py_rvp::reference_internal)
.def("get_input_port_effort", &RobotOutputSender::get_input_port_effort,
py_rvp::reference_internal)
py_rvp::reference_internal)
.def("get_input_port_imu", &RobotOutputSender::get_input_port_imu,
py_rvp::reference_internal);
py_rvp::reference_internal);
py::class_<systems::RobotCommandSender, drake::systems::LeafSystem<double>>(
m, "RobotCommandSender")
.def(py::init<const MultibodyPlant<double>&>());
m.def("AddActuationRecieverAndStateSenderLcm",
&dairlib::systems::AddActuationRecieverAndStateSenderLcm,
py::overload_cast<drake::systems::DiagramBuilder<double>*,
const MultibodyPlant<double>&,
drake::systems::lcm::LcmInterfaceSystem*, std::string,
std::string, double,
drake::multibody::ModelInstanceIndex, bool, double>(
&dairlib::systems::AddActuationRecieverAndStateSenderLcm),
py::arg("builder"), py::arg("plant"), py::arg("lcm"),
py::arg("actuator_channel"), py::arg("state_channel"),
py::arg("publish_rate"), py::arg("model_instance"),
py::arg("publish_efforts"), py::arg("actuator_delay"));
m.def("AddActuationRecieverAndStateSenderLcm",
py::overload_cast<drake::systems::DiagramBuilder<double>*,
const MultibodyPlant<double>&,
drake::systems::lcm::LcmInterfaceSystem*, std::string,
std::string, double, bool, double>(
&dairlib::systems::AddActuationRecieverAndStateSenderLcm),
py::arg("builder"), py::arg("plant"), py::arg("lcm"),
py::arg("actuator_channel"), py::arg("state_channel"),
py::arg("publish_rate"), py::arg("publish_efforts"),
py::arg("actuator_delay"));

}

} // namespace pydairlib
Expand Down
Loading