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  void checkConnection();
70  void timerCallback(const ros::TimerEvent&);
71 
72  void setLedState(uint8_t led_state);
73  void setRumbleState(uint8_t rumble);
74 
75 private:
76  void setReportMode(uint8_t rpt_mode);
78  void resetMotionPlusState();
79  void resetNunchukState();
80  void resetClassicState();
81 
83 
84  static wiimote_c::cwiid_err_t cwiidErrorCallback;
85 
102  void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback);
103  bool serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
104 
105  bool isCollectingWiimote();
106  bool isCollectingNunchuk();
107  bool isCollectingClassic();
108  bool isCollectingMotionplus();
109 
110  bool isPresentNunchuk();
111  bool isPresentClassic();
112  bool isPresentMotionplus();
113 
114  bool calibrateJoystick(uint8_t stick[2], uint8_t (&center)[2], const char *name);
115  void updateJoystickMinMax(uint8_t stick[2], uint8_t (&stick_min)[2],
116  uint8_t (&stick_max)[2], const char *name);
117  void calculateJoystickAxisXY(uint8_t stick_current[2], uint8_t stick_min[2],
118  uint8_t stick_max[2], uint8_t stick_center[2], double (&stick)[2]);
119 
120  void publishJoy();
121  void publishImuData();
122  void publishWiimoteState();
124  void publishWiimoteNunchuk();
125  void publishWiimoteClassic();
126 
127  bool getStateSample();
128 
129  void setLEDBit(uint8_t led, bool on);
130  void setRumbleBit(bool on);
131 
138 
140 
142 
143  // bluetooth device address
144  bdaddr_t bt_device_addr_;
145 
146  // wiimote handle
147  wiimote_c::cwiid_wiimote_t *wiimote_;
148 
149  // Last state of the Wiimote
150  struct wiimote_c::cwiid_state wiimote_state_;
151  void initializeWiimoteState();
152  // Time last state sample was taken
153  uint32_t state_secs_;
154  uint32_t state_nsecs_;
155 
156  // Which data items should be reported in state
157  uint8_t report_mode_;
158 
159  // Calibration status Wiimote
160  struct wiimote_c::acc_cal wiimote_cal_; // wiimote acceleration factory calibration
163 
164  // Joystick related constants
165  const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127; // Theoretical center
166  const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205;
168  const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31; // Theoretical center
171  const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15; // Theoretical center
174 
175  // Calibration status Nunchuk
176  struct wiimote_c::acc_cal nunchuk_cal_; // nunchuk acceleration factory calibration
179  uint8_t nunchuk_stick_center_[2]; // nunchuk stick center position
181  uint8_t nunchuk_stick_max_[2]; // Maximums x,y
182  uint8_t nunchuk_stick_min_[2]; // Minimums x,y
183 
184  // Calibration status Classic Controller
185  uint8_t classic_stick_left_center_[2]; // nunchuk stick center position
189  uint8_t classic_stick_right_center_[2]; // nunchuk stick center position
193 
194  const int IGNORE_DATA_POINTS_ = 100; // throw away the first few data points
195  const int COVARIANCE_DATA_POINTS_ = 100;
198  boost::array<double, 9> linear_acceleration_covariance_;
199  boost::array<double, 9> angular_velocity_covariance_;
200 
201  uint8_t led_state_ = 0;
202  uint8_t rumble_ = 0;
203 
204  uint64_t wiimote_errors = 0;
205 
206  // Convert wiimote accelerator readings from g's to m/sec^2:
207  const double EARTH_GRAVITY_ = 9.80665; // m/sec^2 @sea_level
208 
209  // Method used in Wiimote Python version
210  // TODO(mdhorn): Repeat experiment or create a new one
211  // and collect data from multiple wiimotes and use mean.
212  //
213  // Turning wiimote gyro readings to radians/sec.
214  // This scale factor is highly approximate. Procedure:
215  // - Tape Wiimote to center of an office chair seat
216  // - Rotate the chair at approximately constant speed
217  // for 10 seconds. This resulted in 6 chair revolutions
218  // - On average, the Wiimote gyro read 3570 during this
219  // experiment.
220  // - Speed of chair revolving:
221  // * One full circle is: 2#pi radians
222  // * Six revolutions = 12pi radians. ==> 12pi rad in 10 sec ==> 1.2pi rad/sec
223  // * => 3570 == 1.2pi
224  // * => x*3570 = 1.2pi
225  // * => x = 1.2pi/3570 (1.2pi = 3.769908)
226  // * => scale factor = 0.001055997
227  // So multiplying the gyro readings by this factor
228  // calibrates the readings to show angular velocity
229  // in radians/sec.
230  const double GYRO_SCALE_FACTOR_ = 0.001055997;
231 };
232 
233 #endif // WIIMOTE_WIIMOTE_CONTROLLER_H
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
wiimote_c
Definition: wiimote_controller.h:50
WiimoteNode::publish
void publish()
Definition: wiimote_controller.cpp:518
ros::Publisher
WiimoteNode
Definition: wiimote_controller.h:58
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
WiimoteNode::setRumbleBit
void setRumbleBit(bool on)
Definition: wiimote_controller.cpp:916
WiimoteNode::publishWiimoteNunchukCommon
bool publishWiimoteNunchukCommon()
Definition: wiimote_controller.cpp:1343
WiimoteNode::resetNunchukState
void resetNunchukState()
Definition: wiimote_controller.cpp:487
WiimoteNode::EARTH_GRAVITY_
const double EARTH_GRAVITY_
Definition: wiimote_controller.h:207
ros.h
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
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
WiimoteNode::publishWiimoteState
void publishWiimoteState()
Definition: wiimote_controller.cpp:1201
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
WiimoteNode::nunchuk_stick_center_
uint8_t nunchuk_stick_center_[2]
Definition: wiimote_controller.h:179
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
ros::ServiceServer
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
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
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
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
WiimoteNode::GYRO_SCALE_FACTOR_
const double GYRO_SCALE_FACTOR_
Definition: wiimote_controller.h:230
WiimoteNode::publishImuData
void publishImuData()
Definition: wiimote_controller.cpp:1161
WiimoteNode::nh_
ros::NodeHandle nh_
Definition: wiimote_controller.h:82
WiimoteNode::getStateSample
bool getStateSample()
Definition: wiimote_controller.cpp:742
ros::TimerEvent
WiimoteNode::serviceImuCalibrateCallback
bool serviceImuCalibrateCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: wiimote_controller.cpp:1560
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
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
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
ros::Time
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
WiimoteNode::setReportMode
void setReportMode(uint8_t rpt_mode)
Definition: wiimote_controller.cpp:875
WiimoteNode::state_nsecs_
uint32_t state_nsecs_
Definition: wiimote_controller.h:154
WiimoteNode::isPresentClassic
bool isPresentClassic()
Definition: wiimote_controller.cpp:992
WiimoteNode::timerCallback
void timerCallback(const ros::TimerEvent &)
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
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
WiimoteNode::resetMotionPlusState
void resetMotionPlusState()
Definition: wiimote_controller.cpp:469
WiimoteNode::classic_stick_left_center_
uint8_t classic_stick_left_center_[2]
Definition: wiimote_controller.h:185
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
WiimoteNode::setLEDBit
void setLEDBit(uint8_t led, bool on)
Definition: wiimote_controller.cpp:896
WiimoteNode::IGNORE_DATA_POINTS_
const int IGNORE_DATA_POINTS_
Definition: wiimote_controller.h:194
WiimoteNode::setBluetoothAddr
void setBluetoothAddr(const char *bt_str)
Definition: wiimote_controller.cpp:143
ros::NodeHandle
ros::Subscriber
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
stat_vector_3d.h
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