wiimote_controller.cpp
Go to the documentation of this file.
1 /*
2  * ROS Node for interfacing with a wiimote control unit.
3  * Copyright (c) 2016, Intel Corporation.
4  *
5  * This program is free software; you can redistribute it and/or modify it
6  * under the terms and conditions of the GNU General Public License,
7  * version 2, as published by the Free Software Foundation.
8  *
9  * This program is distributed in the hope it will be useful, but WITHOUT
10  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12  * more details.
13  */
14 
15 /*
16  * This code is based on the original Python implementation
17  * created by Andreas Paepcke and Melonee Wise
18  * Andreas Paepcke <paepcke@anw.willowgarage.com>
19  * with contributions by
20  * David Lu <davidlu@wustl.edu>
21  * Miguel Angel Julian Aguilar <miguel.angel@thecorpora.com>
22  * See https://github.com/ros-drivers/joystick_drivers/tree/indigo-devel/wiimote
23  * for details and history.
24  *
25  * This C++ implementation used the functionality of the existing
26  * Python code as the feature requirements.
27  */
28 
29 /*
30  * Initial C++ implementation by
31  * Mark Horn <mark.d.horn@intel.com>
32  *
33  * The C++ implementation was designed with focus on reduced resource consumption.
34  *
35  * Differences from Python implementation:
36  * - Both "/wiimote/nunchuk" and "/wiimote/classic" topics are only published
37  * if the Nunchuk or Classic Controller are connected to the wiimote respectively.
38  * - Wiimote data is only polled from the controller if the data is required
39  * to publish for a topic which has at least one subscriber.
40  *
41  * Revisions:
42  *
43  */
44 
46 
47 #include "sensor_msgs/Joy.h"
48 #include "std_msgs/Bool.h"
49 
50 #include "wiimote/State.h"
51 #include "wiimote/IrSourceInfo.h"
52 
53 #include <stdarg.h>
54 #include <stdio.h>
55 #include <stdlib.h>
56 #include <unistd.h>
57 
58 #include <signal.h>
59 
60 #include <time.h>
61 #include <math.h>
62 
63 #include <vector>
64 #include <string>
65 
67 {
68  joy_pub_ = nh_.advertise<sensor_msgs::Joy>("/joy", 1);
69  imu_data_pub_ = nh_.advertise<sensor_msgs::Imu>("/imu/data", 1);
70  wiimote_state_pub_ = nh_.advertise<wiimote::State>("/wiimote/state", 1);
77  imu_is_calibrated_pub_ = nh_.advertise<std_msgs::Bool>("/imu/is_calibrated", 1, true);
78 
79  joy_set_feedback_sub_ = nh_.subscribe<sensor_msgs::JoyFeedbackArray>("/joy/set_feedback", 10,
81 
83 
84  // Initialize with the ANY Bluetooth Address
85  setBluetoothAddr("00:00:00:00:00:00");
86 
87  wiimote_ = nullptr;
88 
90 
91  state_secs_ = 0;
92  state_nsecs_ = 0;
93 
94  // Setup the Wii Error Handler
95  wiimote_c::cwiid_set_err(cwiidErrorCallback);
96 
97  report_mode_ = 0;
98 
99  wiimote_calibrated_ = false;
100 
105 }
106 
108 {
109 }
110 
112 {
113  wiimote_state_.rpt_mode = 0;
114  wiimote_state_.led = 0;
115  wiimote_state_.rumble = 0;
116  wiimote_state_.battery = 0;
117  wiimote_state_.buttons = 0;
118  wiimote_state_.acc[0] = 0;
119  wiimote_state_.acc[1] = 0;
120  wiimote_state_.acc[2] = 0;
121 
122  wiimote_state_.ext_type = wiimote_c::CWIID_EXT_NONE;
123  wiimote_state_.error = wiimote_c::CWIID_ERROR_NONE;
124 
125  wiimote_state_.ir_src[0].valid = 0;
126  wiimote_state_.ir_src[1].valid = 0;
127  wiimote_state_.ir_src[2].valid = 0;
128  wiimote_state_.ir_src[3].valid = 0;
129  wiimote_state_.ir_src[0].pos[0] = 0; wiimote_state_.ir_src[0].pos[1] = 0;
130  wiimote_state_.ir_src[1].pos[0] = 0; wiimote_state_.ir_src[1].pos[1] = 0;
131  wiimote_state_.ir_src[2].pos[0] = 0; wiimote_state_.ir_src[2].pos[1] = 0;
132  wiimote_state_.ir_src[3].pos[0] = 0; wiimote_state_.ir_src[3].pos[1] = 0;
133  wiimote_state_.ir_src[0].size = 0;
134  wiimote_state_.ir_src[1].size = 0;
135  wiimote_state_.ir_src[2].size = 0;
136  wiimote_state_.ir_src[3].size = 0;
137 }
138 
140 {
141  return batostr(&bt_device_addr_);
142 }
143 void WiimoteNode::setBluetoothAddr(const char *bt_str)
144 {
145  str2ba(bt_str, &bt_device_addr_);
146 }
147 
148 bool WiimoteNode::pairWiimote(int flags = 0, int timeout = 5)
149 {
150  bool status = true;
151 
152  ROS_INFO("Put Wiimote in discoverable mode now (press 1+2)...");
153  if (timeout == -1)
154  ROS_INFO("Searching indefinitely...");
155  else
156  ROS_INFO("Timeout in about %d seconds if not paired.", timeout);
157 
158  if (!(wiimote_ = wiimote_c::cwiid_open_timeout(&bt_device_addr_, flags, timeout)))
159  {
160  ROS_ERROR("Unable to connect to wiimote");
161  status = false;
162  }
163  else
164  {
165  // Give the hardware time to zero the accelerometer and gyro after pairing
166  // Ensure we are getting valid data before using
167  sleep(1);
168 
170 
171  if (!wiimote_calibrated_)
172  {
173  ROS_ERROR("Wiimote not usable due to calibration failure.");
174  status = false;
175  }
176  }
177 
178  return status;
179 }
181 {
182  return wiimote_c::cwiid_close(wiimote_);
183 }
184 
186 {
187  bool result = true;
188 
189  if (wiimote_c::cwiid_get_acc_cal(wiimote_, wiimote_c::CWIID_EXT_NONE, &wiimote_cal_) != 0)
190  {
192  {
193  ROS_WARN("Failed to read current Wiimote calibration data; proceeding with previous data");
194  }
195  else
196  {
197  ROS_ERROR("Failed to read Wiimote factory calibration data");
198  result = false;
199  }
200  }
201  else
202  {
203  // If any calibration point is zero; we fail
204  if (!(wiimote_cal_.zero[CWIID_X] && wiimote_cal_.zero[CWIID_Y] && wiimote_cal_.zero[CWIID_Z] &&
205  wiimote_cal_.one[CWIID_X] && wiimote_cal_.one[CWIID_Y] && wiimote_cal_.one[CWIID_Z]))
206  {
207  ROS_ERROR("Some Wiimote factory calibration data is missing; calibration failed");
208  ROS_ERROR("Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
209  wiimote_cal_.zero[CWIID_X], wiimote_cal_.zero[CWIID_Y], wiimote_cal_.zero[CWIID_Z],
210  wiimote_cal_.one[CWIID_X], wiimote_cal_.one[CWIID_Y], wiimote_cal_.one[CWIID_Z]);
211 
212  result = false;
213  }
214  else
215  {
216  wiimote_calibrated_ = true;
217  ROS_DEBUG("Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
218  wiimote_cal_.zero[CWIID_X], wiimote_cal_.zero[CWIID_Y], wiimote_cal_.zero[CWIID_Z],
219  wiimote_cal_.one[CWIID_X], wiimote_cal_.one[CWIID_Y], wiimote_cal_.one[CWIID_Z]);
220  }
221  }
222 
223  if (!getStateSample())
224  {
225  ROS_WARN("Could not read Wiimote state; nunchuk may not be calibrated if present.");
226  }
227  else
228  {
229  if (isPresentNunchuk())
230  {
231  if (wiimote_c::cwiid_get_acc_cal(wiimote_, wiimote_c::CWIID_EXT_NUNCHUK, &nunchuk_cal_) != 0)
232  {
234  {
235  ROS_WARN("Failed to read current Nunchuk calibration data; proceeding with previous data");
236  }
237  else
238  {
239  ROS_ERROR("Failed to read Nunchuk factory calibration data");
240  result = false;
242  }
243  }
244  else
245  {
246  // If any calibration point is zero; we fail
247  if (!(nunchuk_cal_.zero[CWIID_X] && nunchuk_cal_.zero[CWIID_Y] && nunchuk_cal_.zero[CWIID_Z] &&
248  nunchuk_cal_.one[CWIID_X] && nunchuk_cal_.one[CWIID_Y] && nunchuk_cal_.one[CWIID_Z]))
249  {
250  ROS_ERROR("Some Nunchuk factory calibration data is missing; calibration failed");
251  ROS_ERROR("Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
252  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.zero[CWIID_Z],
253  nunchuk_cal_.one[CWIID_X], nunchuk_cal_.one[CWIID_Y], nunchuk_cal_.one[CWIID_Z]);
254  result = false;
256  }
257  else
258  {
259  nunchuk_calibrated_ = true;
260  ROS_DEBUG("Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
261  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.zero[CWIID_Z],
262  nunchuk_cal_.one[CWIID_X], nunchuk_cal_.one[CWIID_Y], nunchuk_cal_.one[CWIID_Z]);
263  }
264  }
265  }
266  }
267 
269  {
270  // Save the current reporting mode
271  uint8_t save_report_mode = wiimote_state_.rpt_mode;
272 
273  // Need to ensure we are collecting accelerometer
274  uint8_t new_report_mode = save_report_mode | (CWIID_RPT_ACC | CWIID_RPT_EXT);
275 
276  if (new_report_mode != save_report_mode)
277  {
278  setReportMode(new_report_mode);
279  }
280 
281  ROS_INFO("Collecting additional calibration data; keep wiimote stationary...");
282 
283  StatVector3d linear_acceleration_stat_old = linear_acceleration_stat_;
285  StatVector3d angular_velocity_stat_old = angular_velocity_stat_;
287 
288  bool failed = false;
289  bool data_complete = false;
290  int wiimote_data_points = 0;
291  int motionplus_data_points = 0;
292 
293  while (!failed && !data_complete)
294  {
295  if (getStateSample())
296  {
297  if (wiimote_data_points < COVARIANCE_DATA_POINTS_)
298  {
300  wiimote_state_.acc[CWIID_X],
301  wiimote_state_.acc[CWIID_Y],
302  wiimote_state_.acc[CWIID_Z]);
303 
304  ++wiimote_data_points;
305  }
306 
307  if (isPresentMotionplus())
308  {
309  if (motionplus_data_points < COVARIANCE_DATA_POINTS_)
310  {
311  // ROS_DEBUG("New MotionPlus data :%03d: PHI: %04d, THETA: %04d, PSI: %04d", motionplus_data_points,
312  // wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI],
313  // wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA],
314  // wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI]);
316  wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI],
317  wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA],
318  wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI]);
319 
320  ++motionplus_data_points;
321  }
322  }
323  }
324  else
325  {
326  failed = true;
327  }
328 
329  if (wiimote_data_points >= COVARIANCE_DATA_POINTS_)
330  {
331  if (!isPresentMotionplus())
332  {
333  data_complete = true;
334  }
335  else
336  {
337  if (motionplus_data_points >= COVARIANCE_DATA_POINTS_)
338  {
339  data_complete = true;
340  }
341  }
342  }
343  }
344 
345  if (!failed)
346  {
347  ROS_DEBUG("Calculating calibration data...");
348 
349  // Check the standard deviations > 1.0
351  bool is_bad_cal = false;
352  std::for_each(std::begin(stddev), std::end(stddev), [&](const double d) // NOLINT(build/c++11)
353  {
354  if (d > 1.0)
355  {
356  is_bad_cal = true;
357  ROS_DEBUG("Wiimote standard deviation > 1.0");
358  }
359  }); // NOLINT(whitespace/braces)
360 
361  if (!is_bad_cal)
362  {
364 
365  ROS_DEBUG("Variance Scaled x: %lf, y: %lf, z: %lf", variance.at(CWIID_X),
366  variance.at(CWIID_Y), variance.at(CWIID_Z));
367 
368  linear_acceleration_covariance_[0] = variance.at(CWIID_X);
371 
373  linear_acceleration_covariance_[4] = variance.at(CWIID_Y);
375 
378  linear_acceleration_covariance_[8] = variance.at(CWIID_Z);
379  }
380  else
381  {
382  ROS_ERROR("Failed calibration; using questionable data for linear acceleration");
383 
384  linear_acceleration_stat_ = linear_acceleration_stat_old;
385  angular_velocity_stat_ = angular_velocity_stat_old;
386 
387  result = false;
388  }
389 
391  {
392  // Check the standard deviations > 50.0
394  std::for_each(std::begin(gyro_stddev), std::end(gyro_stddev), [&](const double d) // NOLINT(build/c++11)
395  {
396  if (d > 50.0)
397  {
398  is_bad_cal = true;
399  ROS_DEBUG("MotionPlus standard deviation > 50");
400  }
401  }); // NOLINT(whitespace/braces)
402 
403  if (!is_bad_cal)
404  {
406 
407  ROS_DEBUG("Gyro Variance Scaled x: %lf, y: %lf, z: %lf", gyro_variance.at(CWIID_PHI),
408  gyro_variance.at(CWIID_THETA), gyro_variance.at(CWIID_PSI));
409 
410  angular_velocity_covariance_[0] = gyro_variance.at(CWIID_PHI);
413 
415  angular_velocity_covariance_[4] = gyro_variance.at(CWIID_THETA);
417 
420  angular_velocity_covariance_[8] = gyro_variance.at(CWIID_PSI);
421  }
422  else
423  {
424  ROS_ERROR("Failed calibration; using questionable data for angular velocity");
425 
426  angular_velocity_stat_ = angular_velocity_stat_old;
427 
428  result = false;
429  }
430  }
431  else
432  {
434  }
435  }
436 
437  if (failed)
438  {
439  ROS_ERROR("Failed calibration; using questionable data");
440  result = false;
441  }
442  else
443  {
444  struct timespec state_tv;
445 
446  if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
447  {
449  }
450  else
451  {
452  ROS_WARN("Could not update calibration time.");
453  }
454  }
455 
456  // Restore the pre-existing reporting mode
457  if (new_report_mode != save_report_mode)
458  {
459  setReportMode(save_report_mode);
460  }
461  }
462 
463  // Publish the initial calibration state
464  std_msgs::Bool imu_is_calibrated_data;
465  imu_is_calibrated_data.data = result;
466  imu_is_calibrated_pub_.publish(imu_is_calibrated_data);
467 }
468 
470 {
471  // If no gyro is attached to the Wiimote then we signal
472  // the invalidity of angular rate with a covariance matrix
473  // whose first element is -1:
477 
481 
485 }
486 
488 {
489  nunchuk_calibrated_ = false;
490 
498 }
499 
501 {
516 }
517 
519 {
520  uint8_t joy_subscribers = joy_pub_.getNumSubscribers();
521  uint8_t wii_state_subscribers = wiimote_state_pub_.getNumSubscribers();
522  uint8_t imu_subscribers = imu_data_pub_.getNumSubscribers();
523  uint8_t wii_nunchuk_subscribers = 0;
524  uint8_t wii_classic_subscribers = 0;
525 
526  uint8_t current_report_mode = wiimote_state_.rpt_mode;
527  uint8_t new_report_mode = current_report_mode;
528 
529  /* CWIID_RPT_xxx
530 
531  | | | |M| | |
532  | | | |O| | |
533  | | | |T| | |
534  | | | |I|N|C|
535  | | | |O|U|L|
536  | | | |N|N|A|
537  | | | |P|C|S|
538  | |B|A|L|H|S|
539  |I|T|C|U|U|I|
540  ROS_Topic |R|N|C|S|K|C|
541  |_|_|_|_|_|_|
542  joy | |x|x|x| | |
543  imu_data | | |x|x| | |
544  wiimote_state |x|x|x|x|x| |
545  wiimote_nunchuk | | | | |x| |
546  wiimote_classic | | | | | |x|
547  */
548 
549  if (joy_subscribers || wii_state_subscribers || imu_subscribers)
550  {
551  // Need to collect data on accelerometer and motionplus
552  new_report_mode |= (CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
553 
554  if (joy_subscribers || wii_state_subscribers)
555  {
556  // Need to also collect data on buttons
557  new_report_mode |= (CWIID_RPT_BTN);
558  }
559 
560  if (wii_state_subscribers)
561  {
562  // Need to also collect data on IR and Nunchuk
563  new_report_mode |= (CWIID_RPT_IR | CWIID_RPT_NUNCHUK);
564  }
565  }
566  else
567  {
568  if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers)
569  {
570  // Can stop collecting data on accelerometer and motionplus
571  new_report_mode &= ~(CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
572  }
573 
574  if (!joy_subscribers && !wii_state_subscribers)
575  {
576  // Can also stop collecting data on buttons
577  new_report_mode &= ~(CWIID_RPT_BTN);
578  }
579 
580  if (!wii_state_subscribers)
581  {
582  // Can also stop collecting data on IR
583  new_report_mode &= ~(CWIID_RPT_IR);
584  }
585  }
586 
587  // Is the Nunchuk connected?
588  if (isPresentNunchuk())
589  {
590  // Is the Nunchuk publisher not advertised?
591  if (nullptr == wiimote_nunchuk_pub_)
592  {
594  {
595  // The nunchuk was just connected, so read the calibration data
596  if (!nunchuk_calibrated_)
597  {
599  }
600 
602  {
603  wiimote_nunchuk_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/nunchuk", 1);
604  }
605  else
606  {
607  ROS_ERROR("Topic /wiimote/nunchuk not advertised due to calibration failure");
608  }
609  }
610  }
611 
612  wii_nunchuk_subscribers = wiimote_nunchuk_pub_.getNumSubscribers();
613 
614  if (wii_nunchuk_subscribers)
615  {
616  // Need to collect data on nunchuk
617  new_report_mode |= (CWIID_RPT_NUNCHUK);
618  }
619  else
620  {
621  if (!wii_state_subscribers)
622  {
623  // Can stop collecting data on nunchuk
624  new_report_mode &= ~(CWIID_RPT_NUNCHUK);
625  }
626  }
627  }
628  else // Stop publishing the topic
629  {
630  // Is the Nunchuk publisher advertised?
631  if (nullptr != wiimote_nunchuk_pub_)
632  {
634 
636 
637  if (!wii_state_subscribers)
638  {
639  // Can stop collecting data on nunchuk
640  new_report_mode &= ~(CWIID_RPT_NUNCHUK);
641  }
642  }
643 
644  // If the nunchuk was connect, but failed calibration
645  // then attempt to check factory calibration for the wiimote
647  {
650  }
651  }
652 
653  // Is the Classic Pad connected?
654  if (isPresentClassic())
655  {
656  // Is the Classic Pad publisher not advertised?
657  if (nullptr == wiimote_classic_pub_)
658  {
659  wiimote_classic_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/classic", 1);
660  }
661 
662  wii_classic_subscribers = wiimote_classic_pub_.getNumSubscribers();
663 
664  if (wii_classic_subscribers)
665  {
666  // Need to collect data on classic
667  new_report_mode |= (CWIID_RPT_CLASSIC);
668  }
669  else
670  {
671  // Can stop collecting data on classic
672  new_report_mode &= ~(CWIID_RPT_CLASSIC);
673  }
674  }
675  else // Stop publishing the topic
676  {
677  // Is the Classic Pad publisher advertised?
678  if (nullptr != wiimote_classic_pub_)
679  {
681 
683 
684  // Can stop collecting data on classic
685  new_report_mode &= ~(CWIID_RPT_CLASSIC);
686  }
687  }
688 
689  // Update the reporting mode and returning
690  if (current_report_mode != new_report_mode)
691  {
692  setReportMode(new_report_mode);
693  }
694 
695  if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers &&
696  !wii_nunchuk_subscribers & !wii_classic_subscribers)
697  {
698  // If there are no subscribers, there isn't anything to publish
699  return;
700  }
701 
702 
703  if (!getStateSample())
704  {
705  // If we can not get State from the Wiimote, there isn't anything to publish
706  return;
707  }
708 
709 
710  if (joy_subscribers)
711  {
712  // ROS_DEBUG("Number joy subscribers is: %d", joy_subscribers);
713  publishJoy();
714  }
715 
716  if (imu_subscribers)
717  {
718  // ROS_DEBUG("Number imu_data subscribers is: %d", imu_subscribers);
719  publishImuData();
720  }
721 
722  if (wii_state_subscribers)
723  {
724  // ROS_DEBUG("Number wiimote_state subscribers is: %d", wii_state_subscribers);
726  }
727 
728  if (wii_nunchuk_subscribers)
729  {
730  // ROS_DEBUG("Number wiimote_nunchuk subscribers is: %d", wiimote_nunchuk_pub_.getNumSubscribers());
732  }
733 
734  // Is the Classic Pad connected?
735  if (wii_classic_subscribers)
736  {
737  // ROS_DEBUG("Number wiimote_classic subscribers is: %d", wiimote_classic_pub_.getNumSubscribers());
739  }
740 }
741 
743 {
744  bool result = true;
745  bool get_state_result = true;
746  bool data_valid = false;
747 
748  int count = 0;
749  int big_count = 0;
750  static int wiimote_count = 0;
751  static int motionplus_count = 0;
752 
753  do
754  {
755  get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
756 
757  if (isCollectingWiimote() &&
758  (wiimote_state_.acc[CWIID_X] == 0 &&
759  wiimote_state_.acc[CWIID_Y] == 0 &&
760  wiimote_state_.acc[CWIID_Z] == 0))
761  {
762  if (count > 1 && !(count % 100))
763  {
764  // If we can not get valid data from the Wiimote, wait and try again
765  ROS_INFO("Waiting for valid wiimote data...");
766  count = 0;
767  ++big_count;
768  }
769 
770  usleep(10000); // wait a hundredth of a second
771  ++count;
772  if (big_count > 10)
773  {
774  get_state_result = false;
775  }
776  }
777  else
778  {
779  if (wiimote_count < IGNORE_DATA_POINTS_)
780  {
781  // ROS_DEBUG("Ignoring Wiimote data point %d", wiimote_count);
782  wiimote_count++;
783  }
784  else
785  {
786  data_valid = true;
787  }
788  }
789 
790  usleep(10000); // wait a hundredth of a second
791  }
792  while (get_state_result && !data_valid);
793 
794  if (isPresentMotionplus())
795  {
796  data_valid = false;
797 
798  count = 0;
799  big_count = 0;
800 
801  do
802  {
803  if (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] == 0 &&
804  wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] == 0 &&
805  wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] == 0)
806  {
807  if (count > 1 && !(count % 100))
808  {
809  // If we can not get valid data from the Wiimote, wait and try again
810  ROS_INFO("Waiting for valid MotionPlus data...");
811  count = 0;
812  ++big_count;
813  }
814 
815  usleep(10000); // wait a hundredth of a second
816  ++count;
817  if (big_count > 10)
818  {
819  get_state_result = false;
820  }
821  else
822  {
823  usleep(10000); // wait a hundredth of a second
824  get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
825  }
826  }
827  else
828  {
829  if (motionplus_count < IGNORE_DATA_POINTS_)
830  {
831  ROS_DEBUG("Ignoring MotionPlus data point %d", motionplus_count);
832  motionplus_count++;
833  usleep(1000); // wait a thousandth of a second
834  }
835  else
836  {
837  data_valid = true;
838  // Get a new data point with valid data
839  get_state_result = (wiimote_c::cwiid_get_state(wiimote_, &wiimote_state_) == 0);
840  }
841  }
842  }
843  while (get_state_result && !data_valid);
844  }
845  else
846  {
847  // MotionPlus was removed, so reset the master count
848  motionplus_count = 0;
850  }
851 
852  if (get_state_result)
853  {
854  struct timespec state_tv;
855 
856  if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
857  {
858  state_secs_ = state_tv.tv_sec;
859  state_nsecs_ = state_tv.tv_nsec;
860  }
861  else
862  {
863  ROS_ERROR("Error sampling real-time clock");
864  result = false;
865  }
866  }
867  else
868  {
869  result = false;
870  }
871 
872  return result;
873 }
874 
875 void WiimoteNode::setReportMode(uint8_t rpt_mode)
876 {
877  ROS_DEBUG("Change report mode from %d to %d", wiimote_state_.rpt_mode, rpt_mode);
878 
879  if (wiimote_c::cwiid_set_rpt_mode(wiimote_, rpt_mode))
880  {
881  ROS_ERROR("Error setting report mode: Bit(s):%d", rpt_mode);
882  }
883  else
884  {
885  wiimote_state_.rpt_mode = rpt_mode;
886 
887  // Enable the MotionPlus
888  if (rpt_mode & CWIID_RPT_MOTIONPLUS)
889  {
890  wiimote_c::cwiid_enable(wiimote_, CWIID_FLAG_MOTIONPLUS);
891  ROS_DEBUG("Enabled MotionPlus");
892  }
893  }
894 }
895 
896 void WiimoteNode::setLEDBit(uint8_t led, bool on)
897 {
898  uint8_t bit;
899 
900  if (led > 3)
901  {
902  ROS_WARN("LED ID %d out of bounds; ignoring!", led);
903  }
904 
905  bit = 1 << led;
906 
907  if (on)
908  { // Set bit
909  led_state_ |= bit;
910  }
911  else
912  { // Clear bit
913  led_state_ &= ~(bit);
914  }
915 }
917 {
918  if (on)
919  { // Set bit
920  rumble_ |= 0x1;
921  }
922  else
923  { // Clear bit
924  rumble_ &= ~(0x1);
925  }
926 }
927 
928 void WiimoteNode::setLedState(uint8_t led_state)
929 {
930  if (wiimote_c::cwiid_set_led(wiimote_, led_state))
931  {
932  ROS_ERROR("Error setting LEDs");
933  }
934 }
935 
937 {
938  if (wiimote_c::cwiid_set_led(wiimote_, led_state_))
939  {
940  ROS_INFO("Connection to wiimote lost");
941  ros::shutdown();
942  }
943 }
944 
945 void WiimoteNode::setRumbleState(uint8_t rumble)
946 {
947  if (wiimote_c::cwiid_set_rumble(wiimote_, rumble))
948  {
949  ROS_ERROR("Error setting rumble");
950  }
951 }
952 
953 void WiimoteNode::cwiidErrorCallback(wiimote_c::cwiid_wiimote_t *wiimote, const char *fmt, va_list ap)
954 {
955  const int MAX_BUF = 500;
956  char msgs_buf[MAX_BUF];
957 
958  vsnprintf(msgs_buf, MAX_BUF, fmt, ap);
959 
960  if (wiimote)
961  {
962  ROS_ERROR("Wii Error: ID: %d: %s", wiimote_c::cwiid_get_id(wiimote), msgs_buf);
963  }
964  else
965  {
966  ROS_ERROR("Wii Error: ID: ?: %s", msgs_buf);
967  }
968 }
969 
971 {
972  return wiimote_state_.rpt_mode &
973  (CWIID_RPT_BTN | CWIID_RPT_ACC | CWIID_RPT_IR);
974 }
976 {
977  return wiimote_state_.rpt_mode & CWIID_RPT_NUNCHUK;
978 }
980 {
981  return wiimote_state_.rpt_mode & CWIID_RPT_CLASSIC;
982 }
984 {
985  return wiimote_state_.rpt_mode & CWIID_RPT_MOTIONPLUS;
986 }
987 
989 {
990  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_NUNCHUK;
991 }
993 {
994  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_CLASSIC;
995 }
997 {
998  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_MOTIONPLUS;
999 }
1000 
1001 bool WiimoteNode::calibrateJoystick(uint8_t stick[2], uint8_t (&center)[2], const char *name)
1002 {
1003  bool is_calibrated = false;
1004 
1005  // Grab the current Joystick position as center
1006  // If it is not reporting 0, 0
1007  if (stick[CWIID_X] != 0 && stick[CWIID_Y] != 0)
1008  {
1009  center[CWIID_X] = stick[CWIID_X];
1010  center[CWIID_Y] = stick[CWIID_Y];
1011 
1012  is_calibrated = true;
1013 
1014  ROS_DEBUG("%s Joystick Center:: x:%d, y:%d", name, center[CWIID_X], center[CWIID_Y]);
1015  }
1016 
1017  return is_calibrated;
1018 }
1019 
1020 void WiimoteNode::updateJoystickMinMax(uint8_t stick[2], uint8_t (&stick_min)[2],
1021  uint8_t (&stick_max)[2], const char *name)
1022 {
1023  bool updated = false;
1024 
1025  if (stick[CWIID_X] < stick_min[CWIID_X])
1026  {
1027  stick_min[CWIID_X] = stick[CWIID_X];
1028  updated = true;
1029  }
1030 
1031  if (stick[CWIID_Y] < stick_min[CWIID_Y])
1032  {
1033  stick_min[CWIID_Y] = stick[CWIID_Y];
1034  updated = true;
1035  }
1036 
1037  if (stick[CWIID_X] > stick_max[CWIID_X])
1038  {
1039  stick_max[CWIID_X] = stick[CWIID_X];
1040  updated = true;
1041  }
1042 
1043  if (stick[CWIID_Y] > stick_max[CWIID_Y])
1044  {
1045  stick_max[CWIID_Y] = stick[CWIID_Y];
1046  updated = true;
1047  }
1048 
1049  if (updated)
1050  {
1051  ROS_DEBUG("%s Joystick:: Min x:%3d, y:%3d Max x:%3d, y:%3d", name,
1052  stick_min[CWIID_X], stick_min[CWIID_Y], stick_max[CWIID_X], stick_max[CWIID_Y]);
1053  }
1054 }
1055 
1056 void WiimoteNode::calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2],
1057  uint8_t stick_max[2], uint8_t stick_center[2], double (&stick)[2])
1058 {
1059  double deadzone[2];
1060  int deadzoneMargin = 4;
1061 
1062  // Scale the Wiimote Joystick integer values (0-31, 63, or 255)
1063  // to a double value between 0.0 and 1.0.
1064 
1065  // The width of the center deadzone needs to scale
1066  // with the resolution of the joystick in use.
1067  // Nunchuk range is 0-255; defaults to 4
1068  // Classic Left range is 0-63; set to 2
1069  // Classic Right range is 0-31; set to 1
1070  // Original Python implementation was always 0.05 for all
1071 
1072  // Optimize for Nunchuk case; most common
1073  if (stick_max[CWIID_X] < 128)
1074  {
1075  if (stick_max[CWIID_X] < 32)
1076  {
1077  deadzoneMargin = 1;
1078  }
1079  else if (stick_max[CWIID_X] < 64)
1080  {
1081  deadzoneMargin = 2;
1082  }
1083  else
1084  {
1085  // No known wiimote joystick uses this range
1086  deadzoneMargin = 3;
1087  }
1088  }
1089 
1090  if (stick_current[CWIID_X] > stick_center[CWIID_X])
1091  {
1092  stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1093  ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1094  deadzone[CWIID_X] = deadzoneMargin /
1095  ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1096  }
1097  else
1098  {
1099  stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1100  ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1101  deadzone[CWIID_X] = deadzoneMargin /
1102  ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1103  }
1104  if (stick_current[CWIID_Y] > stick_center[CWIID_Y])
1105  {
1106  stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1107  ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1108  deadzone[CWIID_Y] = deadzoneMargin /
1109  ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1110  }
1111  else
1112  {
1113  stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1114  ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1115  deadzone[CWIID_Y] = deadzoneMargin /
1116  ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1117  }
1118 
1119  // Create a deadzone in the center
1120  if (fabs(stick[CWIID_X]) <= deadzone[CWIID_X])
1121  {
1122  stick[CWIID_X] = 0.0;
1123  }
1124  if (fabs(stick[CWIID_Y]) <= deadzone[CWIID_Y])
1125  {
1126  stick[CWIID_Y] = 0.0;
1127  }
1128 }
1129 
1131 {
1132  sensor_msgs::Joy joy_data;
1133 
1134  joy_data.header.stamp.sec = state_secs_;
1135  joy_data.header.stamp.nsec = state_nsecs_;
1136 
1137  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_X],
1138  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
1139  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Y],
1140  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
1141  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Z],
1142  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
1143 
1144  // NOTE: Order is different for /wiimote/state
1145  // Keep consistency with existing Python Node
1146  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_1) > 0);
1147  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_2) > 0);
1148  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_A) > 0);
1149  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_B) > 0);
1150  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1151  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1152  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1153  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1154  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1155  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1156  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1157 
1158  joy_pub_.publish(joy_data);
1159 }
1160 
1162 {
1163  // The Wiimote provides the Acceleration and optionally Gyro
1164  // if MotionPlus is available, but not orientation information.
1165 
1166  sensor_msgs::Imu imu_data_data;
1167 
1168  imu_data_data.header.stamp.sec = state_secs_;
1169  imu_data_data.header.stamp.nsec = state_nsecs_;
1170 
1171  // Publish that Orientation data is invalid
1172  // [ -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 ]
1173  imu_data_data.orientation_covariance[0] = -1.0;
1174 
1175  // Acceleration
1176  imu_data_data.linear_acceleration.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
1177  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1178  imu_data_data.linear_acceleration.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
1179  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1180  imu_data_data.linear_acceleration.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
1181  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1182 
1183  imu_data_data.linear_acceleration_covariance = linear_acceleration_covariance_;
1184 
1185  // MotionPlus Gyro
1186  if (isPresentMotionplus())
1187  {
1188  imu_data_data.angular_velocity.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1190  imu_data_data.angular_velocity.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1192  imu_data_data.angular_velocity.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1194  }
1195 
1196  imu_data_data.angular_velocity_covariance = angular_velocity_covariance_;
1197 
1198  imu_data_pub_.publish(imu_data_data);
1199 }
1200 
1202 {
1203  wiimote::State wiimote_state_data;
1204 
1205  wiimote_state_data.header.stamp.sec = state_secs_;
1206  wiimote_state_data.header.stamp.nsec = state_nsecs_;
1207 
1208  // Wiimote data
1209  wiimote_state_data.linear_acceleration_zeroed.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
1210  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1211  wiimote_state_data.linear_acceleration_zeroed.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
1212  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1213  wiimote_state_data.linear_acceleration_zeroed.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
1214  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1215 
1216  wiimote_state_data.linear_acceleration_raw.x = wiimote_state_.acc[CWIID_X];
1217  wiimote_state_data.linear_acceleration_raw.y = wiimote_state_.acc[CWIID_Y];
1218  wiimote_state_data.linear_acceleration_raw.z = wiimote_state_.acc[CWIID_Z];
1219 
1220  wiimote_state_data.linear_acceleration_covariance = linear_acceleration_covariance_;
1221 
1222  // MotionPlus Gyro
1223  wiimote_state_data.angular_velocity_covariance = angular_velocity_covariance_;
1224 
1225  if (isPresentMotionplus())
1226  {
1227  wiimote_state_data.angular_velocity_zeroed.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1229  wiimote_state_data.angular_velocity_zeroed.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1231  wiimote_state_data.angular_velocity_zeroed.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1233 
1234  wiimote_state_data.angular_velocity_raw.x = wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI];
1235  wiimote_state_data.angular_velocity_raw.y = wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA];
1236  wiimote_state_data.angular_velocity_raw.z = wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI];
1237  }
1238 
1239  // NOTE: Order is different for /joy
1240  // Keep consistency with existing Python Node
1241  wiimote_state_data.buttons.elems[ 0] = ((wiimote_state_.buttons & CWIID_BTN_1) > 0);
1242  wiimote_state_data.buttons.elems[ 1] = ((wiimote_state_.buttons & CWIID_BTN_2) > 0);
1243  wiimote_state_data.buttons.elems[ 2] = ((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1244  wiimote_state_data.buttons.elems[ 3] = ((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1245  wiimote_state_data.buttons.elems[ 4] = ((wiimote_state_.buttons & CWIID_BTN_A) > 0);
1246  wiimote_state_data.buttons.elems[ 5] = ((wiimote_state_.buttons & CWIID_BTN_B) > 0);
1247  wiimote_state_data.buttons.elems[ 6] = ((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1248  wiimote_state_data.buttons.elems[ 7] = ((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1249  wiimote_state_data.buttons.elems[ 8] = ((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1250  wiimote_state_data.buttons.elems[ 9] = ((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1251  wiimote_state_data.buttons.elems[10] = ((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1252 
1253  // Nunchuk data
1254  if (isPresentNunchuk())
1255  {
1257  {
1258  // Joy stick
1259  double stick[2];
1260 
1263 
1264  wiimote_state_data.nunchuk_joystick_raw[CWIID_X] = wiimote_state_.ext.nunchuk.stick[CWIID_X];
1265  wiimote_state_data.nunchuk_joystick_raw[CWIID_Y] = wiimote_state_.ext.nunchuk.stick[CWIID_Y];
1266 
1267  wiimote_state_data.nunchuk_joystick_zeroed[CWIID_X] = stick[CWIID_X];
1268  wiimote_state_data.nunchuk_joystick_zeroed[CWIID_Y] = stick[CWIID_Y];
1269 
1270  wiimote_state_data.nunchuk_acceleration_raw.x = wiimote_state_.ext.nunchuk.acc[CWIID_X];
1271  wiimote_state_data.nunchuk_acceleration_raw.y = wiimote_state_.ext.nunchuk.acc[CWIID_Y];
1272  wiimote_state_data.nunchuk_acceleration_raw.z = wiimote_state_.ext.nunchuk.acc[CWIID_Z];
1273 
1274  wiimote_state_data.nunchuk_acceleration_zeroed.x =
1275  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
1276  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1277  wiimote_state_data.nunchuk_acceleration_zeroed.y =
1278  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
1279  nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1280  wiimote_state_data.nunchuk_acceleration_zeroed.z =
1281  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
1282  nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1283 
1284  // Keep consistency with existing Python Node
1285  wiimote_state_data.nunchuk_buttons[0] =
1286  ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1287  wiimote_state_data.nunchuk_buttons[1] =
1288  ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1289  }
1290  }
1291 
1292  // IR Tracking Data
1293  for (int ir_idx = 0; ir_idx < CWIID_IR_SRC_COUNT; ir_idx++)
1294  {
1295  wiimote::IrSourceInfo irSourceInfo;
1296 
1297  if (wiimote_state_.ir_src[ir_idx].valid)
1298  {
1299  irSourceInfo.x = wiimote_state_.ir_src[ir_idx].pos[CWIID_X];
1300  irSourceInfo.y = wiimote_state_.ir_src[ir_idx].pos[CWIID_Y];
1301 
1302  irSourceInfo.ir_size = wiimote_state_.ir_src[ir_idx].size;
1303 
1304  if (irSourceInfo.ir_size < 1)
1305  {
1306  irSourceInfo.ir_size = wiimote::State::INVALID;
1307  }
1308  }
1309  else
1310  {
1311  irSourceInfo.x = wiimote::State::INVALID_FLOAT;
1312  irSourceInfo.y = wiimote::State::INVALID_FLOAT;
1313 
1314  irSourceInfo.ir_size = wiimote::State::INVALID;
1315  }
1316 
1317  wiimote_state_data.ir_tracking.push_back(irSourceInfo);
1318  }
1319 
1320  // LEDs / Rumble
1321  for (uint8_t i = 0; i < 4; i++)
1322  {
1323  wiimote_state_data.LEDs[i] = wiimote_state_.led & (0x1 << i);
1324  }
1325  wiimote_state_data.rumble = wiimote_state_.rumble & 0x1;
1326 
1327  // Battery
1328  wiimote_state_data.raw_battery = wiimote_state_.battery;
1329  wiimote_state_data.percent_battery = wiimote_state_.battery * 100.0 / CWIID_BATTERY_MAX;
1330 
1331  // Zeroing time (aka Calibration time)
1332  wiimote_state_data.zeroing_time = calibration_time_;
1333 
1334  // Wiimote state errors
1335  // No usage found in original Python code which every set this variable
1336  // TODO(mdhorn): Use this to report error
1337  // Is this a count? or a bunch of status that are ORed together?
1338  wiimote_state_data.errors = wiimote_errors;
1339 
1340  wiimote_state_pub_.publish(wiimote_state_data);
1341 }
1342 
1344 {
1345  // Testing different Nunchuks show that they have different
1346  // centers and different range of motion.
1347  //
1348  // Best Approximation:
1349  // Grabbing the first set of x, y with the assumption of
1350  // the joystick is centered.
1351  // We know the joystick can only report between 0 and 255
1352  // for each axis; so assume a 20% guard band to set the
1353  // initial minimums and maximums. As the joystick is used,
1354  // updated the min/max values based on observed data.
1355  // This will have the effect of a less throw of the joystick
1356  // throttle during first movement to the max/min position.
1357  //
1358  // TODO(mdhorn): Could be improved by a true user interaction calibration
1359  // to find the center of the joystick, the max and min for each x and y.
1360  // But the effort in coding and extra burden on the one the user
1361  // may not be warranted.
1362 
1363  bool result = true;
1364 
1365  if (isPresentNunchuk())
1366  {
1368  {
1370  wiimote_state_.ext.nunchuk.stick, nunchuk_stick_center_, "Nunchuk");
1371 
1372  // Don't publish if we haven't found the center position
1374  {
1375  result = false;
1376  }
1377  }
1378 
1380  nunchuk_stick_max_, "Nunchuk");
1381  }
1382  else
1383  {
1384  ROS_WARN("State type is not Nunchuk!");
1385  result = false;
1386  }
1387 
1388  return result;
1389 }
1390 
1392 {
1393  sensor_msgs::Joy wiimote_nunchuk_data;
1394 
1396  {
1397  wiimote_nunchuk_data.header.stamp.sec = state_secs_;
1398  wiimote_nunchuk_data.header.stamp.nsec = state_nsecs_;
1399 
1400  // Joy stick
1401  double stick[2];
1402 
1405 
1406  wiimote_nunchuk_data.axes.push_back(stick[CWIID_X]); // x
1407  wiimote_nunchuk_data.axes.push_back(stick[CWIID_Y]); // y
1408 
1409  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
1410  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
1411  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
1412  nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
1413  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
1414  nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
1415 
1416 
1417  // NOTE: Order is different for /wiimote/state
1418  // Keep consistency with existing Python Node
1419  wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1420  wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1421 
1422  wiimote_nunchuk_pub_.publish(wiimote_nunchuk_data);
1423  }
1424 }
1425 
1427 {
1428  // Using the same "Best Approximation" methods from
1429  // WiimoteNode::publishWiimoteNunchuk()
1430 
1431  sensor_msgs::Joy wiimote_classic_data;
1432 
1433  if (isPresentClassic())
1434  {
1435  ROS_WARN("State type is not Classic!");
1436  return;
1437  }
1438 
1440  {
1442  wiimote_state_.ext.classic.l_stick, classic_stick_left_center_, "Classic Left");
1443  }
1444 
1446  {
1448  wiimote_state_.ext.classic.r_stick, classic_stick_right_center_, "Classic Right");
1449  }
1450 
1453  {
1454  // Don't publish if we haven't found the center positions
1455  return;
1456  }
1457 
1459  classic_stick_left_max_, "Classic Left");
1461  classic_stick_right_max_, "Classic Right");
1462 
1463  wiimote_classic_data.header.stamp.sec = state_secs_;
1464  wiimote_classic_data.header.stamp.nsec = state_nsecs_;
1465 
1466  // Joy stick
1467  double stick_left[2];
1468  double stick_right[2];
1469 
1474 
1475  wiimote_classic_data.axes.push_back(stick_left[CWIID_X]); // Left x
1476  wiimote_classic_data.axes.push_back(stick_left[CWIID_Y]); // Left y
1477  wiimote_classic_data.axes.push_back(stick_right[CWIID_X]); // Right x
1478  wiimote_classic_data.axes.push_back(stick_right[CWIID_Y]); // Right y
1479 
1480  // NOTE: Order is different for /wiimote/state
1481  // Keep consistency with existing Python Node
1482  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_X) > 0);
1483  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_Y) > 0);
1484  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_A) > 0);
1485  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_B) > 0);
1486  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_PLUS) > 0);
1487  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_MINUS) > 0);
1488  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_LEFT) > 0);
1489  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_RIGHT) > 0);
1490  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_UP) > 0);
1491  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_DOWN) > 0);
1492  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_HOME) > 0);
1493  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_L) > 0);
1494  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_R) > 0);
1495  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZL) > 0);
1496  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZR) > 0);
1497 
1498  wiimote_classic_pub_.publish(wiimote_classic_data);
1499 }
1500 
1501 // const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback is unused
1502 void WiimoteNode::joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback)
1503 {
1504  bool led_found = false;
1505  bool rumble_found = false;
1506 
1507  for (std::vector<sensor_msgs::JoyFeedback>::const_iterator it = feedback->array.begin();
1508  it != feedback->array.end(); ++it)
1509  {
1510  if ((*it).type == sensor_msgs::JoyFeedback::TYPE_LED)
1511  {
1512  led_found = true;
1513 
1514  if ((*it).intensity >= 0.5)
1515  {
1516  setLEDBit((*it).id, true);
1517  }
1518  else
1519  {
1520  setLEDBit((*it).id, false);
1521  }
1522  }
1523  else if ((*it).type == sensor_msgs::JoyFeedback::TYPE_RUMBLE)
1524  {
1525  if ((*it).id > 0)
1526  {
1527  ROS_WARN("RUMBLE ID %d out of bounds; ignoring!", (*it).id);
1528  }
1529  else
1530  {
1531  rumble_found = true;
1532 
1533  if ((*it).intensity >= 0.5)
1534  {
1535  setRumbleBit(true);
1536  }
1537  else
1538  {
1539  setRumbleBit(false);
1540  }
1541  }
1542  }
1543  else
1544  {
1545  ROS_WARN("Unknown JoyFeedback command; ignored");
1546  }
1547  }
1548 
1549  if (led_found)
1550  {
1552  }
1553 
1554  if (rumble_found)
1555  {
1557  }
1558 }
1559 
1560 bool WiimoteNode::serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1561 {
1562  // Publish the new calibration state
1564 
1565  return true;
1566 }
1567 
1569 
1570 // int sig The signal number is unused
1571 void mySigHandler(int sig)
1572 {
1573  // Do some custom action.
1574  // For example, publish a stop message to some other nodes.
1575 
1576  // Clear the lights and rumble
1577  if (nullptr != g_wiimote_node)
1578  {
1581  }
1582 
1583  // All the default sigint handler does is call shutdown()
1584  ros::shutdown();
1585 
1586  exit(0);
1587 }
1588 
1589 int main(int argc, char *argv[])
1590 {
1591  bool fed_addr = false;
1592  std::string bluetooth_addr;
1593  ros::init(argc, argv, "wiimote_controller");
1594 
1595  g_wiimote_node = new WiimoteNode();
1596  // Do we have a bluetooth address passed in?
1597  if (argc > 1)
1598  {
1599  ROS_INFO("Using Bluetooth address specified from CLI");
1600  g_wiimote_node->setBluetoothAddr(argv[1]);
1601  fed_addr = true;
1602  }
1603 
1604  if (ros::param::get("~bluetooth_addr", bluetooth_addr))
1605  {
1606  g_wiimote_node->setBluetoothAddr(bluetooth_addr.c_str());
1607  fed_addr = true;
1608  }
1609 
1610  int pair_timeout;
1611  double check_connection_interval;
1612  ros::param::param<int>("~pair_timeout", pair_timeout, 5);
1613  ros::param::param<double>("~check_connection_interval", check_connection_interval, 0.0);
1614 
1615  if (fed_addr)
1616  ROS_INFO("* * * Pairing with %s", g_wiimote_node->getBluetoothAddr());
1617 
1618  else
1619  ROS_INFO("Searching for Wiimotes");
1620 
1621  ROS_INFO("Allow all joy sticks to remain at center position until calibrated.");
1622 
1623  if (g_wiimote_node->pairWiimote(0, pair_timeout))
1624  {
1625  ROS_INFO("Wiimote is Paired");
1626 
1627  signal(SIGINT, mySigHandler);
1628  signal(SIGTERM, mySigHandler);
1629  }
1630  else
1631  {
1632  ROS_ERROR("* * * Wiimote pairing failed.");
1633  return -2;
1634  }
1635 
1636  ros::NodeHandle nh;
1637  ros::Timer timer;
1638  if (check_connection_interval > 0.0)
1639  {
1640  timer = nh.createTimer(ros::Duration(check_connection_interval),
1642  }
1643 
1644  ros::Rate loop_rate(10); // 10Hz
1645  while (ros::ok())
1646  {
1648 
1649  ros::spinOnce();
1650 
1651  loop_rate.sleep();
1652  }
1653 
1655  {
1656  ROS_ERROR("Error on wiimote disconnect");
1657  return -1;
1658  }
1659 
1660  return 0;
1661 }
WiimoteNode::isPresentNunchuk
bool isPresentNunchuk()
Definition: wiimote_controller.cpp:988
WiimoteNode::cwiidErrorCallback
static wiimote_c::cwiid_err_t cwiidErrorCallback
Definition: wiimote_controller.h:84
WiimoteNode::classic_stick_right_max_
uint8_t classic_stick_right_max_[2]
Definition: wiimote_controller.h:191
WiimoteNode::isCollectingNunchuk
bool isCollectingNunchuk()
Definition: wiimote_controller.cpp:975
WiimoteNode::publish
void publish()
Definition: wiimote_controller.cpp:518
WiimoteNode
Definition: wiimote_controller.h:58
wiimote
Definition: __init__.py:1
WiimoteNode::classic_stick_right_calibrated_
bool classic_stick_right_calibrated_
Definition: wiimote_controller.h:190
WiimoteNode::imu_is_calibrated_pub_
ros::Publisher imu_is_calibrated_pub_
Definition: wiimote_controller.h:137
WiimoteNode::publishWiimoteClassic
void publishWiimoteClassic()
Definition: wiimote_controller.cpp:1426
WiimoteNode::JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
Definition: wiimote_controller.h:171
WiimoteNode::imu_data_pub_
ros::Publisher imu_data_pub_
Definition: wiimote_controller.h:133
WiimoteNode::joy_pub_
ros::Publisher joy_pub_
Definition: wiimote_controller.h:132
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
WiimoteNode::setRumbleBit
void setRumbleBit(bool on)
Definition: wiimote_controller.cpp:916
WiimoteNode::publishWiimoteNunchukCommon
bool publishWiimoteNunchukCommon()
Definition: wiimote_controller.cpp:1343
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
WiimoteNode::resetNunchukState
void resetNunchukState()
Definition: wiimote_controller.cpp:487
WiimoteNode::EARTH_GRAVITY_
const double EARTH_GRAVITY_
Definition: wiimote_controller.h:207
WiimoteNode::calibration_time_
ros::Time calibration_time_
Definition: wiimote_controller.h:162
WiimoteNode::classic_stick_right_min_
uint8_t classic_stick_right_min_[2]
Definition: wiimote_controller.h:192
time.h
WiimoteNode::WiimoteNode
WiimoteNode()
Definition: wiimote_controller.cpp:66
WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
Definition: wiimote_controller.h:170
WiimoteNode::joy_set_feedback_sub_
ros::Subscriber joy_set_feedback_sub_
Definition: wiimote_controller.h:139
ros::spinOnce
ROSCPP_DECL void spinOnce()
WiimoteNode::publishWiimoteState
void publishWiimoteState()
Definition: wiimote_controller.cpp:1201
ros::shutdown
ROSCPP_DECL void shutdown()
wiimote_controller.h
TVectorDouble
std::vector< double > TVectorDouble
Definition: stat_vector_3d.h:36
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
WiimoteNode::isCollectingWiimote
bool isCollectingWiimote()
Definition: wiimote_controller.cpp:970
WiimoteNode::nunchuk_stick_min_
uint8_t nunchuk_stick_min_[2]
Definition: wiimote_controller.h:182
WiimoteNode::isCollectingMotionplus
bool isCollectingMotionplus()
Definition: wiimote_controller.cpp:983
WiimoteNode::angular_velocity_stat_
StatVector3d angular_velocity_stat_
Definition: wiimote_controller.h:197
WiimoteNode::JOYSTICK_NUNCHUK_DEFAULT_CENTER_
const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_
Definition: wiimote_controller.h:165
WiimoteNode::wiimote_
wiimote_c::cwiid_wiimote_t * wiimote_
Definition: wiimote_controller.h:147
WiimoteNode::classic_stick_left_calibrated_
bool classic_stick_left_calibrated_
Definition: wiimote_controller.h:186
WiimoteNode::initializeWiimoteState
void initializeWiimoteState()
Definition: wiimote_controller.cpp:111
WiimoteNode::wiimote_state_pub_
ros::Publisher wiimote_state_pub_
Definition: wiimote_controller.h:134
WiimoteNode::resetClassicState
void resetClassicState()
Definition: wiimote_controller.cpp:500
WiimoteNode::classic_stick_left_min_
uint8_t classic_stick_left_min_[2]
Definition: wiimote_controller.h:188
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
WiimoteNode::nunchuk_stick_center_
uint8_t nunchuk_stick_center_[2]
Definition: wiimote_controller.h:179
ros::ok
ROSCPP_DECL bool ok()
WiimoteNode::classic_stick_right_center_
uint8_t classic_stick_right_center_[2]
Definition: wiimote_controller.h:189
StatVector3d
Definition: stat_vector_3d.h:38
WiimoteNode::unpairWiimote
int unpairWiimote()
Definition: wiimote_controller.cpp:180
WiimoteNode::report_mode_
uint8_t report_mode_
Definition: wiimote_controller.h:157
WiimoteNode::joySetFeedbackCallback
void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr &feedback)
Definition: wiimote_controller.cpp:1502
WiimoteNode::~WiimoteNode
~WiimoteNode()
Definition: wiimote_controller.cpp:107
WiimoteNode::wiimote_nunchuk_pub_
ros::Publisher wiimote_nunchuk_pub_
Definition: wiimote_controller.h:135
WiimoteNode::nunchuk_cal_
struct wiimote_c::acc_cal nunchuk_cal_
Definition: wiimote_controller.h:176
WiimoteNode::isPresentMotionplus
bool isPresentMotionplus()
Definition: wiimote_controller.cpp:996
StatVector3d::clear
void clear()
Definition: stat_vector_3d.cpp:46
WiimoteNode::angular_velocity_covariance_
boost::array< double, 9 > angular_velocity_covariance_
Definition: wiimote_controller.h:199
WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
Definition: wiimote_controller.h:169
WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MIN_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_
Definition: wiimote_controller.h:167
WiimoteNode::isCollectingClassic
bool isCollectingClassic()
Definition: wiimote_controller.cpp:979
ros::Publisher::shutdown
void shutdown()
ROS_DEBUG
#define ROS_DEBUG(...)
WiimoteNode::rumble_
uint8_t rumble_
Definition: wiimote_controller.h:202
WiimoteNode::wiimote_calibrated_
bool wiimote_calibrated_
Definition: wiimote_controller.h:161
WiimoteNode::setRumbleState
void setRumbleState(uint8_t rumble)
Definition: wiimote_controller.cpp:945
g_wiimote_node
WiimoteNode * g_wiimote_node
Definition: wiimote_controller.cpp:1568
WiimoteNode::publishWiimoteNunchuk
void publishWiimoteNunchuk()
Definition: wiimote_controller.cpp:1391
WiimoteNode::nunchuk_calibrated_
bool nunchuk_calibrated_
Definition: wiimote_controller.h:177
WiimoteNode::bt_device_addr_
bdaddr_t bt_device_addr_
Definition: wiimote_controller.h:144
WiimoteNode::setLedState
void setLedState(uint8_t led_state)
Definition: wiimote_controller.cpp:928
setup.d
d
Definition: setup.py:6
ROS_WARN
#define ROS_WARN(...)
WiimoteNode::GYRO_SCALE_FACTOR_
const double GYRO_SCALE_FACTOR_
Definition: wiimote_controller.h:230
WiimoteNode::publishImuData
void publishImuData()
Definition: wiimote_controller.cpp:1161
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
WiimoteNode::nh_
ros::NodeHandle nh_
Definition: wiimote_controller.h:82
WiimoteNode::getStateSample
bool getStateSample()
Definition: wiimote_controller.cpp:742
WiimoteNode::serviceImuCalibrateCallback
bool serviceImuCalibrateCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: wiimote_controller.cpp:1560
StatVector3d::addData
void addData(int x, int y, int z)
Definition: stat_vector_3d.cpp:60
main
int main(int argc, char *argv[])
Definition: wiimote_controller.cpp:1589
ros::Rate::sleep
bool sleep()
WiimoteNode::calculateJoystickAxisXY
void calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2], uint8_t stick_max[2], uint8_t stick_center[2], double(&stick)[2])
Definition: wiimote_controller.cpp:1056
WiimoteNode::pairWiimote
bool pairWiimote(int flags, int timeout)
Definition: wiimote_controller.cpp:148
WiimoteNode::nunchuk_stick_calibrated_
bool nunchuk_stick_calibrated_
Definition: wiimote_controller.h:180
WiimoteNode::linear_acceleration_covariance_
boost::array< double, 9 > linear_acceleration_covariance_
Definition: wiimote_controller.h:198
StatVector3d::getStandardDeviationRaw
TVectorDouble getStandardDeviationRaw()
Definition: stat_vector_3d.cpp:154
WiimoteNode::linear_acceleration_stat_
StatVector3d linear_acceleration_stat_
Definition: wiimote_controller.h:196
WiimoteNode::checkConnection
void checkConnection()
Definition: wiimote_controller.cpp:936
WiimoteNode::wiimote_cal_
struct wiimote_c::acc_cal wiimote_cal_
Definition: wiimote_controller.h:160
zeroedByCal
#define zeroedByCal(raw, zero, one)
Definition: wiimote_controller.h:55
WiimoteNode::wiimote_state_
struct wiimote_c::cwiid_state wiimote_state_
Definition: wiimote_controller.h:150
WiimoteNode::JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
Definition: wiimote_controller.h:168
WiimoteNode::state_secs_
uint32_t state_secs_
Definition: wiimote_controller.h:153
WiimoteNode::imu_calibrate_srv_
ros::ServiceServer imu_calibrate_srv_
Definition: wiimote_controller.h:141
WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MAX_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_
Definition: wiimote_controller.h:166
StatVector3d::getVarianceScaled
TVectorDouble getVarianceScaled(double scale)
Definition: stat_vector_3d.cpp:144
WiimoteNode::publishJoy
void publishJoy()
Definition: wiimote_controller.cpp:1130
WiimoteNode::COVARIANCE_DATA_POINTS_
const int COVARIANCE_DATA_POINTS_
Definition: wiimote_controller.h:195
WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
Definition: wiimote_controller.h:173
mySigHandler
void mySigHandler(int sig)
Definition: wiimote_controller.cpp:1571
WiimoteNode::setReportMode
void setReportMode(uint8_t rpt_mode)
Definition: wiimote_controller.cpp:875
ROS_ERROR
#define ROS_ERROR(...)
WiimoteNode::state_nsecs_
uint32_t state_nsecs_
Definition: wiimote_controller.h:154
WiimoteNode::isPresentClassic
bool isPresentClassic()
Definition: wiimote_controller.cpp:992
ros::Rate
WiimoteNode::classic_stick_left_max_
uint8_t classic_stick_left_max_[2]
Definition: wiimote_controller.h:187
WiimoteNode::nunchuk_failed_calibration_
bool nunchuk_failed_calibration_
Definition: wiimote_controller.h:178
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
WiimoteNode::calibrateJoystick
bool calibrateJoystick(uint8_t stick[2], uint8_t(&center)[2], const char *name)
Definition: wiimote_controller.cpp:1001
WiimoteNode::checkFactoryCalibrationData
void checkFactoryCalibrationData()
Definition: wiimote_controller.cpp:185
WiimoteNode::getBluetoothAddr
char * getBluetoothAddr()
Definition: wiimote_controller.cpp:139
WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
Definition: wiimote_controller.h:172
ROS_INFO
#define ROS_INFO(...)
WiimoteNode::resetMotionPlusState
void resetMotionPlusState()
Definition: wiimote_controller.cpp:469
StatVector3d::size
int size()
Definition: stat_vector_3d.cpp:55
WiimoteNode::classic_stick_left_center_
uint8_t classic_stick_left_center_[2]
Definition: wiimote_controller.h:185
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
WiimoteNode::nunchuk_stick_max_
uint8_t nunchuk_stick_max_[2]
Definition: wiimote_controller.h:181
WiimoteNode::led_state_
uint8_t led_state_
Definition: wiimote_controller.h:201
ros::Duration
WiimoteNode::setLEDBit
void setLEDBit(uint8_t led, bool on)
Definition: wiimote_controller.cpp:896
ros::Timer
WiimoteNode::IGNORE_DATA_POINTS_
const int IGNORE_DATA_POINTS_
Definition: wiimote_controller.h:194
StatVector3d::getMeanRaw
TVectorDouble getMeanRaw()
Definition: stat_vector_3d.cpp:69
WiimoteNode::setBluetoothAddr
void setBluetoothAddr(const char *bt_str)
Definition: wiimote_controller.cpp:143
ros::NodeHandle
ros::Time::now
static Time now()
WiimoteNode::wiimote_classic_pub_
ros::Publisher wiimote_classic_pub_
Definition: wiimote_controller.h:136
WiimoteNode::updateJoystickMinMax
void updateJoystickMinMax(uint8_t stick[2], uint8_t(&stick_min)[2], uint8_t(&stick_max)[2], const char *name)
Definition: wiimote_controller.cpp:1020
WiimoteNode::wiimote_errors
uint64_t wiimote_errors
Definition: wiimote_controller.h:204


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Thu Dec 5 2024 03:18:13