Skip to content
Open
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
40 changes: 31 additions & 9 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,31 +17,54 @@ 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::ObjectStateSender, drake::systems::LeafSystem<double>>(
m, "ObjectStateSender")
.def(py::init<const MultibodyPlant<double>&,
drake::multibody::ModelInstanceIndex>())
.def("get_input_port_state", &systems::ObjectStateSender::get_input_port_state,
py_rvp::reference_internal);
py::class_<systems::ObjectStateReceiver, drake::systems::LeafSystem<double>>(
m, "ObjectStateReceiver")
.def(py::init<const MultibodyPlant<double>&>())
.def(py::init<const MultibodyPlant<double>&,
drake::multibody::ModelInstanceIndex>());

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("publish_efforts"),
py::arg("actuator_delay"));
py::arg("publish_rate"), py::arg("model_instance"),
py::arg("publish_efforts"), py::arg("actuator_delay"));

}

Expand Down
11 changes: 6 additions & 5 deletions examples/Cassie/systems/cassie_encoder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
namespace dairlib {

using Eigen::VectorXd;
using drake::systems::BasicVector;

CassieEncoder::CassieEncoder(
const drake::multibody::MultibodyPlant<double>& plant)
Expand Down Expand Up @@ -37,17 +38,17 @@ CassieEncoder::CassieEncoder(
}
this->DeclareVectorInputPort(
"robot_state",
systems::BasicVector<double>(num_positions_ + num_velocities_));
BasicVector<double>(num_positions_ + num_velocities_));
this->DeclareVectorOutputPort(
"filtered_state",
systems::BasicVector<double>(num_positions_ + num_velocities_),
BasicVector<double>(num_positions_ + num_velocities_),
&CassieEncoder::UpdateFilter);
}

void CassieEncoder::UpdateFilter(const drake::systems::Context<double>& context,
systems::BasicVector<double>* output) const {
const systems::BasicVector<double>& x =
*this->template EvalVectorInput<systems::BasicVector>(context, 0);
BasicVector<double>* output) const {
const BasicVector<double>& x =
*this->template EvalVectorInput<BasicVector>(context, 0);

VectorXd q = x.value().head(num_positions_);
VectorXd v = x.value().tail(num_velocities_);
Expand Down
2 changes: 1 addition & 1 deletion examples/Cassie/systems/cassie_encoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class CassieEncoder final : public drake::systems::LeafSystem<double> {

protected:
void UpdateFilter(const drake::systems::Context<double>& context,
systems::BasicVector<double>* output) const;
drake::systems::BasicVector<double>* output) const;

private:
struct DriveFilter {
Expand Down
1 change: 1 addition & 0 deletions examples/Cassie/systems/sim_cassie_sensor_aggregator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ namespace systems {

using std::string;
using drake::systems::Context;
using drake::systems::BasicVector;
using drake::AbstractValue;
using dairlib::systems::TimestampedVector;
using Eigen::VectorXd;
Expand Down
211 changes: 211 additions & 0 deletions examples/franka/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,211 @@
# -*- mode: python -*-
# vi: set ft=python :

package(default_visibility = ["//visibility:public"])

cc_library(
name = "urdfs",
data = glob([
"urdf/**",
]),
)

cc_binary(
name = "franka_sim",
srcs = ["franka_sim.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//examples/franka/systems:franka_systems",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/controllers",
"//systems/framework:lcm_driven_loop",
"//systems/primitives:radio_parser",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_osc_controller",
srcs = ["franka_osc_controller.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//examples/franka/systems:franka_systems",
"//lcm:lcm_trajectory_saver",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/controllers:controllers_all",
"//systems/controllers/osc:operational_space_control",
"//systems/framework:lcm_driven_loop",
"//systems/primitives:radio_parser",
"//systems/trajectory_optimization:lcm_trajectory_systems",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_c3_controller",
srcs = ["franka_c3_controller.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//examples/franka/systems:franka_systems",
"//lcm:lcm_trajectory_saver",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/controllers",
"//systems/controllers:c3_controller",
"//systems/controllers:lcs_factory_system",
"//systems/controllers/osc:operational_space_control",
"//systems/framework:lcm_driven_loop",
"//systems/primitives:radio_parser",
"//systems/trajectory_optimization:c3_output_systems",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_visualizer",
srcs = ["franka_visualizer.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//multibody:utils",
"//multibody:visualization_utils",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/primitives",
"//systems/trajectory_optimization:lcm_trajectory_systems",
"//systems/visualization:lcm_visualization_systems",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_bridge_driver_out",
srcs = ["franka_bridge_driver_out.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//examples/franka/systems:franka_state_translator",
"//multibody:utils",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/framework:lcm_driven_loop",
"//systems/primitives",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_bridge_driver_in",
srcs = ["franka_bridge_driver_in.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
deps = [
":parameters",
"//common",
"//examples/franka/systems:franka_state_translator",
"//multibody:utils",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/framework:lcm_driven_loop",
"//systems/primitives",
"@drake//:drake_shared_library",
"@gflags",
],
)

cc_binary(
name = "franka_ros_lcm_bridge",
srcs = ["franka_ros_lcm_bridge.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
tags = ["ros"],
deps = [
":parameters",
"//common",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/primitives",
"//systems/ros:franka_ros_channels",
"//systems/ros:franka_ros_lcm_conversions",
"//systems/ros:ros_pubsub_systems",
"@drake//:drake_shared_library",
"@gflags",
"@ros",
],
)

cc_binary(
name = "franka_lcm_ros_bridge",
srcs = ["franka_lcm_ros_bridge.cc"],
data = [
":urdfs",
"@drake_models//:franka_description",
],
tags = ["ros"],
deps = [
":parameters",
"//common",
"//systems:robot_lcm_systems",
"//systems:system_utils",
"//systems/framework:lcm_driven_loop",
"//systems/ros:franka_ros_channels",
"//systems/ros:franka_ros_lcm_conversions",
"//systems/ros:ros_pubsub_systems",
"@drake//:drake_shared_library",
"@gflags",
"@ros",
],
)

cc_library(
name = "parameters",
hdrs = [
"parameters/franka_c3_controller_params.h",
"parameters/franka_c3_scene_params.h",
"parameters/franka_drake_lcm_driver_channels.h",
"parameters/franka_lcm_channels.h",
"parameters/franka_osc_controller_params.h",
"parameters/franka_sim_params.h",
"parameters/franka_sim_scene_params.h",
],
data = glob([
"*yaml",
]),
deps = [
"@drake//:drake_shared_library",
],
)
Loading