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));
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));
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))
940 ROS_INFO(
"Connection to wiimote lost");
947 if (wiimote_c::cwiid_set_rumble(
wiimote_, rumble))
955 const int MAX_BUF = 500;
956 char msgs_buf[MAX_BUF];
958 vsnprintf(msgs_buf, MAX_BUF, fmt, ap);
962 ROS_ERROR(
"Wii Error: ID: %d: %s", wiimote_c::cwiid_get_id(
wiimote), msgs_buf);
966 ROS_ERROR(
"Wii Error: ID: ?: %s", msgs_buf);
973 (CWIID_RPT_BTN | CWIID_RPT_ACC | CWIID_RPT_IR);
998 return wiimote_state_.ext_type == wiimote_c::CWIID_EXT_MOTIONPLUS;
1003 bool is_calibrated =
false;
1007 if (stick[CWIID_X] != 0 && stick[CWIID_Y] != 0)
1009 center[CWIID_X] = stick[CWIID_X];
1010 center[CWIID_Y] = stick[CWIID_Y];
1012 is_calibrated =
true;
1014 ROS_DEBUG(
"%s Joystick Center:: x:%d, y:%d", name, center[CWIID_X], center[CWIID_Y]);
1017 return is_calibrated;
1021 uint8_t (&stick_max)[2],
const char *name)
1023 bool updated =
false;
1025 if (stick[CWIID_X] < stick_min[CWIID_X])
1027 stick_min[CWIID_X] = stick[CWIID_X];
1031 if (stick[CWIID_Y] < stick_min[CWIID_Y])
1033 stick_min[CWIID_Y] = stick[CWIID_Y];
1037 if (stick[CWIID_X] > stick_max[CWIID_X])
1039 stick_max[CWIID_X] = stick[CWIID_X];
1043 if (stick[CWIID_Y] > stick_max[CWIID_Y])
1045 stick_max[CWIID_Y] = stick[CWIID_Y];
1051 ROS_DEBUG(
"%s Joystick:: Min x:%3d, y:%3d Max x:%3d, y:%3d", name,
1052 stick_min[CWIID_X], stick_min[CWIID_Y], stick_max[CWIID_X], stick_max[CWIID_Y]);
1057 uint8_t stick_max[2], uint8_t stick_center[2],
double (&stick)[2])
1060 int deadzoneMargin = 4;
1073 if (stick_max[CWIID_X] < 128)
1075 if (stick_max[CWIID_X] < 32)
1079 else if (stick_max[CWIID_X] < 64)
1090 if (stick_current[CWIID_X] > stick_center[CWIID_X])
1092 stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1093 ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1094 deadzone[CWIID_X] = deadzoneMargin /
1095 ((stick_max[CWIID_X] - stick_center[CWIID_X]) * 1.0);
1099 stick[CWIID_X] = -(stick_current[CWIID_X] - stick_center[CWIID_X]) /
1100 ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1101 deadzone[CWIID_X] = deadzoneMargin /
1102 ((stick_center[CWIID_X] - stick_min[CWIID_X]) * 1.0);
1104 if (stick_current[CWIID_Y] > stick_center[CWIID_Y])
1106 stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1107 ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1108 deadzone[CWIID_Y] = deadzoneMargin /
1109 ((stick_max[CWIID_Y] - stick_center[CWIID_Y]) * 1.0);
1113 stick[CWIID_Y] = (stick_current[CWIID_Y] - stick_center[CWIID_Y]) /
1114 ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1115 deadzone[CWIID_Y] = deadzoneMargin /
1116 ((stick_center[CWIID_Y] - stick_min[CWIID_Y]) * 1.0);
1120 if (fabs(stick[CWIID_X]) <= deadzone[CWIID_X])
1122 stick[CWIID_X] = 0.0;
1124 if (fabs(stick[CWIID_Y]) <= deadzone[CWIID_Y])
1126 stick[CWIID_Y] = 0.0;
1132 sensor_msgs::Joy joy_data;
1146 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_1) > 0);
1147 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_2) > 0);
1148 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_A) > 0);
1149 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_B) > 0);
1150 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1151 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1152 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1153 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1154 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1155 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1156 joy_data.buttons.push_back((
wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1166 sensor_msgs::Imu imu_data_data;
1173 imu_data_data.orientation_covariance[0] = -1.0;
1188 imu_data_data.angular_velocity.x = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1190 imu_data_data.angular_velocity.y = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1192 imu_data_data.angular_velocity.z = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1203 wiimote::State wiimote_state_data;
1205 wiimote_state_data.header.stamp.sec =
state_secs_;
1216 wiimote_state_data.linear_acceleration_raw.x =
wiimote_state_.acc[CWIID_X];
1217 wiimote_state_data.linear_acceleration_raw.y =
wiimote_state_.acc[CWIID_Y];
1218 wiimote_state_data.linear_acceleration_raw.z =
wiimote_state_.acc[CWIID_Z];
1227 wiimote_state_data.angular_velocity_zeroed.x = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI] -
1229 wiimote_state_data.angular_velocity_zeroed.y = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA] -
1231 wiimote_state_data.angular_velocity_zeroed.z = (
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI] -
1234 wiimote_state_data.angular_velocity_raw.x =
wiimote_state_.ext.motionplus.angle_rate[CWIID_PHI];
1235 wiimote_state_data.angular_velocity_raw.y =
wiimote_state_.ext.motionplus.angle_rate[CWIID_THETA];
1236 wiimote_state_data.angular_velocity_raw.z =
wiimote_state_.ext.motionplus.angle_rate[CWIID_PSI];
1241 wiimote_state_data.buttons.elems[ 0] = ((
wiimote_state_.buttons & CWIID_BTN_1) > 0);
1242 wiimote_state_data.buttons.elems[ 1] = ((
wiimote_state_.buttons & CWIID_BTN_2) > 0);
1243 wiimote_state_data.buttons.elems[ 2] = ((
wiimote_state_.buttons & CWIID_BTN_PLUS) > 0);
1244 wiimote_state_data.buttons.elems[ 3] = ((
wiimote_state_.buttons & CWIID_BTN_MINUS) > 0);
1245 wiimote_state_data.buttons.elems[ 4] = ((
wiimote_state_.buttons & CWIID_BTN_A) > 0);
1246 wiimote_state_data.buttons.elems[ 5] = ((
wiimote_state_.buttons & CWIID_BTN_B) > 0);
1247 wiimote_state_data.buttons.elems[ 6] = ((
wiimote_state_.buttons & CWIID_BTN_UP) > 0);
1248 wiimote_state_data.buttons.elems[ 7] = ((
wiimote_state_.buttons & CWIID_BTN_DOWN) > 0);
1249 wiimote_state_data.buttons.elems[ 8] = ((
wiimote_state_.buttons & CWIID_BTN_LEFT) > 0);
1250 wiimote_state_data.buttons.elems[ 9] = ((
wiimote_state_.buttons & CWIID_BTN_RIGHT) > 0);
1251 wiimote_state_data.buttons.elems[10] = ((
wiimote_state_.buttons & CWIID_BTN_HOME) > 0);
1264 wiimote_state_data.nunchuk_joystick_raw[CWIID_X] =
wiimote_state_.ext.nunchuk.stick[CWIID_X];
1265 wiimote_state_data.nunchuk_joystick_raw[CWIID_Y] =
wiimote_state_.ext.nunchuk.stick[CWIID_Y];
1267 wiimote_state_data.nunchuk_joystick_zeroed[CWIID_X] = stick[CWIID_X];
1268 wiimote_state_data.nunchuk_joystick_zeroed[CWIID_Y] = stick[CWIID_Y];
1270 wiimote_state_data.nunchuk_acceleration_raw.x =
wiimote_state_.ext.nunchuk.acc[CWIID_X];
1271 wiimote_state_data.nunchuk_acceleration_raw.y =
wiimote_state_.ext.nunchuk.acc[CWIID_Y];
1272 wiimote_state_data.nunchuk_acceleration_raw.z =
wiimote_state_.ext.nunchuk.acc[CWIID_Z];
1274 wiimote_state_data.nunchuk_acceleration_zeroed.x =
1277 wiimote_state_data.nunchuk_acceleration_zeroed.y =
1280 wiimote_state_data.nunchuk_acceleration_zeroed.z =
1285 wiimote_state_data.nunchuk_buttons[0] =
1286 ((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1287 wiimote_state_data.nunchuk_buttons[1] =
1288 ((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1293 for (
int ir_idx = 0; ir_idx < CWIID_IR_SRC_COUNT; ir_idx++)
1295 wiimote::IrSourceInfo irSourceInfo;
1304 if (irSourceInfo.ir_size < 1)
1306 irSourceInfo.ir_size = wiimote::State::INVALID;
1311 irSourceInfo.x = wiimote::State::INVALID_FLOAT;
1312 irSourceInfo.y = wiimote::State::INVALID_FLOAT;
1314 irSourceInfo.ir_size = wiimote::State::INVALID;
1317 wiimote_state_data.ir_tracking.push_back(irSourceInfo);
1321 for (uint8_t i = 0; i < 4; i++)
1329 wiimote_state_data.percent_battery =
wiimote_state_.battery * 100.0 / CWIID_BATTERY_MAX;
1384 ROS_WARN(
"State type is not Nunchuk!");
1393 sensor_msgs::Joy wiimote_nunchuk_data;
1397 wiimote_nunchuk_data.header.stamp.sec =
state_secs_;
1406 wiimote_nunchuk_data.axes.push_back(stick[CWIID_X]);
1407 wiimote_nunchuk_data.axes.push_back(stick[CWIID_Y]);
1419 wiimote_nunchuk_data.buttons.push_back((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_Z) > 0);
1420 wiimote_nunchuk_data.buttons.push_back((
wiimote_state_.ext.nunchuk.buttons & CWIID_NUNCHUK_BTN_C) > 0);
1431 sensor_msgs::Joy wiimote_classic_data;
1435 ROS_WARN(
"State type is not Classic!");
1463 wiimote_classic_data.header.stamp.sec =
state_secs_;
1467 double stick_left[2];
1468 double stick_right[2];
1475 wiimote_classic_data.axes.push_back(stick_left[CWIID_X]);
1476 wiimote_classic_data.axes.push_back(stick_left[CWIID_Y]);
1477 wiimote_classic_data.axes.push_back(stick_right[CWIID_X]);
1478 wiimote_classic_data.axes.push_back(stick_right[CWIID_Y]);
1482 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_X) > 0);
1483 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_Y) > 0);
1484 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_A) > 0);
1485 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_B) > 0);
1486 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_PLUS) > 0);
1487 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_MINUS) > 0);
1488 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_LEFT) > 0);
1489 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_RIGHT) > 0);
1490 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_UP) > 0);
1491 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_DOWN) > 0);
1492 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_HOME) > 0);
1493 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_L) > 0);
1494 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_R) > 0);
1495 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZL) > 0);
1496 wiimote_classic_data.buttons.push_back((
wiimote_state_.ext.classic.buttons & CWIID_CLASSIC_BTN_ZR) > 0);
1504 bool led_found =
false;
1505 bool rumble_found =
false;
1507 for (std::vector<sensor_msgs::JoyFeedback>::const_iterator it = feedback->array.begin();
1508 it != feedback->array.end(); ++it)
1510 if ((*it).type == sensor_msgs::JoyFeedback::TYPE_LED)
1514 if ((*it).intensity >= 0.5)
1523 else if ((*it).type == sensor_msgs::JoyFeedback::TYPE_RUMBLE)
1527 ROS_WARN(
"RUMBLE ID %d out of bounds; ignoring!", (*it).id);
1531 rumble_found =
true;
1533 if ((*it).intensity >= 0.5)
1545 ROS_WARN(
"Unknown JoyFeedback command; ignored");
1591 bool fed_addr =
false;
1592 std::string bluetooth_addr;
1593 ros::init(argc, argv,
"wiimote_controller");
1599 ROS_INFO(
"Using Bluetooth address specified from CLI");
1611 double check_connection_interval;
1612 ros::param::param<int>(
"~pair_timeout", pair_timeout, 5);
1613 ros::param::param<double>(
"~check_connection_interval", check_connection_interval, 0.0);
1619 ROS_INFO(
"Searching for Wiimotes");
1621 ROS_INFO(
"Allow all joy sticks to remain at center position until calibrated.");
1632 ROS_ERROR(
"* * * Wiimote pairing failed.");
1638 if (check_connection_interval > 0.0)
1656 ROS_ERROR(
"Error on wiimote disconnect");