src
JoystickDemo.h
Go to the documentation of this file.
1
/*********************************************************************
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2020, Dataspeed Inc.
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of Dataspeed Inc. nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*********************************************************************/
34
35
#ifndef JOYSTICKDEMO_H_
36
#define JOYSTICKDEMO_H_
37
38
#include <
ros/ros.h
>
39
#include <sensor_msgs/Joy.h>
40
#include <std_msgs/Empty.h>
41
42
#include <dbw_polaris_msgs/ThrottleCmd.h>
43
#include <dbw_polaris_msgs/BrakeCmd.h>
44
#include <dbw_polaris_msgs/SteeringCmd.h>
45
#include <dbw_polaris_msgs/GearCmd.h>
46
47
typedef
struct
{
48
ros::Time
stamp;
49
float
brake_joy;
50
float
throttle_joy;
51
float
steering_joy;
52
bool
steering_mult;
53
int
gear_cmd;
54
bool
steering_cal;
55
bool
joy_throttle_valid;
56
bool
joy_brake_valid;
57
}
JoystickDataStruct
;
58
59
class
JoystickDemo
{
60
public
:
61
JoystickDemo
(
ros::NodeHandle
&node,
ros::NodeHandle
&priv_nh);
62
private
:
63
void
recvJoy
(
const
sensor_msgs::Joy::ConstPtr&
msg
);
64
void
cmdCallback
(
const
ros::TimerEvent
& event);
65
66
// Topics
67
ros::Subscriber
sub_joy_
;
68
ros::Publisher
pub_brake_
;
69
ros::Publisher
pub_throttle_
;
70
ros::Publisher
pub_steering_
;
71
ros::Publisher
pub_gear_
;
72
ros::Publisher
pub_enable_
;
73
ros::Publisher
pub_disable_
;
74
75
// Parameters
76
bool
brake_
;
// Send brake commands
77
bool
throttle_
;
// Send throttle commands
78
bool
steer_
;
// Send steering commands
79
bool
shift_
;
// Send shift commands
80
81
// Parameters
82
float
brake_gain_
;
// Adjust brake value
83
float
throttle_gain_
;
// Adjust throttle value
84
85
// Parameters
86
bool
ignore_
;
// Ignore driver overrides
87
bool
enable_
;
// Use enable and disable buttons
88
bool
count_
;
// Increment counter to enable watchdog
89
bool
strq_
;
// Steering torque command (otherwise angle)
90
float
svel_
;
// Steering command speed
91
92
// Variables
93
ros::Timer
timer_
;
94
JoystickDataStruct
data_
;
95
sensor_msgs::Joy
joy_
;
96
uint8_t
counter_
;
97
float
last_steering_filt_output_
;
98
99
enum
{
100
BTN_PARK
= 3,
101
BTN_REVERSE
= 1,
102
BTN_NEUTRAL
= 2,
103
BTN_DRIVE
= 0,
104
BTN_ENABLE
= 5,
105
BTN_DISABLE
= 4,
106
BTN_STEER_MULT_1
= 6,
107
BTN_STEER_MULT_2
= 7,
108
BTN_TRUNK_OPEN
= 9,
109
BTN_TRUNK_CLOSE
= 10,
110
BTN_COUNT_X
= 11,
111
BTN_COUNT_D
= 12,
112
AXIS_THROTTLE
= 5,
113
AXIS_BRAKE
= 2,
114
AXIS_STEER_1
= 0,
115
AXIS_STEER_2
= 3,
116
AXIS_TURN_SIG
= 6,
117
AXIS_DOOR_SELECT
= 6,
118
AXIS_DOOR_ACTION
= 7,
119
AXIS_COUNT_D
= 6,
120
AXIS_COUNT_X
= 8,
121
};
122
};
123
124
#endif
/* JOYSTICKDEMO_H_ */
125
JoystickDemo::strq_
bool strq_
Definition:
JoystickDemo.h:89
JoystickDemo::BTN_STEER_MULT_2
@ BTN_STEER_MULT_2
Definition:
JoystickDemo.h:107
JoystickDemo::AXIS_TURN_SIG
@ AXIS_TURN_SIG
Definition:
JoystickDemo.h:116
JoystickDemo::BTN_STEER_MULT_1
@ BTN_STEER_MULT_1
Definition:
JoystickDemo.h:106
JoystickDemo::throttle_gain_
float throttle_gain_
Definition:
JoystickDemo.h:83
JoystickDataStruct
Definition:
JoystickDemo.h:47
msg
msg
ros::Publisher
JoystickDemo::pub_gear_
ros::Publisher pub_gear_
Definition:
JoystickDemo.h:71
JoystickDemo::steer_
bool steer_
Definition:
JoystickDemo.h:78
JoystickDemo::BTN_COUNT_X
@ BTN_COUNT_X
Definition:
JoystickDemo.h:110
JoystickDemo::pub_disable_
ros::Publisher pub_disable_
Definition:
JoystickDemo.h:73
ros.h
JoystickDemo::AXIS_STEER_2
@ AXIS_STEER_2
Definition:
JoystickDemo.h:115
JoystickDemo::BTN_COUNT_D
@ BTN_COUNT_D
Definition:
JoystickDemo.h:111
JoystickDemo::pub_brake_
ros::Publisher pub_brake_
Definition:
JoystickDemo.h:68
JoystickDemo::throttle_
bool throttle_
Definition:
JoystickDemo.h:77
JoystickDemo::BTN_REVERSE
@ BTN_REVERSE
Definition:
JoystickDemo.h:101
JoystickDemo::BTN_ENABLE
@ BTN_ENABLE
Definition:
JoystickDemo.h:104
JoystickDemo::ignore_
bool ignore_
Definition:
JoystickDemo.h:86
JoystickDemo::AXIS_DOOR_SELECT
@ AXIS_DOOR_SELECT
Definition:
JoystickDemo.h:117
JoystickDemo::BTN_NEUTRAL
@ BTN_NEUTRAL
Definition:
JoystickDemo.h:102
JoystickDemo::joy_
sensor_msgs::Joy joy_
Definition:
JoystickDemo.h:95
JoystickDemo::counter_
uint8_t counter_
Definition:
JoystickDemo.h:96
JoystickDemo::pub_steering_
ros::Publisher pub_steering_
Definition:
JoystickDemo.h:70
JoystickDemo::sub_joy_
ros::Subscriber sub_joy_
Definition:
JoystickDemo.h:67
JoystickDemo::enable_
bool enable_
Definition:
JoystickDemo.h:87
JoystickDemo::BTN_TRUNK_OPEN
@ BTN_TRUNK_OPEN
Definition:
JoystickDemo.h:108
JoystickDemo::recvJoy
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
Definition:
JoystickDemo.cpp:178
JoystickDemo::AXIS_STEER_1
@ AXIS_STEER_1
Definition:
JoystickDemo.h:114
JoystickDemo::brake_
bool brake_
Definition:
JoystickDemo.h:76
ros::TimerEvent
JoystickDemo::svel_
float svel_
Definition:
JoystickDemo.h:90
JoystickDemo
Definition:
JoystickDemo.h:59
JoystickDemo::BTN_TRUNK_CLOSE
@ BTN_TRUNK_CLOSE
Definition:
JoystickDemo.h:109
ros::Time
JoystickDemo::timer_
ros::Timer timer_
Definition:
JoystickDemo.h:93
JoystickDemo::brake_gain_
float brake_gain_
Definition:
JoystickDemo.h:82
JoystickDemo::AXIS_THROTTLE
@ AXIS_THROTTLE
Definition:
JoystickDemo.h:112
JoystickDemo::pub_enable_
ros::Publisher pub_enable_
Definition:
JoystickDemo.h:72
JoystickDemo::AXIS_DOOR_ACTION
@ AXIS_DOOR_ACTION
Definition:
JoystickDemo.h:118
JoystickDemo::BTN_DRIVE
@ BTN_DRIVE
Definition:
JoystickDemo.h:103
JoystickDemo::data_
JoystickDataStruct data_
Definition:
JoystickDemo.h:94
JoystickDemo::last_steering_filt_output_
float last_steering_filt_output_
Definition:
JoystickDemo.h:97
JoystickDemo::AXIS_COUNT_D
@ AXIS_COUNT_D
Definition:
JoystickDemo.h:119
JoystickDemo::BTN_DISABLE
@ BTN_DISABLE
Definition:
JoystickDemo.h:105
JoystickDemo::pub_throttle_
ros::Publisher pub_throttle_
Definition:
JoystickDemo.h:69
JoystickDemo::count_
bool count_
Definition:
JoystickDemo.h:88
JoystickDemo::BTN_PARK
@ BTN_PARK
Definition:
JoystickDemo.h:100
JoystickDemo::cmdCallback
void cmdCallback(const ros::TimerEvent &event)
Definition:
JoystickDemo.cpp:101
JoystickDemo::AXIS_COUNT_X
@ AXIS_COUNT_X
Definition:
JoystickDemo.h:120
ros::Timer
JoystickDemo::AXIS_BRAKE
@ AXIS_BRAKE
Definition:
JoystickDemo.h:113
ros::NodeHandle
ros::Subscriber
JoystickDemo::shift_
bool shift_
Definition:
JoystickDemo.h:79
JoystickDemo::JoystickDemo
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition:
JoystickDemo.cpp:37
dbw_polaris_joystick_demo
Author(s): Micho Radovnikovich
autogenerated on Thu Jan 4 2024 03:36:20