47 #include "sensor_msgs/Joy.h" 48 #include "std_msgs/Bool.h" 50 #include "wiimote/State.h" 51 #include "wiimote/IrSourceInfo.h" 152 ROS_INFO(
"Put Wiimote in discoverable mode now (press 1+2)...");
154 ROS_INFO(
"Searching indefinitely...");
156 ROS_INFO(
"Timeout in about %d seconds if not paired.", timeout);
160 ROS_ERROR(
"Unable to connect to wiimote");
173 ROS_ERROR(
"Wiimote not usable due to calibration failure.");
182 return wiimote_c::cwiid_close(
wiimote_);
193 ROS_WARN(
"Failed to read current Wiimote calibration data; proceeding with previous data");
197 ROS_ERROR(
"Failed to read Wiimote factory calibration data");
207 ROS_ERROR(
"Some Wiimote factory calibration data is missing; calibration failed");
208 ROS_ERROR(
"Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
217 ROS_DEBUG(
"Wiimote Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
225 ROS_WARN(
"Could not read Wiimote state; nunchuk may not be calibrated if present.");
235 ROS_WARN(
"Failed to read current Nunchuk calibration data; proceeding with previous data");
239 ROS_ERROR(
"Failed to read Nunchuk factory calibration data");
250 ROS_ERROR(
"Some Nunchuk factory calibration data is missing; calibration failed");
251 ROS_ERROR(
"Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
260 ROS_DEBUG(
"Nunchuk Cal:: zero[x]:%d, zero[y]:%d, zero[z]:%d,\n\tone[x]:%d, one[y]:%d, one[z]:%d",
274 uint8_t new_report_mode = save_report_mode | (CWIID_RPT_ACC | CWIID_RPT_EXT);
276 if (new_report_mode != save_report_mode)
281 ROS_INFO(
"Collecting additional calibration data; keep wiimote stationary...");
289 bool data_complete =
false;
290 int wiimote_data_points = 0;
291 int motionplus_data_points = 0;
293 while (!failed && !data_complete)
304 ++wiimote_data_points;
320 ++motionplus_data_points;
333 data_complete =
true;
339 data_complete =
true;
347 ROS_DEBUG(
"Calculating calibration data...");
351 bool is_bad_cal =
false;
352 std::for_each(std::begin(stddev), std::end(stddev), [&](
const double d)
357 ROS_DEBUG(
"Wiimote standard deviation > 1.0");
365 ROS_DEBUG(
"Variance Scaled x: %lf, y: %lf, z: %lf", variance.at(CWIID_X),
366 variance.at(CWIID_Y), variance.at(CWIID_Z));
369 linear_acceleration_covariance_[1] = 0.0;
370 linear_acceleration_covariance_[2] = 0.0;
372 linear_acceleration_covariance_[3] = 0.0;
373 linear_acceleration_covariance_[4] = variance.at(CWIID_Y);
374 linear_acceleration_covariance_[5] = 0.0;
376 linear_acceleration_covariance_[6] = 0.0;
377 linear_acceleration_covariance_[7] = 0.0;
378 linear_acceleration_covariance_[8] = variance.at(CWIID_Z);
382 ROS_ERROR(
"Failed calibration; using questionable data for linear acceleration");
394 std::for_each(std::begin(gyro_stddev), std::end(gyro_stddev), [&](
const double d)
399 ROS_DEBUG(
"MotionPlus standard deviation > 50");
407 ROS_DEBUG(
"Gyro Variance Scaled x: %lf, y: %lf, z: %lf", gyro_variance.at(CWIID_PHI),
408 gyro_variance.at(CWIID_THETA), gyro_variance.at(CWIID_PSI));
411 angular_velocity_covariance_[1] = 0.0;
412 angular_velocity_covariance_[2] = 0.0;
414 angular_velocity_covariance_[3] = 0.0;
415 angular_velocity_covariance_[4] = gyro_variance.at(CWIID_THETA);
416 angular_velocity_covariance_[5] = 0.0;
418 angular_velocity_covariance_[6] = 0.0;
419 angular_velocity_covariance_[7] = 0.0;
420 angular_velocity_covariance_[8] = gyro_variance.at(CWIID_PSI);
424 ROS_ERROR(
"Failed calibration; using questionable data for angular velocity");
439 ROS_ERROR(
"Failed calibration; using questionable data");
444 struct timespec state_tv;
446 if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
452 ROS_WARN(
"Could not update calibration time.");
457 if (new_report_mode != save_report_mode)
464 std_msgs::Bool imu_is_calibrated_data;
465 imu_is_calibrated_data.data = result;
523 uint8_t wii_nunchuk_subscribers = 0;
524 uint8_t wii_classic_subscribers = 0;
527 uint8_t new_report_mode = current_report_mode;
549 if (joy_subscribers || wii_state_subscribers || imu_subscribers)
552 new_report_mode |= (CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
554 if (joy_subscribers || wii_state_subscribers)
557 new_report_mode |= (CWIID_RPT_BTN);
560 if (wii_state_subscribers)
563 new_report_mode |= (CWIID_RPT_IR | CWIID_RPT_NUNCHUK);
568 if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers)
571 new_report_mode &= ~(CWIID_RPT_ACC | CWIID_RPT_MOTIONPLUS);
574 if (!joy_subscribers && !wii_state_subscribers)
577 new_report_mode &= ~(CWIID_RPT_BTN);
580 if (!wii_state_subscribers)
583 new_report_mode &= ~(CWIID_RPT_IR);
607 ROS_ERROR(
"Topic /wiimote/nunchuk not advertised due to calibration failure");
614 if (wii_nunchuk_subscribers)
617 new_report_mode |= (CWIID_RPT_NUNCHUK);
621 if (!wii_state_subscribers)
624 new_report_mode &= ~(CWIID_RPT_NUNCHUK);
637 if (!wii_state_subscribers)
640 new_report_mode &= ~(CWIID_RPT_NUNCHUK);
664 if (wii_classic_subscribers)
667 new_report_mode |= (CWIID_RPT_CLASSIC);
672 new_report_mode &= ~(CWIID_RPT_CLASSIC);
685 new_report_mode &= ~(CWIID_RPT_CLASSIC);
690 if (current_report_mode != new_report_mode)
695 if (!joy_subscribers && !wii_state_subscribers && !imu_subscribers &&
696 !wii_nunchuk_subscribers & !wii_classic_subscribers)
722 if (wii_state_subscribers)
728 if (wii_nunchuk_subscribers)
735 if (wii_classic_subscribers)
745 bool get_state_result =
true;
746 bool data_valid =
false;
750 static int wiimote_count = 0;
751 static int motionplus_count = 0;
762 if (count > 1 && !(count % 100))
765 ROS_INFO(
"Waiting for valid wiimote data...");
774 get_state_result =
false;
792 while (get_state_result && !data_valid);
807 if (count > 1 && !(count % 100))
810 ROS_INFO(
"Waiting for valid MotionPlus data...");
819 get_state_result =
false;
831 ROS_DEBUG(
"Ignoring MotionPlus data point %d", motionplus_count);
843 while (get_state_result && !data_valid);
848 motionplus_count = 0;
852 if (get_state_result)
854 struct timespec state_tv;
856 if (clock_gettime(CLOCK_REALTIME, &state_tv) == 0)
863 ROS_ERROR(
"Error sampling real-time clock");
879 if (wiimote_c::cwiid_set_rpt_mode(
wiimote_, rpt_mode))
881 ROS_ERROR(
"Error setting report mode: Bit(s):%d", rpt_mode);
888 if (rpt_mode & CWIID_RPT_MOTIONPLUS)
890 wiimote_c::cwiid_enable(
wiimote_, CWIID_FLAG_MOTIONPLUS);
902 ROS_WARN(
"LED ID %d out of bounds; ignoring!", led);
930 if (wiimote_c::cwiid_set_led(
wiimote_, led_state))
938 if (wiimote_c::cwiid_set_rumble(
wiimote_, rumble))
946 const int MAX_BUF = 500;
947 char msgs_buf[MAX_BUF];
949 vsnprintf(msgs_buf, MAX_BUF, fmt, ap);
953 ROS_ERROR(
"Wii Error: ID: %d: %s", wiimote_c::cwiid_get_id(
wiimote), msgs_buf);
957 ROS_ERROR(
"Wii Error: ID: ?: %s", msgs_buf);
964 (CWIID_RPT_BTN | CWIID_RPT_ACC | CWIID_RPT_IR);
989 return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_MOTIONPLUS;
994 bool is_calibrated =
false;
998 if (stick[CWIID_X] != 0 && stick[CWIID_Y] != 0)
1000 center[CWIID_X] = stick[CWIID_X];
1001 center[CWIID_Y] = stick[CWIID_Y];
1003 is_calibrated =
true;
1005 ROS_DEBUG(
"%s Joystick Center:: x:%d, y:%d", name, center[CWIID_X], center[CWIID_Y]);
1008 return is_calibrated;
1012 uint8_t (&stick_max)[2],
const char *name)
1014 bool updated =
false;
1016 if (stick[CWIID_X] < stick_min[CWIID_X])
1018 stick_min[CWIID_X] = stick[CWIID_X];
1022 if (stick[CWIID_Y] < stick_min[CWIID_Y])
1024 stick_min[CWIID_Y] = stick[CWIID_Y];
1028 if (stick[CWIID_X] > stick_max[CWIID_X])
1030 stick_max[CWIID_X] = stick[CWIID_X];
1034 if (stick[CWIID_Y] > stick_max[CWIID_Y])
1036 stick_max[CWIID_Y] = stick[CWIID_Y];
1042 ROS_DEBUG(
"%s Joystick:: Min x:%3d, y:%3d Max x:%3d, y:%3d", name,
1043 stick_min[CWIID_X], stick_min[CWIID_Y], stick_max[CWIID_X], stick_max[CWIID_Y]);
1048 uint8_t stick_max[2], uint8_t stick_center[2],
double (&stick)[2])
1051 int deadzoneMargin = 4;
1064 if (stick_max[CWIID_X] < 128)
1066 if (stick_max[CWIID_X] < 32)
1070 else if (stick_max[CWIID_X] < 64)
1081 if (stick_current[CWIID_X] > stick_center[CWIID_X])
1083 stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1084 ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1085 deadzone[CWIID_X] = deadzoneMargin /
1086 ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1090 stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1091 ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1092 deadzone[CWIID_X] = deadzoneMargin /
1093 ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1095 if (stick_current[CWIID_Y] > stick_center[CWIID_Y])
1097 stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1098 ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1099 deadzone[CWIID_Y] = deadzoneMargin /
1100 ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1104 stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1105 ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1106 deadzone[CWIID_Y] = deadzoneMargin /
1107 ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1111 if (fabs(stick[CWIID_X]) <= deadzone[CWIID_X])
1113 stick[CWIID_X] = 0.0;
1115 if (fabs(stick[CWIID_Y]) <= deadzone[CWIID_Y])
1117 stick[CWIID_Y] = 0.0;
1123 sensor_msgs::Joy joy_data;
1137 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_1) > 0);
1138 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_2) > 0);
1139 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_A) > 0);
1140 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_B) > 0);
1141 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1142 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1143 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1144 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1145 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1146 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1147 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1157 sensor_msgs::Imu imu_data_data;
1164 imu_data_data.orientation_covariance[0] = -1.0;
1179 imu_data_data.angular_velocity.x = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1181 imu_data_data.angular_velocity.y = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1183 imu_data_data.angular_velocity.z = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1194 wiimote::State wiimote_state_data;
1196 wiimote_state_data.header.stamp.sec =
state_secs_;
1207 wiimote_state_data.linear_acceleration_raw.x =
wiimote_state_.acc[CWIID_X];
1208 wiimote_state_data.linear_acceleration_raw.y =
wiimote_state_.acc[CWIID_Y];
1209 wiimote_state_data.linear_acceleration_raw.z =
wiimote_state_.acc[CWIID_Z];
1218 wiimote_state_data.angular_velocity_zeroed.x = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1220 wiimote_state_data.angular_velocity_zeroed.y = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1222 wiimote_state_data.angular_velocity_zeroed.z = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1225 wiimote_state_data.angular_velocity_raw.x =
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI];
1226 wiimote_state_data.angular_velocity_raw.y =
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA];
1227 wiimote_state_data.angular_velocity_raw.z =
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI];
1232 wiimote_state_data.buttons.elems[ 0] = ((
wiimote_state_.buttons & CWIID_BTN_1) > 0);
1233 wiimote_state_data.buttons.elems[ 1] = ((
wiimote_state_.buttons & CWIID_BTN_2) > 0);
1234 wiimote_state_data.buttons.elems[ 2] = ((
wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1235 wiimote_state_data.buttons.elems[ 3] = ((
wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1236 wiimote_state_data.buttons.elems[ 4] = ((
wiimote_state_.buttons & CWIID_BTN_A) > 0);
1237 wiimote_state_data.buttons.elems[ 5] = ((
wiimote_state_.buttons & CWIID_BTN_B) > 0);
1238 wiimote_state_data.buttons.elems[ 6] = ((
wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1239 wiimote_state_data.buttons.elems[ 7] = ((
wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1240 wiimote_state_data.buttons.elems[ 8] = ((
wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1241 wiimote_state_data.buttons.elems[ 9] = ((
wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1242 wiimote_state_data.buttons.elems[10] = ((
wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1255 wiimote_state_data.nunchuk_joystick_raw[CWIID_X] =
wiimote_state_.ext.nunchuk.stick[CWIID_X];
1256 wiimote_state_data.nunchuk_joystick_raw[CWIID_Y] =
wiimote_state_.ext.nunchuk.stick[CWIID_Y];
1258 wiimote_state_data.nunchuk_joystick_zeroed[CWIID_X] = stick[CWIID_X];
1259 wiimote_state_data.nunchuk_joystick_zeroed[CWIID_Y] = stick[CWIID_Y];
1261 wiimote_state_data.nunchuk_acceleration_raw.x =
wiimote_state_.ext.nunchuk.acc[CWIID_X];
1262 wiimote_state_data.nunchuk_acceleration_raw.y =
wiimote_state_.ext.nunchuk.acc[CWIID_Y];
1263 wiimote_state_data.nunchuk_acceleration_raw.z =
wiimote_state_.ext.nunchuk.acc[CWIID_Z];
1265 wiimote_state_data.nunchuk_acceleration_zeroed.x =
1268 wiimote_state_data.nunchuk_acceleration_zeroed.y =
1271 wiimote_state_data.nunchuk_acceleration_zeroed.z =
1276 wiimote_state_data.nunchuk_buttons[0] =
1277 ((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1278 wiimote_state_data.nunchuk_buttons[1] =
1279 ((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1284 for (
int ir_idx = 0; ir_idx < CWIID_IR_SRC_COUNT; ir_idx++)
1286 wiimote::IrSourceInfo irSourceInfo;
1295 if (irSourceInfo.ir_size < 1)
1297 irSourceInfo.ir_size = wiimote::State::INVALID;
1302 irSourceInfo.x = wiimote::State::INVALID_FLOAT;
1303 irSourceInfo.y = wiimote::State::INVALID_FLOAT;
1305 irSourceInfo.ir_size = wiimote::State::INVALID;
1308 wiimote_state_data.ir_tracking.push_back(irSourceInfo);
1312 for (uint8_t i = 0; i < 4; i++)
1320 wiimote_state_data.percent_battery =
wiimote_state_.battery * 100.0 / CWIID_BATTERY_MAX;
1375 ROS_WARN(
"State type is not Nunchuk!");
1384 sensor_msgs::Joy wiimote_nunchuk_data;
1388 wiimote_nunchuk_data.header.stamp.sec =
state_secs_;
1397 wiimote_nunchuk_data.axes.push_back(stick[CWIID_X]);
1398 wiimote_nunchuk_data.axes.push_back(stick[CWIID_Y]);
1410 wiimote_nunchuk_data.buttons.push_back((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1411 wiimote_nunchuk_data.buttons.push_back((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1422 sensor_msgs::Joy wiimote_classic_data;
1426 ROS_WARN(
"State type is not Classic!");
1454 wiimote_classic_data.header.stamp.sec =
state_secs_;
1458 double stick_left[2];
1459 double stick_right[2];
1466 wiimote_classic_data.axes.push_back(stick_left[CWIID_X]);
1467 wiimote_classic_data.axes.push_back(stick_left[CWIID_Y]);
1468 wiimote_classic_data.axes.push_back(stick_right[CWIID_X]);
1469 wiimote_classic_data.axes.push_back(stick_right[CWIID_Y]);
1473 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_X) > 0);
1474 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_Y) > 0);
1475 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_A) > 0);
1476 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_B) > 0);
1477 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_PLUS) > 0);
1478 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_MINUS) > 0);
1479 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_LEFT) > 0);
1480 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_RIGHT) > 0);
1481 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_UP) > 0);
1482 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_DOWN) > 0);
1483 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_HOME) > 0);
1484 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_L) > 0);
1485 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_R) > 0);
1486 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZL) > 0);
1487 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZR) > 0);
1495 bool led_found =
false;
1496 bool rumble_found =
false;
1498 for (std::vector<sensor_msgs::JoyFeedback>::const_iterator it = feedback->array.begin();
1499 it != feedback->array.end(); ++it)
1501 if ((*it).type == sensor_msgs::JoyFeedback::TYPE_LED)
1505 if ((*it).intensity >= 0.5)
1514 else if ((*it).type == sensor_msgs::JoyFeedback::TYPE_RUMBLE)
1518 ROS_WARN(
"RUMBLE ID %d out of bounds; ignoring!", (*it).id);
1522 rumble_found =
true;
1524 if ((*it).intensity >= 0.5)
1536 ROS_WARN(
"Unknown JoyFeedback command; ignored");
1568 if (
nullptr != g_wiimote_node)
1582 bool fed_addr =
false;
1583 std::string bluetooth_addr;
1584 ros::init(argc, argv,
"wiimote_controller");
1590 ROS_INFO(
"Using Bluetooth address specified from CLI");
1602 ros::param::param<int>(
"~pair_timeout", pair_timeout, 5);
1608 ROS_INFO(
"Searching for Wiimotes");
1610 ROS_INFO(
"Allow all joy sticks to remain at center position until calibrated.");
1614 ROS_INFO(
"Wiimote is Paired");
1621 ROS_ERROR(
"* * * Wiimote pairing failed.");
1638 ROS_ERROR(
"Error on wiimote disconnect");
ros::Time calibration_time_
int main(int argc, char *argv[])
void addData(int x, int y, int z)
ros::Subscriber joy_set_feedback_sub_
void setLEDBit(uint8_t led, bool on)
uint8_t nunchuk_stick_max_[2]
WiimoteNode * g_wiimote_node
void publishWiimoteState()
bool isCollectingWiimote()
uint8_t nunchuk_stick_min_[2]
StatVector3d angular_velocity_stat_
bool isCollectingMotionplus()
void publish(const boost::shared_ptr< M > &message) const
const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_
void setBluetoothAddr(const char *bt_str)
TVectorDouble getStandardDeviationRaw()
ros::Publisher wiimote_state_pub_
bool classic_stick_right_calibrated_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void mySigHandler(int sig)
void publishWiimoteClassic()
static wiimote_c::cwiid_err_t cwiidErrorCallback
void initializeWiimoteState()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher imu_is_calibrated_pub_
boost::array< double, 9 > angular_velocity_covariance_
uint8_t classic_stick_left_min_[2]
uint8_t nunchuk_stick_center_[2]
void setRumbleBit(bool on)
bool publishWiimoteNunchukCommon()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const double EARTH_GRAVITY_
wiimote_c::cwiid_wiimote_t * wiimote_
ros::Publisher wiimote_nunchuk_pub_
uint8_t classic_stick_right_min_[2]
bool classic_stick_left_calibrated_
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_
void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr &feedback)
void setRumbleState(uint8_t rumble)
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
void publishWiimoteNunchuk()
uint8_t classic_stick_right_center_[2]
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool isCollectingClassic()
TVectorDouble getMeanRaw()
const double GYRO_SCALE_FACTOR_
TVectorDouble getVarianceScaled(double scale)
bool isPresentMotionplus()
struct wiimote_c::acc_cal nunchuk_cal_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
struct wiimote_c::cwiid_state wiimote_state_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_
void setLedState(uint8_t led_state)
const int COVARIANCE_DATA_POINTS_
bool pairWiimote(int flags, int timeout)
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
bool nunchuk_stick_calibrated_
StatVector3d linear_acceleration_stat_
uint32_t getNumSubscribers() const
#define zeroedByCal(raw, zero, one)
bool serviceImuCalibrateCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
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])
const int IGNORE_DATA_POINTS_
uint8_t classic_stick_left_max_[2]
boost::array< double, 9 > linear_acceleration_covariance_
bool nunchuk_failed_calibration_
bool calibrateJoystick(uint8_t stick[2], uint8_t(¢er)[2], const char *name)
void checkFactoryCalibrationData()
char * getBluetoothAddr()
ROSCPP_DECL void shutdown()
void setReportMode(uint8_t rpt_mode)
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
void resetMotionPlusState()
struct wiimote_c::acc_cal wiimote_cal_
ros::ServiceServer imu_calibrate_srv_
ROSCPP_DECL void spinOnce()
ros::Publisher wiimote_classic_pub_
void updateJoystickMinMax(uint8_t stick[2], uint8_t(&stick_min)[2], uint8_t(&stick_max)[2], const char *name)
uint8_t classic_stick_right_max_[2]
ros::Publisher imu_data_pub_
uint8_t classic_stick_left_center_[2]
const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
std::vector< double > TVectorDouble
bool isCollectingNunchuk()