joystick_interrupt.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015-2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
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 copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <cmath>
31 #include <string>
32 
33 #include <ros/ros.h>
34 
35 #include <geometry_msgs/Twist.h>
36 #include <sensor_msgs/Joy.h>
37 #include <std_msgs/Bool.h>
38 
40 
42 {
43 private:
50  double linear_vel_;
51  double angular_vel_;
52  double linear_y_vel_;
53  double timeout_;
65  geometry_msgs::Twist last_input_twist_;
66 
67  float getAxisValue(const sensor_msgs::Joy::Ptr& msg, const int axis, const std::string& axis_name) const
68  {
69  if (axis < 0)
70  {
71  return 0.0;
72  }
73  if (static_cast<size_t>(axis) >= msg->axes.size())
74  {
75  ROS_ERROR("Out of range: number of axis (%lu) must be greater than %s (%d).",
76  msg->axes.size(), axis_name.c_str(), axis);
77  return 0.0;
78  }
79  return msg->axes[axis];
80  }
81 
82  float getJoyValue(const sensor_msgs::Joy::Ptr& msg, const int axis, const int axis2,
83  const std::string& axis_name) const
84  {
85  const float value = getAxisValue(msg, axis, axis_name);
86  const float value2 = getAxisValue(msg, axis2, axis_name + "2");
87  return (std::abs(value2) > std::abs(value)) ? value2 : value;
88  }
89 
90  void cbJoy(const sensor_msgs::Joy::Ptr msg)
91  {
92  if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
93  {
94  ROS_ERROR("Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
95  msg->buttons.size(), interrupt_button_);
97  return;
98  }
99  if (!msg->buttons[interrupt_button_])
100  {
101  if (last_joy_msg_ != ros::Time(0))
102  {
104  }
106  return;
107  }
108 
110 
111  float lin_x = getJoyValue(msg, linear_axis_, linear_axis2_, "linear_axis");
112  float lin_y = getJoyValue(msg, linear_y_axis_, linear_y_axis2_, "linear_y_axis");
113  float ang = getJoyValue(msg, angular_axis_, angular_axis2_, "angular_axis");
114 
115  if (high_speed_button_ >= 0)
116  {
117  if (static_cast<size_t>(high_speed_button_) < msg->buttons.size())
118  {
119  if (msg->buttons[high_speed_button_])
120  {
121  lin_x *= linear_high_speed_ratio_;
122  lin_y *= linear_high_speed_ratio_;
124  }
125  }
126  else
127  ROS_ERROR("Out of range: number of buttons (%lu) must be greater than high_speed_button (%d).",
128  msg->buttons.size(), high_speed_button_);
129  }
130 
131  geometry_msgs::Twist cmd_vel;
132  cmd_vel.linear.x = lin_x * linear_vel_;
133  cmd_vel.linear.y = lin_y * linear_y_vel_;
134  cmd_vel.linear.z = 0.0;
135  cmd_vel.angular.z = ang * angular_vel_;
136  cmd_vel.angular.x = cmd_vel.angular.y = 0.0;
137  pub_twist_.publish(cmd_vel);
138  };
139  void cbTwist(const geometry_msgs::Twist::Ptr msg)
140  {
141  last_input_twist_ = *msg;
142  std_msgs::Bool status;
145  {
147  status.data = true;
148  }
149  else
150  {
151  status.data = false;
152  }
153  pub_int_.publish(status);
154  };
155 
156 public:
158  : nh_("")
159  , pnh_("~")
160  {
162  sub_joy_ = nh_.subscribe("joy", 1, &JoystickInterrupt::cbJoy, this);
164  nh_, "cmd_vel_input",
165  pnh_, "cmd_vel_input", 1, &JoystickInterrupt::cbTwist, this);
166  pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
167  nh_, "cmd_vel",
168  pnh_, "cmd_vel", 2);
169  pub_int_ = pnh_.advertise<std_msgs::Bool>("interrupt_status", 2);
170 
171  pnh_.param("linear_vel", linear_vel_, 0.5);
172  pnh_.param("angular_vel", angular_vel_, 0.8);
173  pnh_.param("linear_axis", linear_axis_, 1);
174  pnh_.param("angular_axis", angular_axis_, 0);
175  pnh_.param("linear_axis2", linear_axis2_, -1);
176  pnh_.param("angular_axis2", angular_axis2_, -1);
177  pnh_.param("interrupt_button", interrupt_button_, 6);
178  pnh_.param("high_speed_button", high_speed_button_, -1);
179  pnh_.param("linear_high_speed_ratio", linear_high_speed_ratio_, 1.3);
180  pnh_.param("angular_high_speed_ratio", angular_high_speed_ratio_, 1.1);
181  pnh_.param("timeout", timeout_, 0.5);
182  pnh_.param("linear_y_vel", linear_y_vel_, 0.0);
183  pnh_.param("linear_y_axis", linear_y_axis_, -1);
184  pnh_.param("linear_y_axis2", linear_y_axis2_, -1);
185 
187 
188  if (interrupt_button_ < 0)
189  {
190  ROS_ERROR("interrupt_button must be grater than -1.");
191  ros::shutdown();
192  return;
193  }
194  if (linear_axis_ < 0)
195  {
196  ROS_ERROR("linear_axis must be grater than -1.");
197  ros::shutdown();
198  return;
199  }
200  if (angular_axis_ < 0)
201  {
202  ROS_ERROR("angular_axis must be grater than -1.");
203  ros::shutdown();
204  return;
205  }
206  }
207 };
208 
209 int main(int argc, char* argv[])
210 {
211  ros::init(argc, argv, "joystick_interrupt");
212 
214  ros::spin();
215 
216  return 0;
217 }
JoystickInterrupt::pnh_
ros::NodeHandle pnh_
Definition: joystick_interrupt.cpp:45
ros::Publisher
JoystickInterrupt::JoystickInterrupt
JoystickInterrupt()
Definition: joystick_interrupt.cpp:157
ros::Time::isSimTime
static bool isSimTime()
JoystickInterrupt::linear_vel_
double linear_vel_
Definition: joystick_interrupt.cpp:50
JoystickInterrupt::sub_twist_
ros::Subscriber sub_twist_
Definition: joystick_interrupt.cpp:46
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
JoystickInterrupt::angular_axis2_
int angular_axis2_
Definition: joystick_interrupt.cpp:59
ros.h
JoystickInterrupt::getJoyValue
float getJoyValue(const sensor_msgs::Joy::Ptr &msg, const int axis, const int axis2, const std::string &axis_name) const
Definition: joystick_interrupt.cpp:82
ros::shutdown
ROSCPP_DECL void shutdown()
JoystickInterrupt
Definition: joystick_interrupt.cpp:41
JoystickInterrupt::interrupt_button_
int interrupt_button_
Definition: joystick_interrupt.cpp:62
compatibility.h
JoystickInterrupt::linear_y_vel_
double linear_y_vel_
Definition: joystick_interrupt.cpp:52
JoystickInterrupt::nh_
ros::NodeHandle nh_
Definition: joystick_interrupt.cpp:44
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
JoystickInterrupt::timeout_
double timeout_
Definition: joystick_interrupt.cpp:53
neonavigation_common::compat::subscribe
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints())
JoystickInterrupt::angular_vel_
double angular_vel_
Definition: joystick_interrupt.cpp:51
main
int main(int argc, char *argv[])
Definition: joystick_interrupt.cpp:209
JoystickInterrupt::last_input_twist_
geometry_msgs::Twist last_input_twist_
Definition: joystick_interrupt.cpp:65
JoystickInterrupt::angular_axis_
int angular_axis_
Definition: joystick_interrupt.cpp:57
JoystickInterrupt::linear_axis_
int linear_axis_
Definition: joystick_interrupt.cpp:56
JoystickInterrupt::angular_high_speed_ratio_
double angular_high_speed_ratio_
Definition: joystick_interrupt.cpp:55
JoystickInterrupt::linear_y_axis2_
int linear_y_axis2_
Definition: joystick_interrupt.cpp:61
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())
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
JoystickInterrupt::pub_twist_
ros::Publisher pub_twist_
Definition: joystick_interrupt.cpp:48
JoystickInterrupt::high_speed_button_
int high_speed_button_
Definition: joystick_interrupt.cpp:63
JoystickInterrupt::pub_int_
ros::Publisher pub_int_
Definition: joystick_interrupt.cpp:49
ros::Time
JoystickInterrupt::getAxisValue
float getAxisValue(const sensor_msgs::Joy::Ptr &msg, const int axis, const std::string &axis_name) const
Definition: joystick_interrupt.cpp:67
JoystickInterrupt::cbTwist
void cbTwist(const geometry_msgs::Twist::Ptr msg)
Definition: joystick_interrupt.cpp:139
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
JoystickInterrupt::linear_y_axis_
int linear_y_axis_
Definition: joystick_interrupt.cpp:60
ros::spin
ROSCPP_DECL void spin()
JoystickInterrupt::linear_high_speed_ratio_
double linear_high_speed_ratio_
Definition: joystick_interrupt.cpp:54
JoystickInterrupt::last_joy_msg_
ros::Time last_joy_msg_
Definition: joystick_interrupt.cpp:64
JoystickInterrupt::cbJoy
void cbJoy(const sensor_msgs::Joy::Ptr msg)
Definition: joystick_interrupt.cpp:90
JoystickInterrupt::linear_axis2_
int linear_axis2_
Definition: joystick_interrupt.cpp:58
ros::Duration
JoystickInterrupt::sub_joy_
ros::Subscriber sub_joy_
Definition: joystick_interrupt.cpp:47
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Wed Mar 19 2025 02:14:07