joy.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef ROSFLIGHT_COMMON_JOY_JOY_H
33 #define ROSFLIGHT_COMMON_JOY_JOY_H
34 
35 #include <gazebo_msgs/ModelState.h>
36 #include <ros/ros.h>
37 #include <rosflight_msgs/Command.h>
38 #include <sensor_msgs/Joy.h>
39 
40 struct Axes
41 {
42  int x;
43  int y;
44  int F;
45  int z;
50 };
51 
52 struct Max
53 {
54  double roll;
55  double pitch;
56 
57  double roll_rate;
58  double pitch_rate;
59  double yaw_rate;
60 
61  double aileron;
62  double elevator;
63  double rudder;
64 
65  double xvel;
66  double yvel;
67  double zvel;
68 };
69 
70 struct Button
71 {
72  int index;
73  bool prev_value;
74 };
75 
76 struct Buttons
77 {
82  Button override;
83 };
84 
85 class Joy
86 {
87  typedef sensor_msgs::Joy::_buttons_type ButtonType;
88 
89 private:
94 
95  std::string namespace_;
96  std::string command_topic_;
98 
99  std::string mav_name_;
100  std::string gazebo_ns_;
101 
103 
104  bool override_autopilot_ = true;
105  bool paused = true;
107 
108  rosflight_msgs::Command command_msg_;
109  rosflight_msgs::Command autopilot_command_;
110  sensor_msgs::Joy current_joy_;
111 
114  geometry_msgs::Pose reset_pose_;
115  geometry_msgs::Twist reset_twist_;
116 
121  double last_time_;
122 
124  double v_yaw_step_;
125  double mass_;
126 
127  void StopMav();
128  void ResetMav();
129  void PauseSimulation();
130  void ResumeSimulation();
131 
132  void JoyCallback(const sensor_msgs::JoyConstPtr &msg);
133  void APCommandCallback(const rosflight_msgs::CommandConstPtr &msg);
134  void Publish();
135 
136 public:
137  Joy();
138 };
139 
140 #endif // ROSFLIGHT_COMMON_JOY_JOY_H
double aileron
Definition: joy.h:61
double last_time_
Definition: joy.h:121
double current_y_setpoint_
Definition: joy.h:119
Definition: joy.h:85
int F
Definition: joy.h:44
double yaw_rate
Definition: joy.h:59
double current_yaw_vel_
Definition: joy.h:123
bool prev_value
Definition: joy.h:73
double v_yaw_step_
Definition: joy.h:124
sensor_msgs::Joy current_joy_
Definition: joy.h:110
int y
Definition: joy.h:43
std::string mav_name_
Definition: joy.h:99
geometry_msgs::Twist reset_twist_
Definition: joy.h:115
Definition: joy.h:52
int y_direction
Definition: joy.h:47
Buttons buttons_
Definition: joy.h:113
rosflight_msgs::Command command_msg_
Definition: joy.h:108
double zvel
Definition: joy.h:67
std::string gazebo_ns_
Definition: joy.h:100
ros::Subscriber autopilot_command_sub_
Definition: joy.h:92
double equilibrium_thrust_
Definition: joy.h:106
double current_x_setpoint_
Definition: joy.h:118
double roll_rate
Definition: joy.h:57
Definition: joy.h:40
double xvel
Definition: joy.h:65
int index
Definition: joy.h:72
ros::Publisher command_pub_
Definition: joy.h:91
double current_yaw_setpoint_
Definition: joy.h:120
std::string autopilot_command_topic_
Definition: joy.h:97
double roll
Definition: joy.h:54
ros::NodeHandle nh_
Definition: joy.h:90
double pitch_rate
Definition: joy.h:58
double rudder
Definition: joy.h:63
int z
Definition: joy.h:45
Button fly
Definition: joy.h:78
Definition: joy.h:76
double current_altitude_setpoint_
Definition: joy.h:117
double pitch
Definition: joy.h:55
ros::Subscriber joy_sub_
Definition: joy.h:93
Max max_
Definition: joy.h:112
rosflight_msgs::Command autopilot_command_
Definition: joy.h:109
sensor_msgs::Joy::_buttons_type ButtonType
Definition: joy.h:87
int x_direction
Definition: joy.h:46
double elevator
Definition: joy.h:62
Axes axes_
Definition: joy.h:102
double yvel
Definition: joy.h:66
int z_direction
Definition: joy.h:49
int F_direction
Definition: joy.h:48
geometry_msgs::Pose reset_pose_
Definition: joy.h:114
std::string namespace_
Definition: joy.h:95
Button pause
Definition: joy.h:81
std::string command_topic_
Definition: joy.h:96
int x
Definition: joy.h:42
Button mode
Definition: joy.h:79
double mass_
Definition: joy.h:125
Button reset
Definition: joy.h:80
Definition: joy.h:70


rosflight_utils
Author(s):
autogenerated on Thu Apr 15 2021 05:10:06