forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathdrake_lcm.cc
265 lines (223 loc) · 8.64 KB
/
drake_lcm.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
#include "drake/lcm/drake_lcm.h"
#include <algorithm>
#include <cstdlib>
#include <stdexcept>
#include <utility>
#include <vector>
#include <glib.h>
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/drake_throw.h"
#include "drake/common/scope_exit.h"
namespace drake {
namespace lcm {
namespace {
// Keep this in sync with external/lcm/lcm.c. Unfortunately, LCM does not
// appear to provide *any* API to determine this.
constexpr const char* const kLcmDefaultUrl = "udpm://239.255.76.67:7667?ttl=0";
// Defined below.
class DrakeSubscription;
} // namespace
class DrakeLcm::Impl {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Impl)
explicit Impl(std::string lcm_url)
: requested_lcm_url_(std::move(lcm_url)),
lcm_url_(requested_lcm_url_),
lcm_(requested_lcm_url_) {
// This duplicates logic from external/lcm/lcm.c, but until LCM offers an
// API for this it's the best we can do.
if (lcm_url_.empty()) {
char* env_url = ::getenv("LCM_DEFAULT_URL");
if (env_url) {
lcm_url_ = env_url;
}
if (lcm_url_.empty()) {
lcm_url_ = kLcmDefaultUrl;
}
}
}
std::string requested_lcm_url_;
std::string lcm_url_;
::lcm::LCM lcm_;
std::vector<std::weak_ptr<DrakeSubscription>> subscriptions_;
std::string handle_subscriptions_error_message_;
};
DrakeLcm::DrakeLcm() : DrakeLcm(std::string{}) {}
DrakeLcm::DrakeLcm(std::string lcm_url)
: impl_(std::make_unique<Impl>(std::move(lcm_url))) {
// Ensure that LCM's self-test happens deterministically (here in our ctor),
// and NOT in the receive thread or first HandleSubscriptions call. Without
// this, ThreadSanitizer builds may report false positives related to the
// self-test happening concurrently with the LCM publishing.
impl_->lcm_.getFileno();
}
std::string DrakeLcm::get_lcm_url() const {
return impl_->lcm_url_;
}
::lcm::LCM* DrakeLcm::get_lcm_instance() {
return &impl_->lcm_;
}
void DrakeLcm::Publish(const std::string& channel, const void* data,
int data_size, std::optional<double>) {
DRAKE_THROW_UNLESS(!channel.empty());
impl_->lcm_.publish(channel, data, data_size);
}
namespace {
// The concrete implementation of DrakeSubscriptionInterface used by DrakeLcm.
class DrakeSubscription final : public DrakeSubscriptionInterface {
public:
// We must disable copy/move/assign because we need our memory address to
// remain stable; the native LCM stack keeps a pointer to this object.
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(DrakeSubscription)
using HandlerFunction = DrakeLcmInterface::HandlerFunction;
static std::shared_ptr<DrakeSubscription> Create(
::lcm::LCM* native_instance, const std::string& channel,
HandlerFunction handler) {
DRAKE_DEMAND(native_instance != nullptr);
// The argument to subscribeFunction is regex (not a string literal), so
// we'll need to escape the channel name before calling subscribeFunction.
char* const channel_regex = g_regex_escape_string(channel.c_str(), -1);
ScopeExit guard([channel_regex](){ g_free(channel_regex); });
// Create the result.
auto result = std::make_shared<DrakeSubscription>();
result->native_instance_ = native_instance;
result->user_callback_ = std::move(handler);
result->weak_self_reference_ = result;
result->strong_self_reference_ = result;
result->native_subscription_ = native_instance->subscribeFunction(
channel_regex, &DrakeSubscription::NativeCallback, result.get());
result->native_subscription_->setQueueCapacity(1);
// Sanity checks. (The use_count will be 2 because both 'result' and
// 'strong_self_reference' keep the subscription alive.)
DRAKE_DEMAND(result->native_instance_ != nullptr);
DRAKE_DEMAND(result->native_subscription_ != nullptr);
DRAKE_DEMAND(result->user_callback_ != nullptr);
DRAKE_DEMAND(result->weak_self_reference_.use_count() == 2);
DRAKE_DEMAND(result->strong_self_reference_.use_count() == 2);
DRAKE_DEMAND(result->strong_self_reference_ != nullptr);
return result;
}
~DrakeSubscription() {
DRAKE_DEMAND(strong_self_reference_ == nullptr);
if (native_subscription_) {
DRAKE_DEMAND(native_instance_ != nullptr);
native_instance_->unsubscribe(native_subscription_);
}
}
void set_unsubscribe_on_delete(bool enabled) final {
DRAKE_DEMAND(!weak_self_reference_.expired());
if (enabled) {
// The caller needs to keep this Subscription active.
strong_self_reference_.reset();
} else {
// This DrakeSubscription will keep itself active.
strong_self_reference_ = weak_self_reference_.lock();
}
}
void set_queue_capacity(int capacity) final {
DRAKE_DEMAND(!weak_self_reference_.expired());
if (native_subscription_) {
DRAKE_DEMAND(native_instance_ != nullptr);
native_subscription_->setQueueCapacity(capacity);
}
}
// This is ONLY called from the DrakeLcm dtor. Thus, a HandleSubscriptions
// is never in flight, so we can freely change any/all of our member fields.
void Detach() {
DRAKE_DEMAND(!weak_self_reference_.expired());
if (native_subscription_) {
DRAKE_DEMAND(native_instance_ != nullptr);
native_instance_->unsubscribe(native_subscription_);
}
native_instance_ = {};
native_subscription_ = {};
user_callback_ = {};
weak_self_reference_ = {};
strong_self_reference_ = {};
}
// The native LCM stack calls into here.
static void NativeCallback(
const ::lcm::ReceiveBuffer* buffer,
const std::string& /* channel */ ,
DrakeSubscription* self) {
DRAKE_DEMAND(buffer != nullptr);
DRAKE_DEMAND(self != nullptr);
self->InstanceCallback(buffer);
}
private:
struct AsIfPrivateConstructor {};
public:
// Only use Create; don't call this directly. (We use a private struct to
// prevent anyone but this class from calling the ctor.)
explicit DrakeSubscription(AsIfPrivateConstructor = {}) {}
private:
void InstanceCallback(const ::lcm::ReceiveBuffer* buffer) {
DRAKE_DEMAND(!weak_self_reference_.expired());
if (user_callback_ != nullptr) {
user_callback_(buffer->data, buffer->data_size);
}
}
// The native handle we can use to unsubscribe.
::lcm::LCM* native_instance_{};
::lcm::Subscription* native_subscription_{};
// The user's function that handles raw message data.
DrakeLcmInterface::HandlerFunction user_callback_;
// We can use "strong" to pretend a subscriber is still active.
std::weak_ptr<DrakeSubscriptionInterface> weak_self_reference_;
std::shared_ptr<DrakeSubscriptionInterface> strong_self_reference_;
};
} // namespace
std::shared_ptr<DrakeSubscriptionInterface> DrakeLcm::Subscribe(
const std::string& channel, HandlerFunction handler) {
DRAKE_THROW_UNLESS(!channel.empty());
DRAKE_THROW_UNLESS(handler != nullptr);
// Some housekeeping: scrub any deallocated subscribers.
auto& subs = impl_->subscriptions_;
subs.erase(std::remove_if(
subs.begin(), subs.end(),
[](const auto& weak_subscription) {
return weak_subscription.expired();
}), subs.end());
// Add the new subscriber.
auto result = DrakeSubscription::Create(
&(impl_->lcm_), channel, std::move(handler));
subs.push_back(result);
DRAKE_DEMAND(!subs.back().expired());
return result;
}
int DrakeLcm::HandleSubscriptions(int timeout_millis) {
// Keep pumping handleTimeout until it's empty, but only pause for the
// timeout on the first attempt.
int total_messages = 0;
int zero_or_one = impl_->lcm_.handleTimeout(timeout_millis);
for (; zero_or_one > 0; zero_or_one = impl_->lcm_.handleTimeout(0)) {
DRAKE_DEMAND(zero_or_one == 1);
++total_messages;
}
// If a handler posted an error, raise it now that we're done with LCM C code.
if (!impl_->handle_subscriptions_error_message_.empty()) {
std::string message = std::move(impl_->handle_subscriptions_error_message_);
impl_->handle_subscriptions_error_message_ = {};
throw std::runtime_error(std::move(message));
}
return total_messages;
}
void DrakeLcm::OnHandleSubscriptionsError(const std::string& error_message) {
DRAKE_DEMAND(!error_message.empty());
// Stash the exception message for later. This is "last one wins" if there
// are multiple errors. We can only throw one anyway, and doesn't matter
// which one we throw.
impl_->handle_subscriptions_error_message_ = error_message;
}
DrakeLcm::~DrakeLcm() {
// Invalidate our DrakeSubscription objects.
for (const auto& weak_subscription : impl_->subscriptions_) {
auto subscription = weak_subscription.lock();
if (subscription) {
subscription->Detach();
}
}
}
} // namespace lcm
} // namespace drake