kobuki.cpp
Go to the documentation of this file.
00001 
00009 /*****************************************************************************
00010  ** Includes
00011  *****************************************************************************/
00012 
00013 #include <cmath>
00014 #include <ecl/math.hpp>
00015 #include <ecl/geometry/angle.hpp>
00016 #include <ecl/time/sleep.hpp>
00017 #include <ecl/converters.hpp>
00018 #include <ecl/sigslots.hpp>
00019 #include <ecl/geometry/angle.hpp>
00020 #include <ecl/time/timestamp.hpp>
00021 #include <stdexcept>
00022 #include "../../include/kobuki_driver/kobuki.hpp"
00023 #include "../../include/kobuki_driver/packet_handler/payload_headers.hpp"
00024 
00025 /*****************************************************************************
00026  ** Namespaces
00027  *****************************************************************************/
00028 
00029 namespace kobuki
00030 {
00031 
00032 /*****************************************************************************
00033  ** Implementation [PacketFinder]
00034  *****************************************************************************/
00035 
00036 bool PacketFinder::checkSum()
00037 {
00038   unsigned int packet_size(buffer.size());
00039   unsigned char cs(0);
00040   for (unsigned int i = 2; i < packet_size; i++)
00041   {
00042     cs ^= buffer[i];
00043   }
00044   return cs ? false : true;
00045 }
00046 
00047 /*****************************************************************************
00048  ** Implementation [Initialisation]
00049  *****************************************************************************/
00050 
00051 Kobuki::Kobuki() :
00052     shutdown_requested(false)
00053     , is_enabled(false)
00054     , is_connected(false)
00055     , is_alive(false)
00056     , version_info_reminder(0)
00057     , controller_info_reminder(0)
00058     , heading_offset(0.0/0.0)
00059     , velocity_commands_debug(4, 0)
00060 {
00061 }
00062 
00066 Kobuki::~Kobuki()
00067 {
00068   disable();
00069   shutdown_requested = true; // thread's spin() will catch this and terminate
00070   thread.join();
00071   sig_debug.emit("Device: kobuki driver terminated.");
00072 }
00073 
00074 void Kobuki::init(Parameters &parameters) throw (ecl::StandardException)
00075 {
00076 
00077   if (!parameters.validate())
00078   {
00079     throw ecl::StandardException(LOC, ecl::ConfigurationError, "Kobuki's parameter settings did not validate.");
00080   }
00081   this->parameters = parameters;
00082   std::string sigslots_namespace = parameters.sigslots_namespace;
00083   event_manager.init(sigslots_namespace);
00084 
00085   // connect signals
00086   sig_version_info.connect(sigslots_namespace + std::string("/version_info"));
00087   sig_controller_info.connect(sigslots_namespace + std::string("/controller_info"));
00088   sig_stream_data.connect(sigslots_namespace + std::string("/stream_data"));
00089   sig_raw_data_command.connect(sigslots_namespace + std::string("/raw_data_command"));
00090   sig_raw_data_stream.connect(sigslots_namespace + std::string("/raw_data_stream"));
00091   sig_raw_control_command.connect(sigslots_namespace + std::string("/raw_control_command"));
00092   //sig_serial_timeout.connect(sigslots_namespace+std::string("/serial_timeout"));
00093 
00094   sig_debug.connect(sigslots_namespace + std::string("/ros_debug"));
00095   sig_info.connect(sigslots_namespace + std::string("/ros_info"));
00096   sig_warn.connect(sigslots_namespace + std::string("/ros_warn"));
00097   sig_error.connect(sigslots_namespace + std::string("/ros_error"));
00098   sig_named.connect(sigslots_namespace + std::string("/ros_named"));
00099 
00100   try {
00101     serial.open(parameters.device_port, ecl::BaudRate_115200, ecl::DataBits_8, ecl::StopBits_1, ecl::NoParity);  // this will throw exceptions - NotFoundError, OpenError
00102     is_connected = true;
00103     serial.block(4000); // blocks by default, but just to be clear!
00104   }
00105   catch (const ecl::StandardException &e)
00106   {
00107     if (e.flag() == ecl::NotFoundError) {
00108       sig_warn.emit("device does not (yet) available, is the usb connected?."); // not a failure mode.
00109     } else {
00110       throw ecl::StandardException(LOC, e);
00111     }
00112   }
00113 
00114   ecl::PushAndPop<unsigned char> stx(2, 0);
00115   ecl::PushAndPop<unsigned char> etx(1);
00116   stx.push_back(0xaa);
00117   stx.push_back(0x55);
00118   packet_finder.configure(sigslots_namespace, stx, etx, 1, 256, 1, true);
00119   acceleration_limiter.init(parameters.enable_acceleration_limiter);
00120 
00121   // in case the user changed these from the defaults
00122   Battery::capacity = parameters.battery_capacity;
00123   Battery::low = parameters.battery_low;
00124   Battery::dangerous = parameters.battery_dangerous;
00125 
00126   /******************************************
00127    ** Get Version Info Commands
00128    *******************************************/
00129   version_info_reminder = 10;
00130   sendCommand(Command::GetVersionInfo());
00131 
00132   /******************************************
00133    ** Get Controller Info Commands
00134    *******************************************/
00135   controller_info_reminder = 10;
00136   sendCommand(Command::GetControllerGain());
00137   //sig_controller_info.emit(); //emit default gain
00138 
00139   thread.start(&Kobuki::spin, *this);
00140 }
00141 
00142 /*****************************************************************************
00143  ** Implementation [Runtime]
00144  *****************************************************************************/
00156 void Kobuki::lockDataAccess() {
00157   data_mutex.lock();
00158 }
00159 
00164 void Kobuki::unlockDataAccess() {
00165   data_mutex.unlock();
00166 }
00167 
00177 void Kobuki::spin()
00178 {
00179   ecl::TimeStamp last_signal_time;
00180   ecl::Duration timeout(0.1);
00181   unsigned char buf[256];
00182 
00183   /*********************
00184    ** Simulation Params
00185    **********************/
00186 
00187   while (!shutdown_requested)
00188   {
00189     /*********************
00190      ** Checking Connection
00191      **********************/
00192     if ( !serial.open() ) {
00193       try {
00194         // this will throw exceptions - NotFoundError is the important one, handle it
00195         serial.open(parameters.device_port, ecl::BaudRate_115200, ecl::DataBits_8, ecl::StopBits_1, ecl::NoParity);
00196         sig_info.emit("device is connected.");
00197         is_connected = true;
00198         serial.block(4000); // blocks by default, but just to be clear!
00199         event_manager.update(is_connected, is_alive);
00200         version_info_reminder = 10;
00201         controller_info_reminder = 10;
00202       }
00203       catch (const ecl::StandardException &e)
00204       {
00205         // windows throws OpenError if not connected
00206         if (e.flag() == ecl::NotFoundError) {
00207           sig_info.emit("device does not (yet) available on this port, waiting...");
00208         } else if (e.flag() == ecl::OpenError) {
00209           sig_info.emit("device failed to open, waiting... [" + std::string(e.what()) + "]");
00210         } else {
00211           // This is bad - some unknown error we're not handling! But at least throw and show what error we came across.
00212           throw ecl::StandardException(LOC, e);
00213         }
00214         ecl::Sleep(5)(); // five seconds
00215         is_connected = false;
00216         is_alive = false;
00217         continue;
00218       }
00219     }
00220 
00221     /*********************
00222      ** Read Incoming
00223      **********************/
00224     int n = serial.read((char*)buf, packet_finder.numberOfDataToRead());
00225     if (n == 0)
00226     {
00227       if (is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
00228       {
00229         is_alive = false;
00230         version_info_reminder = 10;
00231         controller_info_reminder = 10;
00232         sig_debug.emit("Timed out while waiting for incoming bytes.");
00233       }
00234       event_manager.update(is_connected, is_alive);
00235       continue;
00236     }
00237     else
00238     {
00239       std::ostringstream ostream;
00240       ostream << "kobuki_node : serial_read(" << n << ")"
00241         << ", packet_finder.numberOfDataToRead(" << packet_finder.numberOfDataToRead() << ")";
00242       //sig_debug.emit(ostream.str());
00243       sig_named.emit(log("debug", "serial", ostream.str()));
00244       // might be useful to send this to a topic if there is subscribers
00245     }
00246 
00247     if (packet_finder.update(buf, n)) // this clears packet finder's buffer and transfers important bytes into it
00248     {
00249       PacketFinder::BufferType local_buffer;
00250       packet_finder.getBuffer(local_buffer); // get a reference to packet finder's buffer.
00251       sig_raw_data_stream.emit(local_buffer);
00252 
00253       packet_finder.getPayload(data_buffer);// get a reference to packet finder's buffer.
00254 
00255       lockDataAccess();
00256       while (data_buffer.size() > 0)
00257       {
00258         //std::cout << "header_id: " << (unsigned int)data_buffer[0] << " | ";
00259         //std::cout << "length: " << (unsigned int)data_buffer[1] << " | ";
00260         //std::cout << "remains: " << data_buffer.size() << " | ";
00261         //std::cout << "local_buffer: " << local_buffer.size() << " | ";
00262         //std::cout << std::endl;
00263         switch (data_buffer[0])
00264         {
00265           // these come with the streamed feedback
00266           case Header::CoreSensors:
00267             if( !core_sensors.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00268             event_manager.update(core_sensors.data, cliff.data.bottom);
00269             break;
00270           case Header::DockInfraRed:
00271             if( !dock_ir.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00272             break;
00273           case Header::Inertia:
00274             if( !inertia.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00275 
00276             // Issue #274: use first imu reading as zero heading; update when reseting odometry
00277             if (std::isnan(heading_offset) == true)
00278               heading_offset = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
00279             break;
00280           case Header::Cliff:
00281             if( !cliff.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00282             break;
00283           case Header::Current:
00284             if( !current.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00285             break;
00286           case Header::GpInput:
00287             if( !gp_input.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00288             event_manager.update(gp_input.data.digital_input);
00289             break;
00290           case Header::ThreeAxisGyro:
00291             if( !three_axis_gyro.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00292             break;
00293           // the rest are only included on request
00294           case Header::Hardware:
00295             if( !hardware.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00296             //sig_version_info.emit(VersionInfo(firmware.data.version, hardware.data.version));
00297             break;
00298           case Header::Firmware:
00299             if( !firmware.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00300             try
00301             {
00302               // Check firmware/driver compatibility; major version must be the same
00303               int version_match = firmware.check_major_version();
00304               if (version_match < 0) {
00305                 sig_error.emit("Robot firmware is outdated and needs to be upgraded. Consult how-to on: " \
00306                                "http://kobuki.yujinrobot.com/home-en/documentation/howtos/upgrading-firmware");
00307                 sig_error.emit("Robot firmware version is " + VersionInfo::toString(firmware.data.version)
00308                              + "; latest version is " + firmware.current_version());
00309                 shutdown_requested = true;
00310               }
00311               else if (version_match > 0) {
00312                 sig_error.emit("Driver version isn't not compatible with robot firmware. Please upgrade driver");
00313                 shutdown_requested = true;
00314               }
00315               else
00316               {
00317                 // And minor version don't need to, but just make a suggestion
00318                 version_match = firmware.check_minor_version();
00319                 if (version_match < 0) {
00320                   sig_warn.emit("Robot firmware is outdated; we suggest you to upgrade it " \
00321                                 "to benefit from the latest features. Consult how-to on: "  \
00322                                 "http://kobuki.yujinrobot.com/home-en/documentation/howtos/upgrading-firmware");
00323                   sig_warn.emit("Robot firmware version is " + VersionInfo::toString(firmware.data.version)
00324                               + "; latest version is " + firmware.current_version());
00325                 }
00326                 else if (version_match > 0) {
00327                   // Driver version is outdated; maybe we should also suggest to upgrade it, but this is not a typical case
00328                 }
00329               }
00330             }
00331             catch (std::out_of_range& e)
00332             {
00333               // Wrong version hardcoded on firmware; lowest value is 10000
00334               sig_error.emit(std::string("Invalid firmware version number: ").append(e.what()));
00335               shutdown_requested = true;
00336             }
00337             break;
00338           case Header::UniqueDeviceID:
00339             if( !unique_device_id.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00340             sig_version_info.emit( VersionInfo( firmware.data.version, hardware.data.version
00341                 , unique_device_id.data.udid0, unique_device_id.data.udid1, unique_device_id.data.udid2 ));
00342             sig_info.emit("Version info - Hardware: " + VersionInfo::toString(hardware.data.version)
00343                                      + ". Firmware: " + VersionInfo::toString(firmware.data.version));
00344             version_info_reminder = 0;
00345             break;
00346           case Header::ControllerInfo:
00347             if( !controller_info.deserialise(data_buffer) ) { fixPayload(data_buffer); break; }
00348             sig_controller_info.emit();
00349             controller_info_reminder = 0;
00350             break;
00351           default: // in the case of unknown or mal-formed sub-payload
00352             fixPayload(data_buffer);
00353             break;
00354         }
00355       }
00356       //std::cout << "---" << std::endl;
00357       unlockDataAccess();
00358 
00359       is_alive = true;
00360       event_manager.update(is_connected, is_alive);
00361       last_signal_time.stamp();
00362       sig_stream_data.emit();
00363       sendBaseControlCommand(); // send the command packet to mainboard;
00364       if( version_info_reminder/*--*/ > 0 ) sendCommand(Command::GetVersionInfo());
00365       if( controller_info_reminder/*--*/ > 0 ) sendCommand(Command::GetControllerGain());
00366     }
00367     else
00368     {
00369       // watchdog
00370       if (is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
00371       {
00372         is_alive = false;
00373         // do not call here the event manager update, as it generates a spurious offline state
00374       }
00375     }
00376   }
00377   sig_error.emit("Driver worker thread shutdown!");
00378 }
00379 
00380 void Kobuki::fixPayload(ecl::PushAndPop<unsigned char> & byteStream)
00381 {
00382   if (byteStream.size() < 3 ) { /* minimum size of sub-payload is 3; header_id, length, data */
00383     sig_named.emit(log("error", "packet", "too small sub-payload detected."));
00384     byteStream.clear();
00385   } else {
00386     std::stringstream ostream;
00387     unsigned int header_id = static_cast<unsigned int>(byteStream.pop_front());
00388     unsigned int length = static_cast<unsigned int>(byteStream.pop_front());
00389     unsigned int remains = byteStream.size();
00390     unsigned int to_pop;
00391 
00392     ostream << "[" << header_id << "]";
00393     ostream << "[" << length << "]";
00394 
00395     ostream << "[";
00396     ostream << std::setfill('0') << std::uppercase;
00397     ostream << std::hex << std::setw(2) << header_id << " " << std::dec;
00398     ostream << std::hex << std::setw(2) << length << " " << std::dec;
00399 
00400     if (remains < length) to_pop = remains;
00401     else                  to_pop = length;
00402 
00403     for (unsigned int i = 0; i < to_pop; i++ ) {
00404       unsigned int byte = static_cast<unsigned int>(byteStream.pop_front());
00405       ostream << std::hex << std::setw(2) << byte << " " << std::dec;
00406     }
00407     ostream << "]";
00408 
00409     if (remains < length) sig_named.emit(log("error", "packet", "malformed sub-payload detected. "  + ostream.str()));
00410     else                  sig_named.emit(log("debug", "packet", "unknown sub-payload detected. " + ostream.str()));
00411   }
00412 }
00413 
00414 
00415 /*****************************************************************************
00416  ** Implementation [Human Friendly Accessors]
00417  *****************************************************************************/
00418 
00419 ecl::Angle<double> Kobuki::getHeading() const
00420 {
00421   ecl::Angle<double> heading;
00422   // raw data angles are in hundredths of a degree, convert to radians.
00423   heading = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
00424   return ecl::wrap_angle(heading - heading_offset);
00425 }
00426 
00427 double Kobuki::getAngularVelocity() const
00428 {
00429   // raw data angles are in hundredths of a degree, convert to radians.
00430   return (static_cast<double>(inertia.data.angle_rate) / 100.0) * ecl::pi / 180.0;
00431 }
00432 
00433 /*****************************************************************************
00434  ** Implementation [Raw Data Accessors]
00435  *****************************************************************************/
00436 
00437 void Kobuki::resetOdometry()
00438 {
00439   diff_drive.reset();
00440 
00441   // Issue #274: use current imu reading as zero heading to emulate reseting gyro
00442   heading_offset = (static_cast<double>(inertia.data.angle) / 100.0) * ecl::pi / 180.0;
00443 }
00444 
00445 void Kobuki::getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle,
00446                                  double &wheel_right_angle_rate)
00447 {
00448   diff_drive.getWheelJointStates(wheel_left_angle, wheel_left_angle_rate, wheel_right_angle, wheel_right_angle_rate);
00449 }
00450 
00462 void Kobuki::updateOdometry(ecl::LegacyPose2D<double> &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
00463 {
00464   diff_drive.update(core_sensors.data.time_stamp, core_sensors.data.left_encoder, core_sensors.data.right_encoder,
00465                       pose_update, pose_update_rates);
00466 }
00467 
00468 /*****************************************************************************
00469  ** Commands
00470  *****************************************************************************/
00471 
00472 void Kobuki::setLed(const enum LedNumber &number, const enum LedColour &colour)
00473 {
00474   sendCommand(Command::SetLedArray(number, colour, kobuki_command.data));
00475 }
00476 
00477 void Kobuki::setDigitalOutput(const DigitalOutput &digital_output) {
00478   sendCommand(Command::SetDigitalOutput(digital_output, kobuki_command.data));
00479 }
00480 
00481 void Kobuki::setExternalPower(const DigitalOutput &digital_output) {
00482   sendCommand(Command::SetExternalPower(digital_output, kobuki_command.data));
00483 }
00484 
00485 //void Kobuki::playSound(const enum Sounds &number)
00486 //{
00487 //  sendCommand(Command::PlaySound(number, kobuki_command.data));
00488 //}
00489 
00490 void Kobuki::playSoundSequence(const enum SoundSequences &number)
00491 {
00492   sendCommand(Command::PlaySoundSequence(number, kobuki_command.data));
00493 }
00494 
00495 bool Kobuki::setControllerGain(const unsigned char &type, const unsigned int &p_gain,
00496                                const unsigned int &i_gain, const unsigned int &d_gain)
00497 {
00498   if ((firmware.flashed_major_version() < 2) && (firmware.flashed_minor_version() < 2)) {
00499     sig_warn.emit("Robot firmware doesn't support this function, so you must upgrade it. " \
00500                   "Consult how-to on: http://kobuki.yujinrobot.com/home-en/documentation/howtos/upgrading-firmware");
00501     sig_warn.emit("Robot firmware version is " + VersionInfo::toString(firmware.data.version)
00502                 + "; latest version is " + firmware.current_version());
00503     return false;
00504   }
00505 
00506   sendCommand(Command::SetControllerGain(type, p_gain, i_gain, d_gain));
00507   return true;
00508 }
00509 
00510 bool Kobuki::getControllerGain()
00511 {
00512   if ((firmware.flashed_major_version() < 2) && (firmware.flashed_minor_version() < 2)) {
00513     sig_warn.emit("Robot firmware doesn't support this function, so you must upgrade it. " \
00514                   "Consult how-to on: http://kobuki.yujinrobot.com/home-en/documentation/howtos/upgrading-firmware");
00515     sig_warn.emit("Robot firmware version is " + VersionInfo::toString(firmware.data.version)
00516                 + "; latest version is " + firmware.current_version());
00517     return false;
00518   }
00519 
00520   sendCommand(Command::GetControllerGain());
00521   return true;
00522 }
00523 
00524 void Kobuki::setBaseControl(const double &linear_velocity, const double &angular_velocity)
00525 {
00526   diff_drive.setVelocityCommands(linear_velocity, angular_velocity);
00527 }
00528 
00529 void Kobuki::sendBaseControlCommand()
00530 {
00531   std::vector<double> velocity_commands_received;
00532   if( acceleration_limiter.isEnabled() ) {
00533     velocity_commands_received=acceleration_limiter.limit(diff_drive.pointVelocity());
00534   } else {
00535     velocity_commands_received=diff_drive.pointVelocity();
00536   }
00537   diff_drive.velocityCommands(velocity_commands_received);
00538   std::vector<short> velocity_commands = diff_drive.velocityCommands();
00539   //std::cout << "speed: " << velocity_commands[0] << ", radius: " << velocity_commands[1] << std::endl;
00540   sendCommand(Command::SetVelocityControl(velocity_commands[0], velocity_commands[1]));
00541 
00542   //experimental; send raw control command and received command velocity
00543   velocity_commands_debug=velocity_commands;
00544   velocity_commands_debug.push_back((short)(velocity_commands_received[0]*1000.0));
00545   velocity_commands_debug.push_back((short)(velocity_commands_received[1]*1000.0));
00546   sig_raw_control_command.emit(velocity_commands_debug);
00547 }
00548 
00559 void Kobuki::sendCommand(Command command)
00560 {
00561   if( !is_alive || !is_connected ) {
00562     //need to do something
00563     sig_debug.emit("Device state is not ready yet.");
00564     if( !is_alive     ) sig_debug.emit(" - Device is not alive.");
00565     if( !is_connected ) sig_debug.emit(" - Device is not connected.");
00566     //std::cout << is_enabled << ", " << is_alive << ", " << is_connected << std::endl;
00567     return;
00568   }
00569   command_mutex.lock();
00570   kobuki_command.resetBuffer(command_buffer);
00571 
00572   if (!command.serialise(command_buffer))
00573   {
00574     sig_error.emit("command serialise failed.");
00575   }
00576   command_buffer[2] = command_buffer.size() - 3;
00577   unsigned char checksum = 0;
00578   for (unsigned int i = 2; i < command_buffer.size(); i++)
00579     checksum ^= (command_buffer[i]);
00580 
00581   command_buffer.push_back(checksum);
00582   //check_device();
00583   serial.write((const char*)&command_buffer[0], command_buffer.size());
00584 
00585   sig_raw_data_command.emit(command_buffer);
00586   command_mutex.unlock();
00587 }
00588 
00589 bool Kobuki::enable()
00590 {
00591   is_enabled = true;
00592   return true;
00593 }
00594 
00595 bool Kobuki::disable()
00596 {
00597   setBaseControl(0.0f, 0.0f);
00598   sendBaseControlCommand();
00599   is_enabled = false;
00600   return true;
00601 }
00602 
00611 void Kobuki::printSigSlotConnections() const {
00612 
00613   std::cout << "========== Void ==========" << std::endl;
00614   ecl::SigSlotsManager<>::printStatistics();
00615   std::cout << "========= String =========" << std::endl;
00616   ecl::SigSlotsManager<const std::string&>::printStatistics();
00617   std::cout << "====== Button Event ======" << std::endl;
00618   ecl::SigSlotsManager<const ButtonEvent&>::printStatistics();
00619   std::cout << "====== Bumper Event ======" << std::endl;
00620   ecl::SigSlotsManager<const BumperEvent&>::printStatistics();
00621   std::cout << "====== Cliff Event =======" << std::endl;
00622   ecl::SigSlotsManager<const CliffEvent&>::printStatistics();
00623   std::cout << "====== Wheel Event =======" << std::endl;
00624   ecl::SigSlotsManager<const WheelEvent&>::printStatistics();
00625   std::cout << "====== Power Event =======" << std::endl;
00626   ecl::SigSlotsManager<const PowerEvent&>::printStatistics();
00627   std::cout << "====== Input Event =======" << std::endl;
00628   ecl::SigSlotsManager<const InputEvent&>::printStatistics();
00629   std::cout << "====== Robot Event =======" << std::endl;
00630   ecl::SigSlotsManager<const RobotEvent&>::printStatistics();
00631   std::cout << "====== VersionInfo =======" << std::endl;
00632   ecl::SigSlotsManager<const VersionInfo&>::printStatistics();
00633   std::cout << "===== Command Buffer =====" << std::endl;
00634   ecl::SigSlotsManager<const Command::Buffer&>::printStatistics();
00635 }
00636 
00637 } // namespace kobuki


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Thu Jun 6 2019 20:24:37