Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
WiimoteNode Class Reference

#include <wiimote_controller.h>

Public Member Functions

char * getBluetoothAddr ()
 
bool pairWiimote (int flags, int timeout)
 
void publish ()
 
void setBluetoothAddr (const char *bt_str)
 
void setLedState (uint8_t led_state)
 
void setRumbleState (uint8_t rumble)
 
int unpairWiimote ()
 
 WiimoteNode ()
 
 ~WiimoteNode ()
 

Private Member Functions

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(&center)[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)
 

Private Attributes

boost::array< double, 9 > angular_velocity_covariance_
 
StatVector3d angular_velocity_stat_
 
bdaddr_t bt_device_addr_
 
ros::Time calibration_time_
 
bool classic_stick_left_calibrated_
 
uint8_t classic_stick_left_center_ [2]
 
uint8_t classic_stick_left_max_ [2]
 
uint8_t classic_stick_left_min_ [2]
 
bool classic_stick_right_calibrated_
 
uint8_t classic_stick_right_center_ [2]
 
uint8_t classic_stick_right_max_ [2]
 
uint8_t classic_stick_right_min_ [2]
 
const int COVARIANCE_DATA_POINTS_ = 100
 
const double EARTH_GRAVITY_ = 9.80665
 
const double GYRO_SCALE_FACTOR_ = 0.001055997
 
const int IGNORE_DATA_POINTS_ = 100
 
ros::ServiceServer imu_calibrate_srv_
 
ros::Publisher imu_data_pub_
 
ros::Publisher imu_is_calibrated_pub_
 
ros::Publisher joy_pub_
 
ros::Subscriber joy_set_feedback_sub_
 
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_ = 50
 
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_ = 13
 
const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31
 
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25
 
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6
 
const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15
 
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205
 
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_ = 50
 
const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127
 
uint8_t led_state_ = 0
 
boost::array< double, 9 > linear_acceleration_covariance_
 
StatVector3d linear_acceleration_stat_
 
ros::NodeHandle nh_
 
struct wiimote_c::acc_cal nunchuk_cal_
 
bool nunchuk_calibrated_
 
bool nunchuk_failed_calibration_
 
bool nunchuk_stick_calibrated_
 
uint8_t nunchuk_stick_center_ [2]
 
uint8_t nunchuk_stick_max_ [2]
 
uint8_t nunchuk_stick_min_ [2]
 
uint8_t report_mode_
 
uint8_t rumble_ = 0
 
uint32_t state_nsecs_
 
uint32_t state_secs_
 
wiimote_c::cwiid_wiimote_t * wiimote_
 
struct wiimote_c::acc_cal wiimote_cal_
 
bool wiimote_calibrated_
 
ros::Publisher wiimote_classic_pub_
 
uint64_t wiimote_errors = 0
 
ros::Publisher wiimote_nunchuk_pub_
 
struct wiimote_c::cwiid_state wiimote_state_
 
ros::Publisher wiimote_state_pub_
 

Static Private Attributes

static wiimote_c::cwiid_err_t cwiidErrorCallback
 

Detailed Description

Definition at line 58 of file wiimote_controller.h.

Constructor & Destructor Documentation

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 ( )

Definition at line 107 of file wiimote_controller.cpp.

Member Function Documentation

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

Definition at line 1047 of file wiimote_controller.cpp.

bool WiimoteNode::calibrateJoystick ( uint8_t  stick[2],
uint8_t(&)  center[2],
const char *  name 
)
private

Definition at line 992 of file wiimote_controller.cpp.

void WiimoteNode::checkFactoryCalibrationData ( )
private

Definition at line 185 of file wiimote_controller.cpp.

char * WiimoteNode::getBluetoothAddr ( )

Definition at line 139 of file wiimote_controller.cpp.

bool WiimoteNode::getStateSample ( )
private

Definition at line 742 of file wiimote_controller.cpp.

void WiimoteNode::initializeWiimoteState ( )
private

Definition at line 111 of file wiimote_controller.cpp.

bool WiimoteNode::isCollectingClassic ( )
private

Definition at line 970 of file wiimote_controller.cpp.

bool WiimoteNode::isCollectingMotionplus ( )
private

Definition at line 974 of file wiimote_controller.cpp.

bool WiimoteNode::isCollectingNunchuk ( )
private

Definition at line 966 of file wiimote_controller.cpp.

bool WiimoteNode::isCollectingWiimote ( )
private

Definition at line 961 of file wiimote_controller.cpp.

bool WiimoteNode::isPresentClassic ( )
private

Definition at line 983 of file wiimote_controller.cpp.

bool WiimoteNode::isPresentMotionplus ( )
private

Definition at line 987 of file wiimote_controller.cpp.

bool WiimoteNode::isPresentNunchuk ( )
private

Definition at line 979 of file wiimote_controller.cpp.

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 1493 of file wiimote_controller.cpp.

bool WiimoteNode::pairWiimote ( int  flags = 0,
int  timeout = 5 
)

Definition at line 148 of file wiimote_controller.cpp.

void WiimoteNode::publish ( )

Definition at line 518 of file wiimote_controller.cpp.

void WiimoteNode::publishImuData ( )
private

Definition at line 1152 of file wiimote_controller.cpp.

void WiimoteNode::publishJoy ( )
private

Definition at line 1121 of file wiimote_controller.cpp.

void WiimoteNode::publishWiimoteClassic ( )
private

Definition at line 1417 of file wiimote_controller.cpp.

void WiimoteNode::publishWiimoteNunchuk ( )
private

Definition at line 1382 of file wiimote_controller.cpp.

bool WiimoteNode::publishWiimoteNunchukCommon ( )
private

Definition at line 1334 of file wiimote_controller.cpp.

void WiimoteNode::publishWiimoteState ( )
private

Definition at line 1192 of file wiimote_controller.cpp.

void WiimoteNode::resetClassicState ( )
private

Definition at line 500 of file wiimote_controller.cpp.

void WiimoteNode::resetMotionPlusState ( )
private

Definition at line 469 of file wiimote_controller.cpp.

void WiimoteNode::resetNunchukState ( )
private

Definition at line 487 of file wiimote_controller.cpp.

bool WiimoteNode::serviceImuCalibrateCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
private

Definition at line 1551 of file wiimote_controller.cpp.

void WiimoteNode::setBluetoothAddr ( const char *  bt_str)

Definition at line 143 of file wiimote_controller.cpp.

void WiimoteNode::setLEDBit ( uint8_t  led,
bool  on 
)
private

Definition at line 896 of file wiimote_controller.cpp.

void WiimoteNode::setLedState ( uint8_t  led_state)

Definition at line 928 of file wiimote_controller.cpp.

void WiimoteNode::setReportMode ( uint8_t  rpt_mode)
private

Definition at line 875 of file wiimote_controller.cpp.

void WiimoteNode::setRumbleBit ( bool  on)
private

Definition at line 916 of file wiimote_controller.cpp.

void WiimoteNode::setRumbleState ( uint8_t  rumble)

Definition at line 936 of file wiimote_controller.cpp.

int WiimoteNode::unpairWiimote ( )

Definition at line 180 of file wiimote_controller.cpp.

void WiimoteNode::updateJoystickMinMax ( uint8_t  stick[2],
uint8_t(&)  stick_min[2],
uint8_t(&)  stick_max[2],
const char *  name 
)
private

Definition at line 1011 of file wiimote_controller.cpp.

Member Data Documentation

boost::array<double, 9> WiimoteNode::angular_velocity_covariance_
private

Definition at line 197 of file wiimote_controller.h.

StatVector3d WiimoteNode::angular_velocity_stat_
private

Definition at line 195 of file wiimote_controller.h.

bdaddr_t WiimoteNode::bt_device_addr_
private

Definition at line 142 of file wiimote_controller.h.

ros::Time WiimoteNode::calibration_time_
private

Definition at line 160 of file wiimote_controller.h.

bool WiimoteNode::classic_stick_left_calibrated_
private

Definition at line 184 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_left_center_[2]
private

Definition at line 183 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_left_max_[2]
private

Definition at line 185 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_left_min_[2]
private

Definition at line 186 of file wiimote_controller.h.

bool WiimoteNode::classic_stick_right_calibrated_
private

Definition at line 188 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_right_center_[2]
private

Definition at line 187 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_right_max_[2]
private

Definition at line 189 of file wiimote_controller.h.

uint8_t WiimoteNode::classic_stick_right_min_[2]
private

Definition at line 190 of file wiimote_controller.h.

const int WiimoteNode::COVARIANCE_DATA_POINTS_ = 100
private

Definition at line 193 of file wiimote_controller.h.

void WiimoteNode::cwiidErrorCallback
staticprivate

Definition at line 82 of file wiimote_controller.h.

const double WiimoteNode::EARTH_GRAVITY_ = 9.80665
private

Definition at line 205 of file wiimote_controller.h.

const double WiimoteNode::GYRO_SCALE_FACTOR_ = 0.001055997
private

Definition at line 228 of file wiimote_controller.h.

const int WiimoteNode::IGNORE_DATA_POINTS_ = 100
private

Definition at line 192 of file wiimote_controller.h.

ros::ServiceServer WiimoteNode::imu_calibrate_srv_
private

Definition at line 139 of file wiimote_controller.h.

ros::Publisher WiimoteNode::imu_data_pub_
private

Definition at line 131 of file wiimote_controller.h.

ros::Publisher WiimoteNode::imu_is_calibrated_pub_
private

Definition at line 135 of file wiimote_controller.h.

ros::Publisher WiimoteNode::joy_pub_
private

Definition at line 130 of file wiimote_controller.h.

ros::Subscriber WiimoteNode::joy_set_feedback_sub_
private

Definition at line 137 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_ = 50
private

Definition at line 167 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_ = 13
private

Definition at line 168 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31
private

Definition at line 166 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25
private

Definition at line 170 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6
private

Definition at line 171 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15
private

Definition at line 169 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205
private

Definition at line 164 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MIN_ = 50
private

Definition at line 165 of file wiimote_controller.h.

const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127
private

Definition at line 163 of file wiimote_controller.h.

uint8_t WiimoteNode::led_state_ = 0
private

Definition at line 199 of file wiimote_controller.h.

boost::array<double, 9> WiimoteNode::linear_acceleration_covariance_
private

Definition at line 196 of file wiimote_controller.h.

StatVector3d WiimoteNode::linear_acceleration_stat_
private

Definition at line 194 of file wiimote_controller.h.

ros::NodeHandle WiimoteNode::nh_
private

Definition at line 80 of file wiimote_controller.h.

struct wiimote_c::acc_cal WiimoteNode::nunchuk_cal_
private

Definition at line 174 of file wiimote_controller.h.

bool WiimoteNode::nunchuk_calibrated_
private

Definition at line 175 of file wiimote_controller.h.

bool WiimoteNode::nunchuk_failed_calibration_
private

Definition at line 176 of file wiimote_controller.h.

bool WiimoteNode::nunchuk_stick_calibrated_
private

Definition at line 178 of file wiimote_controller.h.

uint8_t WiimoteNode::nunchuk_stick_center_[2]
private

Definition at line 177 of file wiimote_controller.h.

uint8_t WiimoteNode::nunchuk_stick_max_[2]
private

Definition at line 179 of file wiimote_controller.h.

uint8_t WiimoteNode::nunchuk_stick_min_[2]
private

Definition at line 180 of file wiimote_controller.h.

uint8_t WiimoteNode::report_mode_
private

Definition at line 155 of file wiimote_controller.h.

uint8_t WiimoteNode::rumble_ = 0
private

Definition at line 200 of file wiimote_controller.h.

uint32_t WiimoteNode::state_nsecs_
private

Definition at line 152 of file wiimote_controller.h.

uint32_t WiimoteNode::state_secs_
private

Definition at line 151 of file wiimote_controller.h.

wiimote_c::cwiid_wiimote_t* WiimoteNode::wiimote_
private

Definition at line 145 of file wiimote_controller.h.

struct wiimote_c::acc_cal WiimoteNode::wiimote_cal_
private

Definition at line 158 of file wiimote_controller.h.

bool WiimoteNode::wiimote_calibrated_
private

Definition at line 159 of file wiimote_controller.h.

ros::Publisher WiimoteNode::wiimote_classic_pub_
private

Definition at line 134 of file wiimote_controller.h.

uint64_t WiimoteNode::wiimote_errors = 0
private

Definition at line 202 of file wiimote_controller.h.

ros::Publisher WiimoteNode::wiimote_nunchuk_pub_
private

Definition at line 133 of file wiimote_controller.h.

struct wiimote_c::cwiid_state WiimoteNode::wiimote_state_
private

Definition at line 148 of file wiimote_controller.h.

ros::Publisher WiimoteNode::wiimote_state_pub_
private

Definition at line 132 of file wiimote_controller.h.


The documentation for this class was generated from the following files:


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