YARP
Yet Another Robot Platform
TcpRosCarrier.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #include "TcpRosCarrier.h"
7 #include "RosSlave.h"
8 #include "TcpRosLogComponent.h"
9 
10 #include <string>
11 #include <map>
12 
13 #include <yarp/os/Bytes.h>
15 #include <yarp/os/NetType.h>
16 #include <yarp/os/Name.h>
17 #include <yarp/os/Route.h>
19 
20 using namespace yarp::os;
21 using namespace yarp::sig;
22 using namespace yarp::wire_rep_utils;
23 
24 void TcpRosCarrier::setParameters(const Bytes& header) {
25  if (header.length()!=8) {
26  return;
27  }
28  headerLen1 = *reinterpret_cast<const NetInt32*>(header.get());
29  headerLen2 = *reinterpret_cast<const NetInt32*>(header.get() + 4);
30 }
31 
32 bool TcpRosCarrier::checkHeader(const Bytes& header) {
33  if (header.length()!=8) {
34  return false;
35  }
36  setParameters(header);
37  if (!(headerLen1<60000&&headerLen1>0 &&
38  headerLen2<60000&&headerLen2>0)) {
39  // not tcpros
40  return false;
41  }
42  // plausibly tcpros.
43  yCTrace(TCPROSCARRIER, "tcpros! %d %d", headerLen1,headerLen2);
44  return true;
45 }
46 
47 
48 std::string TcpRosCarrier::getRosType(ConnectionState& proto) {
49  std::string typ;
50  std::string rtyp;
51  if (proto.getContactable()) {
52  Type t = proto.getContactable()->getType();
53  typ = t.getName();
54  md5sum = t.readProperties().find("md5sum").asString();
55  message_definition = t.readProperties().find("message_definition").asString();
56  user_type = typ;
57  if (typ=="yarp/image") {
58  wire_type = "sensor_msgs/Image";
59  rtyp = "";
60  } else if (typ=="yarp/bottle") {
61  rtyp = proto.getContactable()->getType().getNameOnWire();
62  if (rtyp == "yarp/image") {
63  rtyp = "sensor_msgs/Image";
64  }
65  wire_type = rtyp;
66  } else if (typ!="") {
67  rtyp = typ;
68  wire_type = typ;
69  }
70  }
71  Name n(proto.getRoute().getCarrierName() + "://test");
72  std::string mode = "topic";
73  std::string modeValue = n.getCarrierModifier("topic");
74  if (modeValue=="") {
75  mode = "service";
76  modeValue = n.getCarrierModifier("service");
77  }
78  if (modeValue!="") {
79  std::string package = n.getCarrierModifier("package");
80  if (package!="") {
81  rtyp = package + "/" + modeValue;
82  }
83  }
84 
85  yCTrace(TCPROSCARRIER, "USER TYPE %s", user_type.c_str());
86  yCTrace(TCPROSCARRIER, "WIRE TYPE %s", wire_type.c_str());
87 
88  return rtyp;
89 }
90 
92  yCTrace(TCPROSCARRIER, "Route is %s", proto.getRoute().toString().c_str());
93  Name n(proto.getRoute().getCarrierName() + "://test");
94  std::string mode = "topic";
95  std::string modeValue = n.getCarrierModifier("topic");
96  if (modeValue=="") {
97  mode = "service";
98  modeValue = n.getCarrierModifier("service");
99  isService = true;
100  }
101  if (modeValue=="") {
102  yCInfo(TCPROSCARRIER, "*** no topic or service specified!");
103  mode = "topic";
104  modeValue = "notopic";
105  isService = false;
106  }
107  std::string rawValue = n.getCarrierModifier("raw");
108  if (rawValue=="2") {
109  raw = 2;
110  yCTrace(TCPROSCARRIER, "ROS-native mode requested");
111  } else if (rawValue=="1") {
112  raw = 1;
113  yCTrace(TCPROSCARRIER, "Raw mode requested");
114  } else if (rawValue=="0") {
115  raw = 0;
116  yCTrace(TCPROSCARRIER, "Cooked mode requested");
117  }
118 
119  RosHeader header;
120  yCTrace(TCPROSCARRIER, "Writing to %s", proto.getStreams().getRemoteAddress().toString().c_str());
121  yCTrace(TCPROSCARRIER, "Writing from %s", proto.getStreams().getLocalAddress().toString().c_str());
122 
123  std::string rtyp = getRosType(proto);
124  if (rtyp!="") {
125  header.data["type"] = rtyp;
126  }
127  header.data[mode] = modeValue;
128  header.data["md5sum"] = (md5sum!="")?md5sum:"*";
129  if (message_definition!="") {
130  header.data["message_definition"] = message_definition;
131  }
132  NestedContact nc(proto.getRoute().getFromName());
133  header.data["callerid"] = nc.getNodeName();
134  header.data["persistent"] = "1";
135  std::string header_serial = header.writeHeader();
136  std::string header_len(4,'\0');
137  char *at = (char*)header_len.c_str();
138  RosHeader::appendInt32(at,header_serial.length());
139  yCTrace(TCPROSCARRIER, "Writing %s -- %d bytes",
140  RosHeader::showMessage(header_len).c_str(),
141  (int)header_len.length());
142 
143  Bytes b1((char*)header_len.c_str(),header_len.length());
144  proto.os().write(b1);
145  yCTrace(TCPROSCARRIER, "Writing %s -- %d bytes",
146  RosHeader::showMessage(header_serial).c_str(),
147  (int)header_serial.length());
148  Bytes b2((char*)header_serial.c_str(),header_serial.length());
149  proto.os().write(b2);
150 
151  return proto.os().isOk();
152 }
153 
154 
156  RosHeader header;
157 
158  char mlen[4];
159  Bytes mlen_buf(mlen,4);
160 
161  int res = proto.is().readFull(mlen_buf);
162  if (res<4) {
163  yCWarning(TCPROSCARRIER, "Fail %s %d", __FILE__, __LINE__);
164  return false;
165  }
166  int len = NetType::netInt(mlen_buf);
167  yCTrace(TCPROSCARRIER, "Len %d", len);
168  if (len>10000) {
169  yCWarning(TCPROSCARRIER, "not ready for serious messages");
170  return false;
171  }
172  ManagedBytes m(len);
173  res = proto.is().readFull(m.bytes());
174  if (res!=len) {
175  yCWarning(TCPROSCARRIER, "Fail %s %d", __FILE__, __LINE__);
176  return false;
177  }
178  header.readHeader(std::string(m.get(),m.length()));
179  yCTrace(TCPROSCARRIER, "Message header: %s", header.toString().c_str());
180  std::string rosname;
181  if (header.data.find("type")!=header.data.end()) {
182  rosname = header.data["type"];
183  }
184  yCTrace(TCPROSCARRIER, "<incoming> Type of data is [%s]s", rosname.c_str());
185  if (header.data.find("callerid")!=header.data.end()) {
186  std::string name = header.data["callerid"];
187  yCTrace(TCPROSCARRIER, "<incoming> callerid is %s", name.c_str());
188  yCTrace(TCPROSCARRIER, "Route was %s", proto.getRoute().toString().c_str());
189  Route route = proto.getRoute();
190  route.setToName(name);
191  proto.setRoute(route);
192  yCTrace(TCPROSCARRIER, "Route is now %s", proto.getRoute().toString().c_str());
193  }
194 
195  if (!isService) {
196  isService = (header.data.find("request_type")!=header.data.end());
197  }
198  if (rosname!="" && (user_type != wire_type || user_type == "")) {
199  kind = TcpRosStream::rosToKind(rosname.c_str());
200  TcpRosStream::configureTwiddler(twiddler,kind.c_str(),rosname.c_str(),false,false);
201  translate = TCPROS_TRANSLATE_TWIDDLER;
202  } else {
203  rosname = "";
204  }
205  yCTrace(TCPROSCARRIER, "tcpros %s mode", isService?"service":"topic");
206 
207  // we may be a pull stream
208  sender = isService;
209 
210  processRosHeader(header);
211 
212  auto* stream = new TcpRosStream(proto.giveStreams(),
213  sender,
214  sender,
215  isService,
216  raw,
217  rosname.c_str());
218 
219  if (stream==nullptr) { return false; }
220 
221  yCTrace(TCPROSCARRIER, "Getting ready to hand off streams...");
222 
223  proto.takeStreams(stream);
224 
225  return proto.is().isOk();
226 }
227 
229  Route route = proto.getRoute();
230  route.setFromName("tcpros");
231  proto.setRoute(route);
232  yCTrace(TCPROSCARRIER, "Trying for tcpros header");
233  ManagedBytes m(headerLen1);
234  Bytes mrem(m.get()+4,m.length()-4);
235  NetInt32 ni = headerLen2;
236  memcpy(m.get(),(char*)(&ni), 4);
237  yCTrace(TCPROSCARRIER, "reading %d bytes", (int)mrem.length());
238  int res = proto.is().readFull(mrem);
239  yCTrace(TCPROSCARRIER, "read %d bytes", res);
240  if (res!=(int)mrem.length()) {
241  if (res>=0) {
242  yCError(TCPROSCARRIER, "TCPROS header failure, expected %d bytes, got %d bytes",
243  (int)mrem.length(),res);
244  } else {
245  yCError(TCPROSCARRIER, "TCPROS connection has gone terribly wrong");
246  }
247  return false;
248  }
249  RosHeader header;
250  header.readHeader(std::string(m.get(),m.length()));
251  yCTrace(TCPROSCARRIER, "Got header %s", header.toString().c_str());
252 
253  std::string rosname;
254  if (header.data.find("type")!=header.data.end()) {
255  rosname = header.data["type"];
256  }
257  std::string rtyp = getRosType(proto);
258  if (rtyp!="") {
259  rosname = rtyp;
260  header.data["type"] = rosname;
261  header.data["md5sum"] = (md5sum!="")?md5sum:"*";
262  if (message_definition!="") {
263  header.data["message_definition"] = message_definition;
264  }
265  }
266  yCTrace(TCPROSCARRIER, "<outgoing> Type of data is %s", rosname.c_str());
267 
268  route = proto.getRoute();
269  if (header.data.find("callerid")!=header.data.end()) {
270  route.setFromName(header.data["callerid"]);
271  } else {
272  route.setFromName("tcpros");
273  }
274  proto.setRoute(route);
275 
276  // Let's just ignore everything that is sane and holy, and
277  // send the same header right back.
278  // **UPDATE** Oh, ok, let's modify the callerid. Begrudgingly.
279  NestedContact nc(proto.getRoute().getToName());
280  header.data["callerid"] = nc.getNodeName();
281 
282  std::string header_serial = header.writeHeader();
283  std::string header_len(4,'\0');
284  char *at = (char*)header_len.c_str();
285  RosHeader::appendInt32(at,header_serial.length());
286  yCTrace(TCPROSCARRIER, "Writing %s -- %d bytes",
287  RosHeader::showMessage(header_len).c_str(),
288  (int)header_len.length());
289 
290  Bytes b1((char*)header_len.c_str(),header_len.length());
291  proto.os().write(b1);
292  yCTrace(TCPROSCARRIER, "Writing %s -- %d bytes",
293  RosHeader::showMessage(header_serial).c_str(),
294  (int)header_serial.length());
295  Bytes b2((char*)header_serial.c_str(),header_serial.length());
296  proto.os().write(b2);
297 
298  if (header.data.find("probe")!=header.data.end()) {
299  yCTrace(TCPROSCARRIER, "================PROBE===============");
300  return false;
301  }
302 
303 
304  if (!isService) {
305  isService = (header.data.find("service")!=header.data.end());
306  }
307  if (rosname!="" && (user_type != wire_type || user_type == "")) {
308  if (wire_type!="sensor_msgs/Image") { // currently using a custom method for images
309  kind = TcpRosStream::rosToKind(rosname.c_str());
310  TcpRosStream::configureTwiddler(twiddler,kind.c_str(),rosname.c_str(),true,true);
311  translate = TCPROS_TRANSLATE_TWIDDLER;
312  }
313  } else {
314  rosname = "";
315  }
316  sender = isService;
317 
318  processRosHeader(header);
319 
320  if (isService) {
321  auto* stream = new TcpRosStream(proto.giveStreams(),
322  sender,
323  false,
324  isService,
325  raw,
326  rosname.c_str());
327  if (stream==nullptr) { return false; }
328  proto.takeStreams(stream);
329  return proto.is().isOk();
330  }
331 
332  return true;
333 }
334 
336  SizedWriter *flex_writer = &writer;
337 
338  if (raw!=2) {
339  // At startup, we check for what kind of messages are going
340  // through, and prepare an appropriate byte-rejiggering if
341  // needed.
342  if (translate==TCPROS_TRANSLATE_UNKNOWN) {
343  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_UNKNOWN");
344  FlexImage *img = nullptr;
345  if (user_type=="yarp/image"||user_type=="yarp/bottle") {
346  img = wi.checkForImage(writer);
347  }
348  if (img) {
349  translate = TCPROS_TRANSLATE_IMAGE;
350  std::string frame = "/frame";
351  ri.init(*img,frame);
352  } else {
353  if (WireBottle::extractBlobFromBottle(writer,wt)) {
354  translate = TCPROS_TRANSLATE_BOTTLE_BLOB;
355  } else {
356  translate = TCPROS_TRANSLATE_INHIBIT;
357  }
358  }
359  }
360  } else {
361  translate = TCPROS_TRANSLATE_INHIBIT;
362  }
363 
364  // Apply byte-rejiggering if needed.
365  switch (translate) {
367  {
368  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_IMAGE");
369  FlexImage *img = wi.checkForImage(writer);
370  if (img==nullptr) {
371  yCError(TCPROSCARRIER, "TCPROS Expected an image, but did not get one.");
372  return false;
373  }
374  ri.update(img,seq,Time::now()); // Time here is the timestamp of the ROS message, so Time::now(), the mutable one is correct.
375  seq++;
376  flex_writer = &ri;
377  }
378  break;
380  {
381  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_BOTTLE_BLOB");
382  if (!WireBottle::extractBlobFromBottle(writer,wt)) {
383  yCError(TCPROSCARRIER, "TCPROS Expected a bottle blob, but did not get one.");
384  return false;
385  }
386  flex_writer = &wt;
387  }
388  break;
390  {
391  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_TWIDDLER");
392  twiddler_output.attach(writer,twiddler);
393  if (twiddler_output.update()) {
394  flex_writer = &twiddler_output;
395  } else {
396  flex_writer = nullptr;
397  }
398  }
399  break;
401  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_INHIBIT");
402  break;
403  default:
404  yCTrace(TCPROSCARRIER, "* TCPROS_TRANSLATE_OTHER");
405  break;
406  }
407 
408  if (flex_writer == nullptr) {
409  return false;
410  }
411 
412  int len = 0;
413  for (size_t i=0; i<flex_writer->length(); i++) {
414  len += (int)flex_writer->length(i);
415  }
416  yCTrace(TCPROSCARRIER, "Prepping to write %d blocks (%d bytes)",
417  (int)flex_writer->length(),
418  len);
419 
420  std::string header_len(4,'\0');
421  char *at = (char*)header_len.c_str();
422  RosHeader::appendInt32(at,len);
423  Bytes b1((char*)header_len.c_str(),header_len.length());
424  proto.os().write(b1);
425  flex_writer->write(proto.os());
426 
427  yCTrace(TCPROSCARRIER, "done sending");
428 
429  if (isService) {
430  if (!sender) {
431  if (!persistent) {
432  proto.os().close();
433  }
434  }
435  }
436 
437  return proto.getStreams().isOk();
438 }
439 
441  char twiddle[1];
442  twiddle[0] = 1;
443  Bytes twiddle_buf(twiddle,1);
444  proto.os().write(twiddle_buf);
445  return write(proto,writer);
446 }
447 
448 
450  const yarp::os::Contact& dest,
451  const yarp::os::ContactStyle& style,
452  int mode,
453  bool reversed) {
454  switch (mode) {
456  yCInfo(TCPROSCARRIER, "tcpros disconnect not implemented yet in this direction ");
457  return -1;
458  break;
459  case YARP_ENACT_EXISTS:
460  yCInfo(TCPROSCARRIER, "tcpros connection check not implemented yet in this direction ");
461  return -1;
462  break;
463  }
464 
465  if (!reversed) {
466  return -1;
467  }
468 
469  Contact fullDest = dest;
470  if (fullDest.getPort()<=0) {
471  fullDest = NetworkBase::queryName(fullDest.getName());
472  }
473 
474  Contact fullSrc = src;
475  if (fullSrc.getPort()<=0) {
476  fullSrc = NetworkBase::queryName(fullSrc.getName());
477  }
478 
479  Name n(style.carrier + "://test");
480  std::string topic = n.getCarrierModifier("topic");
481  if (topic=="") {
482  yCInfo(TCPROSCARRIER, "Warning, no topic!");
483  topic = "notopic";
484  }
485 
486  RosSlave slave;
487  yCTrace(TCPROSCARRIER, "Starting temporary slave");
488  slave.start(fullDest.getHost().c_str(),fullDest.getPort());
489  Contact addr_slave = slave.where();
490  Bottle cmd, reply;
491  cmd.addString("publisherUpdate");
492  cmd.addString("dummy_id");
493  cmd.addString(topic);
494  Bottle& lst = cmd.addList();
495  char buf[1000];
496  sprintf(buf,"http://%s:%d/", addr_slave.getHost().c_str(),
497  addr_slave.getPort());
498  lst.addString(buf);
499  ContactStyle req;
500  req.carrier = "xmlrpc";
501  req.timeout = 4;
502  req.quiet = false;
503  bool ok = NetworkBase::write(fullSrc,cmd,reply,req);
504  yCTrace(TCPROSCARRIER, "%s",reply.toString().c_str());
505  if (!ok) {
506  yCError(TCPROSCARRIER, "error talking to %s", fullSrc.toString().c_str());
507  }
508  slave.stop();
509  if (!slave.isOk()) {
510  yCError(TCPROSCARRIER, "Problem: did not get a callback from ROS - can happen if connection already exists.");
511  ok = false;
512  }
513 
514  return ok?0:1;
515 }
516 
517 
518 void TcpRosCarrier::processRosHeader(RosHeader& header) {
519  if (header.data.find("persistent")!=header.data.end()) {
520  persistent = (header.data["persistent"]=="1");
521  } else {
522  persistent = false;
523  }
524 }
#define YARP_ENACT_DISCONNECT
Definition: Carrier.h:13
#define YARP_ENACT_EXISTS
Definition: Carrier.h:14
float t
#define TCPROS_TRANSLATE_UNKNOWN
Definition: TcpRosCarrier.h:19
#define TCPROS_TRANSLATE_BOTTLE_BLOB
Definition: TcpRosCarrier.h:21
#define TCPROS_TRANSLATE_TWIDDLER
Definition: TcpRosCarrier.h:22
#define TCPROS_TRANSLATE_IMAGE
Definition: TcpRosCarrier.h:20
#define TCPROS_TRANSLATE_INHIBIT
Definition: TcpRosCarrier.h:18
const yarp::os::LogComponent & TCPROSCARRIER()
std::string writeHeader()
Definition: RosHeader.cpp:38
std::string toString() const
Definition: RosHeader.cpp:86
static void appendInt32(char *&buf, int x)
Definition: RosHeader.cpp:16
static std::string showMessage(std::string s)
Definition: RosHeader.cpp:28
std::map< std::string, std::string > data
Definition: RosHeader.h:15
bool readHeader(const std::string &bin)
Definition: RosHeader.cpp:59
bool isOk()
Definition: RosSlave.h:61
yarp::os::Contact where()
Definition: RosSlave.h:57
void start(const char *hostname, int portnum)
Definition: RosSlave.h:33
void stop()
Definition: RosSlave.h:40
virtual int connect(const yarp::os::Contact &src, const yarp::os::Contact &dest, const yarp::os::ContactStyle &style, int mode, bool reversed) override
Some carrier types may require special connection logic.
bool reply(yarp::os::ConnectionState &proto, yarp::os::SizedWriter &writer) override
void setParameters(const yarp::os::Bytes &header) override
Configure this carrier based on the first 8 bytes of the connection.
bool write(yarp::os::ConnectionState &proto, yarp::os::SizedWriter &writer) override
Write a message.
bool expectSenderSpecifier(yarp::os::ConnectionState &proto) override
Expect the name of the sending port.
bool sendHeader(yarp::os::ConnectionState &proto) override
Write a header appropriate to the carrier to the connection, followed by any carrier-specific data.
bool checkHeader(const yarp::os::Bytes &header) override
Given the first 8 bytes received on a connection, decide if this is the right carrier type to use for...
bool expectReplyToHeader(yarp::os::ConnectionState &proto) override
Process reply to header, if one is expected for this carrier.
static std::map< std::string, std::string > rosToKind()
static bool configureTwiddler(yarp::wire_rep_utils::WireTwiddler &twiddler, const char *txt, const char *prompt, bool sender, bool reply)
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:74
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
Definition: Bottle.cpp:182
void addString(const char *str)
Places a string in the bottle, at the end of the list.
Definition: Bottle.cpp:170
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:211
A simple abstraction for a block of bytes.
Definition: Bytes.h:25
size_t length() const
Definition: Bytes.cpp:22
const char * get() const
Definition: Bytes.cpp:27
The basic state of a connection - route, streams in use, etc.
virtual Contactable * getContactable() const =0
Get the port associated with the connection.
virtual TwoWayStream & getStreams()=0
Access the streams associated with the connection.
virtual const Route & getRoute() const =0
Get the route associated with this connection.
virtual TwoWayStream * giveStreams()=0
Take ownership of the streams associated with the connection.
virtual void takeStreams(TwoWayStream *streams)=0
Provide streams to be used with the connection.
InputStream & is()
Shorthand for getInputStream()
OutputStream & os()
Shorthand for getOutputStream()
virtual void setRoute(const Route &route)=0
Set the route associated with this connection.
Preferences for how to communicate with a contact.
Definition: ContactStyle.h:24
double timeout
Set a timeout for communication (in units of seconds, fractional seconds allowed).
Definition: ContactStyle.h:47
bool quiet
Suppress all outputs and warnings.
Definition: ContactStyle.h:36
std::string carrier
Request that communication be made using a particular carrier.
Definition: ContactStyle.h:53
Represents how to reach a part of a YARP network.
Definition: Contact.h:36
std::string getName() const
Get the name associated with this Contact.
Definition: Contact.cpp:205
std::string toString() const
Get a textual representation of the Contact.
Definition: Contact.cpp:303
int getPort() const
Get the port number associated with this Contact for socket communication.
Definition: Contact.cpp:239
std::string getHost() const
Get the host name associated with this Contact for socket communication.
Definition: Contact.cpp:228
virtual Type getType()=0
Get the type of data the port has committed to send/receive.
virtual bool isOk() const =0
Check if the stream is ok or in an error state.
yarp::conf::ssize_t readFull(Bytes &b)
Keep reading until buffer is full.
Definition: InputStream.cpp:96
An abstraction for a block of bytes, with optional responsibility for allocating/destroying that bloc...
Definition: ManagedBytes.h:22
const Bytes & bytes() const
const char * get() const
Simple abstraction for a YARP port name.
Definition: Name.h:19
std::string getCarrierModifier(const char *mod, bool *hasModifier=nullptr)
Definition: Name.cpp:44
A placeholder for rich contact information.
Definition: NestedContact.h:24
std::string getNodeName() const
static int netInt(const yarp::os::Bytes &code)
Definition: NetType.cpp:27
static Contact queryName(const std::string &name)
Find out information about a registered name.
Definition: Network.cpp:995
static bool write(const Contact &contact, PortWriter &cmd, PortReader &reply, bool admin=false, bool quiet=false, double timeout=-1)
Send a single command to a port and await a single response.
Definition: Network.cpp:1226
virtual bool isOk() const =0
Check if the stream is ok or in an error state.
virtual void write(char ch)
Write a single byte to the stream.
virtual void close()=0
Terminate the stream.
Information about a connection between two ports.
Definition: Route.h:29
const std::string & getToName() const
Get the destination of the route.
Definition: Route.cpp:103
const std::string & getCarrierName() const
Get the carrier type of the route.
Definition: Route.cpp:123
void setToName(const std::string &toName)
Set the destination of the route.
Definition: Route.cpp:108
std::string toString() const
Render a text form of the route, "source->carrier->dest".
Definition: Route.cpp:138
const std::string & getFromName() const
Get the source of the route.
Definition: Route.cpp:93
void setFromName(const std::string &fromName)
Set the source of the route.
Definition: Route.cpp:98
Minimal requirements for an efficient Writer.
Definition: SizedWriter.h:33
virtual void write(OutputStream &os)
Definition: SizedWriter.cpp:16
virtual size_t length() const =0
virtual const Contact & getLocalAddress() const =0
Get the address of the local side of the stream.
virtual const Contact & getRemoteAddress() const =0
Get the address of the remote side of the stream.
virtual bool isOk() const =0
Check if the stream is ok or in an error state.
std::string getNameOnWire() const
Definition: Type.cpp:144
Image class with user control of representation details.
Definition: Image.h:414
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCTrace(component,...)
Definition: LogComponent.h:85
#define yCWarning(component,...)
Definition: LogComponent.h:143
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:121
An interface to the operating system, including Port based communication.
std::int32_t NetInt32
Definition of the NetInt32 type.
Definition: NetInt32.h:30
bool write(const ImageOf< PixelRgb > &src, const std::string &dest, image_fileformat format=FORMAT_PPM)
Definition: ImageFile.cpp:1098
Signal processing.
Definition: Image.h:22