wiimote_controller.h
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  * Revisions:
34  *
35  */
36 
37 #pragma once
38 #ifndef WIIMOTE_WIIMOTE_CONTROLLER_H
39 #define WIIMOTE_WIIMOTE_CONTROLLER_H
40 
41 #include "ros/ros.h"
42 #include "sensor_msgs/JoyFeedbackArray.h"
43 #include "std_srvs/Empty.h"
44 #include "sensor_msgs/Imu.h"
45 
46 #include "wiimote/stat_vector_3d.h"
47 
48 // We need to link against these
49 #include <bluetooth/bluetooth.h> // libbluetooth.so
50 namespace wiimote_c
51 {
52 #include <cwiid.h> // libcwiid.so
53 }
54 
55 #define zeroedByCal(raw, zero, one) \
56  (((raw - zero) * 1.0) / ((one - zero) * 1.0))
57 
59 {
60 public:
61  WiimoteNode();
62  ~WiimoteNode();
63  char *getBluetoothAddr();
64  void setBluetoothAddr(const char *bt_str);
65  bool pairWiimote(int flags, int timeout);
66  int unpairWiimote();
67 
68  void publish();
69 
70  void setLedState(uint8_t led_state);
71  void setRumbleState(uint8_t rumble);
72 
73 private:
74  void setReportMode(uint8_t rpt_mode);
75  void checkFactoryCalibrationData();
76  void resetMotionPlusState();
77  void resetNunchukState();
78  void resetClassicState();
79 
81 
82  static wiimote_c::cwiid_err_t cwiidErrorCallback;
83 
100  void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback);
101  bool serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
102 
103  bool isCollectingWiimote();
104  bool isCollectingNunchuk();
105  bool isCollectingClassic();
106  bool isCollectingMotionplus();
107 
108  bool isPresentNunchuk();
109  bool isPresentClassic();
110  bool isPresentMotionplus();
111 
112  bool calibrateJoystick(uint8_t stick[2], uint8_t (&center)[2], const char *name);
113  void updateJoystickMinMax(uint8_t stick[2], uint8_t (&stick_min)[2],
114  uint8_t (&stick_max)[2], const char *name);
115  void calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2],
116  uint8_t stick_max[2], uint8_t stick_center[2], double (&stick)[2]);
117 
118  void publishJoy();
119  void publishImuData();
120  void publishWiimoteState();
121  bool publishWiimoteNunchukCommon();
122  void publishWiimoteNunchuk();
123  void publishWiimoteClassic();
124 
125  bool getStateSample();
126 
127  void setLEDBit(uint8_t led, bool on);
128  void setRumbleBit(bool on);
129 
136 
138 
140 
141  // bluetooth device address
142  bdaddr_t bt_device_addr_;
143 
144  // wiimote handle
145  wiimote_c::cwiid_wiimote_t *wiimote_;
146 
147  // Last state of the Wiimote
148  struct wiimote_c::cwiid_state wiimote_state_;
149  void initializeWiimoteState();
150  // Time last state sample was taken
151  uint32_t state_secs_;
152  uint32_t state_nsecs_;
153 
154  // Which data items should be reported in state
155  uint8_t report_mode_;
156 
157  // Calibration status Wiimote
158  struct wiimote_c::acc_cal wiimote_cal_; // wiimote acceleration factory calibration
161 
162  // Joystick related constants
163  const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127; // Theoretical center
164  const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205;
165  const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_ = 50;
166  const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31; // Theoretical center
167  const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_ = 50;
168  const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_ = 13;
169  const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15; // Theoretical center
170  const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25;
171  const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6;
172 
173  // Calibration status Nunchuk
174  struct wiimote_c::acc_cal nunchuk_cal_; // nunchuk acceleration factory calibration
177  uint8_t nunchuk_stick_center_[2]; // nunchuk stick center position
179  uint8_t nunchuk_stick_max_[2]; // Maximums x,y
180  uint8_t nunchuk_stick_min_[2]; // Minimums x,y
181 
182  // Calibration status Classic Controller
183  uint8_t classic_stick_left_center_[2]; // nunchuk stick center position
185  uint8_t classic_stick_left_max_[2];
186  uint8_t classic_stick_left_min_[2];
187  uint8_t classic_stick_right_center_[2]; // nunchuk stick center position
189  uint8_t classic_stick_right_max_[2];
190  uint8_t classic_stick_right_min_[2];
191 
192  const int IGNORE_DATA_POINTS_ = 100; // throw away the first few data points
193  const int COVARIANCE_DATA_POINTS_ = 100;
196  boost::array<double, 9> linear_acceleration_covariance_;
197  boost::array<double, 9> angular_velocity_covariance_;
198 
199  uint8_t led_state_ = 0;
200  uint8_t rumble_ = 0;
201 
202  uint64_t wiimote_errors = 0;
203 
204  // Convert wiimote accelerator readings from g's to m/sec^2:
205  const double EARTH_GRAVITY_ = 9.80665; // m/sec^2 @sea_level
206 
207  // Method used in Wiimote Python version
208  // TODO(mdhorn): Repeat experiment or create a new one
209  // and collect data from multiple wiimotes and use mean.
210  //
211  // Turning wiimote gyro readings to radians/sec.
212  // This scale factor is highly approximate. Procedure:
213  // - Tape Wiimote to center of an office chair seat
214  // - Rotate the chair at approximately constant speed
215  // for 10 seconds. This resulted in 6 chair revolutions
216  // - On average, the Wiimote gyro read 3570 during this
217  // experiment.
218  // - Speed of chair revolving:
219  // * One full circle is: 2#pi radians
220  // * Six revolutions = 12pi radians. ==> 12pi rad in 10 sec ==> 1.2pi rad/sec
221  // * => 3570 == 1.2pi
222  // * => x*3570 = 1.2pi
223  // * => x = 1.2pi/3570 (1.2pi = 3.769908)
224  // * => scale factor = 0.001055997
225  // So multiplying the gyro readings by this factor
226  // calibrates the readings to show angular velocity
227  // in radians/sec.
228  const double GYRO_SCALE_FACTOR_ = 0.001055997;
229 };
230 
231 #endif // WIIMOTE_WIIMOTE_CONTROLLER_H
ros::Time calibration_time_
ros::Subscriber joy_set_feedback_sub_
StatVector3d angular_velocity_stat_
ros::Publisher wiimote_state_pub_
bool classic_stick_right_calibrated_
ros::Publisher joy_pub_
static wiimote_c::cwiid_err_t cwiidErrorCallback
ros::Publisher imu_is_calibrated_pub_
boost::array< double, 9 > angular_velocity_covariance_
wiimote_c::cwiid_wiimote_t * wiimote_
ros::Publisher wiimote_nunchuk_pub_
bool classic_stick_left_calibrated_
uint32_t state_secs_
bdaddr_t bt_device_addr_
ros::NodeHandle nh_
bool nunchuk_stick_calibrated_
StatVector3d linear_acceleration_stat_
boost::array< double, 9 > linear_acceleration_covariance_
bool nunchuk_failed_calibration_
uint32_t state_nsecs_
ros::ServiceServer imu_calibrate_srv_
ros::Publisher wiimote_classic_pub_
ros::Publisher imu_data_pub_


wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Mon Jun 10 2019 13:42:43