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);
369  linear_acceleration_covariance_[1] = 0.0;
370  linear_acceleration_covariance_[2] = 0.0;
371 
372  linear_acceleration_covariance_[3] = 0.0;
373  linear_acceleration_covariance_[4] = variance.at(CWIID_Y);
374  linear_acceleration_covariance_[5] = 0.0;
375 
376  linear_acceleration_covariance_[6] = 0.0;
377  linear_acceleration_covariance_[7] = 0.0;
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);
411  angular_velocity_covariance_[1] = 0.0;
412  angular_velocity_covariance_[2] = 0.0;
413 
414  angular_velocity_covariance_[3] = 0.0;
415  angular_velocity_covariance_[4] = gyro_variance.at(CWIID_THETA);
416  angular_velocity_covariance_[5] = 0.0;
417 
418  angular_velocity_covariance_[6] = 0.0;
419  angular_velocity_covariance_[7] = 0.0;
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 
936 void WiimoteNode::setRumbleState(uint8_t rumble)
937 {
938  if (wiimote_c::cwiid_set_rumble(wiimote_, rumble))
939  {
940  ROS_ERROR("Error setting rumble");
941  }
942 }
943 
944 void WiimoteNode::cwiidErrorCallback(wiimote_c::cwiid_wiimote_t *wiimote, const char *fmt, va_list ap)
945 {
946  const int MAX_BUF = 500;
947  char msgs_buf[MAX_BUF];
948 
949  vsnprintf(msgs_buf, MAX_BUF, fmt, ap);
950 
951  if (wiimote)
952  {
953  ROS_ERROR("Wii Error: ID: %d: %s", wiimote_c::cwiid_get_id(wiimote), msgs_buf);
954  }
955  else
956  {
957  ROS_ERROR("Wii Error: ID: ?: %s", msgs_buf);
958  }
959 }
960 
962 {
963  return wiimote_state_.rpt_mode &
964  (CWIID_RPT_BTN | CWIID_RPT_ACC | CWIID_RPT_IR);
965 }
967 {
968  return wiimote_state_.rpt_mode & CWIID_RPT_NUNCHUK;
969 }
971 {
972  return wiimote_state_.rpt_mode & CWIID_RPT_CLASSIC;
973 }
975 {
976  return wiimote_state_.rpt_mode & CWIID_RPT_MOTIONPLUS;
977 }
978 
980 {
981  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_NUNCHUK;
982 }
984 {
985  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_CLASSIC;
986 }
988 {
989  return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_MOTIONPLUS;
990 }
991 
992 bool WiimoteNode::calibrateJoystick(uint8_t stick[2], uint8_t (&center)[2], const char *name)
993 {
994  bool is_calibrated = false;
995 
996  // Grab the current Joystick position as center
997  // If it is not reporting 0, 0
998  if (stick[CWIID_X] != 0 && stick[CWIID_Y] != 0)
999  {
1000  center[CWIID_X] = stick[CWIID_X];
1001  center[CWIID_Y] = stick[CWIID_Y];
1002 
1003  is_calibrated = true;
1004 
1005  ROS_DEBUG("%s Joystick Center:: x:%d, y:%d", name, center[CWIID_X], center[CWIID_Y]);
1006  }
1007 
1008  return is_calibrated;
1009 }
1010 
1011 void WiimoteNode::updateJoystickMinMax(uint8_t stick[2], uint8_t (&stick_min)[2],
1012  uint8_t (&stick_max)[2], const char *name)
1013 {
1014  bool updated = false;
1015 
1016  if (stick[CWIID_X] < stick_min[CWIID_X])
1017  {
1018  stick_min[CWIID_X] = stick[CWIID_X];
1019  updated = true;
1020  }
1021 
1022  if (stick[CWIID_Y] < stick_min[CWIID_Y])
1023  {
1024  stick_min[CWIID_Y] = stick[CWIID_Y];
1025  updated = true;
1026  }
1027 
1028  if (stick[CWIID_X] > stick_max[CWIID_X])
1029  {
1030  stick_max[CWIID_X] = stick[CWIID_X];
1031  updated = true;
1032  }
1033 
1034  if (stick[CWIID_Y] > stick_max[CWIID_Y])
1035  {
1036  stick_max[CWIID_Y] = stick[CWIID_Y];
1037  updated = true;
1038  }
1039 
1040  if (updated)
1041  {
1042  ROS_DEBUG("%s Joystick:: Min x:%3d, y:%3d Max x:%3d, y:%3d", name,
1043  stick_min[CWIID_X], stick_min[CWIID_Y], stick_max[CWIID_X], stick_max[CWIID_Y]);
1044  }
1045 }
1046 
1047 void WiimoteNode::calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2],
1048  uint8_t stick_max[2], uint8_t stick_center[2], double (&stick)[2])
1049 {
1050  double deadzone[2];
1051  int deadzoneMargin = 4;
1052 
1053  // Scale the Wiimote Joystick integer values (0-31, 63, or 255)
1054  // to a double value between 0.0 and 1.0.
1055 
1056  // The width of the center deadzone needs to scale
1057  // with the resolution of the joystick in use.
1058  // Nunchuk range is 0-255; defaults to 4
1059  // Classic Left range is 0-63; set to 2
1060  // Classic Right range is 0-31; set to 1
1061  // Original Python implementation was always 0.05 for all
1062 
1063  // Optimize for Nunchuk case; most common
1064  if (stick_max[CWIID_X] < 128)
1065  {
1066  if (stick_max[CWIID_X] < 32)
1067  {
1068  deadzoneMargin = 1;
1069  }
1070  else if (stick_max[CWIID_X] < 64)
1071  {
1072  deadzoneMargin = 2;
1073  }
1074  else
1075  {
1076  // No known wiimote joystick uses this range
1077  deadzoneMargin = 3;
1078  }
1079  }
1080 
1081  if (stick_current[CWIID_X] > stick_center[CWIID_X])
1082  {
1083  stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1084  ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1085  deadzone[CWIID_X] = deadzoneMargin /
1086  ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1087  }
1088  else
1089  {
1090  stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1091  ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1092  deadzone[CWIID_X] = deadzoneMargin /
1093  ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1094  }
1095  if (stick_current[CWIID_Y] > stick_center[CWIID_Y])
1096  {
1097  stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1098  ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1099  deadzone[CWIID_Y] = deadzoneMargin /
1100  ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1101  }
1102  else
1103  {
1104  stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1105  ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1106  deadzone[CWIID_Y] = deadzoneMargin /
1107  ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1108  }
1109 
1110  // Create a deadzone in the center
1111  if (fabs(stick[CWIID_X]) <= deadzone[CWIID_X])
1112  {
1113  stick[CWIID_X] = 0.0;
1114  }
1115  if (fabs(stick[CWIID_Y]) <= deadzone[CWIID_Y])
1116  {
1117  stick[CWIID_Y] = 0.0;
1118  }
1119 }
1120 
1122 {
1123  sensor_msgs::Joy joy_data;
1124 
1125  joy_data.header.stamp.sec = state_secs_;
1126  joy_data.header.stamp.nsec = state_nsecs_;
1127 
1128  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_X],
1129  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
1130  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Y],
1131  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
1132  joy_data.axes.push_back(zeroedByCal(wiimote_state_.acc[CWIID_Z],
1133  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
1134 
1135  // NOTE: Order is different for /wiimote/state
1136  // Keep consistency with existing Python Node
1137  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_1) > 0);
1138  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_2) > 0);
1139  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_A) > 0);
1140  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_B) > 0);
1141  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1142  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1143  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1144  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1145  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1146  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1147  joy_data.buttons.push_back((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1148 
1149  joy_pub_.publish(joy_data);
1150 }
1151 
1153 {
1154  // The Wiimote provides the Acceleration and optionally Gyro
1155  // if MotionPlus is available, but not orientation information.
1156 
1157  sensor_msgs::Imu imu_data_data;
1158 
1159  imu_data_data.header.stamp.sec = state_secs_;
1160  imu_data_data.header.stamp.nsec = state_nsecs_;
1161 
1162  // Publish that Orientation data is invalid
1163  // [ -1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 ]
1164  imu_data_data.orientation_covariance[0] = -1.0;
1165 
1166  // Acceleration
1167  imu_data_data.linear_acceleration.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
1168  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1169  imu_data_data.linear_acceleration.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
1170  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1171  imu_data_data.linear_acceleration.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
1172  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1173 
1174  imu_data_data.linear_acceleration_covariance = linear_acceleration_covariance_;
1175 
1176  // MotionPlus Gyro
1177  if (isPresentMotionplus())
1178  {
1179  imu_data_data.angular_velocity.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1181  imu_data_data.angular_velocity.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1183  imu_data_data.angular_velocity.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1185  }
1186 
1187  imu_data_data.angular_velocity_covariance = angular_velocity_covariance_;
1188 
1189  imu_data_pub_.publish(imu_data_data);
1190 }
1191 
1193 {
1194  wiimote::State wiimote_state_data;
1195 
1196  wiimote_state_data.header.stamp.sec = state_secs_;
1197  wiimote_state_data.header.stamp.nsec = state_nsecs_;
1198 
1199  // Wiimote data
1200  wiimote_state_data.linear_acceleration_zeroed.x = zeroedByCal(wiimote_state_.acc[CWIID_X],
1201  wiimote_cal_.zero[CWIID_X], wiimote_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1202  wiimote_state_data.linear_acceleration_zeroed.y = zeroedByCal(wiimote_state_.acc[CWIID_Y],
1203  wiimote_cal_.zero[CWIID_Y], wiimote_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1204  wiimote_state_data.linear_acceleration_zeroed.z = zeroedByCal(wiimote_state_.acc[CWIID_Z],
1205  wiimote_cal_.zero[CWIID_Z], wiimote_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1206 
1207  wiimote_state_data.linear_acceleration_raw.x = wiimote_state_.acc[CWIID_X];
1208  wiimote_state_data.linear_acceleration_raw.y = wiimote_state_.acc[CWIID_Y];
1209  wiimote_state_data.linear_acceleration_raw.z = wiimote_state_.acc[CWIID_Z];
1210 
1211  wiimote_state_data.linear_acceleration_covariance = linear_acceleration_covariance_;
1212 
1213  // MotionPlus Gyro
1214  wiimote_state_data.angular_velocity_covariance = angular_velocity_covariance_;
1215 
1216  if (isPresentMotionplus())
1217  {
1218  wiimote_state_data.angular_velocity_zeroed.x = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1220  wiimote_state_data.angular_velocity_zeroed.y = (wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1222  wiimote_state_data.angular_velocity_zeroed.z = (wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1224 
1225  wiimote_state_data.angular_velocity_raw.x = wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI];
1226  wiimote_state_data.angular_velocity_raw.y = wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA];
1227  wiimote_state_data.angular_velocity_raw.z = wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI];
1228  }
1229 
1230  // NOTE: Order is different for /joy
1231  // Keep consistency with existing Python Node
1232  wiimote_state_data.buttons.elems[ 0] = ((wiimote_state_.buttons & CWIID_BTN_1) > 0);
1233  wiimote_state_data.buttons.elems[ 1] = ((wiimote_state_.buttons & CWIID_BTN_2) > 0);
1234  wiimote_state_data.buttons.elems[ 2] = ((wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1235  wiimote_state_data.buttons.elems[ 3] = ((wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1236  wiimote_state_data.buttons.elems[ 4] = ((wiimote_state_.buttons & CWIID_BTN_A) > 0);
1237  wiimote_state_data.buttons.elems[ 5] = ((wiimote_state_.buttons & CWIID_BTN_B) > 0);
1238  wiimote_state_data.buttons.elems[ 6] = ((wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1239  wiimote_state_data.buttons.elems[ 7] = ((wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1240  wiimote_state_data.buttons.elems[ 8] = ((wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1241  wiimote_state_data.buttons.elems[ 9] = ((wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1242  wiimote_state_data.buttons.elems[10] = ((wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1243 
1244  // Nunchuk data
1245  if (isPresentNunchuk())
1246  {
1248  {
1249  // Joy stick
1250  double stick[2];
1251 
1254 
1255  wiimote_state_data.nunchuk_joystick_raw[CWIID_X] = wiimote_state_.ext.nunchuk.stick[CWIID_X];
1256  wiimote_state_data.nunchuk_joystick_raw[CWIID_Y] = wiimote_state_.ext.nunchuk.stick[CWIID_Y];
1257 
1258  wiimote_state_data.nunchuk_joystick_zeroed[CWIID_X] = stick[CWIID_X];
1259  wiimote_state_data.nunchuk_joystick_zeroed[CWIID_Y] = stick[CWIID_Y];
1260 
1261  wiimote_state_data.nunchuk_acceleration_raw.x = wiimote_state_.ext.nunchuk.acc[CWIID_X];
1262  wiimote_state_data.nunchuk_acceleration_raw.y = wiimote_state_.ext.nunchuk.acc[CWIID_Y];
1263  wiimote_state_data.nunchuk_acceleration_raw.z = wiimote_state_.ext.nunchuk.acc[CWIID_Z];
1264 
1265  wiimote_state_data.nunchuk_acceleration_zeroed.x =
1266  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
1267  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_;
1268  wiimote_state_data.nunchuk_acceleration_zeroed.y =
1269  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
1270  nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_;
1271  wiimote_state_data.nunchuk_acceleration_zeroed.z =
1272  zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
1273  nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_;
1274 
1275  // Keep consistency with existing Python Node
1276  wiimote_state_data.nunchuk_buttons[0] =
1277  ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1278  wiimote_state_data.nunchuk_buttons[1] =
1279  ((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1280  }
1281  }
1282 
1283  // IR Tracking Data
1284  for (int ir_idx = 0; ir_idx < CWIID_IR_SRC_COUNT; ir_idx++)
1285  {
1286  wiimote::IrSourceInfo irSourceInfo;
1287 
1288  if (wiimote_state_.ir_src[ir_idx].valid)
1289  {
1290  irSourceInfo.x = wiimote_state_.ir_src[ir_idx].pos[CWIID_X];
1291  irSourceInfo.y = wiimote_state_.ir_src[ir_idx].pos[CWIID_Y];
1292 
1293  irSourceInfo.ir_size = wiimote_state_.ir_src[ir_idx].size;
1294 
1295  if (irSourceInfo.ir_size < 1)
1296  {
1297  irSourceInfo.ir_size = wiimote::State::INVALID;
1298  }
1299  }
1300  else
1301  {
1302  irSourceInfo.x = wiimote::State::INVALID_FLOAT;
1303  irSourceInfo.y = wiimote::State::INVALID_FLOAT;
1304 
1305  irSourceInfo.ir_size = wiimote::State::INVALID;
1306  }
1307 
1308  wiimote_state_data.ir_tracking.push_back(irSourceInfo);
1309  }
1310 
1311  // LEDs / Rumble
1312  for (uint8_t i = 0; i < 4; i++)
1313  {
1314  wiimote_state_data.LEDs[i] = wiimote_state_.led & (0x1 << i);
1315  }
1316  wiimote_state_data.rumble = wiimote_state_.rumble & 0x1;
1317 
1318  // Battery
1319  wiimote_state_data.raw_battery = wiimote_state_.battery;
1320  wiimote_state_data.percent_battery = wiimote_state_.battery * 100.0 / CWIID_BATTERY_MAX;
1321 
1322  // Zeroing time (aka Calibration time)
1323  wiimote_state_data.zeroing_time = calibration_time_;
1324 
1325  // Wiimote state errors
1326  // No usage found in original Python code which every set this variable
1327  // TODO(mdhorn): Use this to report error
1328  // Is this a count? or a bunch of status that are ORed together?
1329  wiimote_state_data.errors = wiimote_errors;
1330 
1331  wiimote_state_pub_.publish(wiimote_state_data);
1332 }
1333 
1335 {
1336  // Testing different Nunchuks show that they have different
1337  // centers and different range of motion.
1338  //
1339  // Best Approximation:
1340  // Grabbing the first set of x, y with the assumption of
1341  // the joystick is centered.
1342  // We know the joystick can only report between 0 and 255
1343  // for each axis; so assume a 20% guard band to set the
1344  // initial minimums and maximums. As the joystick is used,
1345  // updated the min/max values based on observed data.
1346  // This will have the effect of a less throw of the joystick
1347  // throttle during first movement to the max/min position.
1348  //
1349  // TODO(mdhorn): Could be improved by a true user interaction calibration
1350  // to find the center of the joystick, the max and min for each x and y.
1351  // But the effort in coding and extra burden on the one the user
1352  // may not be warranted.
1353 
1354  bool result = true;
1355 
1356  if (isPresentNunchuk())
1357  {
1359  {
1361  wiimote_state_.ext.nunchuk.stick, nunchuk_stick_center_, "Nunchuk");
1362 
1363  // Don't publish if we haven't found the center position
1365  {
1366  result = false;
1367  }
1368  }
1369 
1371  nunchuk_stick_max_, "Nunchuk");
1372  }
1373  else
1374  {
1375  ROS_WARN("State type is not Nunchuk!");
1376  result = false;
1377  }
1378 
1379  return result;
1380 }
1381 
1383 {
1384  sensor_msgs::Joy wiimote_nunchuk_data;
1385 
1387  {
1388  wiimote_nunchuk_data.header.stamp.sec = state_secs_;
1389  wiimote_nunchuk_data.header.stamp.nsec = state_nsecs_;
1390 
1391  // Joy stick
1392  double stick[2];
1393 
1396 
1397  wiimote_nunchuk_data.axes.push_back(stick[CWIID_X]); // x
1398  wiimote_nunchuk_data.axes.push_back(stick[CWIID_Y]); // y
1399 
1400  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_X],
1401  nunchuk_cal_.zero[CWIID_X], nunchuk_cal_.one[CWIID_X]) * EARTH_GRAVITY_);
1402  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Y],
1403  nunchuk_cal_.zero[CWIID_Y], nunchuk_cal_.one[CWIID_Y]) * EARTH_GRAVITY_);
1404  wiimote_nunchuk_data.axes.push_back(zeroedByCal(wiimote_state_.ext.nunchuk.acc[CWIID_Z],
1405  nunchuk_cal_.zero[CWIID_Z], nunchuk_cal_.one[CWIID_Z]) * EARTH_GRAVITY_);
1406 
1407 
1408  // NOTE: Order is different for /wiimote/state
1409  // Keep consistency with existing Python Node
1410  wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1411  wiimote_nunchuk_data.buttons.push_back((wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1412 
1413  wiimote_nunchuk_pub_.publish(wiimote_nunchuk_data);
1414  }
1415 }
1416 
1418 {
1419  // Using the same "Best Approximation" methods from
1420  // WiimoteNode::publishWiimoteNunchuk()
1421 
1422  sensor_msgs::Joy wiimote_classic_data;
1423 
1424  if (isPresentClassic())
1425  {
1426  ROS_WARN("State type is not Classic!");
1427  return;
1428  }
1429 
1431  {
1433  wiimote_state_.ext.classic.l_stick, classic_stick_left_center_, "Classic Left");
1434  }
1435 
1437  {
1439  wiimote_state_.ext.classic.r_stick, classic_stick_right_center_, "Classic Right");
1440  }
1441 
1444  {
1445  // Don't publish if we haven't found the center positions
1446  return;
1447  }
1448 
1450  classic_stick_left_max_, "Classic Left");
1452  classic_stick_right_max_, "Classic Right");
1453 
1454  wiimote_classic_data.header.stamp.sec = state_secs_;
1455  wiimote_classic_data.header.stamp.nsec = state_nsecs_;
1456 
1457  // Joy stick
1458  double stick_left[2];
1459  double stick_right[2];
1460 
1465 
1466  wiimote_classic_data.axes.push_back(stick_left[CWIID_X]); // Left x
1467  wiimote_classic_data.axes.push_back(stick_left[CWIID_Y]); // Left y
1468  wiimote_classic_data.axes.push_back(stick_right[CWIID_X]); // Right x
1469  wiimote_classic_data.axes.push_back(stick_right[CWIID_Y]); // Right y
1470 
1471  // NOTE: Order is different for /wiimote/state
1472  // Keep consistency with existing Python Node
1473  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_X) > 0);
1474  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_Y) > 0);
1475  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_A) > 0);
1476  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_B) > 0);
1477  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_PLUS) > 0);
1478  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_MINUS) > 0);
1479  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_LEFT) > 0);
1480  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_RIGHT) > 0);
1481  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_UP) > 0);
1482  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_DOWN) > 0);
1483  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_HOME) > 0);
1484  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_L) > 0);
1485  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_R) > 0);
1486  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZL) > 0);
1487  wiimote_classic_data.buttons.push_back((wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZR) > 0);
1488 
1489  wiimote_classic_pub_.publish(wiimote_classic_data);
1490 }
1491 
1492 // const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback is unused
1493 void WiimoteNode::joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback)
1494 {
1495  bool led_found = false;
1496  bool rumble_found = false;
1497 
1498  for (std::vector<sensor_msgs::JoyFeedback>::const_iterator it = feedback->array.begin();
1499  it != feedback->array.end(); ++it)
1500  {
1501  if ((*it).type == sensor_msgs::JoyFeedback::TYPE_LED)
1502  {
1503  led_found = true;
1504 
1505  if ((*it).intensity >= 0.5)
1506  {
1507  setLEDBit((*it).id, true);
1508  }
1509  else
1510  {
1511  setLEDBit((*it).id, false);
1512  }
1513  }
1514  else if ((*it).type == sensor_msgs::JoyFeedback::TYPE_RUMBLE)
1515  {
1516  if ((*it).id > 0)
1517  {
1518  ROS_WARN("RUMBLE ID %d out of bounds; ignoring!", (*it).id);
1519  }
1520  else
1521  {
1522  rumble_found = true;
1523 
1524  if ((*it).intensity >= 0.5)
1525  {
1526  setRumbleBit(true);
1527  }
1528  else
1529  {
1530  setRumbleBit(false);
1531  }
1532  }
1533  }
1534  else
1535  {
1536  ROS_WARN("Unknown JoyFeedback command; ignored");
1537  }
1538  }
1539 
1540  if (led_found)
1541  {
1543  }
1544 
1545  if (rumble_found)
1546  {
1548  }
1549 }
1550 
1551 bool WiimoteNode::serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
1552 {
1553  // Publish the new calibration state
1555 
1556  return true;
1557 }
1558 
1560 
1561 // int sig The signal number is unused
1562 void mySigHandler(int sig)
1563 {
1564  // Do some custom action.
1565  // For example, publish a stop message to some other nodes.
1566 
1567  // Clear the lights and rumble
1568  if (nullptr != g_wiimote_node)
1569  {
1570  g_wiimote_node->setRumbleState(0);
1571  g_wiimote_node->setLedState(0);
1572  }
1573 
1574  // All the default sigint handler does is call shutdown()
1575  ros::shutdown();
1576 
1577  exit(0);
1578 }
1579 
1580 int main(int argc, char *argv[])
1581 {
1582  bool fed_addr = false;
1583  std::string bluetooth_addr;
1584  ros::init(argc, argv, "wiimote_controller");
1585 
1586  g_wiimote_node = new WiimoteNode();
1587  // Do we have a bluetooth address passed in?
1588  if (argc > 1)
1589  {
1590  ROS_INFO("Using Bluetooth address specified from CLI");
1591  g_wiimote_node->setBluetoothAddr(argv[1]);
1592  fed_addr = true;
1593  }
1594 
1595  if (ros::param::get("~bluetooth_addr", bluetooth_addr))
1596  {
1597  g_wiimote_node->setBluetoothAddr(bluetooth_addr.c_str());
1598  fed_addr = true;
1599  }
1600 
1601  int pair_timeout;
1602  ros::param::param<int>("~pair_timeout", pair_timeout, 5);
1603 
1604  if (fed_addr)
1605  ROS_INFO("* * * Pairing with %s", g_wiimote_node->getBluetoothAddr());
1606 
1607  else
1608  ROS_INFO("Searching for Wiimotes");
1609 
1610  ROS_INFO("Allow all joy sticks to remain at center position until calibrated.");
1611 
1612  if (g_wiimote_node->pairWiimote(0, pair_timeout))
1613  {
1614  ROS_INFO("Wiimote is Paired");
1615 
1616  signal(SIGINT, mySigHandler);
1617  signal(SIGTERM, mySigHandler);
1618  }
1619  else
1620  {
1621  ROS_ERROR("* * * Wiimote pairing failed.");
1622  ros::shutdown();
1623  }
1624 
1625  ros::Rate loop_rate(10); // 10Hz
1626 
1627  while (ros::ok())
1628  {
1629  g_wiimote_node->publish();
1630 
1631  ros::spinOnce();
1632 
1633  loop_rate.sleep();
1634  }
1635 
1636  if (g_wiimote_node->unpairWiimote())
1637  {
1638  ROS_ERROR("Error on wiimote disconnect");
1639  return -1;
1640  }
1641 
1642  return 0;
1643 }
d
Definition: setup.py:6
ros::Time calibration_time_
int main(int argc, char *argv[])
void addData(int x, int y, int z)
ros::Subscriber joy_set_feedback_sub_
void setLEDBit(uint8_t led, bool on)
uint8_t nunchuk_stick_max_[2]
WiimoteNode * g_wiimote_node
uint8_t nunchuk_stick_min_[2]
StatVector3d angular_velocity_stat_
bool isCollectingMotionplus()
void publish(const boost::shared_ptr< M > &message) const
const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_
void setBluetoothAddr(const char *bt_str)
TVectorDouble getStandardDeviationRaw()
ros::Publisher wiimote_state_pub_
bool classic_stick_right_calibrated_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void mySigHandler(int sig)
ros::Publisher joy_pub_
static wiimote_c::cwiid_err_t cwiidErrorCallback
void initializeWiimoteState()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher imu_is_calibrated_pub_
boost::array< double, 9 > angular_velocity_covariance_
uint8_t classic_stick_left_min_[2]
uint8_t nunchuk_stick_center_[2]
void setRumbleBit(bool on)
bool publishWiimoteNunchukCommon()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const double EARTH_GRAVITY_
wiimote_c::cwiid_wiimote_t * wiimote_
ros::Publisher wiimote_nunchuk_pub_
#define ROS_WARN(...)
uint8_t classic_stick_right_min_[2]
bool classic_stick_left_calibrated_
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_
void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr &feedback)
void setRumbleState(uint8_t rumble)
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
uint8_t classic_stick_right_center_[2]
ROSCPP_DECL bool get(const std::string &key, std::string &s)
TVectorDouble getMeanRaw()
const double GYRO_SCALE_FACTOR_
#define ROS_INFO(...)
TVectorDouble getVarianceScaled(double scale)
struct wiimote_c::acc_cal nunchuk_cal_
uint32_t state_secs_
ROSCPP_DECL bool ok()
bdaddr_t bt_device_addr_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle nh_
const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
struct wiimote_c::cwiid_state wiimote_state_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_
bool sleep()
void setLedState(uint8_t led_state)
const int COVARIANCE_DATA_POINTS_
bool pairWiimote(int flags, int timeout)
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
bool nunchuk_stick_calibrated_
StatVector3d linear_acceleration_stat_
uint32_t getNumSubscribers() const
#define zeroedByCal(raw, zero, one)
bool serviceImuCalibrateCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
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])
const int IGNORE_DATA_POINTS_
uint8_t classic_stick_left_max_[2]
boost::array< double, 9 > linear_acceleration_covariance_
bool nunchuk_failed_calibration_
bool calibrateJoystick(uint8_t stick[2], uint8_t(&center)[2], const char *name)
static Time now()
void checkFactoryCalibrationData()
char * getBluetoothAddr()
ROSCPP_DECL void shutdown()
uint32_t state_nsecs_
void setReportMode(uint8_t rpt_mode)
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
struct wiimote_c::acc_cal wiimote_cal_
ros::ServiceServer imu_calibrate_srv_
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
ros::Publisher wiimote_classic_pub_
void updateJoystickMinMax(uint8_t stick[2], uint8_t(&stick_min)[2], uint8_t(&stick_max)[2], const char *name)
uint64_t wiimote_errors
uint8_t classic_stick_right_max_[2]
ros::Publisher imu_data_pub_
uint8_t classic_stick_left_center_[2]
const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
std::vector< double > TVectorDouble
#define ROS_DEBUG(...)


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Fri Jun 7 2019 22:01:33