wiimote_controller.cpp
Go to the documentation of this file.
00001 /*
00002  * ROS Node for interfacing with a wiimote control unit.
00003  * Copyright (c) 2016, Intel Corporation.
00004  *
00005  * This program is free software; you can redistribute it and/or modify it
00006  * under the terms and conditions of the GNU General Public License,
00007  * version 2, as published by the Free Software Foundation.
00008  *
00009  * This program is distributed in the hope it will be useful, but WITHOUT
00010  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00011  * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00012  * more details.
00013  */
00014 
00015 /*
00016  * This code is based on the original Python implementation
00017  * created by Andreas Paepcke and Melonee Wise
00018  *  Andreas Paepcke <paepcke@anw.willowgarage.com>
00019  * with contributions by
00020  *  David Lu <davidlu@wustl.edu>
00021  *  Miguel Angel Julian Aguilar <miguel.angel@thecorpora.com>
00022  * See https://github.com/ros-drivers/joystick_drivers/tree/indigo-devel/wiimote
00023  * for details and history.
00024  *
00025  * This C++ implementation used the functionality of the existing
00026  * Python code as the feature requirements.
00027  */
00028 
00029 /*
00030  * Initial C++ implementation by
00031  *   Mark Horn <mark.d.horn@intel.com>
00032  *
00033  * The C++ implementation was designed with focus on reduced resource consumption.
00034  *
00035  * Differences from Python implementation:
00036  * - Both "/wiimote/nunchuk" and "/wiimote/classic" topics are only published
00037  *   if the Nunchuk or Classic Controller are connected to the wiimote respectively.
00038  * - Wiimote data is only polled from the controller if the data is required
00039  *   to publish for a topic which has at least one subscriber.
00040  *
00041  * Revisions:
00042  *
00043  */
00044 
00045 #include "wiimote/wiimote_controller.h"
00046 
00047 #include "sensor_msgs/Joy.h"
00048 #include "std_msgs/Bool.h"
00049 
00050 #include "wiimote/State.h"
00051 #include "wiimote/IrSourceInfo.h"
00052 
00053 #include <stdarg.h>
00054 #include <stdio.h>
00055 #include <stdlib.h>
00056 #include <unistd.h>
00057 
00058 #include <signal.h>
00059 
00060 #include <time.h>
00061 #include <math.h>
00062 
00063 #include <vector>
00064 #include <string>
00065 
00066 WiimoteNode::WiimoteNode()
00067 {
00068   joy_pub_ = nh_.advertise<sensor_msgs::Joy>("/joy", 1);
00069   imu_data_pub_ = nh_.advertise<sensor_msgs::Imu>("/imu/data", 1);
00070   wiimote_state_pub_ = nh_.advertise<wiimote::State>("/wiimote/state", 1);
00077   imu_is_calibrated_pub_ = nh_.advertise<std_msgs::Bool>("/imu/is_calibrated", 1, true);
00078 
00079   joy_set_feedback_sub_ = nh_.subscribe<sensor_msgs::JoyFeedbackArray>("/joy/set_feedback", 10,
00080       &WiimoteNode::joySetFeedbackCallback, this);
00081 
00082   imu_calibrate_srv_ = nh_.advertiseService("/imu/calibrate", &WiimoteNode::serviceImuCalibrateCallback, this);
00083 
00084   // Initialize with the ANY Bluetooth Address
00085   setBluetoothAddr("00:00:00:00:00:00");
00086 
00087   wiimote_ = nullptr;
00088 
00089   initializeWiimoteState();
00090 
00091   state_secs_ = 0;
00092   state_nsecs_ = 0;
00093 
00094   // Setup the Wii Error Handler
00095   wiimote_c::cwiid_set_err(cwiidErrorCallback);
00096 
00097   report_mode_ = 0;
00098 
00099   wiimote_calibrated_ = false;
00100 
00101   resetMotionPlusState();
00102   resetNunchukState();
00103   resetClassicState();
00104   nunchuk_failed_calibration_ = false;
00105 }
00106 
00107 WiimoteNode::~WiimoteNode()
00108 {
00109 }
00110 
00111 void WiimoteNode::initializeWiimoteState()
00112 {
00113   wiimote_state_.rpt_mode = 0;
00114   wiimote_state_.led = 0;
00115   wiimote_state_.rumble = 0;
00116   wiimote_state_.battery = 0;
00117   wiimote_state_.buttons = 0;
00118   wiimote_state_.acc[0] = 0;
00119   wiimote_state_.acc[1] = 0;
00120   wiimote_state_.acc[2] = 0;
00121 
00122   wiimote_state_.ext_type = wiimote_c::CWIID_EXT_NONE;
00123   wiimote_state_.error = wiimote_c::CWIID_ERROR_NONE;
00124 
00125   wiimote_state_.ir_src[0].valid = 0;
00126   wiimote_state_.ir_src[1].valid = 0;
00127   wiimote_state_.ir_src[2].valid = 0;
00128   wiimote_state_.ir_src[3].valid = 0;
00129   wiimote_state_.ir_src[0].pos[0] = 0; wiimote_state_.ir_src[0].pos[1] = 0;
00130   wiimote_state_.ir_src[1].pos[0] = 0; wiimote_state_.ir_src[1].pos[1] = 0;
00131   wiimote_state_.ir_src[2].pos[0] = 0; wiimote_state_.ir_src[2].pos[1] = 0;
00132   wiimote_state_.ir_src[3].pos[0] = 0; wiimote_state_.ir_src[3].pos[1] = 0;
00133   wiimote_state_.ir_src[0].size = 0;
00134   wiimote_state_.ir_src[1].size = 0;
00135   wiimote_state_.ir_src[2].size = 0;
00136   wiimote_state_.ir_src[3].size = 0;
00137 }
00138 
00139 char *WiimoteNode::getBluetoothAddr()
00140 {
00141   return batostr(&bt_device_addr_);
00142 }
00143 void WiimoteNode::setBluetoothAddr(const char *bt_str)
00144 {
00145   str2ba(bt_str, &bt_device_addr_);
00146 }
00147 
00148 bool WiimoteNode::pairWiimote(int flags = 0, int timeout = 5)
00149 {
00150   bool status = true;
00151 
00152   ROS_INFO("Put Wiimote in discoverable mode now (press 1+2)...");
00153   if (timeout == -1)
00154     ROS_INFO("Searching indefinitely...");
00155   else
00156     ROS_INFO("Timeout in about %d seconds if not paired.", timeout);
00157 
00158   if (!(wiimote_ = wiimote_c::cwiid_open_timeout(&bt_device_addr_, flags, timeout)))
00159   {
00160     ROS_ERROR("Unable to connect to wiimote");
00161     status = false;
00162   }
00163   else
00164   {
00165     // Give the hardware time to zero the accelerometer and gyro after pairing
00166     // Ensure we are getting valid data before using
00167     sleep(1);
00168 
00169     checkFactoryCalibrationData();
00170 
00171     if (!wiimote_calibrated_)
00172     {
00173       ROS_ERROR("Wiimote not usable due to calibration failure.");
00174       status = false;
00175     }
00176   }
00177 
00178   return status;
00179 }
00180 int WiimoteNode::unpairWiimote()
00181 {
00182   return wiimote_c::cwiid_close(wiimote_);
00183 }
00184 
00185 void WiimoteNode::checkFactoryCalibrationData()
00186 {
00187   bool result = true;
00188 
00189   if (wiimote_c::cwiid_get_acc_cal(wiimote_, wiimote_c::CWIID_EXT_NONE, &wiimote_cal_) != 0)
00190   {
00191     if (wiimote_calibrated_)
00192     {
00193       ROS_WARN("Failed to read current Wiimote calibration data; proceeding with previous data");
00194     }
00195     else
00196     {
00197       ROS_ERROR("Failed to read Wiimote factory calibration data");
00198       result = false;
00199     }
00200   }
00201   else
00202   {
00203     // If any calibration point is zero; we fail
00204     if (!(wiimote_cal_.zero[CWIID_X] && wiimote_cal_.zero[CWIID_Y] && wiimote_cal_.zero[CWIID_Z] &&
00205         wiimote_cal_.one[CWIID_X] && wiimote_cal_.one[CWIID_Y] && wiimote_cal_.one[CWIID_Z]))
00206     {
00207       ROS_ERROR("Some Wiimote factory calibration data is missing; calibration failed");
00208       ROS_ERROR("Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
00209           wiimote_cal_.zero[CWIID_X], wiimote_cal_.zero[CWIID_Y], wiimote_cal_.zero[CWIID_Z],
00210           wiimote_cal_.one[CWIID_X], wiimote_cal_.one[CWIID_Y], wiimote_cal_.one[CWIID_Z]);
00211 
00212       result = false;
00213     }
00214     else
00215     {
00216       wiimote_calibrated_ = true;
00217       ROS_DEBUG("Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
00218           wiimote_cal_.zero[CWIID_X], wiimote_cal_.zero[CWIID_Y], wiimote_cal_.zero[CWIID_Z],
00219           wiimote_cal_.one[CWIID_X], wiimote_cal_.one[CWIID_Y], wiimote_cal_.one[CWIID_Z]);
00220     }
00221   }
00222 
00223   if (!getStateSample())
00224   {
00225     ROS_WARN("Could not read Wiimote state; nunchuk may not be calibrated if present.");
00226   }
00227   else
00228   {
00229     if (isPresentNunchuk())
00230     {
00231       if (wiimote_c::cwiid_get_acc_cal(wiimote_, wiimote_c::CWIID_EXT_NUNCHUK, &nunchuk_cal_) != 0)
00232       {
00233         if (nunchuk_calibrated_)
00234         {
00235           ROS_WARN("Failed to read current Nunchuk calibration data; proceeding with previous data");
00236         }
00237         else
00238         {
00239           ROS_ERROR("Failed to read Nunchuk factory calibration data");
00240           result = false;
00241           nunchuk_failed_calibration_ = true;
00242         }
00243       }
00244       else
00245       {
00246         // If any calibration point is zero; we fail
00247         if (!(nunchuk_cal_.zero[CWIID_X] && nunchuk_cal_.zero[CWIID_Y] && nunchuk_cal_.zero[CWIID_Z] &&
00248             nunchuk_cal_.one[CWIID_X] && nunchuk_cal_.one[CWIID_Y] && nunchuk_cal_.one[CWIID_Z]))
00249         {
00250           ROS_ERROR("Some Nunchuk factory calibration data is missing; calibration failed");
00251           ROS_ERROR("Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
00252               nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.zero[CWIID_Z],
00253               nunchuk_cal_.one[CWIID_X], nunchuk_cal_.one[CWIID_Y], nunchuk_cal_.one[CWIID_Z]);
00254           result = false;
00255           nunchuk_failed_calibration_ = true;
00256         }
00257         else
00258         {
00259           nunchuk_calibrated_ = true;
00260           ROS_DEBUG("Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
00261               nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.zero[CWIID_Z],
00262               nunchuk_cal_.one[CWIID_X], nunchuk_cal_.one[CWIID_Y], nunchuk_cal_.one[CWIID_Z]);
00263         }
00264       }
00265     }
00266   }
00267 
00268   if (wiimote_calibrated_)
00269   {
00270     // Save the current reporting mode
00271     uint8_t save_report_mode = wiimote_state_.rpt_mode;
00272 
00273     // Need to ensure we are collecting accelerometer
00274     uint8_t new_report_mode = save_report_mode | (CWIID_RPT_ACC | CWIID_RPT_EXT);
00275 
00276     if (new_report_mode != save_report_mode)
00277     {
00278       setReportMode(new_report_mode);
00279     }
00280 
00281     ROS_INFO("Collecting additional calibration data; keep wiimote stationary...");
00282 
00283     StatVector3d linear_acceleration_stat_old = linear_acceleration_stat_;
00284     linear_acceleration_stat_.clear();
00285     StatVector3d angular_velocity_stat_old = angular_velocity_stat_;
00286     angular_velocity_stat_.clear();
00287 
00288     bool failed = false;
00289     bool data_complete = false;
00290     int wiimote_data_points = 0;
00291     int motionplus_data_points = 0;
00292 
00293     while (!failed && !data_complete)
00294     {
00295       if (getStateSample())
00296       {
00297         if (wiimote_data_points < COVARIANCE_DATA_POINTS_)
00298         {
00299           linear_acceleration_stat_.addData(
00300               wiimote_state_.acc[CWIID_X],
00301               wiimote_state_.acc[CWIID_Y],
00302               wiimote_state_.acc[CWIID_Z]);
00303 
00304           ++wiimote_data_points;
00305         }
00306 
00307         if (isPresentMotionplus())
00308         {
00309           if (motionplus_data_points < COVARIANCE_DATA_POINTS_)
00310           {
00311             // ROS_DEBUG("New MotionPlus data :%03d: PHI: %04d, THETA: %04d, PSI: %04d", motionplus_data_points,
00312             //     wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI],
00313             //     wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA],
00314             //     wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI]);
00315             angular_velocity_stat_.addData(
00316                 wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI],
00317                 wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA],
00318                 wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI]);
00319 
00320             ++motionplus_data_points;
00321           }
00322         }
00323       }
00324       else
00325       {
00326         failed = true;
00327       }
00328 
00329       if (wiimote_data_points >= COVARIANCE_DATA_POINTS_)
00330       {
00331         if (!isPresentMotionplus())
00332         {
00333           data_complete = true;
00334         }
00335         else
00336         {
00337           if (motionplus_data_points >= COVARIANCE_DATA_POINTS_)
00338           {
00339             data_complete = true;
00340           }
00341         }
00342       }
00343     }
00344 
00345     if (!failed)
00346     {
00347       ROS_DEBUG("Calculating calibration data...");
00348 
00349       // Check the standard deviations > 1.0
00350       TVectorDouble stddev = linear_acceleration_stat_.getStandardDeviationRaw();
00351       bool is_bad_cal = false;
00352       std::for_each(std::begin(stddev), std::end(stddev), [&](const double d)  // NOLINT(build/c++11)
00353       {
00354         if (d > 1.0)
00355         {
00356           is_bad_cal = true;
00357           ROS_DEBUG("Wiimote standard deviation > 1.0");
00358         }
00359       });  // NOLINT(whitespace/braces)
00360 
00361       if (!is_bad_cal)
00362       {
00363         TVectorDouble variance = linear_acceleration_stat_.getVarianceScaled(EARTH_GRAVITY_);
00364 
00365         ROS_DEBUG("Variance Scaled x: %lf, y: %lf, z: %lf", variance.at(CWIID_X),
00366             variance.at(CWIID_Y), variance.at(CWIID_Z));
00367 
00368         linear_acceleration_covariance_[0] = variance.at(CWIID_X);
00369         linear_acceleration_covariance_[1] = 0.0;
00370         linear_acceleration_covariance_[2] = 0.0;
00371 
00372         linear_acceleration_covariance_[3] = 0.0;
00373         linear_acceleration_covariance_[4] = variance.at(CWIID_Y);
00374         linear_acceleration_covariance_[5] = 0.0;
00375 
00376         linear_acceleration_covariance_[6] = 0.0;
00377         linear_acceleration_covariance_[7] = 0.0;
00378         linear_acceleration_covariance_[8] = variance.at(CWIID_Z);
00379       }
00380       else
00381       {
00382         ROS_ERROR("Failed calibration; using questionable data for linear acceleration");
00383 
00384         linear_acceleration_stat_ = linear_acceleration_stat_old;
00385         angular_velocity_stat_ = angular_velocity_stat_old;
00386 
00387         result = false;
00388       }
00389 
00390       if (angular_velocity_stat_.size() == COVARIANCE_DATA_POINTS_)
00391       {
00392         // Check the standard deviations > 50.0
00393         TVectorDouble gyro_stddev = angular_velocity_stat_.getStandardDeviationRaw();
00394         std::for_each(std::begin(gyro_stddev), std::end(gyro_stddev), [&](const double d)  // NOLINT(build/c++11)
00395         {
00396           if (d > 50.0)
00397           {
00398             is_bad_cal = true;
00399             ROS_DEBUG("MotionPlus standard deviation > 50");
00400           }
00401         });  // NOLINT(whitespace/braces)
00402 
00403         if (!is_bad_cal)
00404         {
00405           TVectorDouble gyro_variance = angular_velocity_stat_.getVarianceScaled(GYRO_SCALE_FACTOR_);
00406 
00407           ROS_DEBUG("Gyro Variance Scaled x: %lf, y: %lf, z: %lf", gyro_variance.at(CWIID_PHI),
00408               gyro_variance.at(CWIID_THETA), gyro_variance.at(CWIID_PSI));
00409 
00410           angular_velocity_covariance_[0] = gyro_variance.at(CWIID_PHI);
00411           angular_velocity_covariance_[1] = 0.0;
00412           angular_velocity_covariance_[2] = 0.0;
00413 
00414           angular_velocity_covariance_[3] = 0.0;
00415           angular_velocity_covariance_[4] = gyro_variance.at(CWIID_THETA);
00416           angular_velocity_covariance_[5] = 0.0;
00417 
00418           angular_velocity_covariance_[6] = 0.0;
00419           angular_velocity_covariance_[7] = 0.0;
00420           angular_velocity_covariance_[8] = gyro_variance.at(CWIID_PSI);
00421         }
00422         else
00423         {
00424           ROS_ERROR("Failed calibration; using questionable data for angular velocity");
00425 
00426           angular_velocity_stat_ = angular_velocity_stat_old;
00427 
00428           result = false;
00429         }
00430       }
00431       else
00432       {
00433         resetMotionPlusState();
00434       }
00435     }
00436 
00437     if (failed)
00438     {
00439       ROS_ERROR("Failed calibration; using questionable data");
00440       result = false;
00441     }
00442     else
00443     {
00444       struct timespec state_tv;
00445 
00446       if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
00447       {
00448         calibration_time_ = ros::Time::now();
00449       }
00450       else
00451       {
00452         ROS_WARN("Could not update calibration time.");
00453       }
00454     }
00455 
00456     // Restore the pre-existing reporting mode
00457     if (new_report_mode != save_report_mode)
00458     {
00459       setReportMode(save_report_mode);
00460     }
00461   }
00462 
00463   // Publish the initial calibration state
00464   std_msgs::Bool imu_is_calibrated_data;
00465   imu_is_calibrated_data.data = result;
00466   imu_is_calibrated_pub_.publish(imu_is_calibrated_data);
00467 }
00468 
00469 void WiimoteNode::resetMotionPlusState()
00470 {
00471   // If no gyro is attached to the Wiimote then we signal
00472   // the invalidity of angular rate with a covariance matrix
00473   // whose first element is -1:
00474   angular_velocity_covariance_[0] = -1.0;
00475   angular_velocity_covariance_[1] = 0.0;
00476   angular_velocity_covariance_[2] = 0.0;
00477 
00478   angular_velocity_covariance_[3] = 0.0;
00479   angular_velocity_covariance_[4] = 0.0;
00480   angular_velocity_covariance_[5] = 0.0;
00481 
00482   angular_velocity_covariance_[6] = 0.0;
00483   angular_velocity_covariance_[7] = 0.0;
00484   angular_velocity_covariance_[8] = 0.0;
00485 }
00486 
00487 void WiimoteNode::resetNunchukState()
00488 {
00489   nunchuk_calibrated_ = false;
00490 
00491   nunchuk_stick_calibrated_ = false;
00492   nunchuk_stick_center_[CWIID_X] = JOYSTICK_NUNCHUK_DEFAULT_CENTER_;
00493   nunchuk_stick_center_[CWIID_Y] = JOYSTICK_NUNCHUK_DEFAULT_CENTER_;
00494   nunchuk_stick_max_[CWIID_X] = JOYSTICK_NUNCHUK_20PERCENT_MAX_;
00495   nunchuk_stick_max_[CWIID_Y] = JOYSTICK_NUNCHUK_20PERCENT_MAX_;
00496   nunchuk_stick_min_[CWIID_X] = JOYSTICK_NUNCHUK_20PERCENT_MIN_;
00497   nunchuk_stick_min_[CWIID_Y] = JOYSTICK_NUNCHUK_20PERCENT_MIN_;
00498 }
00499 
00500 void WiimoteNode::resetClassicState()
00501 {
00502   classic_stick_left_calibrated_ = false;
00503   classic_stick_right_calibrated_ = false;
00504   classic_stick_left_center_[CWIID_X] = JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_;
00505   classic_stick_left_center_[CWIID_Y] = JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_;
00506   classic_stick_right_center_[CWIID_X] = JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_;
00507   classic_stick_right_center_[CWIID_Y] = JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_;
00508   classic_stick_left_max_[CWIID_X] = JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_;
00509   classic_stick_left_max_[CWIID_Y] = JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_;
00510   classic_stick_left_min_[CWIID_X] = JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_;
00511   classic_stick_left_min_[CWIID_Y] = JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_;
00512   classic_stick_right_max_[CWIID_X] = JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_;
00513   classic_stick_right_max_[CWIID_Y] = JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_;
00514   classic_stick_right_min_[CWIID_X] = JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_;
00515   classic_stick_right_min_[CWIID_Y] = JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_;
00516 }
00517 
00518 void WiimoteNode::publish()
00519 {
00520   uint8_t joy_subscribers = joy_pub_.getNumSubscribers();
00521   uint8_t wii_state_subscribers = wiimote_state_pub_.getNumSubscribers();
00522   uint8_t imu_subscribers = imu_data_pub_.getNumSubscribers();
00523   uint8_t wii_nunchuk_subscribers = 0;
00524   uint8_t wii_classic_subscribers = 0;
00525 
00526   uint8_t current_report_mode = wiimote_state_.rpt_mode;
00527   uint8_t new_report_mode = current_report_mode;
00528 
00529   /*              CWIID_RPT_xxx
00530 
00531                   | | | |M| | |
00532                   | | | |O| | |
00533                   | | | |T| | |
00534                   | | | |I|N|C|
00535                   | | | |O|U|L|
00536                   | | | |N|N|A|
00537                   | | | |P|C|S|
00538                   | |B|A|L|H|S|
00539                   |I|T|C|U|U|I|
00540   ROS_Topic       |R|N|C|S|K|C|
00541                   |_|_|_|_|_|_|
00542   joy             | |x|x|x| | |
00543   imu_data        | | |x|x| | |
00544   wiimote_state   |x|x|x|x|x| |
00545   wiimote_nunchuk | | | | |x| |
00546   wiimote_classic | | | | | |x|
00547   */
00548 
00549   if (joy_subscribers || wii_state_subscribers || imu_subscribers)
00550   {
00551     // Need to collect data on accelerometer and motionplus
00552     new_report_mode |= (CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
00553 
00554     if (joy_subscribers || wii_state_subscribers)
00555     {
00556       // Need to also collect data on buttons
00557       new_report_mode |= (CWIID_RPT_BTN);
00558     }
00559 
00560     if (wii_state_subscribers)
00561     {
00562       // Need to also collect data on IR and Nunchuk
00563       new_report_mode |= (CWIID_RPT_IR | CWIID_RPT_NUNCHUK);
00564     }
00565   }
00566   else
00567   {
00568     if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers)
00569     {
00570       // Can stop collecting data on accelerometer and motionplus
00571       new_report_mode &= ~(CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
00572     }
00573 
00574     if (!joy_subscribers && !wii_state_subscribers)
00575     {
00576       // Can also stop collecting data on buttons
00577       new_report_mode &= ~(CWIID_RPT_BTN);
00578     }
00579 
00580     if (!wii_state_subscribers)
00581     {
00582       // Can also stop collecting data on IR
00583       new_report_mode &= ~(CWIID_RPT_IR);
00584     }
00585   }
00586 
00587   // Is the Nunchuk connected?
00588   if (isPresentNunchuk())
00589   {
00590     // Is the Nunchuk publisher not advertised?
00591     if (nullptr == wiimote_nunchuk_pub_)
00592     {
00593       if (!nunchuk_failed_calibration_)
00594       {
00595         // The nunchuk was just connected, so read the calibration data
00596         if (!nunchuk_calibrated_)
00597         {
00598           checkFactoryCalibrationData();
00599         }
00600 
00601         if (nunchuk_calibrated_)
00602         {
00603           wiimote_nunchuk_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/nunchuk", 1);
00604         }
00605         else
00606         {
00607           ROS_ERROR("Topic /wiimote/nunchuk not advertised due to calibration failure");
00608         }
00609       }
00610     }
00611 
00612     wii_nunchuk_subscribers = wiimote_nunchuk_pub_.getNumSubscribers();
00613 
00614     if (wii_nunchuk_subscribers)
00615     {
00616       // Need to collect data on nunchuk
00617       new_report_mode |= (CWIID_RPT_NUNCHUK);
00618     }
00619     else
00620     {
00621       if (!wii_state_subscribers)
00622       {
00623         // Can stop collecting data on nunchuk
00624         new_report_mode &= ~(CWIID_RPT_NUNCHUK);
00625       }
00626     }
00627   }
00628   else  // Stop publishing the topic
00629   {
00630     // Is the Nunchuk publisher advertised?
00631     if (nullptr != wiimote_nunchuk_pub_)
00632     {
00633       wiimote_nunchuk_pub_.shutdown();
00634 
00635       resetNunchukState();
00636 
00637       if (!wii_state_subscribers)
00638       {
00639         // Can stop collecting data on nunchuk
00640         new_report_mode &= ~(CWIID_RPT_NUNCHUK);
00641       }
00642     }
00643 
00644     // If the nunchuk was connect, but failed calibration
00645     // then attempt to check factory calibration for the wiimote
00646     if (nunchuk_failed_calibration_)
00647     {
00648       checkFactoryCalibrationData();
00649       nunchuk_failed_calibration_ = false;
00650     }
00651   }
00652 
00653   // Is the Classic Pad connected?
00654   if (isPresentClassic())
00655   {
00656     // Is the Classic Pad publisher not advertised?
00657     if (nullptr == wiimote_classic_pub_)
00658     {
00659       wiimote_classic_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/classic", 1);
00660     }
00661 
00662     wii_classic_subscribers = wiimote_classic_pub_.getNumSubscribers();
00663 
00664     if (wii_classic_subscribers)
00665     {
00666       // Need to collect data on classic
00667       new_report_mode |= (CWIID_RPT_CLASSIC);
00668     }
00669     else
00670     {
00671       // Can stop collecting data on classic
00672       new_report_mode &= ~(CWIID_RPT_CLASSIC);
00673     }
00674   }
00675   else  // Stop publishing the topic
00676   {
00677     // Is the Classic Pad publisher advertised?
00678     if (nullptr != wiimote_classic_pub_)
00679     {
00680       wiimote_classic_pub_.shutdown();
00681 
00682       resetClassicState();
00683 
00684       // Can stop collecting data on classic
00685       new_report_mode &= ~(CWIID_RPT_CLASSIC);
00686     }
00687   }
00688 
00689   // Update the reporting mode and returning
00690   if (current_report_mode != new_report_mode)
00691   {
00692     setReportMode(new_report_mode);
00693   }
00694 
00695   if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers &&
00696       !wii_nunchuk_subscribers & !wii_classic_subscribers)
00697   {
00698     // If there are no subscribers, there isn't anything to publish
00699     return;
00700   }
00701 
00702 
00703   if (!getStateSample())
00704   {
00705     // If we can not get State from the Wiimote, there isn't anything to publish
00706     return;
00707   }
00708 
00709 
00710   if (joy_subscribers)
00711   {
00712     // ROS_DEBUG("Number joy subscribers is: %d", joy_subscribers);
00713     publishJoy();
00714   }
00715 
00716   if (imu_subscribers)
00717   {
00718     // ROS_DEBUG("Number imu_data subscribers is: %d", imu_subscribers);
00719     publishImuData();
00720   }
00721 
00722   if (wii_state_subscribers)
00723   {
00724     // ROS_DEBUG("Number wiimote_state subscribers is: %d", wii_state_subscribers);
00725     publishWiimoteState();
00726   }
00727 
00728   if (wii_nunchuk_subscribers)
00729   {
00730     // ROS_DEBUG("Number wiimote_nunchuk subscribers is: %d", wiimote_nunchuk_pub_.getNumSubscribers());
00731     publishWiimoteNunchuk();
00732   }
00733 
00734   // Is the Classic Pad connected?
00735   if (wii_classic_subscribers)
00736   {
00737     // ROS_DEBUG("Number wiimote_classic subscribers is: %d", wiimote_classic_pub_.getNumSubscribers());
00738     publishWiimoteClassic();
00739   }
00740 }
00741 
00742 bool WiimoteNode::getStateSample()
00743 {
00744   bool result = true;
00745   bool get_state_result = true;
00746   bool data_valid = false;
00747 
00748   int count = 0;
00749   int big_count = 0;
00750   static int wiimote_count = 0;
00751   static int motionplus_count = 0;
00752 
00753   do
00754   {
00755     get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
00756 
00757     if (isCollectingWiimote() &&
00758         (wiimote_state_.acc[CWIID_X] == 0 &&
00759          wiimote_state_.acc[CWIID_Y] == 0 &&
00760          wiimote_state_.acc[CWIID_Z] == 0))
00761     {
00762       if (count > 1 && !(count % 100))
00763       {
00764         // If we can not get valid data from the Wiimote, wait and try again
00765         ROS_INFO("Waiting for valid wiimote data...");
00766         count = 0;
00767         ++big_count;
00768       }
00769 
00770       usleep(10000);  // wait a hundredth of a second
00771       ++count;
00772       if (big_count > 10)
00773       {
00774         get_state_result = false;
00775       }
00776     }
00777     else
00778     {
00779       if (wiimote_count < IGNORE_DATA_POINTS_)
00780       {
00781         // ROS_DEBUG("Ignoring Wiimote data point %d", wiimote_count);
00782         wiimote_count++;
00783       }
00784       else
00785       {
00786         data_valid = true;
00787       }
00788     }
00789 
00790     usleep(10000);  // wait a hundredth of a second
00791   }
00792   while (get_state_result && !data_valid);
00793 
00794   if (isPresentMotionplus())
00795   {
00796     data_valid = false;
00797 
00798     count = 0;
00799     big_count = 0;
00800 
00801     do
00802     {
00803       if (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] == 0 &&
00804           wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] == 0 &&
00805           wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] == 0)
00806       {
00807         if (count > 1 && !(count % 100))
00808         {
00809           // If we can not get valid data from the Wiimote, wait and try again
00810           ROS_INFO("Waiting for valid MotionPlus data...");
00811           count = 0;
00812           ++big_count;
00813         }
00814 
00815         usleep(10000);  // wait a hundredth of a second
00816         ++count;
00817         if (big_count > 10)
00818         {
00819           get_state_result = false;
00820         }
00821         else
00822         {
00823           usleep(10000);  // wait a hundredth of a second
00824           get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
00825         }
00826       }
00827       else
00828       {
00829         if (motionplus_count < IGNORE_DATA_POINTS_)
00830         {
00831           ROS_DEBUG("Ignoring MotionPlus data point %d", motionplus_count);
00832           motionplus_count++;
00833           usleep(1000);  // wait a thousandth of a second
00834         }
00835         else
00836         {
00837           data_valid = true;
00838           // Get a new data point with valid data
00839           get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
00840         }
00841       }
00842     }
00843     while (get_state_result && !data_valid);
00844   }
00845   else
00846   {
00847     // MotionPlus was removed, so reset the master count
00848     motionplus_count = 0;
00849     resetMotionPlusState();
00850   }
00851 
00852   if (get_state_result)
00853   {
00854     struct timespec state_tv;
00855 
00856     if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
00857     {
00858       state_secs_ = state_tv.tv_sec;
00859       state_nsecs_ = state_tv.tv_nsec;
00860     }
00861     else
00862     {
00863       ROS_ERROR("Error sampling real-time clock");
00864       result = false;
00865     }
00866   }
00867   else
00868   {
00869     result = false;
00870   }
00871 
00872   return result;
00873 }
00874 
00875 void WiimoteNode::setReportMode(uint8_t rpt_mode)
00876 {
00877   ROS_DEBUG("Change report mode from %d to %d", wiimote_state_.rpt_mode, rpt_mode);
00878 
00879   if (wiimote_c::cwiid_set_rpt_mode(wiimote_, rpt_mode))
00880   {
00881     ROS_ERROR("Error setting report mode: Bit(s):%d", rpt_mode);
00882   }
00883   else
00884   {
00885     wiimote_state_.rpt_mode = rpt_mode;
00886 
00887     // Enable the MotionPlus
00888     if (rpt_mode & CWIID_RPT_MOTIONPLUS)
00889     {
00890       wiimote_c::cwiid_enable(wiimote_, CWIID_FLAG_MOTIONPLUS);
00891       ROS_DEBUG("Enabled MotionPlus");
00892     }
00893   }
00894 }
00895 
00896 void WiimoteNode::setLEDBit(uint8_t led, bool on)
00897 {
00898   uint8_t bit;
00899 
00900   if (led > 3)
00901   {
00902     ROS_WARN("LED ID %d out of bounds; ignoring!", led);
00903   }
00904 
00905   bit = 1 << led;
00906 
00907   if (on)
00908   {  // Set bit
00909     led_state_ |= bit;
00910   }
00911   else
00912   {  // Clear bit
00913     led_state_ &= ~(bit);
00914   }
00915 }
00916 void WiimoteNode::setRumbleBit(bool on)
00917 {
00918   if (on)
00919   {  // Set bit
00920     rumble_ |= 0x1;
00921   }
00922   else
00923   {  // Clear bit
00924     rumble_ &= ~(0x1);
00925   }
00926 }
00927 
00928 void WiimoteNode::setLedState(uint8_t led_state)
00929 {
00930   if (wiimote_c::cwiid_set_led(wiimote_, led_state))
00931   {
00932     ROS_ERROR("Error setting LEDs");
00933   }
00934 }
00935 
00936 void WiimoteNode::setRumbleState(uint8_t rumble)
00937 {
00938   if (wiimote_c::cwiid_set_rumble(wiimote_, rumble))
00939   {
00940     ROS_ERROR("Error setting rumble");
00941   }
00942 }
00943 
00944 void WiimoteNode::cwiidErrorCallback(wiimote_c::cwiid_wiimote_t *wiimote, const char *fmt, va_list ap)
00945 {
00946   const int MAX_BUF = 500;
00947   char msgs_buf[MAX_BUF];
00948 
00949   vsnprintf(msgs_buf, MAX_BUF, fmt, ap);
00950 
00951   if (wiimote)
00952   {
00953     ROS_ERROR("Wii Error: ID: %d: %s", wiimote_c::cwiid_get_id(wiimote), msgs_buf);
00954   }
00955   else
00956   {
00957     ROS_ERROR("Wii Error: ID: ?: %s", msgs_buf);
00958   }
00959 }
00960 
00961 bool WiimoteNode::isCollectingWiimote()
00962 {
00963   return wiimote_state_.rpt_mode &
00964     (CWIID_RPT_BTN | CWIID_RPT_ACC | CWIID_RPT_IR);
00965 }
00966 bool WiimoteNode::isCollectingNunchuk()
00967 {
00968   return wiimote_state_.rpt_mode & CWIID_RPT_NUNCHUK;
00969 }
00970 bool WiimoteNode::isCollectingClassic()
00971 {
00972   return wiimote_state_.rpt_mode & CWIID_RPT_CLASSIC;
00973 }
00974 bool WiimoteNode::isCollectingMotionplus()
00975 {
00976   return wiimote_state_.rpt_mode & CWIID_RPT_MOTIONPLUS;
00977 }
00978 
00979 bool WiimoteNode::isPresentNunchuk()
00980 {
00981   return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_NUNCHUK;
00982 }
00983 bool WiimoteNode::isPresentClassic()
00984 {
00985   return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_CLASSIC;
00986 }
00987 bool WiimoteNode::isPresentMotionplus()
00988 {
00989   return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_MOTIONPLUS;
00990 }
00991 
00992 bool WiimoteNode::calibrateJoystick(uint8_t stick[2], uint8_t (&center)[2], const char *name)
00993 {
00994   bool is_calibrated = false;
00995 
00996   // Grab the current Joystick position as center
00997   // If it is not reporting 0, 0
00998   if (stick[CWIID_X] != 0 && stick[CWIID_Y] != 0)
00999   {
01000     center[CWIID_X] = stick[CWIID_X];
01001     center[CWIID_Y] = stick[CWIID_Y];
01002 
01003     is_calibrated = true;
01004 
01005     ROS_DEBUG("%s Joystick Center:: x:%d, y:%d", name, center[CWIID_X], center[CWIID_Y]);
01006   }
01007 
01008   return is_calibrated;
01009 }
01010 
01011 void WiimoteNode::updateJoystickMinMax(uint8_t stick[2], uint8_t (&stick_min)[2],
01012     uint8_t (&stick_max)[2], const char *name)
01013 {
01014   bool updated = false;
01015 
01016   if (stick[CWIID_X] < stick_min[CWIID_X])
01017   {
01018     stick_min[CWIID_X] = stick[CWIID_X];
01019     updated = true;
01020   }
01021 
01022   if (stick[CWIID_Y] < stick_min[CWIID_Y])
01023   {
01024     stick_min[CWIID_Y] = stick[CWIID_Y];
01025     updated = true;
01026   }
01027 
01028   if (stick[CWIID_X] > stick_max[CWIID_X])
01029   {
01030     stick_max[CWIID_X] = stick[CWIID_X];
01031     updated = true;
01032   }
01033 
01034   if (stick[CWIID_Y] > stick_max[CWIID_Y])
01035   {
01036     stick_max[CWIID_Y] = stick[CWIID_Y];
01037     updated = true;
01038   }
01039 
01040   if (updated)
01041   {
01042     ROS_DEBUG("%s Joystick:: Min x:%3d, y:%3d  Max x:%3d, y:%3d", name,
01043         stick_min[CWIID_X], stick_min[CWIID_Y], stick_max[CWIID_X], stick_max[CWIID_Y]);
01044   }
01045 }
01046 
01047 void WiimoteNode::calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2],
01048     uint8_t stick_max[2], uint8_t stick_center[2], double (&stick)[2])
01049 {
01050   double deadzone[2];
01051   int deadzoneMargin = 4;
01052 
01053   // Scale the Wiimote Joystick integer values (0-31, 63, or 255)
01054   // to a double value between 0.0 and 1.0.
01055 
01056   // The width of the center deadzone needs to scale
01057   // with the resolution of the joystick in use.
01058   // Nunchuk range is 0-255; defaults to 4
01059   // Classic Left range is 0-63; set to 2
01060   // Classic Right range is 0-31; set to 1
01061   // Original Python implementation was always 0.05 for all
01062 
01063   // Optimize for Nunchuk case; most common
01064   if (stick_max[CWIID_X] < 128)
01065   {
01066     if (stick_max[CWIID_X] < 32)
01067     {
01068       deadzoneMargin = 1;
01069     }
01070     else if (stick_max[CWIID_X] < 64)
01071     {
01072       deadzoneMargin = 2;
01073     }
01074     else
01075     {
01076       // No known wiimote joystick uses this range
01077       deadzoneMargin = 3;
01078     }
01079   }
01080 
01081   if (stick_current[CWIID_X] > stick_center[CWIID_X])
01082   {
01083     stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
01084       ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
01085     deadzone[CWIID_X] = deadzoneMargin /
01086       ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
01087   }
01088   else
01089   {
01090     stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
01091       ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
01092     deadzone[CWIID_X] = deadzoneMargin /
01093       ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
01094   }
01095   if (stick_current[CWIID_Y] > stick_center[CWIID_Y])
01096   {
01097     stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
01098       ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
01099     deadzone[CWIID_Y] = deadzoneMargin /
01100       ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
01101   }
01102   else
01103   {
01104     stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
01105       ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
01106     deadzone[CWIID_Y] = deadzoneMargin /
01107       ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
01108   }
01109 
01110   // Create a deadzone in the center
01111   if (fabs(stick[CWIID_X]) <= deadzone[CWIID_X])
01112   {
01113     stick[CWIID_X] = 0.0;
01114   }
01115   if (fabs(stick[CWIID_Y]) <= deadzone[CWIID_Y])
01116   {
01117     stick[CWIID_Y] = 0.0;
01118   }
01119 }
01120 
01121 void WiimoteNode::publishJoy()
01122 {
01123   sensor_msgs::Joy joy_data;
01124 
01125   joy_data.header.stamp.sec = state_secs_;
01126   joy_data.header.stamp.nsec = state_nsecs_;
01127 
01128   joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_X],
01129         wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
01130   joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Y],
01131         wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
01132   joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Z],
01133         wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
01134 
01135   // NOTE: Order is different for /wiimote/state
01136   // Keep consistency with existing Python Node
01137   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_1) > 0);
01138   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_2) > 0);
01139   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_A) > 0);
01140   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_B) > 0);
01141   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
01142   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
01143   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
01144   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
01145   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
01146   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
01147   joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
01148 
01149   joy_pub_.publish(joy_data);
01150 }
01151 
01152 void WiimoteNode::publishImuData()
01153 {
01154   // The Wiimote provides the Acceleration and optionally Gyro
01155   // if MotionPlus is available, but not orientation information.
01156 
01157   sensor_msgs::Imu imu_data_data;
01158 
01159   imu_data_data.header.stamp.sec = state_secs_;
01160   imu_data_data.header.stamp.nsec = state_nsecs_;
01161 
01162   // Publish that Orientation data is invalid
01163   // [ -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 ]
01164   imu_data_data.orientation_covariance[0] = -1.0;
01165 
01166   // Acceleration
01167   imu_data_data.linear_acceleration.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
01168       wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
01169   imu_data_data.linear_acceleration.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
01170       wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
01171   imu_data_data.linear_acceleration.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
01172       wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
01173 
01174   imu_data_data.linear_acceleration_covariance = linear_acceleration_covariance_;
01175 
01176   // MotionPlus Gyro
01177   if (isPresentMotionplus())
01178   {
01179     imu_data_data.angular_velocity.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
01180         angular_velocity_stat_.getMeanRaw()[CWIID_PHI]) * GYRO_SCALE_FACTOR_;
01181     imu_data_data.angular_velocity.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
01182         angular_velocity_stat_.getMeanRaw()[CWIID_THETA]) * GYRO_SCALE_FACTOR_;
01183     imu_data_data.angular_velocity.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
01184         angular_velocity_stat_.getMeanRaw()[CWIID_PSI]) * GYRO_SCALE_FACTOR_;
01185   }
01186 
01187   imu_data_data.angular_velocity_covariance = angular_velocity_covariance_;
01188 
01189   imu_data_pub_.publish(imu_data_data);
01190 }
01191 
01192 void WiimoteNode::publishWiimoteState()
01193 {
01194   wiimote::State wiimote_state_data;
01195 
01196   wiimote_state_data.header.stamp.sec = state_secs_;
01197   wiimote_state_data.header.stamp.nsec = state_nsecs_;
01198 
01199   // Wiimote data
01200   wiimote_state_data.linear_acceleration_zeroed.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
01201       wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
01202   wiimote_state_data.linear_acceleration_zeroed.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
01203       wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
01204   wiimote_state_data.linear_acceleration_zeroed.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
01205       wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
01206 
01207   wiimote_state_data.linear_acceleration_raw.x = wiimote_state_.acc[CWIID_X];
01208   wiimote_state_data.linear_acceleration_raw.y = wiimote_state_.acc[CWIID_Y];
01209   wiimote_state_data.linear_acceleration_raw.z = wiimote_state_.acc[CWIID_Z];
01210 
01211   wiimote_state_data.linear_acceleration_covariance = linear_acceleration_covariance_;
01212 
01213   // MotionPlus Gyro
01214   wiimote_state_data.angular_velocity_covariance = angular_velocity_covariance_;
01215 
01216   if (isPresentMotionplus())
01217   {
01218     wiimote_state_data.angular_velocity_zeroed.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
01219         angular_velocity_stat_.getMeanRaw()[CWIID_PHI]) * GYRO_SCALE_FACTOR_;
01220     wiimote_state_data.angular_velocity_zeroed.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
01221         angular_velocity_stat_.getMeanRaw()[CWIID_THETA]) * GYRO_SCALE_FACTOR_;
01222     wiimote_state_data.angular_velocity_zeroed.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
01223         angular_velocity_stat_.getMeanRaw()[CWIID_PSI]) * GYRO_SCALE_FACTOR_;
01224 
01225     wiimote_state_data.angular_velocity_raw.x = wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI];
01226     wiimote_state_data.angular_velocity_raw.y = wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA];
01227     wiimote_state_data.angular_velocity_raw.z = wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI];
01228   }
01229 
01230   // NOTE: Order is different for /joy
01231   // Keep consistency with existing Python Node
01232   wiimote_state_data.buttons.elems[ 0] = ((wiimote_state_.buttons & CWIID_BTN_1) > 0);
01233   wiimote_state_data.buttons.elems[ 1] = ((wiimote_state_.buttons & CWIID_BTN_2) > 0);
01234   wiimote_state_data.buttons.elems[ 2] = ((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
01235   wiimote_state_data.buttons.elems[ 3] = ((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
01236   wiimote_state_data.buttons.elems[ 4] = ((wiimote_state_.buttons & CWIID_BTN_A) > 0);
01237   wiimote_state_data.buttons.elems[ 5] = ((wiimote_state_.buttons & CWIID_BTN_B) > 0);
01238   wiimote_state_data.buttons.elems[ 6] = ((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
01239   wiimote_state_data.buttons.elems[ 7] = ((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
01240   wiimote_state_data.buttons.elems[ 8] = ((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
01241   wiimote_state_data.buttons.elems[ 9] = ((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
01242   wiimote_state_data.buttons.elems[10] = ((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
01243 
01244   // Nunchuk data
01245   if (isPresentNunchuk())
01246   {
01247     if (publishWiimoteNunchukCommon())
01248     {
01249       // Joy stick
01250       double stick[2];
01251 
01252       calculateJoystickAxisXY(wiimote_state_.ext.nunchuk.stick, nunchuk_stick_min_,
01253           nunchuk_stick_max_, nunchuk_stick_center_, stick);
01254 
01255       wiimote_state_data.nunchuk_joystick_raw[CWIID_X] = wiimote_state_.ext.nunchuk.stick[CWIID_X];
01256       wiimote_state_data.nunchuk_joystick_raw[CWIID_Y] = wiimote_state_.ext.nunchuk.stick[CWIID_Y];
01257 
01258       wiimote_state_data.nunchuk_joystick_zeroed[CWIID_X] = stick[CWIID_X];
01259       wiimote_state_data.nunchuk_joystick_zeroed[CWIID_Y] = stick[CWIID_Y];
01260 
01261       wiimote_state_data.nunchuk_acceleration_raw.x = wiimote_state_.ext.nunchuk.acc[CWIID_X];
01262       wiimote_state_data.nunchuk_acceleration_raw.y = wiimote_state_.ext.nunchuk.acc[CWIID_Y];
01263       wiimote_state_data.nunchuk_acceleration_raw.z = wiimote_state_.ext.nunchuk.acc[CWIID_Z];
01264 
01265       wiimote_state_data.nunchuk_acceleration_zeroed.x =
01266         zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
01267             nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
01268       wiimote_state_data.nunchuk_acceleration_zeroed.y =
01269         zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
01270             nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
01271       wiimote_state_data.nunchuk_acceleration_zeroed.z =
01272         zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
01273             nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
01274 
01275       // Keep consistency with existing Python Node
01276       wiimote_state_data.nunchuk_buttons[0] =
01277         ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
01278       wiimote_state_data.nunchuk_buttons[1] =
01279         ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
01280     }
01281   }
01282 
01283   // IR Tracking Data
01284   for (int ir_idx = 0; ir_idx < CWIID_IR_SRC_COUNT; ir_idx++)
01285   {
01286     wiimote::IrSourceInfo irSourceInfo;
01287 
01288     if (wiimote_state_.ir_src[ir_idx].valid)
01289     {
01290       irSourceInfo.x = wiimote_state_.ir_src[ir_idx].pos[CWIID_X];
01291       irSourceInfo.y = wiimote_state_.ir_src[ir_idx].pos[CWIID_Y];
01292 
01293       irSourceInfo.ir_size = wiimote_state_.ir_src[ir_idx].size;
01294 
01295       if (irSourceInfo.ir_size < 1)
01296       {
01297         irSourceInfo.ir_size = wiimote::State::INVALID;
01298       }
01299     }
01300     else
01301     {
01302       irSourceInfo.x = wiimote::State::INVALID_FLOAT;
01303       irSourceInfo.y = wiimote::State::INVALID_FLOAT;
01304 
01305       irSourceInfo.ir_size = wiimote::State::INVALID;
01306     }
01307 
01308     wiimote_state_data.ir_tracking.push_back(irSourceInfo);
01309   }
01310 
01311   // LEDs / Rumble
01312   for (uint8_t i = 0; i < 4; i++)
01313   {
01314     wiimote_state_data.LEDs[i] = wiimote_state_.led & (0x1 << i);
01315   }
01316   wiimote_state_data.rumble = wiimote_state_.rumble & 0x1;
01317 
01318   // Battery
01319   wiimote_state_data.raw_battery = wiimote_state_.battery;
01320   wiimote_state_data.percent_battery = wiimote_state_.battery * 100.0 / CWIID_BATTERY_MAX;
01321 
01322   // Zeroing time (aka Calibration time)
01323   wiimote_state_data.zeroing_time = calibration_time_;
01324 
01325   // Wiimote state errors
01326   // No usage found in original Python code which every set this variable
01327   // TODO(mdhorn): Use this to report error
01328   // Is this a count? or a bunch of status that are ORed together?
01329   wiimote_state_data.errors = wiimote_errors;
01330 
01331   wiimote_state_pub_.publish(wiimote_state_data);
01332 }
01333 
01334 bool WiimoteNode::publishWiimoteNunchukCommon()
01335 {
01336   // Testing different Nunchuks show that they have different
01337   // centers and different range of motion.
01338   //
01339   // Best Approximation:
01340   // Grabbing the first set of x, y with the assumption of
01341   // the joystick is centered.
01342   // We know the joystick can only report between 0 and 255
01343   // for each axis; so assume a 20% guard band to set the
01344   // initial minimums and maximums. As the joystick is used,
01345   // updated the min/max values based on observed data.
01346   // This will have the effect of a less throw of the joystick
01347   // throttle during first movement to the max/min position.
01348   //
01349   // TODO(mdhorn): Could be improved by a true user interaction calibration
01350   // to find the center of the joystick, the max and min for each x and y.
01351   // But the effort in coding and extra burden on the one the user
01352   // may not be warranted.
01353 
01354   bool result = true;
01355 
01356   if (isPresentNunchuk())
01357   {
01358     if (!nunchuk_stick_calibrated_)
01359     {
01360       nunchuk_stick_calibrated_ = calibrateJoystick(
01361           wiimote_state_.ext.nunchuk.stick, nunchuk_stick_center_, "Nunchuk");
01362 
01363       // Don't publish if we haven't found the center position
01364       if (!nunchuk_stick_calibrated_)
01365       {
01366         result = false;
01367       }
01368     }
01369 
01370     updateJoystickMinMax(wiimote_state_.ext.nunchuk.stick, nunchuk_stick_min_,
01371         nunchuk_stick_max_, "Nunchuk");
01372   }
01373   else
01374   {
01375     ROS_WARN("State type is not Nunchuk!");
01376     result = false;
01377   }
01378 
01379   return result;
01380 }
01381 
01382 void WiimoteNode::publishWiimoteNunchuk()
01383 {
01384   sensor_msgs::Joy wiimote_nunchuk_data;
01385 
01386   if (publishWiimoteNunchukCommon())
01387   {
01388     wiimote_nunchuk_data.header.stamp.sec = state_secs_;
01389     wiimote_nunchuk_data.header.stamp.nsec = state_nsecs_;
01390 
01391     // Joy stick
01392     double stick[2];
01393 
01394     calculateJoystickAxisXY(wiimote_state_.ext.nunchuk.stick, nunchuk_stick_min_,
01395         nunchuk_stick_max_, nunchuk_stick_center_, stick);
01396 
01397     wiimote_nunchuk_data.axes.push_back(stick[CWIID_X]);  // x
01398     wiimote_nunchuk_data.axes.push_back(stick[CWIID_Y]);  // y
01399 
01400     wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
01401           nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
01402     wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
01403           nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
01404     wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
01405           nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
01406 
01407 
01408     // NOTE: Order is different for /wiimote/state
01409     // Keep consistency with existing Python Node
01410     wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
01411     wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
01412 
01413     wiimote_nunchuk_pub_.publish(wiimote_nunchuk_data);
01414   }
01415 }
01416 
01417 void WiimoteNode::publishWiimoteClassic()
01418 {
01419   // Using the same "Best Approximation" methods from
01420   // WiimoteNode::publishWiimoteNunchuk()
01421 
01422   sensor_msgs::Joy wiimote_classic_data;
01423 
01424   if (isPresentClassic())
01425   {
01426     ROS_WARN("State type is not Classic!");
01427     return;
01428   }
01429 
01430   if (!classic_stick_left_calibrated_)
01431   {
01432     classic_stick_left_calibrated_ = calibrateJoystick(
01433         wiimote_state_.ext.classic.l_stick, classic_stick_left_center_, "Classic Left");
01434   }
01435 
01436   if (!classic_stick_right_calibrated_)
01437   {
01438     classic_stick_right_calibrated_ = calibrateJoystick(
01439         wiimote_state_.ext.classic.r_stick, classic_stick_right_center_, "Classic Right");
01440   }
01441 
01442   if ((!classic_stick_left_calibrated_) ||
01443       (!classic_stick_right_calibrated_))
01444   {
01445     // Don't publish if we haven't found the center positions
01446     return;
01447   }
01448 
01449   updateJoystickMinMax(wiimote_state_.ext.classic.l_stick, classic_stick_left_min_,
01450       classic_stick_left_max_, "Classic Left");
01451   updateJoystickMinMax(wiimote_state_.ext.classic.r_stick, classic_stick_right_min_,
01452       classic_stick_right_max_, "Classic Right");
01453 
01454   wiimote_classic_data.header.stamp.sec = state_secs_;
01455   wiimote_classic_data.header.stamp.nsec = state_nsecs_;
01456 
01457   // Joy stick
01458   double stick_left[2];
01459   double stick_right[2];
01460 
01461   calculateJoystickAxisXY(wiimote_state_.ext.classic.l_stick, classic_stick_left_min_,
01462       classic_stick_left_max_, classic_stick_left_center_, stick_left);
01463   calculateJoystickAxisXY(wiimote_state_.ext.classic.r_stick, classic_stick_right_min_,
01464       classic_stick_right_max_, classic_stick_right_center_, stick_right);
01465 
01466   wiimote_classic_data.axes.push_back(stick_left[CWIID_X]);   // Left x
01467   wiimote_classic_data.axes.push_back(stick_left[CWIID_Y]);   // Left y
01468   wiimote_classic_data.axes.push_back(stick_right[CWIID_X]);  // Right x
01469   wiimote_classic_data.axes.push_back(stick_right[CWIID_Y]);  // Right y
01470 
01471   // NOTE: Order is different for /wiimote/state
01472   // Keep consistency with existing Python Node
01473   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_X) > 0);
01474   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_Y) > 0);
01475   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_A) > 0);
01476   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_B) > 0);
01477   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_PLUS) > 0);
01478   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_MINUS) > 0);
01479   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_LEFT) > 0);
01480   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_RIGHT) > 0);
01481   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_UP) > 0);
01482   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_DOWN) > 0);
01483   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_HOME) > 0);
01484   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_L) > 0);
01485   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_R) > 0);
01486   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZL) > 0);
01487   wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZR) > 0);
01488 
01489   wiimote_classic_pub_.publish(wiimote_classic_data);
01490 }
01491 
01492 // const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback is unused
01493 void WiimoteNode::joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback)
01494 {
01495   bool led_found = false;
01496   bool rumble_found = false;
01497 
01498   for (std::vector<sensor_msgs::JoyFeedback>::const_iterator it = feedback->array.begin();
01499       it != feedback->array.end(); ++it)
01500   {
01501     if ((*it).type == sensor_msgs::JoyFeedback::TYPE_LED)
01502     {
01503       led_found = true;
01504 
01505       if ((*it).intensity >= 0.5)
01506       {
01507         setLEDBit((*it).id, true);
01508       }
01509       else
01510       {
01511         setLEDBit((*it).id, false);
01512       }
01513     }
01514     else if ((*it).type == sensor_msgs::JoyFeedback::TYPE_RUMBLE)
01515     {
01516       if ((*it).id > 0)
01517       {
01518         ROS_WARN("RUMBLE ID %d out of bounds; ignoring!", (*it).id);
01519       }
01520       else
01521       {
01522         rumble_found = true;
01523 
01524         if ((*it).intensity >= 0.5)
01525         {
01526           setRumbleBit(true);
01527         }
01528         else
01529         {
01530           setRumbleBit(false);
01531         }
01532       }
01533     }
01534     else
01535     {
01536       ROS_WARN("Unknown JoyFeedback command; ignored");
01537     }
01538   }
01539 
01540   if (led_found)
01541   {
01542     setLedState(led_state_);
01543   }
01544 
01545   if (rumble_found)
01546   {
01547     setRumbleState(rumble_);
01548   }
01549 }
01550 
01551 bool WiimoteNode::serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
01552 {
01553   // Publish the new calibration state
01554   checkFactoryCalibrationData();
01555 
01556   return true;
01557 }
01558 
01559 WiimoteNode *g_wiimote_node;
01560 
01561 // int sig The signal number is unused
01562 void mySigHandler(int sig)
01563 {
01564   // Do some custom action.
01565   // For example, publish a stop message to some other nodes.
01566 
01567   // Clear the lights and rumble
01568   if (nullptr != g_wiimote_node)
01569   {
01570     g_wiimote_node->setRumbleState(0);
01571     g_wiimote_node->setLedState(0);
01572   }
01573 
01574   // All the default sigint handler does is call shutdown()
01575   ros::shutdown();
01576 
01577   exit(0);
01578 }
01579 
01580 int main(int argc, char *argv[])
01581 {
01582   bool fed_addr = false;
01583   std::string bluetooth_addr;
01584   ros::init(argc, argv, "wiimote_controller");
01585 
01586   g_wiimote_node = new WiimoteNode();
01587   // Do we have a bluetooth address passed in?
01588   if (argc > 1)
01589   {
01590     ROS_INFO("Using Bluetooth address specified from CLI");
01591     g_wiimote_node->setBluetoothAddr(argv[1]);
01592     fed_addr = true;
01593   }
01594 
01595   if (ros::param::get("~bluetooth_addr", bluetooth_addr))
01596   {
01597     g_wiimote_node->setBluetoothAddr(bluetooth_addr.c_str());
01598     fed_addr = true;
01599   }
01600 
01601   int pair_timeout;
01602   ros::param::param<int>("~pair_timeout", pair_timeout, 5);
01603 
01604   if (fed_addr)
01605     ROS_INFO("* * * Pairing with %s", g_wiimote_node->getBluetoothAddr());
01606 
01607   else
01608     ROS_INFO("Searching for Wiimotes");
01609 
01610   ROS_INFO("Allow all joy sticks to remain at center position until calibrated.");
01611 
01612   if (g_wiimote_node->pairWiimote(0, pair_timeout))
01613   {
01614     ROS_INFO("Wiimote is Paired");
01615 
01616     signal(SIGINT, mySigHandler);
01617     signal(SIGTERM, mySigHandler);
01618   }
01619   else
01620   {
01621     ROS_ERROR("* * * Wiimote pairing failed.");
01622     ros::shutdown();
01623   }
01624 
01625   ros::Rate loop_rate(10);  // 10Hz
01626 
01627   while (ros::ok())
01628   {
01629     g_wiimote_node->publish();
01630 
01631     ros::spinOnce();
01632 
01633     loop_rate.sleep();
01634   }
01635 
01636   if (g_wiimote_node->unpairWiimote())
01637   {
01638     ROS_ERROR("Error on wiimote disconnect");
01639     return -1;
01640   }
01641 
01642   return 0;
01643 }


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Sun Jul 9 2017 02:34:58