A pure virtual interface that enables LCM to be mocked.
Because it must be pure, in general it will receive breaking API changes without notice. Users should not subclass this interface directly, but rather use one of the existing subclasses such as DrakeLcmBase instead.
Similarly, method arguments will receive breaking API changes without notice. Users should not call this interface directly, but rather use drake::lcm::Publish() or drake::lcm::Subscribe() instead.
#include <drake/lcm/drake_lcm_interface.h>
Public Types | |
using | HandlerFunction = std::function< void(const void *, int)> |
A callback used by DrakeLcmInterface::Subscribe(), with arguments: More... | |
using | MultichannelHandlerFunction = std::function< void(std::string_view, const void *, int)> |
A callback used by DrakeLcmInterface::SubscribeMultipleChannels (which therefore needs the receiving channel passed in). More... | |
Public Member Functions | |
virtual | ~DrakeLcmInterface () |
virtual std::string | get_lcm_url () const =0 |
Returns a URL describing the transport of this LCM interface. More... | |
virtual void | Publish (const std::string &channel, const void *data, int data_size, std::optional< double > time_sec)=0 |
Most users should use the drake::lcm::Publish() free function, instead of this interface method. More... | |
virtual std::shared_ptr< DrakeSubscriptionInterface > | Subscribe (const std::string &channel, HandlerFunction)=0 |
Most users should use the drake::lcm::Subscribe() free function or the drake::lcm::Subscriber wrapper class, instead of this interface method. More... | |
virtual std::shared_ptr< DrakeSubscriptionInterface > | SubscribeMultichannel (std::string_view regex, MultichannelHandlerFunction)=0 |
Subscribes to all channels whose name matches the given regular expression. More... | |
virtual std::shared_ptr< DrakeSubscriptionInterface > | SubscribeAllChannels (MultichannelHandlerFunction)=0 |
Subscribe to all channels; this is useful for logging and redirecting LCM traffic without regard to its content. More... | |
virtual int | HandleSubscriptions (int timeout_millis)=0 |
Invokes the HandlerFunction callbacks for all subscriptions' pending messages. More... | |
Does not allow copy, move, or assignment | |
DrakeLcmInterface (const DrakeLcmInterface &)=delete | |
DrakeLcmInterface & | operator= (const DrakeLcmInterface &)=delete |
DrakeLcmInterface (DrakeLcmInterface &&)=delete | |
DrakeLcmInterface & | operator= (DrakeLcmInterface &&)=delete |
Protected Member Functions | |
DrakeLcmInterface () | |
Friends | |
void | internal::OnHandleSubscriptionsError (DrakeLcmInterface *, const std::string &) |
using HandlerFunction = std::function<void(const void*, int)> |
A callback used by DrakeLcmInterface::Subscribe(), with arguments:
message_buffer
A pointer to the byte vector that is the serial representation of the LCM message.message_size
The size of message_buffer
.A callback should never throw an exception, because it is indirectly called from C functions.
using MultichannelHandlerFunction = std::function<void(std::string_view, const void*, int)> |
A callback used by DrakeLcmInterface::SubscribeMultipleChannels (which therefore needs the receiving channel passed in).
|
delete |
|
delete |
|
virtual |
|
protected |
|
pure virtual |
Returns a URL describing the transport of this LCM interface.
When the URL refers to a transport offered by LCM itself (e.g., memq or udpm), then this function must return the conventional URL spelling. If the implementation of DrakeLcmInterface is using a non-standard back end, the result implementation-defined.
In either case, it is always formatted using URI syntax rules per the RFC(s).
Implemented in DrakeLcmLog, LcmInterfaceSystem, DrakeLcm, and DrakeLcmBase.
Invokes the HandlerFunction callbacks for all subscriptions' pending messages.
If timeout_millis
is >0, blocks for up to that long until at least one message is handled.
std::exception | when a subscribed handler throws. |
Implemented in DrakeLcmLog, LcmInterfaceSystem, DrakeLcm, and DrakeLcmBase.
|
delete |
|
delete |
|
pure virtual |
Most users should use the drake::lcm::Publish() free function, instead of this interface method.
Publishes an LCM message on channel channel
.
channel | The channel on which to publish the message. Must not be the empty string. |
data | A buffer containing the serialized bytes of the message to publish. |
data_size | The length of @data in bytes. |
time_sec | Time in seconds when the publish event occurred. If unknown, use nullopt or a default-constructed optional. |
Implemented in LcmInterfaceSystem, DrakeLcmLog, DrakeLcm, and DrakeLcmBase.
|
pure virtual |
Most users should use the drake::lcm::Subscribe() free function or the drake::lcm::Subscriber wrapper class, instead of this interface method.
Subscribes to an LCM channel without automatic message decoding. The handler will be invoked when a message arrives on channel channel
.
The handler should never throw an exception, because it is indirectly called from C functions.
channel | The channel to subscribe to. Must not be the empty string. To use a regex, see SubscribeMultichannel(). |
false
. Refer to the DrakeSubscriptionInterface class overview for details. Implemented in DrakeLcmLog, LcmInterfaceSystem, DrakeLcm, and DrakeLcmBase.
|
pure virtual |
Subscribe to all channels; this is useful for logging and redirecting LCM traffic without regard to its content.
Implemented in DrakeLcmLog, LcmInterfaceSystem, DrakeLcm, and DrakeLcmBase.
|
pure virtual |
Subscribes to all channels whose name matches the given regular expression.
The regex
is treated as an anchored "match" not a "search", i.e., it must match the entire channel name. The specific regular expression grammar is left unspecified, so it's best to use only patterns that have identical semantics in all grammars, e.g., ".*"
.
Implemented in DrakeLcmLog, LcmInterfaceSystem, DrakeLcm, and DrakeLcmBase.
|
friend |