kobuki.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Includes
11  *****************************************************************************/
12 
13 #include <cmath>
14 #include <ecl/math.hpp>
15 #include <ecl/geometry/angle.hpp>
16 #include <ecl/time/sleep.hpp>
17 #include <ecl/converters.hpp>
18 #include <ecl/sigslots.hpp>
19 #include <ecl/geometry/angle.hpp>
20 #include <ecl/time/timestamp.hpp>
21 #include <stdexcept>
22 #include "../../include/kobuki_driver/kobuki.hpp"
23 #include "../../include/kobuki_driver/packet_handler/payload_headers.hpp"
24 
25 /*****************************************************************************
26  ** Namespaces
27  *****************************************************************************/
28 
29 namespace kobuki
30 {
31 
32 /*****************************************************************************
33  ** Implementation [PacketFinder]
34  *****************************************************************************/
35 
37 {
38  unsigned int packet_size(buffer.size());
39  unsigned char cs(0);
40  for (unsigned int i = 2; i < packet_size; i++)
41  {
42  cs ^= buffer[i];
43  }
44  return cs ? false : true;
45 }
46 
47 /*****************************************************************************
48  ** Implementation [Initialisation]
49  *****************************************************************************/
50 
52  shutdown_requested(false)
53  , is_enabled(false)
54  , heading_offset(0.0/0.0)
55  , is_connected(false)
56  , is_alive(false)
57  , version_info_reminder(0)
58  , controller_info_reminder(0)
59  , velocity_commands_debug(4, 0)
60 {
61 }
62 
67 {
68  disable();
69  shutdown_requested = true; // thread's spin() will catch this and terminate
70  thread.join();
71  sig_debug.emit("Device: kobuki driver terminated.");
72 }
73 
74 void Kobuki::init(Parameters &parameters)
75 {
76 
77  if (!parameters.validate())
78  {
79  throw ecl::StandardException(LOC, ecl::ConfigurationError, "Kobuki's parameter settings did not validate.");
80  }
81  this->parameters = parameters;
82  std::string sigslots_namespace = parameters.sigslots_namespace;
83  event_manager.init(sigslots_namespace);
84 
85  // connect signals
86  sig_version_info.connect(sigslots_namespace + std::string("/version_info"));
87  sig_controller_info.connect(sigslots_namespace + std::string("/controller_info"));
88  sig_stream_data.connect(sigslots_namespace + std::string("/stream_data"));
89  sig_raw_data_command.connect(sigslots_namespace + std::string("/raw_data_command"));
90  sig_raw_data_stream.connect(sigslots_namespace + std::string("/raw_data_stream"));
91  sig_raw_control_command.connect(sigslots_namespace + std::string("/raw_control_command"));
92  //sig_serial_timeout.connect(sigslots_namespace+std::string("/serial_timeout"));
93 
94  sig_debug.connect(sigslots_namespace + std::string("/ros_debug"));
95  sig_info.connect(sigslots_namespace + std::string("/ros_info"));
96  sig_warn.connect(sigslots_namespace + std::string("/ros_warn"));
97  sig_error.connect(sigslots_namespace + std::string("/ros_error"));
98  sig_named.connect(sigslots_namespace + std::string("/ros_named"));
99 
100  try {
101  serial.open(parameters.device_port, ecl::BaudRate_115200, ecl::DataBits_8, ecl::StopBits_1, ecl::NoParity); // this will throw exceptions - NotFoundError, OpenError
102  is_connected = true;
103  serial.block(4000); // blocks by default, but just to be clear!
104  }
105  catch (const ecl::StandardException &e)
106  {
107  if (e.flag() == ecl::NotFoundError) {
108  sig_warn.emit("device does not (yet) available, is the usb connected?."); // not a failure mode.
109  } else {
110  throw ecl::StandardException(LOC, e);
111  }
112  }
113 
116  stx.push_back(0xaa);
117  stx.push_back(0x55);
118  packet_finder.configure(sigslots_namespace, stx, etx, 1, 256, 1, true);
120 
121  // in case the user changed these from the defaults
125 
126  /******************************************
127  ** Get Version Info Commands
128  *******************************************/
131 
132  /******************************************
133  ** Get Controller Info Commands
134  *******************************************/
137  //sig_controller_info.emit(); //emit default gain
138 
139  thread.start(&Kobuki::spin, *this);
140 }
141 
142 /*****************************************************************************
143  ** Implementation [Runtime]
144  *****************************************************************************/
156 void Kobuki::lockDataAccess() {
157  data_mutex.lock();
158 }
159 
165  data_mutex.unlock();
166 }
167 
177 void Kobuki::spin()
178 {
179  ecl::TimeStamp last_signal_time;
180  ecl::Duration timeout(0.1);
181  unsigned char buf[256];
182 
183  while (!shutdown_requested)
184  {
185  /*********************
186  ** Checking Connection
187  **********************/
188  if ( !serial.open() ) {
189  try {
190  // this will throw exceptions - NotFoundError is the important one, handle it
192  sig_info.emit("device is connected.");
193  is_connected = true;
194  serial.block(4000); // blocks by default, but just to be clear!
198  }
199  catch (const ecl::StandardException &e)
200  {
201  // windows throws OpenError if not connected
202  if (e.flag() == ecl::NotFoundError) {
203  sig_info.emit("device does not (yet) available on this port, waiting...");
204  } else if (e.flag() == ecl::OpenError) {
205  sig_info.emit("device failed to open, waiting... [" + std::string(e.what()) + "]");
206  } else {
207  // This is bad - some unknown error we're not handling! But at least throw and show what error we came across.
208  throw ecl::StandardException(LOC, e);
209  }
210  ecl::Sleep(5)(); // five seconds
211  is_connected = false;
212  is_alive = false;
213  continue;
214  }
215  }
216 
217  /*********************
218  ** Read Incoming
219  **********************/
220  int n = serial.read((char*)buf, packet_finder.numberOfDataToRead());
221  if (n == 0)
222  {
223  if (is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
224  {
225  is_alive = false;
228  sig_debug.emit("Timed out while waiting for incoming bytes.");
229  }
231  continue;
232  }
233  else
234  {
235  std::ostringstream ostream;
236  ostream << "kobuki_node : serial_read(" << n << ")"
237  << ", packet_finder.numberOfDataToRead(" << packet_finder.numberOfDataToRead() << ")";
238  //sig_debug.emit(ostream.str());
239  sig_named.emit(log("debug", "serial", ostream.str()));
240  // might be useful to send this to a topic if there is subscribers
241  }
242 
243  if (packet_finder.update(buf, n)) // this clears packet finder's buffer and transfers important bytes into it
244  {
245  PacketFinder::BufferType local_buffer;
246  packet_finder.getBuffer(local_buffer); // get a reference to packet finder's buffer.
247  sig_raw_data_stream.emit(local_buffer);
248 
249  packet_finder.getPayload(data_buffer);// get a reference to packet finder's buffer.
250 
251  lockDataAccess();
252  while (data_buffer.size() > 0)
253  {
254  //std::cout << "header_id: " << (unsigned int)data_buffer[0] << " | ";
255  //std::cout << "length: " << (unsigned int)data_buffer[1] << " | ";
256  //std::cout << "remains: " << data_buffer.size() << " | ";
257  //std::cout << "local_buffer: " << local_buffer.size() << " | ";
258  //std::cout << std::endl;
259  switch (data_buffer[0])
260  {
261  // these come with the streamed feedback
262  case Header::CoreSensors:
265  break;
268  break;
269  case Header::Inertia:
271 
272  // Issue #274: use first imu reading as zero heading; update when reseting odometry
273  if (std::isnan(heading_offset) == true)
274  heading_offset = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
275  break;
276  case Header::Cliff:
277  if( !cliff.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
278  break;
279  case Header::Current:
281  break;
282  case Header::GpInput:
285  break;
288  break;
289  // the rest are only included on request
290  case Header::Hardware:
292  //sig_version_info.emit(VersionInfo(firmware.data.version, hardware.data.version));
293  break;
294  case Header::Firmware:
296  try
297  {
298  // Check firmware/driver compatibility; major version must be the same
299  int version_match = firmware.checkMajorVersion();
300  if (version_match < 0) {
301  sig_error.emit("This software is incompatible with Kobuki's firmware.");
302  sig_error.emit("You need to upgrade your firmware. For more information,");
303  sig_error.emit("refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
304  sig_error.emit(" - Firmware Version: " + VersionInfo::toString(firmware.version()));
305  sig_error.emit(" - Recommended Versions: " + VersionInfo::toString(firmware.RECOMMENDED_VERSIONS));
306  shutdown_requested = true;
307  sig_error.emit("Kobuki shutting down.");
308  }
309  else if (version_match > 0) {
310  sig_error.emit("This software is incompatible with Kobuki's firmware.");
311  sig_error.emit("You need to upgrade your software. For more information,");
312  sig_error.emit("refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
313  sig_error.emit(" - Firmware Version: " + VersionInfo::toString(firmware.version()));
314  sig_error.emit(" - Recommended Versions: " + VersionInfo::toString(firmware.RECOMMENDED_VERSIONS));
315  shutdown_requested = true;
316  sig_error.emit("Kobuki shutting down.");
317  }
318  else
319  {
320  // And minor version don't need to, but just make a suggestion
321  version_match = firmware.checkRecommendedVersion();
322  if (version_match < 0) {
323  sig_warn.emit("The firmware does not match any of the recommended versions for this software.");
324  sig_warn.emit("Consider replacing the firmware. For more information,");
325  sig_warn.emit("refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
326  sig_warn.emit(" - Firmware Version: " + VersionInfo::toString(firmware.version()));
327  sig_warn.emit(" - Recommended Versions: " + VersionInfo::toString(firmware.RECOMMENDED_VERSIONS));
328  }
329  else if (version_match > 0) {
330  sig_warn.emit("This software is significantly behind the latest firmware.");
331  sig_warn.emit("Please upgrade your software. For more information,");
332  sig_warn.emit("refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
333  sig_warn.emit(" - Firmware Version: " + VersionInfo::toString(firmware.version()));
334  sig_warn.emit(" - Recommended Versions: " + VersionInfo::toString(firmware.RECOMMENDED_VERSIONS));
335  }
336  }
337  }
338  catch (std::out_of_range& e)
339  {
340  // Wrong version hardcoded on firmware; lowest value is 10000
341  sig_error.emit(std::string("Invalid firmware version number: ").append(e.what()));
342  shutdown_requested = true;
343  }
344  break;
349  sig_info.emit("Version info - Hardware: " + VersionInfo::toString(hardware.data.version)
350  + ". Firmware: " + VersionInfo::toString(firmware.version()));
352  break;
357  break;
358  default: // in the case of unknown or mal-formed sub-payload
360  break;
361  }
362  }
363  //std::cout << "---" << std::endl;
365 
366  is_alive = true;
368  last_signal_time.stamp();
370  sendBaseControlCommand(); // send the command packet to mainboard;
373  }
374  else
375  {
376  // watchdog
377  if (is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
378  {
379  is_alive = false;
380  // do not call here the event manager update, as it generates a spurious offline state
381  }
382  }
383  }
384  sig_error.emit("Driver worker thread shutdown!");
385 }
386 
388 {
389  if (byteStream.size() < 3 ) { /* minimum size of sub-payload is 3; header_id, length, data */
390  sig_named.emit(log("error", "packet", "too small sub-payload detected."));
391  byteStream.clear();
392  } else {
393  std::stringstream ostream;
394  unsigned int header_id = static_cast<unsigned int>(byteStream.pop_front());
395  unsigned int length = static_cast<unsigned int>(byteStream.pop_front());
396  unsigned int remains = byteStream.size();
397  unsigned int to_pop;
398 
399  ostream << "[" << header_id << "]";
400  ostream << "[" << length << "]";
401 
402  ostream << "[";
403  ostream << std::setfill('0') << std::uppercase;
404  ostream << std::hex << std::setw(2) << header_id << " " << std::dec;
405  ostream << std::hex << std::setw(2) << length << " " << std::dec;
406 
407  if (remains < length) to_pop = remains;
408  else to_pop = length;
409 
410  for (unsigned int i = 0; i < to_pop; i++ ) {
411  unsigned int byte = static_cast<unsigned int>(byteStream.pop_front());
412  ostream << std::hex << std::setw(2) << byte << " " << std::dec;
413  }
414  ostream << "]";
415 
416  if (remains < length) sig_named.emit(log("error", "packet", "malformed sub-payload detected. " + ostream.str()));
417  else sig_named.emit(log("debug", "packet", "unknown sub-payload detected. " + ostream.str()));
418  }
419 }
420 
421 
422 /*****************************************************************************
423  ** Implementation [Human Friendly Accessors]
424  *****************************************************************************/
425 
427 {
428  ecl::Angle<double> heading;
429  // raw data angles are in hundredths of a degree, convert to radians.
430  heading = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
431  return ecl::wrap_angle(heading - heading_offset);
432 }
433 
434 double Kobuki::getAngularVelocity() const
435 {
436  // raw data angles are in hundredths of a degree, convert to radians.
437  return (static_cast<double>(inertia.data.angle_rate) / 100.0) * ecl::pi / 180.0;
438 }
439 
440 /*****************************************************************************
441  ** Implementation [Raw Data Accessors]
442  *****************************************************************************/
443 
445 {
446  diff_drive.reset();
447 
448  // Issue #274: use current imu reading as zero heading to emulate reseting gyro
449  heading_offset = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
450 }
451 
452 void Kobuki::getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle,
453  double &wheel_right_angle_rate)
454 {
455  diff_drive.getWheelJointStates(wheel_left_angle, wheel_left_angle_rate, wheel_right_angle, wheel_right_angle_rate);
456 }
457 
469 void Kobuki::updateOdometry(ecl::LegacyPose2D<double> &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
470 {
472  pose_update, pose_update_rates);
473 }
474 
475 /*****************************************************************************
476  ** Commands
477  *****************************************************************************/
478 
479 void Kobuki::setLed(const enum LedNumber &number, const enum LedColour &colour)
480 {
482 }
483 
484 void Kobuki::setDigitalOutput(const DigitalOutput &digital_output) {
486 }
487 
488 void Kobuki::setExternalPower(const DigitalOutput &digital_output) {
490 }
491 
492 //void Kobuki::playSound(const enum Sounds &number)
493 //{
494 // sendCommand(Command::PlaySound(number, kobuki_command.data));
495 //}
496 
497 void Kobuki::playSoundSequence(const enum SoundSequences &number)
498 {
500 }
501 
502 bool Kobuki::setControllerGain(const unsigned char &type, const unsigned int &p_gain,
503  const unsigned int &i_gain, const unsigned int &d_gain)
504 {
505  if ((firmware.majorVersion() < 2) && (firmware.minorVersion() < 2)) {
506  sig_warn.emit("Your robot firmware will need to be upgraded to get/set of PID gains." \
507  "Refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
508  sig_warn.emit("Robot firmware version is " + VersionInfo::toString(firmware.version())
509  + ". You will need at least 1.2.x");
510  return false;
511  }
512 
513  sendCommand(Command::SetControllerGain(type, p_gain, i_gain, d_gain));
514  return true;
515 }
516 
518 {
519  if ((firmware.majorVersion() < 2) && (firmware.minorVersion() < 2)) {
520  sig_warn.emit("Your robot firmware will need to be upgraded to get/set PID gains." \
521  "Refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
522  sig_warn.emit("Robot firmware version is " + VersionInfo::toString(firmware.version())
523  + ". You will need at least 1.2.x");
524  return false;
525  }
526 
528  return true;
529 }
530 
531 void Kobuki::setBaseControl(const double &linear_velocity, const double &angular_velocity)
532 {
533  diff_drive.setVelocityCommands(linear_velocity, angular_velocity);
534 }
535 
537 {
538  std::vector<double> velocity_commands_received;
540  velocity_commands_received=acceleration_limiter.limit(diff_drive.pointVelocity());
541  } else {
542  velocity_commands_received=diff_drive.pointVelocity();
543  }
544  diff_drive.velocityCommands(velocity_commands_received);
545  std::vector<short> velocity_commands = diff_drive.velocityCommands();
546  // std::cout << "speed: " << velocity_commands[0] << ", radius: " << velocity_commands[1] << std::endl;
547  sendCommand(Command::SetVelocityControl(velocity_commands[0], velocity_commands[1]));
548 
549  //experimental; send raw control command and received command velocity
550  velocity_commands_debug=velocity_commands;
551  velocity_commands_debug.push_back((short)(velocity_commands_received[0]*1000.0));
552  velocity_commands_debug.push_back((short)(velocity_commands_received[1]*1000.0));
554 }
555 
566 void Kobuki::sendCommand(Command command)
567 {
568  if( !is_alive || !is_connected ) {
569  //need to do something
570  sig_debug.emit("Device state is not ready yet.");
571  if( !is_alive ) sig_debug.emit(" - Device is not alive.");
572  if( !is_connected ) sig_debug.emit(" - Device is not connected.");
573  //std::cout << is_enabled << ", " << is_alive << ", " << is_connected << std::endl;
574  return;
575  }
576  command_mutex.lock();
578 
579  if (!command.serialise(command_buffer))
580  {
581  sig_error.emit("command serialise failed.");
582  }
584  unsigned char checksum = 0;
585  for (unsigned int i = 2; i < command_buffer.size(); i++)
586  checksum ^= (command_buffer[i]);
587 
588  command_buffer.push_back(checksum);
589  //check_device();
590  serial.write((const char*)&command_buffer[0], command_buffer.size());
591 
593  command_mutex.unlock();
594 }
595 
596 bool Kobuki::enable()
597 {
598  is_enabled = true;
599  return true;
600 }
601 
602 bool Kobuki::disable()
603 {
604  setBaseControl(0.0f, 0.0f);
606  is_enabled = false;
607  return true;
608 }
609 
618 void Kobuki::printSigSlotConnections() const {
619 
620  std::cout << "========== Void ==========" << std::endl;
622  std::cout << "========= String =========" << std::endl;
624  std::cout << "====== Button Event ======" << std::endl;
626  std::cout << "====== Bumper Event ======" << std::endl;
628  std::cout << "====== Cliff Event =======" << std::endl;
630  std::cout << "====== Wheel Event =======" << std::endl;
632  std::cout << "====== Power Event =======" << std::endl;
634  std::cout << "====== Input Event =======" << std::endl;
636  std::cout << "====== Robot Event =======" << std::endl;
638  std::cout << "====== VersionInfo =======" << std::endl;
640  std::cout << "===== Command Buffer =====" << std::endl;
642 }
643 
644 } // namespace kobuki
kobuki::Kobuki::sig_error
ecl::Signal< const std::string & > sig_error
Definition: kobuki.hpp:269
ecl::Signal::connect
void connect(const std::string &topic)
ecl::OpenError
OpenError
kobuki::Parameters::sigslots_namespace
std::string sigslots_namespace
The first part of a sigslot connection namespace ["/kobuki"].
Definition: parameters.hpp:69
kobuki::LedNumber
LedNumber
Definition: led_array.hpp:39
ecl::NotFoundError
NotFoundError
kobuki::Kobuki::sig_raw_data_stream
ecl::Signal< PacketFinder::BufferType & > sig_raw_data_stream
Definition: kobuki.hpp:272
kobuki::Inertia::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: inertia.hpp:72
kobuki::Kobuki::parameters
Parameters parameters
Definition: kobuki.hpp:201
kobuki::Kobuki::core_sensors
CoreSensors core_sensors
Definition: kobuki.hpp:212
kobuki::Kobuki::setLed
void setLed(const enum LedNumber &number, const enum LedColour &colour)
Definition: kobuki.cpp:483
kobuki::DiffDrive::getWheelJointStates
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
Definition: diff_drive.cpp:121
kobuki::Kobuki::getHeading
ecl::Angle< double > getHeading() const
Definition: kobuki.cpp:430
kobuki::UniqueDeviceID::Data::udid1
uint32_t udid1
Definition: unique_device_id.hpp:55
ecl::DataBits_8
DataBits_8
kobuki::EventManager::update
void update(const CoreSensors::Data &new_state, const std::vector< uint16_t > &cliff_data)
Definition: event_manager.cpp:47
ecl::SigSlotsManager::printStatistics
static void printStatistics()
kobuki::PacketFinderBase::BufferType
ecl::PushAndPop< unsigned char > BufferType
Definition: packet_finder.hpp:91
kobuki::PacketFinderBase::getPayload
void getPayload(BufferType &bufferRef)
Definition: packet_finder.cpp:119
kobuki::Firmware::RECOMMENDED_VERSIONS
static const std::vector< uint32_t > RECOMMENDED_VERSIONS
Definition: firmware.hpp:54
kobuki::DockIR::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: dock_ir.hpp:67
kobuki::Battery::low
static double low
Definition: battery.hpp:79
kobuki::Parameters::enable_acceleration_limiter
bool enable_acceleration_limiter
Enable or disable the acceleration limiter [true].
Definition: parameters.hpp:71
kobuki::Kobuki::thread
ecl::Thread thread
Definition: kobuki.hpp:184
kobuki
Definition: command.hpp:31
kobuki::Cliff::Data::bottom
std::vector< uint16_t > bottom
Definition: cliff.hpp:56
kobuki::Kobuki::dock_ir
DockIR dock_ir
Definition: kobuki.hpp:214
kobuki::DigitalOutput
Definition: digital_output.hpp:33
kobuki::Kobuki::acceleration_limiter
AccelerationLimiter acceleration_limiter
Definition: kobuki.hpp:207
kobuki::UniqueDeviceID::data
struct kobuki::UniqueDeviceID::Data data
kobuki::ThreeAxisGyro::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: three_axis_gyro.hpp:70
kobuki::Command::SetDigitalOutput
static Command SetDigitalOutput(const DigitalOutput &digital_output, Command::Data &current_data)
Definition: command.cpp:88
kobuki::Command::data
Data data
Definition: command.hpp:138
kobuki::LedColour
LedColour
Definition: led_array.hpp:44
kobuki::UniqueDeviceID::Data::udid0
uint32_t udid0
Definition: unique_device_id.hpp:54
ecl::pi
const double pi
kobuki::Header::ThreeAxisGyro
@ ThreeAxisGyro
Definition: payload_headers.hpp:54
kobuki::Kobuki::setControllerGain
bool setControllerGain(const unsigned char &type, const unsigned int &p_gain, const unsigned int &i_gain, const unsigned int &d_gain)
Definition: kobuki.cpp:506
ecl::Signal::emit
void emit(Data data)
kobuki::AccelerationLimiter::init
void init(bool enable_acceleration_limiter, double linear_acceleration_max_=0.5, double angular_acceleration_max_=3.5, double linear_deceleration_max_=-0.5 *1.2, double angular_deceleration_max_=-3.5 *1.2)
Definition: acceleration_limiter.hpp:77
kobuki::Kobuki::sig_debug
ecl::Signal< const std::string & > sig_debug
Definition: kobuki.hpp:269
kobuki::Kobuki::shutdown_requested
bool shutdown_requested
Definition: kobuki.hpp:185
sigslots.hpp
kobuki::Kobuki::fixPayload
void fixPayload(ecl::PushAndPop< unsigned char > &byteStream)
Definition: kobuki.cpp:391
kobuki::GpInput::data
struct kobuki::GpInput::Data data
ecl::BaudRate_115200
BaudRate_115200
kobuki::Kobuki::serial
ecl::Serial serial
Definition: kobuki.hpp:224
kobuki::DiffDrive::velocityCommands
void velocityCommands(const double &vx, const double &wz)
Definition: diff_drive.cpp:140
kobuki::Kobuki::version_info_reminder
int version_info_reminder
Definition: kobuki.hpp:229
sleep.hpp
kobuki::VersionInfo::toString
static std::string toString(const uint32_t &version)
Definition: version_info.hpp:82
kobuki::Command::GetVersionInfo
static Command GetVersionInfo()
Definition: command.cpp:150
kobuki::Kobuki::enable
bool enable()
Definition: kobuki.cpp:600
kobuki::Kobuki::firmware
Firmware firmware
Definition: kobuki.hpp:219
kobuki::GpInput::Data::digital_input
uint16_t digital_input
Definition: gp_input.hpp:55
kobuki::Kobuki::getWheelJointStates
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
Definition: kobuki.cpp:456
kobuki::Kobuki::printSigSlotConnections
void printSigSlotConnections() const
Print a list of all relevant sigslot connections.
Definition: kobuki.cpp:622
ecl::LegacyPose2D< double >
kobuki::Kobuki::init
void init(Parameters &parameters)
Definition: kobuki.cpp:78
kobuki::Kobuki::velocity_commands_debug
std::vector< short > velocity_commands_debug
Definition: kobuki.hpp:244
kobuki::Firmware::majorVersion
int majorVersion() const
Definition: firmware.hpp:80
kobuki::Header::Firmware
@ Firmware
Definition: payload_headers.hpp:54
kobuki::Battery::capacity
static double capacity
Definition: battery.hpp:78
kobuki::Kobuki::getControllerGain
bool getControllerGain()
Definition: kobuki.cpp:521
kobuki::Header::DockInfraRed
@ DockInfraRed
Definition: payload_headers.hpp:51
kobuki::GpInput::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: gp_input.hpp:80
kobuki::Firmware::version
const uint32_t & version() const
Definition: firmware.hpp:79
kobuki::Kobuki::sig_controller_info
ecl::Signal sig_controller_info
Definition: kobuki.hpp:267
ecl::PushAndPop::push_back
void push_back(const Type &datum)
f
void f(int i)
ecl::wrap_angle
ecl_geometry_PUBLIC double wrap_angle(const double &angle)
kobuki::Header::ControllerInfo
@ ControllerInfo
Definition: payload_headers.hpp:56
kobuki::CoreSensors::data
struct kobuki::CoreSensors::Data data
kobuki::PacketFinder::checkSum
bool checkSum()
Definition: kobuki.cpp:40
kobuki::EventManager::init
void init(const std::string &sigslots_namespace)
Definition: event_manager.cpp:32
kobuki::UniqueDeviceID::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: unique_device_id.hpp:70
kobuki::Header::GpInput
@ GpInput
Definition: payload_headers.hpp:54
math.hpp
kobuki::Command::SetLedArray
static Command SetLedArray(const enum LedNumber &number, const enum LedColour &colour, Command::Data &current_data)
Definition: command.cpp:57
ecl::NoParity
NoParity
kobuki::Kobuki::unique_device_id
UniqueDeviceID unique_device_id
Definition: kobuki.hpp:220
kobuki::Header::UniqueDeviceID
@ UniqueDeviceID
Definition: payload_headers.hpp:56
kobuki::DiffDrive::setVelocityCommands
void setVelocityCommands(const double &vx, const double &wz)
Definition: diff_drive.cpp:131
kobuki::Kobuki::data_buffer
PacketFinder::BufferType data_buffer
Definition: kobuki.hpp:226
kobuki::Battery::dangerous
static double dangerous
Definition: battery.hpp:80
kobuki::Kobuki::updateOdometry
void updateOdometry(ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
Use the current sensor data (encoders and gyro) to calculate an update for the odometry.
Definition: kobuki.cpp:473
kobuki::Kobuki::command_buffer
Command::Buffer command_buffer
Definition: kobuki.hpp:243
kobuki::Kobuki::setDigitalOutput
void setDigitalOutput(const DigitalOutput &digital_output)
Definition: kobuki.cpp:488
kobuki::Hardware::Data::version
uint32_t version
Definition: hardware.hpp:53
kobuki::CoreSensors::Data::left_encoder
uint16_t left_encoder
Definition: core_sensors.hpp:59
kobuki::Kobuki::sig_info
ecl::Signal< const std::string & > sig_info
Definition: kobuki.hpp:269
kobuki::Header::CoreSensors
@ CoreSensors
Definition: payload_headers.hpp:51
kobuki::Kobuki::cliff
Cliff cliff
Definition: kobuki.hpp:215
LOC
#define LOC
kobuki::Kobuki::lockDataAccess
void lockDataAccess()
Definition: kobuki.cpp:160
kobuki::Kobuki::hardware
Hardware hardware
Definition: kobuki.hpp:218
kobuki::Kobuki::sig_version_info
ecl::Signal< const VersionInfo & > sig_version_info
Definition: kobuki.hpp:268
kobuki::Kobuki::inertia
Inertia inertia
Definition: kobuki.hpp:213
kobuki::Kobuki::setExternalPower
void setExternalPower(const DigitalOutput &digital_output)
Definition: kobuki.cpp:492
kobuki::Kobuki::unlockDataAccess
void unlockDataAccess()
Definition: kobuki.cpp:168
kobuki::DiffDrive::reset
void reset()
Definition: diff_drive.cpp:112
kobuki::Firmware::checkMajorVersion
int checkMajorVersion() const
Definition: firmware.cpp:91
ecl::StandardException
kobuki::Kobuki::kobuki_command
Command kobuki_command
Definition: kobuki.hpp:242
kobuki::Command::SetExternalPower
static Command SetExternalPower(const DigitalOutput &digital_output, Command::Data &current_data)
Definition: command.cpp:119
kobuki::PacketFinderBase::buffer
BufferType buffer
Definition: packet_finder.hpp:114
kobuki::PacketFinderBase::update
virtual bool update(const unsigned char *incoming, unsigned int numberOfIncoming)
Definition: packet_finder.cpp:135
kobuki::DiffDrive::pointVelocity
std::vector< double > pointVelocity() const
Definition: diff_drive.cpp:190
kobuki::Command::PlaySoundSequence
static Command PlaySoundSequence(const enum SoundSequences &number, Command::Data &current_data)
Definition: command.cpp:139
kobuki::Kobuki::spin
void spin()
Performs a scan looking for incoming data packets.
Definition: kobuki.cpp:181
kobuki::Hardware::data
struct kobuki::Hardware::Data data
kobuki::Kobuki::command_mutex
ecl::Mutex command_mutex
Definition: kobuki.hpp:237
kobuki::Kobuki::is_alive
bool is_alive
Definition: kobuki.hpp:227
kobuki::Header::Inertia
@ Inertia
Definition: payload_headers.hpp:51
kobuki::ControllerInfo::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: controller_info.hpp:71
kobuki::AccelerationLimiter::isEnabled
bool isEnabled() const
Definition: acceleration_limiter.hpp:88
ecl::Duration
TimeStamp Duration
kobuki::Parameters
Parameter list and validator for the kobuki.
Definition: parameters.hpp:42
kobuki::Kobuki::current
Current current
Definition: kobuki.hpp:216
kobuki::Kobuki::~Kobuki
~Kobuki()
Definition: kobuki.cpp:70
kobuki::Kobuki::controller_info
ControllerInfo controller_info
Definition: kobuki.hpp:222
kobuki::Kobuki::sig_raw_control_command
ecl::Signal< const std::vector< short > & > sig_raw_control_command
Definition: kobuki.hpp:273
kobuki::Kobuki::playSoundSequence
void playSoundSequence(const enum SoundSequences &number)
Definition: kobuki.cpp:501
angle.hpp
kobuki::Kobuki::heading_offset
double heading_offset
Definition: kobuki.hpp:196
kobuki::Firmware::minorVersion
int minorVersion() const
Definition: firmware.hpp:81
kobuki::Kobuki::resetOdometry
void resetOdometry()
Definition: kobuki.cpp:448
kobuki::Parameters::validate
bool validate()
A validator to ensure the user has supplied correct/sensible parameter values.
Definition: parameters.hpp:88
kobuki::Inertia::Data::angle_rate
int16_t angle_rate
Definition: inertia.hpp:54
kobuki::AccelerationLimiter::limit
std::vector< double > limit(const std::vector< double > &command)
Limits the input velocity commands if gatekeeper is enabled.
Definition: acceleration_limiter.hpp:97
kobuki::Hardware::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: hardware.hpp:66
kobuki::Kobuki::controller_info_reminder
int controller_info_reminder
Definition: kobuki.hpp:230
kobuki::Kobuki::sig_named
ecl::Signal< const std::vector< std::string > & > sig_named
Definition: kobuki.hpp:270
kobuki::Kobuki::disable
bool disable()
Definition: kobuki.cpp:606
kobuki::PacketFinderBase::configure
void configure(const std::string &sigslots_namespace, const BufferType &putStx, const BufferType &putEtx, unsigned int sizeLengthField, unsigned int sizeMaxPayload, unsigned int sizeChecksumField, bool variableSizePayload)
Definition: packet_finder.cpp:41
kobuki::Inertia::data
struct kobuki::Inertia::Data data
kobuki::Inertia::Data::angle
int16_t angle
Definition: inertia.hpp:53
kobuki::Command::SetVelocityControl
static Command SetVelocityControl(DiffDrive &diff_drive)
Definition: command.cpp:161
kobuki::Header::Hardware
@ Hardware
Definition: payload_headers.hpp:54
kobuki::Kobuki::getAngularVelocity
double getAngularVelocity() const
Definition: kobuki.cpp:438
ecl::StandardException::what
const char * what() const
kobuki::PacketFinderBase::getBuffer
void getBuffer(BufferType &bufferRef)
Definition: packet_finder.cpp:114
ecl::PushAndPop::pop_front
Type pop_front()
kobuki::Cliff::data
struct kobuki::Cliff::Data data
kobuki::Command::resetBuffer
void resetBuffer(Buffer &buffer)
Definition: command.cpp:206
kobuki::CoreSensors::Data::right_encoder
uint16_t right_encoder
Definition: core_sensors.hpp:60
kobuki::PacketFinderBase::numberOfDataToRead
unsigned int numberOfDataToRead()
Definition: packet_finder.cpp:82
ecl::StopBits_1
StopBits_1
ecl::PushAndPop< unsigned char >
kobuki::Kobuki::setBaseControl
void setBaseControl(const double &linear_velocity, const double &angular_velocity)
Definition: kobuki.cpp:535
kobuki::Header::Cliff
@ Cliff
Definition: payload_headers.hpp:51
kobuki::Command::SetControllerGain
static Command SetControllerGain(const unsigned char &type, const unsigned int &p_gain, const unsigned int &i_gain, const unsigned int &d_gain)
Definition: command.cpp:180
kobuki::UniqueDeviceID::Data::udid2
uint32_t udid2
Definition: unique_device_id.hpp:56
kobuki::Parameters::battery_dangerous
double battery_dangerous
Threshold for battery level in danger of depletion [13.2V].
Definition: parameters.hpp:74
kobuki::Cliff::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: cliff.hpp:69
kobuki::Kobuki::packet_finder
PacketFinder packet_finder
Definition: kobuki.hpp:225
kobuki::Kobuki::three_axis_gyro
ThreeAxisGyro three_axis_gyro
Definition: kobuki.hpp:221
kobuki::Kobuki::data_mutex
ecl::Mutex data_mutex
Definition: kobuki.hpp:241
kobuki::Kobuki::Kobuki
Kobuki()
Definition: kobuki.cpp:55
kobuki::Header::Current
@ Current
Definition: payload_headers.hpp:51
kobuki::Kobuki::is_enabled
bool is_enabled
Definition: kobuki.hpp:191
ecl::Angle
kobuki::Kobuki::sig_stream_data
ecl::Signal sig_stream_data
Definition: kobuki.hpp:267
kobuki::Firmware::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: firmware.cpp:48
kobuki::CoreSensors::Data::time_stamp
uint16_t time_stamp
Definition: core_sensors.hpp:55
kobuki::Current::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: current.hpp:71
kobuki::Parameters::battery_low
double battery_low
Threshold for battery level warnings [14.0V].
Definition: parameters.hpp:73
kobuki::Firmware::checkRecommendedVersion
int checkRecommendedVersion() const
Definition: firmware.cpp:99
converters.hpp
kobuki::Kobuki::event_manager
EventManager event_manager
Definition: kobuki.hpp:249
kobuki::Kobuki::sendCommand
void sendCommand(Command command)
Send the prepared command to the serial port.
Definition: kobuki.cpp:570
kobuki::Kobuki::sig_raw_data_command
ecl::Signal< Command::Buffer & > sig_raw_data_command
Definition: kobuki.hpp:271
kobuki::DiffDrive::update
void update(const uint16_t &time_stamp, const uint16_t &left_encoder, const uint16_t &right_encoder, ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
Updates the odometry from firmware stamps and encoders.
Definition: diff_drive.cpp:59
ecl::PushAndPop::size
unsigned int size() const
kobuki::Parameters::device_port
std::string device_port
The serial device port name [/dev/kobuki].
Definition: parameters.hpp:68
kobuki::Kobuki::sig_warn
ecl::Signal< const std::string & > sig_warn
Definition: kobuki.hpp:269
kobuki::CoreSensors::deserialise
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
Definition: core_sensors.cpp:50
kobuki::Kobuki::gp_input
GpInput gp_input
Definition: kobuki.hpp:217
kobuki::Command::GetControllerGain
static Command GetControllerGain()
Definition: command.cpp:192
kobuki::Parameters::battery_capacity
double battery_capacity
Capacity voltage of the battery [16.5V].
Definition: parameters.hpp:72
kobuki::Kobuki::log
std::vector< std::string > log(std::string msg)
Definition: kobuki.hpp:254
timestamp.hpp
kobuki::SoundSequences
SoundSequences
Definition: sound.hpp:36
kobuki::Kobuki::diff_drive
DiffDrive diff_drive
Definition: kobuki.hpp:190
ecl::PushAndPop::clear
void clear()
ecl::ConfigurationError
ConfigurationError
kobuki::Kobuki::sendBaseControlCommand
void sendBaseControlCommand()
Definition: kobuki.cpp:540
kobuki::VersionInfo
Definition: version_info.hpp:45
kobuki::Kobuki::is_connected
bool is_connected
Definition: kobuki.hpp:202


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Wed Mar 2 2022 00:26:14