joy_teleop_node.cpp
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 
31 
32 int main(int argc, char** argv) {
33  ros::init(argc, argv, "joy_teleop_node");
34 
35  ros::NodeHandle nh;
36 
37  nh.param<int>("enable_button", enable_button, 1);
38  nh.param<int>("stop_button", stop_button, 2);
39  nh.param<int>("e_stop_button", e_stop_button, 3);
40  nh.param<int>("linear_speed_axis", linear_speed_axis, 1);
41  nh.param<int>("angular_speed_axis", angular_speed_axis, 0);
42 
43  nh.param<double>("max_linear_speed", max_linear_speed, 0.3);
44  nh.param<double>("max_angular_speed", max_angular_speed, 0.3);
45 
46  nh.param<int>("enable_e_stop", enable_e_stop, 0);
47 
48  std::string cmd_vel_topic, e_stop_pub_topic, joy_topic, e_stop_sub_topic;
49 
50  nh.param<std::string>("cmd_vel_topic", cmd_vel_topic, "joy/cmd_vel");
51  nh.param<std::string>("e_stop_pub_topic", e_stop_pub_topic, "/e_stop_sw_enable");
52 
53  nh.param<std::string>("joy_topic", joy_topic, "/joy");
54 
55  cmd_vel_pub = nh.advertise<geometry_msgs::Twist>(cmd_vel_topic, 1);
56 
57  joy_subscriber = nh.subscribe(joy_topic, 1, joy_callback);
58 
59  if (enable_e_stop) {
60  ROS_INFO("Enable e-stop: %d", enable_e_stop);
61  e_stop_pub = nh.advertise<std_msgs::Bool>(e_stop_pub_topic, 1);
62  }
63 
64  ros::Rate r(5);
65  while (ros::ok()) {
66  if (dead_man) {
68  }
69  r.sleep();
70  ros::spinOnce();
71  }
72 
73  return 0;
74  //ros::spin();
75 }
max_linear_speed
double max_linear_speed
Definition: joy_teleop.h:45
angular_speed_axis
int angular_speed_axis
Definition: joy_teleop.h:41
cmd_vel_pub
ros::Publisher cmd_vel_pub
Definition: joy_teleop.h:50
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
dead_man
bool dead_man
Definition: joy_teleop.h:53
ros::spinOnce
ROSCPP_DECL void spinOnce()
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
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
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
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
joy_subscriber
ros::Subscriber joy_subscriber
Definition: joy_teleop.h:48
ros::Rate::sleep
bool sleep()
enable_e_stop
int enable_e_stop
Definition: joy_teleop.h:43
main
int main(int argc, char **argv)
Definition: joy_teleop_node.cpp:32
stop_button
int stop_button
Definition: joy_teleop.h:38
e_stop_button
int e_stop_button
Definition: joy_teleop.h:39
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
joy_teleop.h
ROS_INFO
#define ROS_INFO(...)
cmd_to_send
geometry_msgs::Twist cmd_to_send
Definition: joy_teleop.h:54
ros::NodeHandle


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