38 #ifndef WIIMOTE_WIIMOTE_CONTROLLER_H 39 #define WIIMOTE_WIIMOTE_CONTROLLER_H 42 #include "sensor_msgs/JoyFeedbackArray.h" 43 #include "std_srvs/Empty.h" 44 #include "sensor_msgs/Imu.h" 49 #include <bluetooth/bluetooth.h> 55 #define zeroedByCal(raw, zero, one) \ 56 (((raw - zero) * 1.0) / ((one - zero) * 1.0)) 63 char *getBluetoothAddr();
64 void setBluetoothAddr(
const char *bt_str);
65 bool pairWiimote(
int flags,
int timeout);
70 void setLedState(uint8_t led_state);
71 void setRumbleState(uint8_t rumble);
74 void setReportMode(uint8_t rpt_mode);
75 void checkFactoryCalibrationData();
76 void resetMotionPlusState();
77 void resetNunchukState();
78 void resetClassicState();
100 void joySetFeedbackCallback(
const sensor_msgs::JoyFeedbackArray::ConstPtr& feedback);
101 bool serviceImuCalibrateCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
103 bool isCollectingWiimote();
104 bool isCollectingNunchuk();
105 bool isCollectingClassic();
106 bool isCollectingMotionplus();
108 bool isPresentNunchuk();
109 bool isPresentClassic();
110 bool isPresentMotionplus();
112 bool calibrateJoystick(uint8_t stick[2], uint8_t (¢er)[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]);
119 void publishImuData();
120 void publishWiimoteState();
121 bool publishWiimoteNunchukCommon();
122 void publishWiimoteNunchuk();
123 void publishWiimoteClassic();
125 bool getStateSample();
127 void setLEDBit(uint8_t led,
bool on);
128 void setRumbleBit(
bool on);
148 struct wiimote_c::cwiid_state wiimote_state_;
149 void initializeWiimoteState();
158 struct wiimote_c::acc_cal wiimote_cal_;
163 const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127;
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;
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;
170 const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25;
171 const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6;
174 struct wiimote_c::acc_cal nunchuk_cal_;
177 uint8_t nunchuk_stick_center_[2];
179 uint8_t nunchuk_stick_max_[2];
180 uint8_t nunchuk_stick_min_[2];
183 uint8_t classic_stick_left_center_[2];
185 uint8_t classic_stick_left_max_[2];
186 uint8_t classic_stick_left_min_[2];
187 uint8_t classic_stick_right_center_[2];
189 uint8_t classic_stick_right_max_[2];
190 uint8_t classic_stick_right_min_[2];
192 const int IGNORE_DATA_POINTS_ = 100;
193 const int COVARIANCE_DATA_POINTS_ = 100;
199 uint8_t led_state_ = 0;
202 uint64_t wiimote_errors = 0;
205 const double EARTH_GRAVITY_ = 9.80665;
228 const double GYRO_SCALE_FACTOR_ = 0.001055997;
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_
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_
bool nunchuk_stick_calibrated_
StatVector3d linear_acceleration_stat_
boost::array< double, 9 > linear_acceleration_covariance_
bool nunchuk_failed_calibration_
ros::ServiceServer imu_calibrate_srv_
ros::Publisher wiimote_classic_pub_
ros::Publisher imu_data_pub_