joy.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 
22 #ifndef ROTORS_JOY_INTERFACE_JOY_H_
23 #define ROTORS_JOY_INTERFACE_JOY_H_
24 
25 #include <geometry_msgs/PoseStamped.h>
26 #include <mav_msgs/RollPitchYawrateThrust.h>
27 #include <ros/ros.h>
28 #include <sensor_msgs/Joy.h>
29 
30 struct Axes {
31  int roll;
32  int pitch;
33  int thrust;
37 };
38 
39 struct Buttons {
40  int takeoff;
41  int land;
43  int ctrl_mode;
44  int yaw_left;
45  int yaw_right;
46 };
47 
48 struct Max {
49  double v_xy;
50  double roll;
51  double pitch;
52  double rate_yaw;
53  double thrust;
54 };
55 
56 class Joy {
57  typedef sensor_msgs::Joy::_buttons_type ButtonType;
58 
59  private:
63 
64  std::string namespace_;
65 
68 
69  mav_msgs::RollPitchYawrateThrust control_msg_;
70  geometry_msgs::PoseStamped pose_;
71  sensor_msgs::Joy current_joy_;
72 
74 
76  double v_yaw_step_;
77 
79 
80  void StopMav();
81 
82  void JoyCallback(const sensor_msgs::JoyConstPtr& msg);
83  void Publish();
84 
85  public:
86  Joy();
87 };
88 
89 #endif // ROTORS_JOY_INTERFACE_JOY_H_
Definition: joy.h:56
double current_yaw_vel_
Definition: joy.h:75
bool is_fixed_wing_
Definition: joy.h:78
double v_yaw_step_
Definition: joy.h:76
int pitch
Definition: joy.h:32
sensor_msgs::Joy current_joy_
Definition: joy.h:71
Definition: joy.h:48
Buttons buttons_
Definition: joy.h:67
int land
Definition: joy.h:41
Definition: joy.h:30
mav_msgs::RollPitchYawrateThrust control_msg_
Definition: joy.h:69
int yaw_left
Definition: joy.h:44
int ctrl_mode
Definition: joy.h:43
int thrust
Definition: joy.h:33
double v_xy
Definition: joy.h:49
ros::Publisher ctrl_pub_
Definition: joy.h:61
double roll
Definition: joy.h:50
ros::NodeHandle nh_
Definition: joy.h:60
Definition: joy.h:39
int yaw_right
Definition: joy.h:45
double pitch
Definition: joy.h:51
int takeoff
Definition: joy.h:40
ros::Subscriber joy_sub_
Definition: joy.h:62
Max max_
Definition: joy.h:73
double thrust
Definition: joy.h:53
int pitch_direction
Definition: joy.h:35
sensor_msgs::Joy::_buttons_type ButtonType
Definition: joy.h:57
int roll
Definition: joy.h:31
int ctrl_enable
Definition: joy.h:42
Axes axes_
Definition: joy.h:66
double rate_yaw
Definition: joy.h:52
std::string namespace_
Definition: joy.h:64
geometry_msgs::PoseStamped pose_
Definition: joy.h:70
int thrust_direction
Definition: joy.h:36
int roll_direction
Definition: joy.h:34


rotors_joy_interface
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:18