include
rotors_joy_interface
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
;
34
int
roll_direction
;
35
int
pitch_direction
;
36
int
thrust_direction
;
37
};
38
39
struct
Buttons
{
40
int
takeoff
;
41
int
land
;
42
int
ctrl_enable
;
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
:
60
ros::NodeHandle
nh_
;
61
ros::Publisher
ctrl_pub_
;
62
ros::Subscriber
joy_sub_
;
63
64
std::string
namespace_
;
65
66
Axes
axes_
;
67
Buttons
buttons_
;
68
69
mav_msgs::RollPitchYawrateThrust
control_msg_
;
70
geometry_msgs::PoseStamped
pose_
;
71
sensor_msgs::Joy
current_joy_
;
72
73
Max
max_
;
74
75
double
current_yaw_vel_
;
76
double
v_yaw_step_
;
77
78
bool
is_fixed_wing_
;
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_
Joy
Definition:
joy.h:56
ros::NodeHandle
Joy::current_yaw_vel_
double current_yaw_vel_
Definition:
joy.h:75
Joy::is_fixed_wing_
bool is_fixed_wing_
Definition:
joy.h:78
Joy::v_yaw_step_
double v_yaw_step_
Definition:
joy.h:76
Axes::pitch
int pitch
Definition:
joy.h:32
Joy::current_joy_
sensor_msgs::Joy current_joy_
Definition:
joy.h:71
Max
Definition:
joy.h:48
Joy::buttons_
Buttons buttons_
Definition:
joy.h:67
Buttons::land
int land
Definition:
joy.h:41
Axes
Definition:
joy.h:30
Joy::control_msg_
mav_msgs::RollPitchYawrateThrust control_msg_
Definition:
joy.h:69
Buttons::yaw_left
int yaw_left
Definition:
joy.h:44
Buttons::ctrl_mode
int ctrl_mode
Definition:
joy.h:43
Axes::thrust
int thrust
Definition:
joy.h:33
Max::v_xy
double v_xy
Definition:
joy.h:49
Joy::ctrl_pub_
ros::Publisher ctrl_pub_
Definition:
joy.h:61
ros::Subscriber
Max::roll
double roll
Definition:
joy.h:50
Joy::nh_
ros::NodeHandle nh_
Definition:
joy.h:60
Buttons
Definition:
joy.h:39
Buttons::yaw_right
int yaw_right
Definition:
joy.h:45
Max::pitch
double pitch
Definition:
joy.h:51
Buttons::takeoff
int takeoff
Definition:
joy.h:40
Joy::joy_sub_
ros::Subscriber joy_sub_
Definition:
joy.h:62
Joy::max_
Max max_
Definition:
joy.h:73
Max::thrust
double thrust
Definition:
joy.h:53
ros.h
Axes::pitch_direction
int pitch_direction
Definition:
joy.h:35
Joy::ButtonType
sensor_msgs::Joy::_buttons_type ButtonType
Definition:
joy.h:57
Axes::roll
int roll
Definition:
joy.h:31
Buttons::ctrl_enable
int ctrl_enable
Definition:
joy.h:42
Joy::axes_
Axes axes_
Definition:
joy.h:66
Max::rate_yaw
double rate_yaw
Definition:
joy.h:52
Joy::namespace_
std::string namespace_
Definition:
joy.h:64
Joy::pose_
geometry_msgs::PoseStamped pose_
Definition:
joy.h:70
Axes::thrust_direction
int thrust_direction
Definition:
joy.h:36
ros::Publisher
Axes::roll_direction
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