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 
32 #include <ros/ros.h>
33 
34 #include <geometry_msgs/Twist.h>
35 #include <sensor_msgs/Joy.h>
36 #include <std_msgs/Bool.h>
37 
39 
41 {
42 private:
49  double linear_vel_;
50  double angular_vel_;
51  double timeout_;
61  geometry_msgs::Twist last_input_twist_;
62 
63  void cbJoy(const sensor_msgs::Joy::Ptr msg)
64  {
65  if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
66  {
67  ROS_ERROR("Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
68  msg->buttons.size(), interrupt_button_);
69  last_joy_msg_ = ros::Time(0);
70  return;
71  }
72  if (!msg->buttons[interrupt_button_])
73  {
74  if (last_joy_msg_ != ros::Time(0))
75  {
76  pub_twist_.publish(last_input_twist_);
77  }
78  last_joy_msg_ = ros::Time(0);
79  return;
80  }
81 
82  last_joy_msg_ = ros::Time::now();
83 
84  float lin(0.0f);
85  float ang(0.0f);
86  if (static_cast<size_t>(linear_axis_) < msg->axes.size())
87  lin = msg->axes[linear_axis_];
88  else
89  ROS_ERROR("Out of range: number of axis (%lu) must be greater than linear_axis (%d).",
90  msg->axes.size(), linear_axis_);
91  if (static_cast<size_t>(angular_axis_) < msg->axes.size())
92  ang = msg->axes[angular_axis_];
93  else
94  ROS_ERROR("Out of range: number of axis (%lu) must be greater than angular_axis (%d).",
95  msg->axes.size(), angular_axis_);
96 
97  if (linear_axis2_ >= 0)
98  {
99  if (static_cast<size_t>(linear_axis2_) < msg->axes.size())
100  {
101  if (std::abs(msg->axes[linear_axis2_]) > std::abs(lin))
102  lin = msg->axes[linear_axis2_];
103  }
104  else
105  ROS_ERROR("Out of range: number of axis (%lu) must be greater than linear_axis2 (%d).",
106  msg->axes.size(), linear_axis2_);
107  }
108  if (angular_axis2_ >= 0)
109  {
110  if (static_cast<size_t>(angular_axis2_) < msg->axes.size())
111  {
112  if (std::abs(msg->axes[angular_axis2_]) > std::abs(ang))
113  ang = msg->axes[angular_axis2_];
114  }
115  else
116  ROS_ERROR("Out of range: number of axis (%lu) must be greater than angular_axis2 (%d).",
117  msg->axes.size(), angular_axis2_);
118  }
119 
120  if (high_speed_button_ >= 0)
121  {
122  if (static_cast<size_t>(high_speed_button_) < msg->buttons.size())
123  {
124  if (msg->buttons[high_speed_button_])
125  {
128  }
129  }
130  else
131  ROS_ERROR("Out of range: number of buttons (%lu) must be greater than high_speed_button (%d).",
132  msg->buttons.size(), high_speed_button_);
133  }
134 
135  geometry_msgs::Twist cmd_vel;
136  cmd_vel.linear.x = lin * linear_vel_;
137  cmd_vel.linear.y = cmd_vel.linear.z = 0.0;
138  cmd_vel.angular.z = ang * angular_vel_;
139  cmd_vel.angular.x = cmd_vel.angular.y = 0.0;
140  pub_twist_.publish(cmd_vel);
141  };
142  void cbTwist(const geometry_msgs::Twist::Ptr msg)
143  {
144  last_input_twist_ = *msg;
145  std_msgs::Bool status;
146  if (ros::Time::now() - last_joy_msg_ > ros::Duration(timeout_) ||
147  (ros::Time::isSimTime() && last_joy_msg_ == ros::Time(0)))
148  {
149  pub_twist_.publish(last_input_twist_);
150  status.data = true;
151  }
152  else
153  {
154  status.data = false;
155  }
156  pub_int_.publish(status);
157  };
158 
159 public:
161  : nh_("")
162  , pnh_("~")
163  {
165  sub_joy_ = nh_.subscribe("joy", 1, &JoystickInterrupt::cbJoy, this);
167  nh_, "cmd_vel_input",
168  pnh_, "cmd_vel_input", 1, &JoystickInterrupt::cbTwist, this);
169  pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
170  nh_, "cmd_vel",
171  pnh_, "cmd_vel", 2);
172  pub_int_ = pnh_.advertise<std_msgs::Bool>("interrupt_status", 2);
173 
174  pnh_.param("linear_vel", linear_vel_, 0.5);
175  pnh_.param("angular_vel", angular_vel_, 0.8);
176  pnh_.param("linear_axis", linear_axis_, 1);
177  pnh_.param("angular_axis", angular_axis_, 0);
178  pnh_.param("linear_axis2", linear_axis2_, -1);
179  pnh_.param("angular_axis2", angular_axis2_, -1);
180  pnh_.param("interrupt_button", interrupt_button_, 6);
181  pnh_.param("high_speed_button", high_speed_button_, -1);
182  pnh_.param("linear_high_speed_ratio", linear_high_speed_ratio_, 1.3);
183  pnh_.param("angular_high_speed_ratio", angular_high_speed_ratio_, 1.1);
184  pnh_.param("timeout", timeout_, 0.5);
185  last_joy_msg_ = ros::Time(0);
186 
187  if (interrupt_button_ < 0)
188  {
189  ROS_ERROR("interrupt_button must be grater than -1.");
190  ros::shutdown();
191  return;
192  }
193  if (linear_axis_ < 0)
194  {
195  ROS_ERROR("linear_axis must be grater than -1.");
196  ros::shutdown();
197  return;
198  }
199  if (angular_axis_ < 0)
200  {
201  ROS_ERROR("angular_axis must be grater than -1.");
202  ros::shutdown();
203  return;
204  }
205  }
206 };
207 
208 int main(int argc, char* argv[])
209 {
210  ros::init(argc, argv, "joystick_interrupt");
211 
213  ros::spin();
214 
215  return 0;
216 }
void publish(const boost::shared_ptr< M > &message) const
f
void cbJoy(const sensor_msgs::Joy::Ptr msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
geometry_msgs::Twist last_input_twist_
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, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
ros::Subscriber sub_twist_
int main(int argc, char *argv[])
ros::Publisher pub_twist_
ros::Publisher pub_int_
ROSCPP_DECL void spin()
ros::Subscriber sub_joy_
ros::NodeHandle pnh_
static Time now()
ROSCPP_DECL void shutdown()
#define ROS_ERROR(...)
void cbTwist(const geometry_msgs::Twist::Ptr msg)
static bool isSimTime()


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:31