joy_teleop.h
Go to the documentation of this file.
1 /*
2 
3 Copyright (c) 2021, Botsync Pte. Ltd.
4 All rights reserved.
5 
6 Redistribution and use in source and binary forms, with or without
7 modification, are permitted provided that the following conditions are met:
8  * Redistributions of source code must retain the above copyright
9  notice, this list of conditions and the following disclaimer.
10  * Redistributions in binary form must reproduce the above copyright
11  notice, this list of conditions and the following disclaimer in the
12  documentation and/or other materials provided with the distribution.
13  * Neither the name of the Botsync Pte. Ltd. nor the
14  names of its contributors may be used to endorse or promote products
15  derived from this software without specific prior written permission.
16 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 
28 */
29 
30 #include <ros/ros.h>
31 #include <sensor_msgs/Joy.h>
32 #include <geometry_msgs/Twist.h>
33 #include <std_msgs/Bool.h>
34 
35 bool e_stop_status = false;
36 
42 
44 
47 
49 
52 
53 bool dead_man = false;
54 geometry_msgs::Twist cmd_to_send;
55 
56 void joy_callback(const sensor_msgs::Joy::ConstPtr& joy);
max_linear_speed
double max_linear_speed
Definition: joy_teleop.h:45
angular_speed_axis
int angular_speed_axis
Definition: joy_teleop.h:41
ros::Publisher
cmd_vel_pub
ros::Publisher cmd_vel_pub
Definition: joy_teleop.h:50
ros.h
dead_man
bool dead_man
Definition: joy_teleop.h:53
linear_speed_axis
int linear_speed_axis
Definition: joy_teleop.h:40
enable_button
int enable_button
Definition: joy_teleop.h:37
joy_callback
void joy_callback(const sensor_msgs::Joy::ConstPtr &joy)
Definition: joy_teleop.cpp:32
max_angular_speed
double max_angular_speed
Definition: joy_teleop.h:46
e_stop_pub
ros::Publisher e_stop_pub
Definition: joy_teleop.h:51
joy_subscriber
ros::Subscriber joy_subscriber
Definition: joy_teleop.h:48
enable_e_stop
int enable_e_stop
Definition: joy_teleop.h:43
stop_button
int stop_button
Definition: joy_teleop.h:38
e_stop_button
int e_stop_button
Definition: joy_teleop.h:39
e_stop_status
bool e_stop_status
Definition: joy_teleop.h:35
cmd_to_send
geometry_msgs::Twist cmd_to_send
Definition: joy_teleop.h:54
ros::Subscriber


volta_teleoperator
Author(s): Nikhil Venkatesh , Mahendra L Seervi
autogenerated on Wed Mar 2 2022 01:13:34