#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 |
( |
| ) |
|
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 |
( |
| ) |
|
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 |
bool WiimoteNode::calibrateJoystick |
( |
uint8_t |
stick[2], |
|
|
uint8_t(&) |
center[2], |
|
|
const char * |
name |
|
) |
| |
|
private |
void WiimoteNode::checkFactoryCalibrationData |
( |
| ) |
|
|
private |
char * WiimoteNode::getBluetoothAddr |
( |
| ) |
|
bool WiimoteNode::getStateSample |
( |
| ) |
|
|
private |
void WiimoteNode::initializeWiimoteState |
( |
| ) |
|
|
private |
bool WiimoteNode::isCollectingClassic |
( |
| ) |
|
|
private |
bool WiimoteNode::isCollectingMotionplus |
( |
| ) |
|
|
private |
bool WiimoteNode::isCollectingNunchuk |
( |
| ) |
|
|
private |
bool WiimoteNode::isCollectingWiimote |
( |
| ) |
|
|
private |
bool WiimoteNode::isPresentClassic |
( |
| ) |
|
|
private |
bool WiimoteNode::isPresentMotionplus |
( |
| ) |
|
|
private |
bool WiimoteNode::isPresentNunchuk |
( |
| ) |
|
|
private |
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 |
|
) |
| |
void WiimoteNode::publish |
( |
| ) |
|
void WiimoteNode::publishImuData |
( |
| ) |
|
|
private |
void WiimoteNode::publishJoy |
( |
| ) |
|
|
private |
void WiimoteNode::publishWiimoteClassic |
( |
| ) |
|
|
private |
void WiimoteNode::publishWiimoteNunchuk |
( |
| ) |
|
|
private |
bool WiimoteNode::publishWiimoteNunchukCommon |
( |
| ) |
|
|
private |
void WiimoteNode::publishWiimoteState |
( |
| ) |
|
|
private |
void WiimoteNode::resetClassicState |
( |
| ) |
|
|
private |
void WiimoteNode::resetMotionPlusState |
( |
| ) |
|
|
private |
void WiimoteNode::resetNunchukState |
( |
| ) |
|
|
private |
bool WiimoteNode::serviceImuCalibrateCallback |
( |
std_srvs::Empty::Request & |
, |
|
|
std_srvs::Empty::Response & |
|
|
) |
| |
|
private |
void WiimoteNode::setBluetoothAddr |
( |
const char * |
bt_str | ) |
|
void WiimoteNode::setLEDBit |
( |
uint8_t |
led, |
|
|
bool |
on |
|
) |
| |
|
private |
void WiimoteNode::setLedState |
( |
uint8_t |
led_state | ) |
|
void WiimoteNode::setReportMode |
( |
uint8_t |
rpt_mode | ) |
|
|
private |
void WiimoteNode::setRumbleBit |
( |
bool |
on | ) |
|
|
private |
void WiimoteNode::setRumbleState |
( |
uint8_t |
rumble | ) |
|
int WiimoteNode::unpairWiimote |
( |
| ) |
|
void WiimoteNode::updateJoystickMinMax |
( |
uint8_t |
stick[2], |
|
|
uint8_t(&) |
stick_min[2], |
|
|
uint8_t(&) |
stick_max[2], |
|
|
const char * |
name |
|
) |
| |
|
private |
boost::array<double, 9> WiimoteNode::angular_velocity_covariance_ |
|
private |
bdaddr_t WiimoteNode::bt_device_addr_ |
|
private |
bool WiimoteNode::classic_stick_left_calibrated_ |
|
private |
uint8_t WiimoteNode::classic_stick_left_center_[2] |
|
private |
uint8_t WiimoteNode::classic_stick_left_max_[2] |
|
private |
uint8_t WiimoteNode::classic_stick_left_min_[2] |
|
private |
bool WiimoteNode::classic_stick_right_calibrated_ |
|
private |
uint8_t WiimoteNode::classic_stick_right_center_[2] |
|
private |
uint8_t WiimoteNode::classic_stick_right_max_[2] |
|
private |
uint8_t WiimoteNode::classic_stick_right_min_[2] |
|
private |
const int WiimoteNode::COVARIANCE_DATA_POINTS_ = 100 |
|
private |
void WiimoteNode::cwiidErrorCallback |
|
staticprivate |
const double WiimoteNode::EARTH_GRAVITY_ = 9.80665 |
|
private |
const double WiimoteNode::GYRO_SCALE_FACTOR_ = 0.001055997 |
|
private |
const int WiimoteNode::IGNORE_DATA_POINTS_ = 100 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_ = 50 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_ = 13 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_ = 31 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_ = 25 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_ = 6 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_ = 15 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MAX_ = 205 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_20PERCENT_MIN_ = 50 |
|
private |
const uint8_t WiimoteNode::JOYSTICK_NUNCHUK_DEFAULT_CENTER_ = 127 |
|
private |
uint8_t WiimoteNode::led_state_ = 0 |
|
private |
boost::array<double, 9> WiimoteNode::linear_acceleration_covariance_ |
|
private |
struct wiimote_c::acc_cal WiimoteNode::nunchuk_cal_ |
|
private |
bool WiimoteNode::nunchuk_calibrated_ |
|
private |
bool WiimoteNode::nunchuk_failed_calibration_ |
|
private |
bool WiimoteNode::nunchuk_stick_calibrated_ |
|
private |
uint8_t WiimoteNode::nunchuk_stick_center_[2] |
|
private |
uint8_t WiimoteNode::nunchuk_stick_max_[2] |
|
private |
uint8_t WiimoteNode::nunchuk_stick_min_[2] |
|
private |
uint8_t WiimoteNode::report_mode_ |
|
private |
uint8_t WiimoteNode::rumble_ = 0 |
|
private |
uint32_t WiimoteNode::state_nsecs_ |
|
private |
uint32_t WiimoteNode::state_secs_ |
|
private |
wiimote_c::cwiid_wiimote_t* WiimoteNode::wiimote_ |
|
private |
struct wiimote_c::acc_cal WiimoteNode::wiimote_cal_ |
|
private |
bool WiimoteNode::wiimote_calibrated_ |
|
private |
uint64_t WiimoteNode::wiimote_errors = 0 |
|
private |
struct wiimote_c::cwiid_state WiimoteNode::wiimote_state_ |
|
private |
The documentation for this class was generated from the following files: