#include <wiimote_controller.h>
|  | 
| 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]) | 
|  | 
| bool | calibrateJoystick (uint8_t stick[2], uint8_t(¢er)[2], const char *name) | 
|  | 
| void | checkFactoryCalibrationData () | 
|  | 
| bool | getStateSample () | 
|  | 
| void | initializeWiimoteState () | 
|  | 
| bool | isCollectingClassic () | 
|  | 
| bool | isCollectingMotionplus () | 
|  | 
| bool | isCollectingNunchuk () | 
|  | 
| bool | isCollectingWiimote () | 
|  | 
| bool | isPresentClassic () | 
|  | 
| bool | isPresentMotionplus () | 
|  | 
| bool | isPresentNunchuk () | 
|  | 
| void | joySetFeedbackCallback (const sensor_msgs::JoyFeedbackArray::ConstPtr &feedback) | 
|  | 
| void | publishImuData () | 
|  | 
| void | publishJoy () | 
|  | 
| void | publishWiimoteClassic () | 
|  | 
| void | publishWiimoteNunchuk () | 
|  | 
| bool | publishWiimoteNunchukCommon () | 
|  | 
| void | publishWiimoteState () | 
|  | 
| void | resetClassicState () | 
|  | 
| void | resetMotionPlusState () | 
|  | 
| void | resetNunchukState () | 
|  | 
| bool | serviceImuCalibrateCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &) | 
|  | 
| void | setLEDBit (uint8_t led, bool on) | 
|  | 
| void | setReportMode (uint8_t rpt_mode) | 
|  | 
| void | setRumbleBit (bool on) | 
|  | 
| void | updateJoystickMinMax (uint8_t stick[2], uint8_t(&stick_min)[2], uint8_t(&stick_max)[2], const char *name) | 
|  | 
Definition at line 58 of file wiimote_controller.h.
 
◆ WiimoteNode()
      
        
          | WiimoteNode::WiimoteNode | ( |  | ) |  | 
      
 
Optional Publications – only advertise if the hardware is connected This is done in the main loop in the ::publish method wiimote_nunchuk_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/nunchuk", 1); wiimote_classic_pub_ = nh_.advertise<sensor_msgs::Joy>("/wiimote/classic", 1);
Definition at line 66 of file wiimote_controller.cpp.
 
 
◆ ~WiimoteNode()
      
        
          | WiimoteNode::~WiimoteNode | ( |  | ) |  | 
      
 
 
◆ calculateJoystickAxisXY()
  
  | 
        
          | void WiimoteNode::calculateJoystickAxisXY | ( | uint8_t | stick_current[2], |  
          |  |  | uint8_t | stick_min[2], |  
          |  |  | uint8_t | stick_max[2], |  
          |  |  | uint8_t | stick_center[2], |  
          |  |  | double(&) | stick[2] |  
          |  | ) |  |  |  | private | 
 
 
◆ calibrateJoystick()
  
  | 
        
          | bool WiimoteNode::calibrateJoystick | ( | uint8_t | stick[2], |  
          |  |  | uint8_t(&) | center[2], |  
          |  |  | const char * | name |  
          |  | ) |  |  |  | private | 
 
 
◆ checkConnection()
      
        
          | void WiimoteNode::checkConnection | ( |  | ) |  | 
      
 
 
◆ checkFactoryCalibrationData()
  
  | 
        
          | void WiimoteNode::checkFactoryCalibrationData | ( |  | ) |  |  | private | 
 
 
◆ getBluetoothAddr()
      
        
          | char * WiimoteNode::getBluetoothAddr | ( |  | ) |  | 
      
 
 
◆ getStateSample()
  
  | 
        
          | bool WiimoteNode::getStateSample | ( |  | ) |  |  | private | 
 
 
◆ initializeWiimoteState()
  
  | 
        
          | void WiimoteNode::initializeWiimoteState | ( |  | ) |  |  | private | 
 
 
◆ isCollectingClassic()
  
  | 
        
          | bool WiimoteNode::isCollectingClassic | ( |  | ) |  |  | private | 
 
 
◆ isCollectingMotionplus()
  
  | 
        
          | bool WiimoteNode::isCollectingMotionplus | ( |  | ) |  |  | private | 
 
 
◆ isCollectingNunchuk()
  
  | 
        
          | bool WiimoteNode::isCollectingNunchuk | ( |  | ) |  |  | private | 
 
 
◆ isCollectingWiimote()
  
  | 
        
          | bool WiimoteNode::isCollectingWiimote | ( |  | ) |  |  | private | 
 
 
◆ isPresentClassic()
  
  | 
        
          | bool WiimoteNode::isPresentClassic | ( |  | ) |  |  | private | 
 
 
◆ isPresentMotionplus()
  
  | 
        
          | bool WiimoteNode::isPresentMotionplus | ( |  | ) |  |  | private | 
 
 
◆ isPresentNunchuk()
  
  | 
        
          | bool WiimoteNode::isPresentNunchuk | ( |  | ) |  |  | private | 
 
 
◆ joySetFeedbackCallback()
  
  | 
        
          | void WiimoteNode::joySetFeedbackCallback | ( | const sensor_msgs::JoyFeedbackArray::ConstPtr & | feedback | ) |  |  | private | 
 
Node [/wiimote_controller] Publications: /joy [sensor_msgs/Joy] /wiimote/state [wiimote/State] /wiimote/nunchuk [sensor_msgs/Joy] /wiimote/classic [sensor_msgs/Joy] /imu/is_calibrated [std_msgs/Bool] /imu/data [sensor_msgs/Imu]
Subscriptions: /joy/set_feedback [sensor_msgs/JoyFeedbackArray]
Services: /imu/calibrate 
Definition at line 1502 of file wiimote_controller.cpp.
 
 
◆ pairWiimote()
      
        
          | bool WiimoteNode::pairWiimote | ( | int | flags = 0, | 
        
          |  |  | int | timeout = 5 | 
        
          |  | ) |  |  | 
      
 
 
◆ publish()
      
        
          | void WiimoteNode::publish | ( |  | ) |  | 
      
 
 
◆ publishImuData()
  
  | 
        
          | void WiimoteNode::publishImuData | ( |  | ) |  |  | private | 
 
 
◆ publishJoy()
  
  | 
        
          | void WiimoteNode::publishJoy | ( |  | ) |  |  | private | 
 
 
◆ publishWiimoteClassic()
  
  | 
        
          | void WiimoteNode::publishWiimoteClassic | ( |  | ) |  |  | private | 
 
 
◆ publishWiimoteNunchuk()
  
  | 
        
          | void WiimoteNode::publishWiimoteNunchuk | ( |  | ) |  |  | private | 
 
 
◆ publishWiimoteNunchukCommon()
  
  | 
        
          | bool WiimoteNode::publishWiimoteNunchukCommon | ( |  | ) |  |  | private | 
 
 
◆ publishWiimoteState()
  
  | 
        
          | void WiimoteNode::publishWiimoteState | ( |  | ) |  |  | private | 
 
 
◆ resetClassicState()
  
  | 
        
          | void WiimoteNode::resetClassicState | ( |  | ) |  |  | private | 
 
 
◆ resetMotionPlusState()
  
  | 
        
          | void WiimoteNode::resetMotionPlusState | ( |  | ) |  |  | private | 
 
 
◆ resetNunchukState()
  
  | 
        
          | void WiimoteNode::resetNunchukState | ( |  | ) |  |  | private | 
 
 
◆ serviceImuCalibrateCallback()
  
  | 
        
          | bool WiimoteNode::serviceImuCalibrateCallback | ( | std_srvs::Empty::Request & | , |  
          |  |  | std_srvs::Empty::Response & |  |  
          |  | ) |  |  |  | private | 
 
 
◆ setBluetoothAddr()
      
        
          | void WiimoteNode::setBluetoothAddr | ( | const char * | bt_str | ) |  | 
      
 
 
◆ setLEDBit()
  
  | 
        
          | void WiimoteNode::setLEDBit | ( | uint8_t | led, |  
          |  |  | bool | on |  
          |  | ) |  |  |  | private | 
 
 
◆ setLedState()
      
        
          | void WiimoteNode::setLedState | ( | uint8_t | led_state | ) |  | 
      
 
 
◆ setReportMode()
  
  | 
        
          | void WiimoteNode::setReportMode | ( | uint8_t | rpt_mode | ) |  |  | private | 
 
 
◆ setRumbleBit()
  
  | 
        
          | void WiimoteNode::setRumbleBit | ( | bool | on | ) |  |  | private | 
 
 
◆ setRumbleState()
      
        
          | void WiimoteNode::setRumbleState | ( | uint8_t | rumble | ) |  | 
      
 
 
◆ timerCallback()
◆ unpairWiimote()
      
        
          | int WiimoteNode::unpairWiimote | ( |  | ) |  | 
      
 
 
◆ updateJoystickMinMax()
  
  | 
        
          | void WiimoteNode::updateJoystickMinMax | ( | uint8_t | stick[2], |  
          |  |  | uint8_t(&) | stick_min[2], |  
          |  |  | uint8_t(&) | stick_max[2], |  
          |  |  | const char * | name |  
          |  | ) |  |  |  | private | 
 
 
◆ angular_velocity_covariance_
  
  | 
        
          | boost::array<double, 9> WiimoteNode::angular_velocity_covariance_ |  | private | 
 
 
◆ angular_velocity_stat_
◆ bt_device_addr_
  
  | 
        
          | bdaddr_t WiimoteNode::bt_device_addr_ |  | private | 
 
 
◆ calibration_time_
◆ classic_stick_left_calibrated_
  
  | 
        
          | bool WiimoteNode::classic_stick_left_calibrated_ |  | private | 
 
 
◆ classic_stick_left_center_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_left_center_[2] |  | private | 
 
 
◆ classic_stick_left_max_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_left_max_[2] |  | private | 
 
 
◆ classic_stick_left_min_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_left_min_[2] |  | private | 
 
 
◆ classic_stick_right_calibrated_
  
  | 
        
          | bool WiimoteNode::classic_stick_right_calibrated_ |  | private | 
 
 
◆ classic_stick_right_center_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_right_center_[2] |  | private | 
 
 
◆ classic_stick_right_max_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_right_max_[2] |  | private | 
 
 
◆ classic_stick_right_min_
  
  | 
        
          | uint8_t WiimoteNode::classic_stick_right_min_[2] |  | private | 
 
 
◆ COVARIANCE_DATA_POINTS_
  
  | 
        
          | const int WiimoteNode::COVARIANCE_DATA_POINTS_ = 100 |  | private | 
 
 
◆ cwiidErrorCallback
  
  | 
        
          | void WiimoteNode::cwiidErrorCallback |  | staticprivate | 
 
 
◆ EARTH_GRAVITY_
  
  | 
        
          | const double WiimoteNode::EARTH_GRAVITY_ = 9.80665 |  | private | 
 
 
◆ GYRO_SCALE_FACTOR_
  
  | 
        
          | const double WiimoteNode::GYRO_SCALE_FACTOR_ = 0.001055997 |  | private | 
 
 
◆ IGNORE_DATA_POINTS_
  
  | 
        
          | const int WiimoteNode::IGNORE_DATA_POINTS_ = 100 |  | private | 
 
 
◆ imu_calibrate_srv_
◆ imu_data_pub_
◆ imu_is_calibrated_pub_
◆ joy_pub_
◆ joy_set_feedback_sub_
◆ JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_ = 50 |  | private | 
 
 
◆ JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_ = 13 |  | private | 
 
 
◆ JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31 |  | private | 
 
 
◆ JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25 |  | private | 
 
 
◆ JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6 |  | private | 
 
 
◆ JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15 |  | private | 
 
 
◆ JOYSTICK_NUNCHUK_20PERCENT_MAX_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205 |  | private | 
 
 
◆ JOYSTICK_NUNCHUK_20PERCENT_MIN_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MIN_ = 50 |  | private | 
 
 
◆ JOYSTICK_NUNCHUK_DEFAULT_CENTER_
  
  | 
        
          | const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127 |  | private | 
 
 
◆ led_state_
  
  | 
        
          | uint8_t WiimoteNode::led_state_ = 0 |  | private | 
 
 
◆ linear_acceleration_covariance_
  
  | 
        
          | boost::array<double, 9> WiimoteNode::linear_acceleration_covariance_ |  | private | 
 
 
◆ linear_acceleration_stat_
◆ nh_
◆ nunchuk_cal_
  
  | 
        
          | struct wiimote_c::acc_cal WiimoteNode::nunchuk_cal_ |  | private | 
 
 
◆ nunchuk_calibrated_
  
  | 
        
          | bool WiimoteNode::nunchuk_calibrated_ |  | private | 
 
 
◆ nunchuk_failed_calibration_
  
  | 
        
          | bool WiimoteNode::nunchuk_failed_calibration_ |  | private | 
 
 
◆ nunchuk_stick_calibrated_
  
  | 
        
          | bool WiimoteNode::nunchuk_stick_calibrated_ |  | private | 
 
 
◆ nunchuk_stick_center_
  
  | 
        
          | uint8_t WiimoteNode::nunchuk_stick_center_[2] |  | private | 
 
 
◆ nunchuk_stick_max_
  
  | 
        
          | uint8_t WiimoteNode::nunchuk_stick_max_[2] |  | private | 
 
 
◆ nunchuk_stick_min_
  
  | 
        
          | uint8_t WiimoteNode::nunchuk_stick_min_[2] |  | private | 
 
 
◆ report_mode_
  
  | 
        
          | uint8_t WiimoteNode::report_mode_ |  | private | 
 
 
◆ rumble_
  
  | 
        
          | uint8_t WiimoteNode::rumble_ = 0 |  | private | 
 
 
◆ state_nsecs_
  
  | 
        
          | uint32_t WiimoteNode::state_nsecs_ |  | private | 
 
 
◆ state_secs_
  
  | 
        
          | uint32_t WiimoteNode::state_secs_ |  | private | 
 
 
◆ wiimote_
  
  | 
        
          | wiimote_c::cwiid_wiimote_t* WiimoteNode::wiimote_ |  | private | 
 
 
◆ wiimote_cal_
  
  | 
        
          | struct wiimote_c::acc_cal WiimoteNode::wiimote_cal_ |  | private | 
 
 
◆ wiimote_calibrated_
  
  | 
        
          | bool WiimoteNode::wiimote_calibrated_ |  | private | 
 
 
◆ wiimote_classic_pub_
◆ wiimote_errors
  
  | 
        
          | uint64_t WiimoteNode::wiimote_errors = 0 |  | private | 
 
 
◆ wiimote_nunchuk_pub_
◆ wiimote_state_
  
  | 
        
          | struct wiimote_c::cwiid_state WiimoteNode::wiimote_state_ |  | private | 
 
 
◆ wiimote_state_pub_
The documentation for this class was generated from the following files: