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


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:53