test_joystick_interrupt.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 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/Int32.h>
34 
35 #include <gtest/gtest.h>
36 
37 class JoystickInterruptTest : public ::testing::Test
38 {
39 protected:
44 
45  geometry_msgs::Twist::ConstPtr cmd_vel_;
46 
47  void cbCmdVel(const geometry_msgs::Twist::ConstPtr& msg)
48  {
49  cmd_vel_ = msg;
50  }
51 
52 public:
54  : nh_()
55  {
56  pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_input", 1);
57  pub_joy_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
58  sub_cmd_vel_ = nh_.subscribe("cmd_vel", 1, &JoystickInterruptTest::cbCmdVel, this);
59 
60  ros::Rate wait(10);
61  for (size_t i = 0; i < 100; ++i)
62  {
63  wait.sleep();
64  ros::spinOnce();
65  if (i > 5 && pub_cmd_vel_.getNumSubscribers() > 0)
66  break;
67  }
68  }
70  const float lin,
71  const float ang)
72  {
73  geometry_msgs::Twist cmd_vel_out;
74  cmd_vel_out.linear.x = lin;
75  cmd_vel_out.angular.z = ang;
76  pub_cmd_vel_.publish(cmd_vel_out);
77  }
78  void publishJoy(
79  const int button,
80  const int high_speed,
81  const float lin0,
82  const float ang0,
83  const float lin1,
84  const float ang1)
85  {
86  sensor_msgs::Joy joy;
87  joy.header.stamp = ros::Time::now();
88  joy.buttons.resize(2);
89  joy.buttons[0] = button;
90  joy.buttons[1] = high_speed;
91  joy.axes.resize(4);
92  joy.axes[0] = lin0;
93  joy.axes[1] = ang0;
94  joy.axes[2] = lin1;
95  joy.axes[3] = ang1;
96  pub_joy_.publish(joy);
97  }
98 };
99 
101 {
102  ros::Duration(1.0).sleep();
103  ros::Rate rate(20);
104  for (size_t i = 0; i < 25; ++i)
105  {
106  publishCmdVel(0.1, 0.2);
107  if (i < 5)
108  publishJoy(0, 0, 0, 0, 0, 0);
109  else if (i < 10)
110  publishJoy(0, 0, 1, 1, 0, 0);
111  else if (i < 15)
112  publishJoy(0, 0, 0, 0, 1, 1);
113  else if (i < 20)
114  publishJoy(0, 1, 1, 1, 0, 0);
115  else
116  publishJoy(0, 1, 0, 0, 1, 1);
117 
118  rate.sleep();
119  ros::spinOnce();
120  if (i < 3)
121  continue;
122  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
123  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
124  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
125  }
126 }
127 
129 {
130  ros::Duration(1.0).sleep();
131  ros::Rate rate(20);
132  for (size_t i = 0; i < 25; ++i)
133  {
134  publishCmdVel(0.1, 0.2);
135  if (i < 5)
136  publishJoy(0, 0, 0, 0, 0, 0);
137  else if (i < 10)
138  publishJoy(1, 0, 1, 0, 0, 0);
139  else if (i < 15)
140  publishJoy(1, 0, 0, 0, 1, 0);
141  else if (i < 20)
142  publishJoy(1, 0, 0, 1, 0, 0);
143  else
144  publishJoy(1, 0, 0, 0, 0, 1);
145 
146  rate.sleep();
147  ros::spinOnce();
148  if (i < 3)
149  continue;
150  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
151  if (i < 5)
152  {
153  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
154  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
155  }
156  else if (i < 15)
157  {
158  ASSERT_NEAR(cmd_vel_->linear.x, 1.0, 1e-3);
159  ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
160  }
161  else
162  {
163  ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
164  ASSERT_NEAR(cmd_vel_->angular.z, 1.0, 1e-3);
165  }
166  }
167 }
168 
169 TEST_F(JoystickInterruptTest, InterruptNoTwistInput)
170 {
171  ros::Duration(1.0).sleep();
172  // make sure the internal state of the joystick interrupt node
173  // (i.e. last_input_twist_) is set back to a zero twist.
174  publishCmdVel(0, 0);
175  ros::Rate rate(20);
176  for (size_t i = 0; i < 20; ++i)
177  {
178  if (i < 5)
179  publishJoy(0, 0, 0, 0, 0, 0);
180  else if (i < 10)
181  publishJoy(1, 0, 1, 0.5, 0, 0);
182  else if (i < 15)
183  publishJoy(0, 0, 1, 0, 0, 0);
184  else
185  publishJoy(0, 0, 0, 0.5, 0, 0);
186 
187  rate.sleep();
188  ros::spinOnce();
189  if (i < 3)
190  continue;
191  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
192  if (i < 5)
193  {
194  ASSERT_NEAR(cmd_vel_->linear.x, 0, 1e-3);
195  ASSERT_NEAR(cmd_vel_->angular.z, 0, 1e-3);
196  }
197  else if (i < 10)
198  {
199  ASSERT_NEAR(cmd_vel_->linear.x, 1.0, 1e-3);
200  ASSERT_NEAR(cmd_vel_->angular.z, 0.5, 1e-3);
201  }
202  else
203  {
204  ASSERT_NEAR(cmd_vel_->linear.x, 0, 1e-3);
205  ASSERT_NEAR(cmd_vel_->angular.z, 0, 1e-3);
206  }
207  }
208 }
209 
210 TEST_F(JoystickInterruptTest, InterruptHighSpeed)
211 {
212  ros::Duration(1.0).sleep();
213  ros::Rate rate(20);
214  for (size_t i = 0; i < 25; ++i)
215  {
216  publishCmdVel(0.1, 0.2);
217  if (i < 5)
218  publishJoy(0, 0, 0, 0, 0, 0);
219  else if (i < 10)
220  publishJoy(1, 1, 1, 0, 0, 0);
221  else if (i < 15)
222  publishJoy(1, 1, 0, 0, 1, 0);
223  else if (i < 20)
224  publishJoy(1, 1, 0, 1, 0, 0);
225  else
226  publishJoy(1, 1, 0, 0, 0, 1);
227 
228  rate.sleep();
229  ros::spinOnce();
230  if (i < 3)
231  continue;
232  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
233  if (i < 5)
234  {
235  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
236  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
237  }
238  else if (i < 15)
239  {
240  ASSERT_NEAR(cmd_vel_->linear.x, 2.0, 1e-3);
241  ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
242  }
243  else
244  {
245  ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
246  ASSERT_NEAR(cmd_vel_->angular.z, 2.0, 1e-3);
247  }
248  }
249 }
250 
251 class JoystickMuxTest : public ::testing::Test
252 {
253 protected:
259 
260  std_msgs::Int32::ConstPtr msg_;
261 
262  void cbMsg(const std_msgs::Int32::ConstPtr& msg)
263  {
264  msg_ = msg;
265  }
266 
267 public:
269  {
270  pub1_ = nh_.advertise<std_msgs::Int32>("mux_input0", 1);
271  pub2_ = nh_.advertise<std_msgs::Int32>("mux_input1", 1);
272  pub_joy_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
273  sub_ = nh_.subscribe("mux_output", 1, &JoystickMuxTest::cbMsg, this);
274 
275  ros::Rate wait(10);
276  for (size_t i = 0; i < 100; ++i)
277  {
278  wait.sleep();
279  ros::spinOnce();
280  if (i > 5 && pub1_.getNumSubscribers() > 0)
281  break;
282  }
283  }
285  {
286  ros::Rate wait(10);
287  for (size_t i = 0; i < 100; ++i)
288  {
289  wait.sleep();
290  ros::spinOnce();
291  if (i > 5 && sub_.getNumPublishers() > 0)
292  break;
293  }
294  }
295  void publish1(const int32_t v)
296  {
297  std_msgs::Int32 msg_out;
298  msg_out.data = v;
299  pub1_.publish(msg_out);
300  }
301  void publish2(const int32_t v)
302  {
303  std_msgs::Int32 msg_out;
304  msg_out.data = v;
305  pub2_.publish(msg_out);
306  }
307  void publishJoy(const int button)
308  {
309  sensor_msgs::Joy joy;
310  joy.header.stamp = ros::Time::now();
311  joy.buttons.resize(1);
312  joy.buttons[0] = button;
313  pub_joy_.publish(joy);
314  }
316  {
317  sensor_msgs::Joy joy;
318  joy.header.stamp = ros::Time::now();
319  pub_joy_.publish(joy);
320  }
321 };
322 
324 {
325  publish1(0);
326  publish2(0);
327  waitPublisher();
328  for (int btn = 0; btn < 2; ++btn)
329  {
330  publishJoy(btn);
331  ros::Duration(1.0).sleep();
332  ros::Rate rate(20);
333  for (int i = 0; i < 15; ++i)
334  {
335  publishJoy(btn);
336  publish1(i);
337  publish2(-i);
338 
339  rate.sleep();
340  ros::spinOnce();
341 
342  if (i < 5)
343  continue;
344 
345  ASSERT_TRUE(static_cast<bool>(msg_)) << "button: " << btn;
346  if (btn)
347  {
348  ASSERT_NEAR(-i, msg_->data, 2) << "button: " << btn;
349  }
350  else
351  {
352  ASSERT_NEAR(i, msg_->data, 2) << "button:" << btn;
353  }
354  }
355  }
356 }
357 /*
358 TEST_F(JoystickMuxTest, Timeout)
359 {
360  publish1(0);
361  publish2(0);
362  waitPublisher();
363  ros::Rate rate(20);
364  publishJoy(1);
365  for (int i = 0; i < 20; ++i)
366  {
367  publish1(i);
368  publish2(-i);
369 
370  rate.sleep();
371  ros::spinOnce();
372 
373  if (i < 5)
374  continue;
375 
376  ASSERT_TRUE(static_cast<bool>(msg_));
377  if (i < 10)
378  {
379  ASSERT_NEAR(-i, msg_->data, 2);
380  }
381  else if (i > 13)
382  {
383  // after timeout
384  ASSERT_NEAR(i, msg_->data, 2);
385  }
386  }
387 }
388 
389 TEST_F(JoystickMuxTest, ButtonNumberInsufficient)
390 {
391  publish1(0);
392  publish2(0);
393  waitPublisher();
394  ros::Rate rate(20);
395  for (int i = 0; i < 20; ++i)
396  {
397  publishEmptyJoy();
398  publish1(i);
399  publish2(-i);
400 
401  rate.sleep();
402  ros::spinOnce();
403 
404  if (i < 3)
405  continue;
406 
407  ASSERT_TRUE(static_cast<bool>(msg_));
408  ASSERT_NEAR(i, msg_->data, 2);
409  }
410 }*/
411 
412 int main(int argc, char** argv)
413 {
414  testing::InitGoogleTest(&argc, argv);
415  ros::init(argc, argv, "test_joystick_interrupt");
416 
417  return RUN_ALL_TESTS();
418 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publishJoy(const int button, const int high_speed, const float lin0, const float ang0, const float lin1, const float ang1)
void cbMsg(const std_msgs::Int32::ConstPtr &msg)
void publish2(const int32_t v)
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
uint32_t getNumPublishers() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Twist::ConstPtr cmd_vel_
bool sleep()
uint32_t getNumSubscribers() const
void publishJoy(const int button)
static Time now()
void publish1(const int32_t v)
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
void publishCmdVel(const float lin, const float ang)
std_msgs::Int32::ConstPtr msg_
TEST_F(JoystickInterruptTest, NoInterrupt)


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