teleop_wiimote.h
Go to the documentation of this file.
1 /*
2  * ROS Node for using a wiimote control unit to direct a robot.
3  * Copyright (c) 2016, Intel Corporation.
4  *
5  * This program is free software; you can redistribute it and/or modify it
6  * under the terms and conditions of the GNU General Public License,
7  * version 2, as published by the Free Software Foundation.
8  *
9  * This program is distributed in the hope it will be useful, but WITHOUT
10  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12  * more details.
13  */
14 
15 /*
16  * Initial C++ implementation by
17  * Mark Horn <mark.d.horn@intel.com>
18  *
19  * Revisions:
20  *
21  */
22 
23 #pragma once
24 #ifndef WIIMOTE_TELEOP_WIIMOTE_H
25 #define WIIMOTE_TELEOP_WIIMOTE_H
26 
27 #include "ros/ros.h"
28 #include "sensor_msgs/Joy.h"
29 #include "wiimote/State.h"
30 
31 #include <math.h>
32 
33 // Sane defaults based on the TurtleBot
34 // TurtleBot maximum speed documented at 25.6"/second ~= 0.65024 m/s
35 #define DEFAULT_MAX_LINEAR_X 0.65024 // m/s
36 // TurtleBot maximum angular speed is documented at 180 degrees Pi / second
37 #define DEFAULT_MAX_ANGULAR_Z M_PI // rad/s
38 
39 #define DEFAULT_PERCENT_LINEAR_THROTTLE 0.75
40 #define DEFAULT_PERCENT_ANGULAR_THROTTLE 0.75
41 
43 {
44 public:
45  TeleopWiimote();
46 
47 private:
48  void rumbleFeedback(int useconds);
49  void setLEDFeedback(double value);
50  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
51  void wiimoteStateCallback(const wiimote::State::ConstPtr& wiistate);
52 
53  double linear_x_max_velocity_; // m/s
54  double linear_x_min_velocity_; // m/s
55  double angular_z_max_velocity_; // rad/s
56  double angular_z_min_velocity_; // rad/s
57 
58  double percent_linear_throttle_; // 0.0 - 1.0 (1.0 = 100%)
59  double percent_angular_throttle_; // 0.0 - 1.0 (1.0 = 100%)
60 
65 
66  bool dpad_in_use_ = false;
67  bool njoy_in_use_ = false;
68 };
69 
70 #endif // WIIMOTE_TELEOP_WIIMOTE_H
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
double linear_x_min_velocity_
void wiimoteStateCallback(const wiimote::State::ConstPtr &wiistate)
ros::Publisher joy_pub_
double linear_x_max_velocity_
void rumbleFeedback(int useconds)
void setLEDFeedback(double value)
ros::Subscriber wiimote_sub_
ros::Publisher vel_pub_
double angular_z_max_velocity_
double percent_angular_throttle_
ros::Subscriber joy_sub_
double angular_z_min_velocity_
double percent_linear_throttle_


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