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


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Thu Aug 27 2015 13:43:58