Skip to content

Commit

Permalink
examples: Port to LcmInterfaceSystem (RobotLocomotion#11124)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Apr 2, 2019
1 parent d0dd5b0 commit 9c02abf
Show file tree
Hide file tree
Showing 16 changed files with 126 additions and 156 deletions.
54 changes: 31 additions & 23 deletions attic/multibody/rigid_body_plant/test/drake_visualizer_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,11 @@ using DrakeShapes::Cylinder;
using DrakeShapes::Mesh;
using DrakeShapes::Sphere;

using LoadSubscriber = drake::lcm::Subscriber<lcmt_viewer_load_robot>;
using DrawSubscriber = drake::lcm::Subscriber<lcmt_viewer_draw>;

// Verifies that @p message is correct.
void VerifyLoadMessage(const std::vector<uint8_t>& message_bytes) {
void VerifyLoadMessage(const drake::lcmt_viewer_load_robot& message) {
// Instantiates the expected message.
drake::lcmt_viewer_load_robot expected_message;
expected_message.num_links = 6;
Expand Down Expand Up @@ -185,21 +188,20 @@ void VerifyLoadMessage(const std::vector<uint8_t>& message_bytes) {
expected_message.link.push_back(link_data);
}

// Ensures both messages have the same length.
EXPECT_EQ(expected_message.getEncodedSize(),
static_cast<int>(message_bytes.size()));
const int byte_count = expected_message.getEncodedSize();

// Serialize the expected message.
std::vector<uint8_t> expected_message_bytes(byte_count);
expected_message.encode(expected_message_bytes.data(), 0, byte_count);
std::vector<uint8_t> expected_bytes(expected_message.getEncodedSize());
expected_message.encode(expected_bytes.data(), 0, expected_bytes.size());

// Serialize the actual message.
std::vector<uint8_t> actual_bytes(message.getEncodedSize());
message.encode(actual_bytes.data(), 0, actual_bytes.size());

// Verifies that the messages are equal.
EXPECT_EQ(expected_message_bytes, message_bytes);
EXPECT_EQ(expected_bytes, actual_bytes);
}

// Verifies that @p message_bytes is correct.
void VerifyDrawMessage(const std::vector<uint8_t>& message_bytes) {
// Verifies that @p message is correct.
void VerifyDrawMessage(const drake::lcmt_viewer_draw& message) {
// TODO(liang.fok): Replace the following two lines with
// `Eigen::Quaterniond::Identity()` and a common helper method that converts
// it into a std::vector<float>. Related issue: #3470.
Expand Down Expand Up @@ -272,16 +274,16 @@ void VerifyDrawMessage(const std::vector<uint8_t>& message_bytes) {
expected_message.quaternion.push_back(zero_quaternion);
}

// Ensures both messages have the same length.
const int byte_count = expected_message.getEncodedSize();
EXPECT_EQ(byte_count, static_cast<int>(message_bytes.size()));
// Serialize the expected message.
std::vector<uint8_t> expected_bytes(expected_message.getEncodedSize());
expected_message.encode(expected_bytes.data(), 0, expected_bytes.size());

// Serializes the expected message.
std::vector<uint8_t> expected_message_bytes(byte_count);
expected_message.encode(expected_message_bytes.data(), 0, byte_count);
// Serialize the actual message.
std::vector<uint8_t> actual_bytes(message.getEncodedSize());
message.encode(actual_bytes.data(), 0, actual_bytes.size());

// Verifies that the messages are equal.
EXPECT_EQ(expected_message_bytes, message_bytes);
EXPECT_EQ(expected_bytes, actual_bytes);
}

// Creates a RigidBodyTree. The tree has 6 rigid bodies including the world. The
Expand Down Expand Up @@ -465,6 +467,8 @@ GTEST_TEST(DrakeVisualizerTests, BasicTest) {
unique_ptr<RigidBodyTree<double>> tree = CreateRigidBodyTree();
drake::lcm::DrakeMockLcm lcm;
const DrakeVisualizer dut(*tree, &lcm);
LoadSubscriber load_sub(&lcm, "DRAKE_VIEWER_LOAD_ROBOT");
DrawSubscriber draw_sub(&lcm, "DRAKE_VIEWER_DRAW");

EXPECT_EQ("drake_visualizer", dut.get_name());

Expand All @@ -483,10 +487,11 @@ GTEST_TEST(DrakeVisualizerTests, BasicTest) {
PublishLoadRobotModelMessageHelper(dut, *context);

dut.Publish(*context.get());
lcm.HandleSubscriptions(0);

// Verifies that the correct messages were actually transmitted.
VerifyLoadMessage(lcm.get_last_published_message("DRAKE_VIEWER_LOAD_ROBOT"));
VerifyDrawMessage(lcm.get_last_published_message("DRAKE_VIEWER_DRAW"));
VerifyLoadMessage(load_sub.message());
VerifyDrawMessage(draw_sub.message());
}

// Tests that the published LCM message has the expected timestamps.
Expand All @@ -495,6 +500,8 @@ GTEST_TEST(DrakeVisualizerTests, TestPublishPeriod) {

unique_ptr<RigidBodyTree<double>> tree = CreateRigidBodyTree();
drake::lcm::DrakeMockLcm lcm;
LoadSubscriber load_sub(&lcm, "DRAKE_VIEWER_LOAD_ROBOT");
DrawSubscriber draw_sub(&lcm, "DRAKE_VIEWER_DRAW");

// Instantiates the "device under test".
DrakeVisualizer dut(*tree, &lcm);
Expand All @@ -510,16 +517,17 @@ GTEST_TEST(DrakeVisualizerTests, TestPublishPeriod) {
drake::systems::Simulator<double> simulator(dut, std::move(context));
simulator.set_publish_every_time_step(false);
simulator.Initialize();
VerifyLoadMessage(lcm.get_last_published_message("DRAKE_VIEWER_LOAD_ROBOT"));
lcm.HandleSubscriptions(0);
VerifyLoadMessage(load_sub.message());

for (double time = 0; time < 4; time += 0.01) {
simulator.AdvanceTo(time);
lcm.HandleSubscriptions(0);
EXPECT_NEAR(simulator.get_mutable_context().get_time(), time, 1e-10);
// Note that the expected time is in milliseconds.
const double expected_time =
std::floor(time / kPublishPeriod) * kPublishPeriod * 1000;
EXPECT_EQ(lcm.DecodeLastPublishedMessageAs<lcmt_viewer_draw>(
"DRAKE_VIEWER_DRAW").timestamp, expected_time);
EXPECT_EQ(draw_sub.message().timestamp, expected_time);
}
}

Expand Down
20 changes: 11 additions & 9 deletions attic/multibody/rigid_body_plant/test/frame_visualizer_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ GTEST_TEST(FrameVisualizerTests, TestMessageGeneration) {
lcm_channel = "DRAKE_DRAW_FRAMES_CUSTOM";
dut.set_lcm_channel(lcm_channel);
}
drake::lcm::Subscriber<drake::lcmt_viewer_draw> draw_sub(
&lcm, lcm_channel);

auto context = dut.CreateDefaultContext();
EXPECT_EQ(1, context->num_input_ports());
Expand Down Expand Up @@ -81,18 +83,18 @@ GTEST_TEST(FrameVisualizerTests, TestMessageGeneration) {
expected_message.quaternion.push_back(
{q_WF.w(), q_WF.x(), q_WF.y(), q_WF.z()});

// Ensures both messages have the same length.
const std::vector<uint8_t>& message_bytes =
lcm.get_last_published_message(lcm_channel);
const int byte_count = expected_message.getEncodedSize();
EXPECT_EQ(byte_count, static_cast<int>(message_bytes.size()));
// Serialize the expected message.
std::vector<uint8_t> expected_bytes(expected_message.getEncodedSize());
expected_message.encode(expected_bytes.data(), 0, expected_bytes.size());

// Serializes the expected message.
std::vector<uint8_t> expected_message_bytes(byte_count);
expected_message.encode(expected_message_bytes.data(), 0, byte_count);
// Serialize the actual message.
lcm.HandleSubscriptions(0);
const auto& message = draw_sub.message();
std::vector<uint8_t> actual_bytes(message.getEncodedSize());
message.encode(actual_bytes.data(), 0, actual_bytes.size());

// Verifies that the messages are equal.
EXPECT_EQ(expected_message_bytes, message_bytes);
EXPECT_EQ(expected_bytes, actual_bytes);
}
}

Expand Down
13 changes: 5 additions & 8 deletions examples/acrobot/run_plant_w_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include "drake/common/find_resource.h"
#include "drake/examples/acrobot/acrobot_lcm.h"
#include "drake/examples/acrobot/acrobot_plant.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/lcmt_acrobot_u.hpp"
#include "drake/lcmt_acrobot_x.hpp"
#include "drake/multibody/joints/floating_base_types.h"
Expand All @@ -26,6 +25,7 @@
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/lcm/lcm_interface_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"

Expand All @@ -48,26 +48,26 @@ int DoMain() {
const std::string channel_x = "acrobot_xhat";
const std::string channel_u = "acrobot_u";

lcm::DrakeLcm lcm;
auto tree = std::make_unique<RigidBodyTree<double>>();
parsers::urdf::AddModelInstanceFromUrdfFileToWorld(
FindResourceOrThrow("drake/examples/acrobot/Acrobot.urdf"),
multibody::joints::kFixed, tree.get());
auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, &lcm);
auto lcm = builder.AddSystem<systems::lcm::LcmInterfaceSystem>();
auto publisher = builder.AddSystem<systems::DrakeVisualizer>(*tree, lcm);
auto acrobot = builder.AddSystem<AcrobotPlant>();
// Connects plant to visualizer.
builder.Connect(acrobot->get_output_port(0), publisher->get_input_port(0));

// Creates command receiver and subscriber.
auto command_sub = builder.AddSystem(
systems::lcm::LcmSubscriberSystem::Make<lcmt_acrobot_u>(channel_u, &lcm));
systems::lcm::LcmSubscriberSystem::Make<lcmt_acrobot_u>(channel_u, lcm));
auto command_receiver = builder.AddSystem<AcrobotCommandReceiver>();
builder.Connect(command_sub->get_output_port(),
command_receiver->get_input_port(0));

// Creates state sender and publisher.
auto state_pub = builder.AddSystem(
systems::lcm::LcmPublisherSystem::Make<lcmt_acrobot_x>(channel_x, &lcm));
systems::lcm::LcmPublisherSystem::Make<lcmt_acrobot_x>(channel_x, lcm));
auto state_sender = builder.AddSystem<AcrobotStateSender>();
builder.Connect(state_sender->get_output_port(0),
state_pub->get_input_port());
Expand All @@ -92,13 +92,10 @@ int DoMain() {
x0->set_theta1dot(0.0);
x0->set_theta2dot(0.0);

lcm.StartReceiveThread();

simulator.set_target_realtime_rate(FLAGS_realtime_factor);
simulator.Initialize();
simulator.AdvanceTo(FLAGS_simulation_sec);

lcm.StopReceiveThread();
return 0;
}
} // namespace
Expand Down
12 changes: 5 additions & 7 deletions examples/acrobot/spong_controller_w_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,11 @@

#include "drake/examples/acrobot/acrobot_lcm.h"
#include "drake/examples/acrobot/spong_controller.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/lcmt_acrobot_u.hpp"
#include "drake/lcmt_acrobot_x.hpp"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/leaf_system.h"
#include "drake/systems/lcm/lcm_interface_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"

Expand All @@ -36,19 +36,19 @@ int DoMain() {
drake::systems::DiagramBuilder<double> builder;
const std::string channel_x = "acrobot_xhat";
const std::string channel_u = "acrobot_u";
lcm::DrakeLcm lcm;

// -----------------controller--------------------------------------
// Create state receiver.
auto lcm = builder.AddSystem<systems::lcm::LcmInterfaceSystem>();
auto state_sub = builder.AddSystem(
systems::lcm::LcmSubscriberSystem::Make<lcmt_acrobot_x>(channel_x, &lcm));
systems::lcm::LcmSubscriberSystem::Make<lcmt_acrobot_x>(channel_x, lcm));
auto state_receiver = builder.AddSystem<AcrobotStateReceiver>();
builder.Connect(state_sub->get_output_port(),
state_receiver->get_input_port(0));

// Create command sender.
auto command_pub = builder.AddSystem(
systems::lcm::LcmPublisherSystem::Make<lcmt_acrobot_u>(channel_u, &lcm));
systems::lcm::LcmPublisherSystem::Make<lcmt_acrobot_u>(channel_u, lcm));
auto command_sender = builder.AddSystem<AcrobotCommandSender>();
builder.Connect(command_sender->get_output_port(0),
command_pub->get_input_port());
Expand All @@ -62,19 +62,17 @@ int DoMain() {
auto diagram = builder.Build();
auto context = diagram->CreateDefaultContext();

lcm.StartReceiveThread();

using clock = std::chrono::system_clock;
const auto& start_time = clock::now();
const auto& max_duration =
std::chrono::duration<double>(FLAGS_time_limit_sec);
while ((clock::now() - start_time) <= max_duration) {
lcm->HandleSubscriptions(0);
const systems::Context<double>& pub_context =
diagram->GetSubsystemContext(*command_pub, *context);
command_pub->Publish(pub_context);
}

lcm.StopReceiveThread();
return 0;
}

Expand Down
24 changes: 8 additions & 16 deletions examples/acrobot/test/acrobot_lcm_msg_generator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,9 @@ int DoMain() {
const std::string channel_u = "acrobot_u";

// Decode channel_x into msg_x.
std::mutex msg_x_mutex; // Guards msg_x.
lcmt_acrobot_x msg_x{};
lcm::Subscribe<lcmt_acrobot_x>(&lcm, channel_x, [&](const auto& received) {
std::lock_guard<std::mutex> lock(msg_x_mutex);
msg_x = received;
});
drake::lcm::Subscriber<lcmt_acrobot_x> subscription(&lcm, channel_x);
const lcmt_acrobot_x& msg_x = subscription.message();

lcm.StartReceiveThread();
for (int i = 0; i < 1e5; ++i) {
// Publishes a dummy msg_x.
{
Expand All @@ -44,20 +39,17 @@ int DoMain() {
}

// Publishes msg_u using received msg_x.
{
std::lock_guard<std::mutex> lock(msg_x_mutex);
if (msg_x.timestamp > 0) {
// Calculates some output from received state.
lcmt_acrobot_u msg_u{};
msg_u.tau = msg_x.theta1 + msg_x.theta2;
Publish(&lcm, channel_u, msg_u);
}
lcm.HandleSubscriptions(0 /* timeout */);
if (msg_x.timestamp > 0) {
// Calculates some output from received state.
lcmt_acrobot_u msg_u{};
msg_u.tau = msg_x.theta1 + msg_x.theta2;
Publish(&lcm, channel_u, msg_u);
}

sleep_for(milliseconds(500));
}

lcm.StopReceiveThread();
return 0;
}
} // namespace
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include "drake/examples/allegro_hand/allegro_common.h"
#include "drake/examples/allegro_hand/allegro_lcm.h"
#include "drake/geometry/geometry_visualization.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/lcmt_allegro_command.hpp"
#include "drake/lcmt_allegro_status.hpp"
#include "drake/math/rotation_matrix.h"
Expand All @@ -29,6 +28,7 @@
#include "drake/systems/controllers/pid_controller.h"
#include "drake/systems/framework/diagram.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/lcm/lcm_interface_system.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"
#include "drake/systems/primitives/matrix_gain.h"
Expand Down Expand Up @@ -56,7 +56,7 @@ void DoMain() {
DRAKE_DEMAND(FLAGS_simulation_time > 0);

systems::DiagramBuilder<double> builder;
lcm::DrakeLcm lcm;
auto lcm = builder.AddSystem<systems::lcm::LcmInterfaceSystem>();

geometry::SceneGraph<double>& scene_graph =
*builder.AddSystem<geometry::SceneGraph>();
Expand Down Expand Up @@ -105,7 +105,7 @@ void DoMain() {
plant.get_geometry_query_input_port());

// Publish contact results for visualization.
multibody::ConnectContactResultsToDrakeVisualizer(&builder, plant, &lcm);
multibody::ConnectContactResultsToDrakeVisualizer(&builder, plant, lcm);

// PID controller for position control of the finger joints
VectorX<double> kp, kd, ki;
Expand Down Expand Up @@ -134,14 +134,14 @@ void DoMain() {
// Create the command subscriber and status publisher for the hand.
auto& hand_command_sub = *builder.AddSystem(
systems::lcm::LcmSubscriberSystem::Make<lcmt_allegro_command>(
"ALLEGRO_COMMAND", &lcm));
"ALLEGRO_COMMAND", lcm));
hand_command_sub.set_name("hand_command_subscriber");
auto& hand_command_receiver =
*builder.AddSystem<AllegroCommandReceiver>(kAllegroNumJoints);
hand_command_receiver.set_name("hand_command_receiver");
auto& hand_status_pub = *builder.AddSystem(
systems::lcm::LcmPublisherSystem::Make<lcmt_allegro_status>(
"ALLEGRO_STATUS", &lcm, kLcmStatusPeriod /* publish period */));
"ALLEGRO_STATUS", lcm, kLcmStatusPeriod /* publish period */));
hand_status_pub.set_name("hand_status_publisher");
auto& status_sender =
*builder.AddSystem<AllegroStatusSender>(kAllegroNumJoints);
Expand All @@ -162,7 +162,7 @@ void DoMain() {

// Now the model is complete.
std::unique_ptr<systems::Diagram<double>> diagram = builder.Build();
geometry::DispatchLoadMessage(scene_graph, &lcm);
geometry::DispatchLoadMessage(scene_graph, lcm);
// Create a context for this system:
std::unique_ptr<systems::Context<double>> diagram_context =
diagram->CreateDefaultContext();
Expand All @@ -185,8 +185,6 @@ void DoMain() {
X_WM.makeAffine();
plant.SetFreeBodyPose(&plant_context, mug, X_WM);

lcm.StartReceiveThread();

// Set up simulator.
systems::Simulator<double> simulator(*diagram, std::move(diagram_context));
simulator.set_publish_every_time_step(true);
Expand All @@ -200,8 +198,6 @@ void DoMain() {
VectorX<double>::Zero(plant.num_actuators()));

simulator.AdvanceTo(FLAGS_simulation_time);

lcm.StopReceiveThread();
}

} // namespace
Expand Down
Loading

0 comments on commit 9c02abf

Please sign in to comment.