Go to the documentation of this file.
38 #ifndef WIIMOTE_WIIMOTE_CONTROLLER_H
39 #define WIIMOTE_WIIMOTE_CONTROLLER_H
42 #include "sensor_msgs/JoyFeedbackArray.h"
43 #include "std_srvs/Empty.h"
44 #include "sensor_msgs/Imu.h"
49 #include <bluetooth/bluetooth.h>
55 #define zeroedByCal(raw, zero, one) \
56 (((raw - zero) * 1.0) / ((one - zero) * 1.0))
114 bool calibrateJoystick(uint8_t stick[2], uint8_t (¢er)[2],
const char *name);
116 uint8_t (&stick_max)[2],
const char *name);
118 uint8_t stick_max[2], uint8_t stick_center[2],
double (&stick)[2]);
233 #endif // WIIMOTE_WIIMOTE_CONTROLLER_H
static wiimote_c::cwiid_err_t cwiidErrorCallback
uint8_t classic_stick_right_max_[2]
bool isCollectingNunchuk()
bool classic_stick_right_calibrated_
ros::Publisher imu_is_calibrated_pub_
void publishWiimoteClassic()
const uint8_t JOYSTICK_CLASSIC_RIGHT_DEFAULT_CENTER_
ros::Publisher imu_data_pub_
void setRumbleBit(bool on)
bool publishWiimoteNunchukCommon()
const double EARTH_GRAVITY_
ros::Time calibration_time_
uint8_t classic_stick_right_min_[2]
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MIN_
ros::Subscriber joy_set_feedback_sub_
void publishWiimoteState()
bool isCollectingWiimote()
uint8_t nunchuk_stick_min_[2]
bool isCollectingMotionplus()
StatVector3d angular_velocity_stat_
const uint8_t JOYSTICK_NUNCHUK_DEFAULT_CENTER_
wiimote_c::cwiid_wiimote_t * wiimote_
bool classic_stick_left_calibrated_
void initializeWiimoteState()
ros::Publisher wiimote_state_pub_
uint8_t classic_stick_left_min_[2]
uint8_t nunchuk_stick_center_[2]
uint8_t classic_stick_right_center_[2]
void joySetFeedbackCallback(const sensor_msgs::JoyFeedbackArray::ConstPtr &feedback)
ros::Publisher wiimote_nunchuk_pub_
struct wiimote_c::acc_cal nunchuk_cal_
bool isPresentMotionplus()
boost::array< double, 9 > angular_velocity_covariance_
const uint8_t JOYSTICK_CLASSIC_LEFT_20PERCENT_MAX_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MIN_
bool isCollectingClassic()
void setRumbleState(uint8_t rumble)
void publishWiimoteNunchuk()
void setLedState(uint8_t led_state)
const double GYRO_SCALE_FACTOR_
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])
bool pairWiimote(int flags, int timeout)
bool nunchuk_stick_calibrated_
boost::array< double, 9 > linear_acceleration_covariance_
StatVector3d linear_acceleration_stat_
struct wiimote_c::acc_cal wiimote_cal_
struct wiimote_c::cwiid_state wiimote_state_
const uint8_t JOYSTICK_CLASSIC_LEFT_DEFAULT_CENTER_
ros::ServiceServer imu_calibrate_srv_
const uint8_t JOYSTICK_NUNCHUK_20PERCENT_MAX_
const int COVARIANCE_DATA_POINTS_
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MIN_
void setReportMode(uint8_t rpt_mode)
void timerCallback(const ros::TimerEvent &)
uint8_t classic_stick_left_max_[2]
bool nunchuk_failed_calibration_
bool calibrateJoystick(uint8_t stick[2], uint8_t(¢er)[2], const char *name)
void checkFactoryCalibrationData()
char * getBluetoothAddr()
const uint8_t JOYSTICK_CLASSIC_RIGHT_20PERCENT_MAX_
void resetMotionPlusState()
uint8_t classic_stick_left_center_[2]
uint8_t nunchuk_stick_max_[2]
void setLEDBit(uint8_t led, bool on)
const int IGNORE_DATA_POINTS_
void setBluetoothAddr(const char *bt_str)
ros::Publisher wiimote_classic_pub_
void updateJoystickMinMax(uint8_t stick[2], uint8_t(&stick_min)[2], uint8_t(&stick_max)[2], const char *name)
wiimote
Author(s): Andreas Paepcke, Melonee Wise, Mark Horn
autogenerated on Thu Dec 5 2024 03:18:13