Skip to content

Commit

Permalink
proto: Use lcm encoding (not protobuf) for call_python (RobotLocomoti…
Browse files Browse the repository at this point in the history
…on#12442)

In 0d7f74c way back in 2017, we stopped
using LCM for call_matlab because its runtime support library for was
incompatible with MATLAB.  However, the message serialization itself was
never a problem (only the networking), and anyway for call_python there
are no compatibility problems with LCM.  So to drop the heavy dependency
on protobuf, we'll use LCM message serialization for call_python RPCs.

(As a consequence, some of the build system code for generating protobuf
messages is now dead code, but I'll do that purge separately because it's
finicky and substantial.)
  • Loading branch information
jwnimmer-tri authored Dec 6, 2019
1 parent 2f88c5c commit 703113b
Show file tree
Hide file tree
Showing 8 changed files with 264 additions and 292 deletions.
27 changes: 2 additions & 25 deletions common/proto/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,6 @@ load(
"drake_py_library",
"drake_py_unittest",
)
load(
"@drake//tools/skylark:drake_proto.bzl",
"drake_cc_proto_library",
"drake_py_proto_library",
)
load("@drake//tools/install:install.bzl", "install")
load("//tools/lint:lint.bzl", "add_lint_tests")

Expand All @@ -27,27 +22,10 @@ drake_cc_package_library(
deps = [
":call_python",
":protobuf",
":python_remote_message_proto",
":rpc_pipe_temp_directory",
],
)

drake_cc_proto_library(
name = "python_remote_message_proto",
srcs = [
"python_remote_message.proto",
],
visibility = ["//visibility:private"],
)

drake_py_proto_library(
name = "python_remote_message_proto_py",
srcs = [
"python_remote_message.proto",
],
visibility = ["//visibility:private"],
)

drake_cc_library(
name = "protobuf",
srcs = ["protobuf.cc"],
Expand All @@ -68,10 +46,9 @@ drake_cc_library(
srcs = ["call_python.cc"],
hdrs = ["call_python.h"],
deps = [
":python_remote_message_proto",
":rpc_pipe_temp_directory",
"//common:copyable_unique_ptr",
"//common:essential",
"//lcmtypes:call_python",
],
)

Expand All @@ -80,7 +57,7 @@ drake_py_library(
srcs = ["call_python_client.py"],
imports = ["."],
deps = [
":python_remote_message_proto_py",
"//lcmtypes:lcmtypes_drake_py",
],
)

Expand Down
184 changes: 85 additions & 99 deletions common/proto/call_python.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
#include <fstream>
#include <limits>
#include <memory>
#include <optional>
#include <vector>

#include "drake/common/drake_assert.h"
#include "drake/common/never_destroyed.h"
Expand All @@ -22,99 +24,99 @@ PythonRemoteVariable::PythonRemoteVariable()
: unique_id_(py_globally_unique_id++)
{}

namespace internal {

// Copies `size` bytes at `data` into `message->data`.
void CopyBytes(const void* bytes, const int size,
lcmt_call_python_data* message) {
message->num_bytes = size;
message->data.resize(size);
std::memcpy(message->data.data(), bytes, size);
}

void ToPythonRemoteData(const PythonRemoteVariable& variable,
PythonRemoteData* data) {
data->set_type(PythonRemoteData::REMOTE_VARIABLE_REFERENCE);
data->set_shape_type(PythonRemoteData::SCALAR);
data->set_rows(1);
data->set_cols(1);
int num_bytes = sizeof(int64_t);
lcmt_call_python_data* message) {
message->data_type = lcmt_call_python_data::REMOTE_VARIABLE_REFERENCE;
message->shape_type = lcmt_call_python_data::SCALAR;
message->rows = 1;
message->cols = 1;
int64_t uid = variable.unique_id();
data->set_data(&uid, num_bytes);
CopyBytes(&uid, sizeof(uid), message);
}

void ToPythonRemoteData(double scalar, PythonRemoteData* data) {
data->set_type(PythonRemoteData::DOUBLE);
data->set_shape_type(PythonRemoteData::SCALAR);
data->set_rows(1);
data->set_cols(1);
int num_bytes = sizeof(double);
data->set_data(&scalar, num_bytes);
void ToPythonRemoteData(double scalar, lcmt_call_python_data* message) {
message->data_type = lcmt_call_python_data::DOUBLE;
message->shape_type = lcmt_call_python_data::SCALAR;
message->rows = 1;
message->cols = 1;
CopyBytes(&scalar, sizeof(scalar), message);
}

void ToPythonRemoteData(int scalar, PythonRemoteData* data) {
data->set_type(PythonRemoteData::INT);
data->set_shape_type(PythonRemoteData::SCALAR);
data->set_rows(1);
data->set_cols(1);
int num_bytes = sizeof(int);
data->set_data(&scalar, num_bytes);
void ToPythonRemoteData(int scalar, lcmt_call_python_data* message) {
message->data_type = lcmt_call_python_data::INT;
message->shape_type = lcmt_call_python_data::SCALAR;
message->rows = 1;
message->cols = 1;
CopyBytes(&scalar, sizeof(scalar), message);
}

void ToPythonRemoteData(const std::string& str, PythonRemoteData* data) {
data->set_type(PythonRemoteData::CHAR);
data->set_shape_type(PythonRemoteData::VECTOR);
data->set_rows(1);
data->set_cols(str.length());
int num_bytes = sizeof(char) * str.length();
data->set_data(str.data(), num_bytes);
void ToPythonRemoteData(const std::string& str,
lcmt_call_python_data* message) {
message->data_type = lcmt_call_python_data::CHAR;
message->shape_type = lcmt_call_python_data::VECTOR;
message->rows = 1;
message->cols = str.length();
CopyBytes(str.data(), str.size(), message);
}

namespace internal {

void ToPythonRemoteDataMatrix(const Eigen::Ref<const MatrixX<bool>>& mat,
PythonRemoteData* data, bool is_vector) {
data->set_type(PythonRemoteData::LOGICAL);
data->set_shape_type(
is_vector ? PythonRemoteData::VECTOR : PythonRemoteData::MATRIX);
data->set_rows(mat.rows());
data->set_cols(mat.cols());
lcmt_call_python_data* message, bool is_vector) {
message->data_type = lcmt_call_python_data::LOGICAL;
message->shape_type =
is_vector ? lcmt_call_python_data::VECTOR : lcmt_call_python_data::MATRIX;
message->rows = mat.rows();
message->cols = mat.cols();
int num_bytes = sizeof(bool) * mat.rows() * mat.cols();
data->set_data(mat.data(), num_bytes);
CopyBytes(mat.data(), num_bytes, message);
}

void ToPythonRemoteDataMatrix(const Eigen::Ref<const Eigen::MatrixXd>& mat,
PythonRemoteData* data, bool is_vector) {
data->set_type(PythonRemoteData::DOUBLE);
data->set_shape_type(
is_vector ? PythonRemoteData::VECTOR : PythonRemoteData::MATRIX);
data->set_rows(mat.rows());
data->set_cols(mat.cols());
lcmt_call_python_data* message, bool is_vector) {
message->data_type = lcmt_call_python_data::DOUBLE;
message->shape_type =
is_vector ? lcmt_call_python_data::VECTOR : lcmt_call_python_data::MATRIX;
message->rows = mat.rows();
message->cols = mat.cols();
int num_bytes = sizeof(double) * mat.rows() * mat.cols();
data->set_data(mat.data(), num_bytes);
CopyBytes(mat.data(), num_bytes, message);
}

void ToPythonRemoteDataMatrix(
const Eigen::Ref<const Eigen::MatrixXi>& mat,
PythonRemoteData* data, bool is_vector) {
data->set_type(PythonRemoteData::INT);
data->set_shape_type(
is_vector ? PythonRemoteData::VECTOR : PythonRemoteData::MATRIX);
data->set_rows(mat.rows());
data->set_cols(mat.cols());
lcmt_call_python_data* message, bool is_vector) {
message->data_type = lcmt_call_python_data::INT;
message->shape_type =
is_vector ? lcmt_call_python_data::VECTOR : lcmt_call_python_data::MATRIX;
message->rows = mat.rows();
message->cols = mat.cols();
int num_bytes = sizeof(int) * mat.rows() * mat.cols();
data->set_data(mat.data(), num_bytes);
CopyBytes(mat.data(), num_bytes, message);
}

} // namespace internal

namespace {

auto GetPythonOutputStream(const std::string* filename = nullptr) {
static std::unique_ptr<google::protobuf::io::FileOutputStream> raw_output;
if (!raw_output) {
// Latch-initialize the ofstream output that writes to the python client.
// The return value is a long-lived pointer to a singleton.
std::ofstream* InitOutput(const std::optional<std::string>& filename) {
static never_destroyed<std::unique_ptr<std::ofstream>> raw_output;
if (!raw_output.access()) {
// If we do not yet have a file, create it.
const std::string filename_default
= GetRpcPipeTempDirectory() + "/python_rpc";
const std::string filename_actual = filename ? *filename : filename_default;
// NOTE(russt): This code violates the style-guide by expecting the file to
// be closed properly at program termination (these streams will be stored
// as static globals). Experimentally we found that the output file could
// be corrupt unless we included *both* the Flush() call and the
// SetCloseOnDelete() calls below. Sadly, I cannot explain why.
raw_output = std::make_unique<google::protobuf::io::FileOutputStream>(
open(filename_actual.c_str(), O_WRONLY | O_CREAT, S_IRWXU));
raw_output->SetCloseOnDelete(true);
raw_output.access() = std::make_unique<std::ofstream>(filename_actual);
} else {
// If we already have a file, ensure that this does not come from
// `CallPythonInit`.
Expand All @@ -123,53 +125,37 @@ auto GetPythonOutputStream(const std::string* filename = nullptr) {
"`CallPython` or `CallPythonInit` has already been called");
}
}
return raw_output.get();
return raw_output.access().get();
}

void PublishCall(
google::protobuf::io::FileOutputStream* praw_output,
const PythonRemoteMessage& message) {
DRAKE_DEMAND(praw_output);
auto& raw_output = *praw_output;

{ // Defines the lifetime of the CodedOutputStream.
google::protobuf::io::CodedOutputStream output(&raw_output);

// Write the size.
#if GOOGLE_PROTOBUF_VERSION < 3011000
const int size = message.ByteSize();
#else
const size_t size = message.ByteSizeLong();
if (size > std::numeric_limits<int>::max()) {
throw std::runtime_error(
"Message size is greater than the maximum finite value of int");
}
#endif
output.WriteVarint32(size);

uint8_t* buffer = output.GetDirectBufferForNBytesAndAdvance(size);
if (buffer != nullptr) {
// Optimization: The message fits in one buffer, so use the faster
// direct-to-array serialization path.
message.SerializeWithCachedSizesToArray(buffer);
} else {
// Slightly-slower path when the message is multiple buffers.
message.SerializeWithCachedSizes(&output);
DRAKE_DEMAND(!output.HadError());
}
}
void PublishCall(std::ofstream* stream_arg, const lcmt_call_python& message) {
DRAKE_DEMAND(stream_arg != nullptr);
std::ofstream& stream = *stream_arg;

const int num_bytes = message.getEncodedSize();
DRAKE_DEMAND(num_bytes >= 0);
const size_t size_bytes = static_cast<size_t>(num_bytes);
std::vector<uint8_t> encoded(size_bytes);
message.encode(encoded.data(), 0, num_bytes);

stream << size_bytes;
stream << '\0';
const void* const data = encoded.data();
stream.write(static_cast<const char*>(data), encoded.size());
stream << '\0';

raw_output.Flush();
stream.flush();
}

} // namespace

void CallPythonInit(const std::string& filename) {
GetPythonOutputStream(&filename);
InitOutput(filename);
}

void internal::PublishCallPython(const PythonRemoteMessage& message) {
PublishCall(GetPythonOutputStream(), message);
void internal::PublishCallPython(const lcmt_call_python& message) {
static const never_destroyed<std::ofstream*> output{InitOutput(std::nullopt)};
PublishCall(output.access(), message);
}

} // namespace common
Expand Down
Loading

0 comments on commit 703113b

Please sign in to comment.