MRPT  1.9.9
CCANBusReader.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 // This file contains portions of code from sicklms200.cc from the Player/Stage
11 // project.
12 
13 #include "hwdrivers-precomp.h" // Precompiled headers
14 
16 #include <mrpt/system/CTicTac.h>
17 #include <mrpt/system/crc.h>
18 #include <mrpt/system/os.h>
19 #include <cstdio> // printf
20 #include <cstring> // memset
21 
22 #include <iostream>
23 #include <thread>
24 
26 
27 #define RET_ERROR(msg) \
28  { \
29  cout << "[" << __CURRENT_FUNCTION_NAME__ << "] " << msg << endl; \
30  return false; \
31  }
32 
33 using namespace std;
34 using namespace mrpt;
35 using namespace mrpt::obs;
36 using namespace mrpt::hwdrivers;
37 using namespace mrpt::system;
38 
39 char hexCharToInt(char n)
40 {
41  if (n >= '0' && n <= '9')
42  return (n - '0');
43  else
44 
45  if (n >= 'A' && n <= 'F')
46  return (n - 'A' + 10);
47  else
48  return 0;
49 }
50 
51 /*-------------------------------------------------------------
52  CCANBusReader
53 -------------------------------------------------------------*/
54 CCANBusReader::CCANBusReader()
55  : mrpt::system::COutputLogger("CCANBusReader"), m_com_port()
56 
57 {
58  m_sensorLabel = "CANBusReader";
60 }
61 
62 /*-------------------------------------------------------------
63  ~CCANBusReader
64 -------------------------------------------------------------*/
66 {
68  {
69  try
70  {
72  }
73  catch (...)
74  {
75  }
76  }
77 
78  if (m_mySerialPort)
79  {
80  delete m_mySerialPort;
81  m_mySerialPort = nullptr;
82  }
83 }
84 
86 {
89  bool thereIsObservation;
90  bool hardwareError;
91 
92  doProcessSimple(thereIsObservation, *obs, hardwareError);
93  if (thereIsObservation)
94  appendObservation(obs);
95  else
96  cout << "No frame received" << endl;
97 }
98 
99 /*-------------------------------------------------------------
100  doProcess
101 -------------------------------------------------------------*/
103  bool& outThereIsObservation,
104  mrpt::obs::CObservationCANBusJ1939& outObservation, bool& hardwareError)
105 {
106  outThereIsObservation = false;
107  hardwareError = false;
108 
109  if (!tryToOpenComms())
110  {
111  hardwareError = true;
112  return;
113  }
114 
115  m_state = ssWorking;
116 
117  // Wait for a scan:
118  uint8_t out_prio, out_pdu_format, out_pdu_spec, out_src_address,
119  out_data_length;
120  uint16_t out_pgn;
121  vector<uint8_t> out_data;
122  vector<char> out_raw_frame;
124  out_prio, out_pdu_format, out_pdu_spec, out_src_address,
125  out_data_length, out_pgn, out_data, out_raw_frame))
126  return;
127 
128  // Yes, we have a new scan:
129  // cout << "we've got a frame" << endl;
130  // -----------------------------------------------
131  // Extract the observation:
132  // -----------------------------------------------
133  outObservation.timestamp = mrpt::system::now();
134  outObservation.sensorLabel = m_sensorLabel; // Set label
135 
136  // And the scan ranges:
137  outObservation.m_priority = out_prio;
138  outObservation.m_pdu_spec = out_pdu_spec;
139  outObservation.m_pdu_format = out_pdu_format;
140  outObservation.m_src_address = out_src_address;
141  outObservation.m_pgn = out_pgn;
142  outObservation.m_data_length = out_data_length;
143  outObservation.m_data.resize(out_data.size());
144  for (uint8_t k = 0; k < out_data.size(); ++k)
145  outObservation.m_data[k] = out_data[k];
146  outObservation.m_raw_frame.resize(out_raw_frame.size());
147  for (uint8_t k = 0; k < out_raw_frame.size(); ++k)
148  outObservation.m_raw_frame[k] = out_raw_frame[k];
149 
150  // we've got a new observation
151  outThereIsObservation = true;
152 }
153 
154 /*-------------------------------------------------------------
155  loadConfig_sensorSpecific
156 -------------------------------------------------------------*/
158  const mrpt::config::CConfigFileBase& configSource,
159  const std::string& iniSection)
160 {
161  // m_sensorPose = CPose3D(
162  // configSource.read_float(iniSection,"pose_x",0),
163  // configSource.read_float(iniSection,"pose_y",0),
164  // configSource.read_float(iniSection,"pose_z",0),
165  // DEG2RAD( configSource.read_float(iniSection,"pose_yaw",0) ),
166  // DEG2RAD( configSource.read_float(iniSection,"pose_pitch",0) ),
167  // DEG2RAD( configSource.read_float(iniSection,"pose_roll",0) )
168  // ); // irrelevant
169 
171  configSource.read_int(iniSection, "CANBusSpeed", m_canbus_speed);
172  m_canreader_timestamp = configSource.read_bool(
173  iniSection, "useCANReaderTimestamp", m_canreader_timestamp);
174 
175 #ifdef _WIN32
176  m_com_port =
177  configSource.read_string(iniSection, "COM_port_WIN", m_com_port, true);
178 #else
179  m_com_port =
180  configSource.read_string(iniSection, "COM_port_LIN", m_com_port, true);
181 #endif
182 
184  configSource.read_int(iniSection, "COM_baudRate", m_com_baudRate);
186  configSource.read_int(iniSection, "nTries_connect", m_nTries_connect);
187 }
188 
189 /*-------------------------------------------------------------
190  Tries to open the com port and setup
191  all the LMS protocol. Returns true if OK or already open.
192 -------------------------------------------------------------*/
194 {
195  if (err_msg) *err_msg = "";
196  try
197  {
198  if (!m_mySerialPort)
199  {
200  // There is no COMMS port open yet...
201  if (!m_com_port.empty())
202  {
203  // cout << "Creating port" << endl;
205  new mrpt::comms::CSerialPort(); // Create the port myself:
206  }
207  else
208  throw std::logic_error(
209  "ERROR: No serial port attached with bindIO, neither it "
210  "set with 'setSerialPort'");
211  }
212 
213  // We assure now we have a stream... try to open it, if it's not done
214  // yet.
215  bool just_open = false;
216  if (m_mySerialPort != nullptr)
217  {
218  if (!m_mySerialPort->isOpen())
219  {
220  // Try to open it now:
222  m_mySerialPort->open(); // will raise an exception on error.
223 
224  // Set basic params:
225  m_mySerialPort->setConfig(9600);
226  m_mySerialPort->setTimeouts(100, 0, 10, 0, 50);
227 
228  just_open = true;
229  }
230  }
231 
232  // It seems the port was open and working so we are done here.
233  if (!just_open) return true;
234 
235  // ==================================================================
236  // Otherwise, it was just opened now, we must send the
237  // ** initialization commands **
238  // and put the CAN Converter in recording mode:
239  // ==================================================================
240  cout << "Setting up serial comms in port " << m_com_port;
241  if (!setupSerialComms()) RET_ERROR("error");
242  cout << " ... done" << endl;
243 
244  // initialize
245  // set CAN Bus speed
246  /**/
247  bool res;
248  cout << "Setting up CAN BUS Speed at: " << m_canbus_speed << endl;
249  for (int nTry = 0; nTry < 250000 /*4*/; nTry++)
250  if (true == (res = sendCANBusReaderSpeed())) break;
251  if (!res) return false;
252  cout << " ... done" << endl;
253 
254  // open the CAN channel. If true, at this point, frames should be poping
255  // out the CAN Bus
256  cout << "Opening CAN BUS and starting to receive." << endl;
257  for (int nTry = 0; nTry < 250000 /*4*/; nTry++)
258  if (true == (res = CANBusOpenChannel())) break;
259  if (!res) return false;
260  cout << " ... done" << endl;
261 
262  // cout << "Autopoll" << endl;
263  // for (int nTry=0;nTry<250000/*4*/;nTry++)
264  // if (true==(res=CANBusAutoPoll()))
265  // break;
266  // if(!res) return false;
267  // cout << " ... done" << endl;
268 
269  return res;
270  /**/
271  }
272  catch (const std::exception& e)
273  {
274  std::string s =
275  "[CCANBusReader] Error trying to open CANBusReader at port ";
276  s += e.what();
277  if (err_msg) *err_msg = s;
279  return false;
280  }
281 }
282 
283 /*-------------------------------------------------------------
284  Tries to send the command to set up the speed of the
285  CAN Bus reader -> tractor link
286 -------------------------------------------------------------*/
288 {
289  // command: S0 --> S8 according to the selected speed
290  unsigned char cmd[2];
291 
292  cmd[0] = 'S';
293  switch (m_canbus_speed)
294  {
295  case 10000:
296  cmd[1] = '0';
297  break;
298  case 20000:
299  cmd[1] = '1';
300  break;
301  case 50000:
302  cmd[1] = '2';
303  break;
304  case 100000:
305  cmd[1] = '3';
306  break;
307  case 125000:
308  cmd[1] = '4';
309  break;
310  case 250000:
311  cmd[1] = '5';
312  break;
313  case 500000:
314  cmd[1] = '6';
315  break;
316  case 800000:
317  cmd[1] = '7';
318  break;
319  case 1000000:
320  cmd[1] = '8';
321  break;
322  default:
323  RET_ERROR("Incorrect CAN Bus speed");
324  break;
325  }
326  sendCommandToCANReader(cmd, 2);
327  return waitACK(50);
328 }
329 
331 {
332  unsigned char cmd[1];
333  cmd[0] = 'O';
334  sendCommandToCANReader(cmd, 1);
336  return m_CANBusChannel_isOpen;
337 }
338 
340 {
341  unsigned char cmd[1];
342  cmd[0] = 'C';
343  sendCommandToCANReader(cmd, 1);
344  // m_CANBusChannel_isOpen = !waitACK(50);
345  m_CANBusChannel_isOpen = false;
346  // return !m_CANBusChannel_isOpen;
347  return true;
348 }
349 
351 {
352  unsigned char cmd[1];
353  cmd[0] = 'A';
354  sendCommandToCANReader(cmd, 1);
355  return waitACK(50);
356 }
357 
359 {
360  unsigned char cmd[2];
361  cmd[0] = 'X';
362  cmd[1] = '1';
363  sendCommandToCANReader(cmd, 2);
364  return waitACK(50);
365 }
366 
368 {
369  unsigned char cmd[1];
370  cmd[0] = 'P';
371  sendCommandToCANReader(cmd, 1);
372  return waitACK(50);
373 }
374 
375 /*-------------------------------------------------------------
376  waitContinuousSampleFrame
377 -------------------------------------------------------------*/
379  uint8_t& out_prio, uint8_t& out_pdu_format, uint8_t& out_pdu_spec,
380  uint8_t& out_src_address, uint8_t& out_data_length, uint16_t& out_pgn,
381  vector<uint8_t>& out_data, vector<char>& out_raw_frame)
382 {
383  size_t nRead, nBytesToRead;
384  size_t nFrameBytes = 0;
385  size_t lengthField;
386  unsigned char buf[40];
387 
388  // clear buffer
389  for (unsigned char& k : buf) k = 0;
390 
391  uint8_t dlc = 0;
392  while (nFrameBytes < (lengthField = (10U + dlc + 1U)))
393  {
394  // cout << "trying to receive" << endl;
395  if (lengthField > 30)
396  {
397  cout << "#" << int(dlc) << " ";
398  nFrameBytes = 0; // No es cabecera de trama correcta
399  for (unsigned char& k : buf) k = 0;
400  dlc = 0;
401  }
402 
403  if (nFrameBytes < 10)
404  nBytesToRead = 1;
405  else
406  {
407  dlc = 2 * uint8_t(hexCharToInt(buf[9]));
408  // cout << "dlc: " << int(dlc) << endl;
409  nBytesToRead = (lengthField)-nFrameBytes;
410  }
411 
412  try
413  {
414  nRead = m_mySerialPort->Read(buf + nFrameBytes, nBytesToRead);
415  // cout << "to read: " << nBytesToRead << " received: " <<
416  // nRead << " -> ";
417  // for( uint8_t k = 0; k < nRead; ++k )
418  // cout << int(buf[k+nFrameBytes]);
419  // cout << endl;
420  }
421  catch (const std::exception& e)
422  {
423  // Disconnected?
425  "[waitContinuousSampleFrame] Disconnecting due to comms error: "
426  << e.what());
427  return false;
428  }
429 
430  if (!nRead) return false;
431 
432  if (nRead < nBytesToRead) std::this_thread::sleep_for(30ms);
433 
434  // Reading OK:
435  // Was it the first one?
436  if (nFrameBytes > 0 || (nFrameBytes == 0 && buf[0] == 0x54 /*T*/))
437  nFrameBytes += nRead;
438  else
439  {
440  nFrameBytes = 0; // No es cabecera de trama correcta
441  for (unsigned char& k : buf) k = 0;
442  }
443  } // end while
444 
445  // Process frame
446  // convert ASCII text into integer
447  vector<uint8_t> aux;
448  out_raw_frame.resize(nFrameBytes);
449  for (uint8_t k = 0; k < nFrameBytes; ++k)
450  {
451  aux.push_back(hexCharToInt(buf[k]));
452  out_raw_frame[k] = buf[k];
453  }
454 
455  out_prio = (aux[1] << 2) | (aux[2] >> 2);
456  out_pdu_format = (aux[3] << 4) | aux[4];
457  out_pdu_spec = (aux[5] << 4) | aux[6];
458  out_src_address = (aux[7] << 4) | aux[8];
459  out_data_length = aux[9];
460  out_pgn = uint16_t(out_pdu_format) << 8 | uint16_t(out_pdu_spec);
461  out_data.resize(out_data_length);
462  for (uint8_t k = 0, k2 = 0; k < 2 * out_data_length; k += 2, k2++)
463  out_data[k2] = (aux[10 + k] << 4) | aux[11 + k];
464 
465  if (buf[nFrameBytes - 1] != 0x0D)
466  {
467  cout << format(
468  "[CCANBusReader::waitContinuousSampleFrame] expected 0x0D "
469  "ending flag, 0x%X found instead",
470  buf[nFrameBytes])
471  << endl;
472  return false; // Bad ending flag
473  }
474 
475  // All OK
476  return true;
477 }
478 
479 /*-------------------------------------------------------------
480  initialize
481 -------------------------------------------------------------*/
483 {
484  string err_str;
486  if (!tryToOpenComms(&err_str))
487  {
488  cerr << err_str << endl;
489  throw std::logic_error(err_str);
490  }
491 }
492 
493 /*-----------------------------------------------------------------
494  Assures laser is connected and operating at 38400, in
495  its case returns true.
496  -----------------------------------------------------------------*/
498 {
499  ASSERT_(
500  m_com_baudRate == 9600 || m_com_baudRate == 38400 ||
501  m_com_baudRate == 57600 || m_com_baudRate == 500000);
502 
503  if (m_mySerialPort == nullptr) return true;
504 
505  int detected_rate = 0;
506  for (size_t reps = 0; !detected_rate && reps < m_nTries_connect; reps++)
507  {
508  m_nTries_current = reps;
509 
510  int rates[] = {0, 9600, 38400, 57600, 500000};
511 
512  // Try first the desired rate to speed up the process, just in case
513  // the converter is already setup from a previous run:
514  rates[0] = m_com_baudRate;
515 
516  detected_rate = 0;
517 
518  for (size_t i = 0;
519  !detected_rate && i < sizeof(rates) / sizeof(rates[0]); i++)
520  {
521  // Are we already receiving at 500k?
522  // ------------------------------------------------
523  m_mySerialPort->setConfig(rates[i]);
524  std::this_thread::sleep_for(100ms);
526 
527  // close the connection
528  /**/
529  cout << endl << "Closing CAN Channel " << endl;
530  for (int nTry = 0; nTry < 250000 /*4*/; nTry++)
531  if (true == CANBusCloseChannel()) break;
532  cout << " ... done" << endl;
533  /**/
534 
535  std::this_thread::sleep_for(100ms);
537 
538  for (int nTry = 0; nTry < 250000 /*4*/ && !detected_rate; nTry++)
539  {
541 
542  // Ask for the laser version at the current rate:
543  if (queryVersion(true))
544  {
545  detected_rate = rates[i];
546  break;
547  }
548  std::this_thread::sleep_for(20ms);
549  } // for tries
550  // There is no link, or the baudrate is wrong...
551  }
552 
553  // Try again in a while:
554  if (!detected_rate && reps != (m_nTries_connect - 1))
555  std::this_thread::sleep_for(5000ms);
556  }
557 
558  // Switch "this" serial port to the detected baudrate
559  setBaudRate(detected_rate);
560 
563 
564  // Wait...
565  std::this_thread::sleep_for(500ms);
566 
567  // And check comms at the new baud rate:
568  return true;
569 }
570 
571 /*-----------------------------------------------------------------
572  Query to LMS a status query.
573  Returns true if response is read ok.
574  -----------------------------------------------------------------*/
575 bool CCANBusReader::queryVersion(bool printOutVersion)
576 {
578 
579  uint8_t cmd[1];
580  cmd[0] = 'V';
581  uint16_t cmd_len = 1;
582 
583  if (!sendCommandToCANReader(cmd, cmd_len, false)) return false;
584  return waitForVersion(500, printOutVersion);
585 }
586 
587 // Returns false if timeout
589 {
590  uint8_t b = 0;
591  CTicTac tictac;
592  tictac.Tic();
593 
594  do
595  {
596  if (m_mySerialPort->Read(&b, 1))
597  {
598  // Byte rx:
599  if (b == 0x0D /*0x30*/)
600  {
601  cout << int(b) << endl;
602  return true; // [CR]
603  }
604  }
605  } while (tictac.Tac() < timeout_ms * 1e-3);
606 
607  if (b == 0x07) // [BELL]
608  RET_ERROR(format("ERROR received."))
609  else if (b != 0)
610  RET_ERROR(format("Unexpected code received: 0x%02X", b))
611  else
612  return false; // RET_ERROR("Timeout")
613 }
614 
615 bool CCANBusReader::waitForVersion(uint16_t timeout, bool printOutVersion)
616 {
617  uint8_t b;
618  unsigned int nBytes = 0;
619 
620  CTicTac tictac;
621  tictac.Tic();
622  const double maxTime = timeout * 1e-3;
623 
624  while (nBytes < 6)
625  {
626  if (m_mySerialPort->Read(&b, 1))
627  {
628  // cout << "received " << nBytes << " bytes: " << char(b)
629  //<<
630  // endl;
631  // First byte must be STX:
632  if (nBytes > 0 || (nBytes == 0 && b == 'V'))
633  {
634  // Store in frame:
635  m_received_frame_buffer[nBytes] = b;
636  nBytes++;
637  }
638  }
639  if (tictac.Tac() >= maxTime)
640  {
641  cout << "Version timeout" << endl;
642  return false; // Timeout
643  }
644  }
645 
646  // Check len:
647  if (m_received_frame_buffer[nBytes - 1] != 0x0D)
648  {
649  printf(
650  "[CCANBusReader::waitForVersion] Error: expected 0x0D final byte, "
651  "received %x\n",
652  m_received_frame_buffer[nBytes - 1]);
653  return false;
654  }
655 
656  if (printOutVersion)
657  {
658  cout << "Version: ";
659  for (uint8_t k = 0; k < nBytes; ++k)
660  cout << char(m_received_frame_buffer[k]);
661  cout << endl;
662  }
663  return true;
664 }
665 // Returns false if timeout
667 {
668  uint8_t b;
669  unsigned int nBytes = 0;
670 
671  CTicTac tictac;
672  tictac.Tic();
673  const double maxTime = timeout * 1e-3;
674  uint8_t dlc = 0;
675  while (nBytes < 10 || (nBytes < (10U + dlc + 1U /*CR*/)))
676  {
677  if (m_mySerialPort->Read(&b, 1))
678  {
679  // First byte must be STX:
680  if (nBytes > 1 || (!nBytes && b == 0x54 /*'T'*/))
681  {
682  // Store in frame:
683  m_received_frame_buffer[nBytes] = b;
684  nBytes++;
685  }
686  if (nBytes == 10)
687  dlc = 2 * uint8_t(hexCharToInt(
688  m_received_frame_buffer[9])); // here is the
689  // number of
690  // BYTES of
691  // data -> 2
692  // hex values
693  // for byte
694  }
695  if (tictac.Tac() >= maxTime) return false; // Timeout
696  }
697  // Check final flag
698  if (m_received_frame_buffer[10U + dlc] != 0x0D)
699  {
700  printf(
701  "[CCANBusReader::waitIncomingFrame] Error: expected 0x0D as final "
702  "flag, received %x\n",
703  m_received_frame_buffer[10U + dlc]);
704  return false;
705  }
706 
707 #if 0
708  printf("RX: ");
709  for (unsigned int i=0;i<nBytes;i++)
710  printf("%02X ",m_received_frame_buffer[i]);
711  printf("\n");
712 #endif
713 
714  // OK
715  return true;
716 }
717 
719  const uint8_t* cmd, const uint16_t cmd_len, bool wait)
720 {
721  MRPT_UNUSED_PARAM(wait);
722  uint8_t cmd_full[1024];
723  ASSERT_(sizeof(cmd_full) > cmd_len);
724 
725  // command is just plain text so no frame header nor CRC is needed
726  memcpy(cmd_full, cmd, cmd_len);
727  cmd_full[cmd_len] = 0x0D; // [CR] at the end
728 
729  const size_t toWrite = cmd_len + 1;
730 
731 #if 1
732  printf("TX: ");
733  for (unsigned int i = 0; i < toWrite; i++) printf("%02X ", cmd_full[i]);
734  printf("\n");
735 #endif
736 
737  // const int NTRIES = 3;
738 
739  // for (int k=0;k<NTRIES;k++)
740  // {
741  if (toWrite != m_mySerialPort->Write(cmd_full, toWrite))
742  {
743  cout << "[CCANBusReader::SendCommandToCANReader] Error writing data to "
744  "serial port."
745  << endl;
746  return false;
747  }
748  return true;
749  // std::this_thread::sleep_for(15ms);
750  // if(wait)
751  // {
752  // if(waitACK(5000))
753  // return true;
754  // std::this_thread::sleep_for(10ms);
755  // }
756  // else
757  // return true; // perform special wait outside this method
758  // }
759 
760  return false;
761 }
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:86
size_t Read(void *Buffer, size_t Count) override
Implements the virtual method responsible for reading from the stream - Unlike CStream::ReadBuffer, this method will not raise an exception on zero bytes read, as long as there is not any fatal error in the communications.
bool sendCANBusReaderSpeed()
Sends the specified speed to the CAN Converter.
unsigned __int16 uint16_t
Definition: rptypes.h:47
void appendObservation(const mrpt::serialization::CSerializable::Ptr &obj)
Like appendObservations() but for just one observation.
std::string read_string(const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
A communications serial port built as an implementation of a utils::CStream.
Definition: CSerialPort.h:41
bool waitACK(uint16_t timeout_ms)
char hexCharToInt(char n)
std::string m_sensorLabel
See CGenericSensor.
bool waitContinuousSampleFrame(uint8_t &out_prio, uint8_t &out_pdu_format, uint8_t &out_pdu_spec, uint8_t &out_src_address, uint8_t &out_data_length, uint16_t &out_pgn, std::vector< uint8_t > &out_data, std::vector< char > &out_raw_frame)
This class stores a message from a CAN BUS with the protocol J1939.
GLenum GLsizei n
Definition: glext.h:5136
void doProcessSimple(bool &outThereIsObservation, mrpt::obs::CObservationCANBusJ1939 &outObservation, bool &hardwareError)
Specific laser scanner "software drivers" must process here new data from the I/O stream...
A high-performance stopwatch, with typical resolution of nanoseconds.
void open()
Open the port.
Definition: CSerialPort.cpp:86
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:86
Contains classes for various device interfaces.
bool waitIncomingFrame(uint16_t timeout)
STL namespace.
void setBaudRate(int baud)
Changes the serial port baud rate (call prior to &#39;doProcess&#39;); valid values are 9600,38400 and 500000.
GLdouble s
Definition: glext.h:3682
void setConfig(int baudRate, int parity=0, int bits=8, int nStopBits=1, bool enableFlowControl=false)
Changes the configuration of the port.
int read_int(const std::string &section, const std::string &name, int defaultValue, bool failIfNotFound=false) const
unsigned char uint8_t
Definition: rptypes.h:44
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
bool CANBusCloseChannel()
Closes the CAN Channel.
This class allows loading and storing values and vectors of different types from a configuration text...
bool waitForVersion(uint16_t timeout, bool printOutVersion=false)
#define RET_ERROR(msg)
Versatile class for consistent logging and management of output messages.
void setSerialPortName(const std::string &COM_name)
Sets the serial port to open (it is an error to try to change this while open yet).
Definition: CSerialPort.cpp:77
This "software driver" implements the communication protocol for interfacing a SICK LMS 2XX laser sca...
Definition: CCANBusReader.h:57
bool isOpen() const
Returns if port has been correctly open.
This namespace contains representation of robot actions and observations.
size_t Write(const void *Buffer, size_t Count) override
Introduces a pure virtual method responsible for writing to the stream.
GLubyte GLubyte b
Definition: glext.h:6372
void initialize() override
Set-up communication with the laser.
void purgeBuffers()
Purge tx and rx buffers.
uint8_t m_received_frame_buffer[2000]
Definition: CCANBusReader.h:88
bool tryToOpenComms(std::string *err_msg=nullptr)
Tries to open the com port and setup all the LMS protocol.
GLsizei const GLchar ** string
Definition: glext.h:4116
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
void setTimeouts(int ReadIntervalTimeout, int ReadTotalTimeoutMultiplier, int ReadTotalTimeoutConstant, int WriteTotalTimeoutMultiplier, int WriteTotalTimeoutConstant)
Changes the timeouts of the port, in milliseconds.
~CCANBusReader() override
Destructor.
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:62
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
bool sendCommandToCANReader(const uint8_t *cmd, const uint16_t cmd_len, bool wait=true)
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
std::vector< char > m_raw_frame
The ASCII frame.
mrpt::comms::CSerialPort * m_mySerialPort
Will be !=nullptr only if I created it, so I must destroy it at the end.
Definition: CCANBusReader.h:96
uint16_t m_pgn
The Parameter Group Number within this frame.
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &iniSection) override
See the class documentation at the top for expected parameters.
std::string m_com_port
If set to non-empty, the serial port will be attempted to be opened automatically when this class is ...
Definition: CCANBusReader.h:93
int m_com_baudRate
Baudrate: 9600, 38400, 500000.
Definition: CCANBusReader.h:98
uint8_t m_src_address
The address of the source node within this frame.
GLuint res
Definition: glext.h:7385
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:75
void doProcess() override
This method will be invoked at a minimum rate of "process_rate" (Hz)
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
std::vector< uint8_t > m_data
The data within this frame (0-8 bytes)
bool CANBusOpenChannel()
Opens the CAN Channel.
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
Definition: os.cpp:358
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
Definition: common.h:186
bool queryVersion(bool printOutVersion=false)
unsigned int m_nTries_connect
Default = 1.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019