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 <sensor_msgs/Joy.h>
32 #include <geometry_msgs/Twist.h>
33 
34 #include <gtest/gtest.h>
35 
36 class JoystickInterruptTest : public ::testing::Test
37 {
38 protected:
43 
44  geometry_msgs::Twist::ConstPtr cmd_vel_;
45 
46  void cbCmdVel(const geometry_msgs::Twist::ConstPtr& msg)
47  {
48  cmd_vel_ = msg;
49  }
50 
51 public:
53  : nh_()
54  {
55  pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_input", 1);
56  pub_joy_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
57  sub_cmd_vel_ = nh_.subscribe("cmd_vel", 1, &JoystickInterruptTest::cbCmdVel, this);
58  }
60  const float lin,
61  const float ang)
62  {
63  geometry_msgs::Twist cmd_vel_out;
64  cmd_vel_out.linear.x = lin;
65  cmd_vel_out.angular.z = ang;
66  pub_cmd_vel_.publish(cmd_vel_out);
67  }
68  void publishJoy(
69  const int button,
70  const int high_speed,
71  const float lin0,
72  const float ang0,
73  const float lin1,
74  const float ang1)
75  {
76  sensor_msgs::Joy joy;
77  joy.header.stamp = ros::Time::now();
78  joy.buttons.resize(2);
79  joy.buttons[0] = button;
80  joy.buttons[1] = high_speed;
81  joy.axes.resize(4);
82  joy.axes[0] = lin0;
83  joy.axes[1] = ang0;
84  joy.axes[2] = lin1;
85  joy.axes[3] = ang1;
86  pub_joy_.publish(joy);
87  }
88 };
89 
91 {
92  ros::Duration(1.0).sleep();
93  ros::Rate rate(20);
94  for (size_t i = 0; i < 25; ++i)
95  {
96  publishCmdVel(0.1, 0.2);
97  if (i < 5)
98  publishJoy(0, 0, 0, 0, 0, 0);
99  else if (i < 10)
100  publishJoy(0, 0, 1, 1, 0, 0);
101  else if (i < 15)
102  publishJoy(0, 0, 0, 0, 1, 1);
103  else if (i < 20)
104  publishJoy(0, 1, 1, 1, 0, 0);
105  else
106  publishJoy(0, 1, 0, 0, 1, 1);
107 
108  rate.sleep();
109  ros::spinOnce();
110  if (i < 3)
111  continue;
112  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
113  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
114  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
115  }
116 }
117 
119 {
120  ros::Duration(1.0).sleep();
121  ros::Rate rate(20);
122  for (size_t i = 0; i < 25; ++i)
123  {
124  publishCmdVel(0.1, 0.2);
125  if (i < 5)
126  publishJoy(0, 0, 0, 0, 0, 0);
127  else if (i < 10)
128  publishJoy(1, 0, 1, 0, 0, 0);
129  else if (i < 15)
130  publishJoy(1, 0, 0, 0, 1, 0);
131  else if (i < 20)
132  publishJoy(1, 0, 0, 1, 0, 0);
133  else
134  publishJoy(1, 0, 0, 0, 0, 1);
135 
136  rate.sleep();
137  ros::spinOnce();
138  if (i < 3)
139  continue;
140  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
141  if (i < 5)
142  {
143  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
144  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
145  }
146  else if (i < 15)
147  {
148  ASSERT_NEAR(cmd_vel_->linear.x, 1.0, 1e-3);
149  ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
150  }
151  else
152  {
153  ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
154  ASSERT_NEAR(cmd_vel_->angular.z, 1.0, 1e-3);
155  }
156  }
157 }
158 
159 TEST_F(JoystickInterruptTest, InterruptHighSpeed)
160 {
161  ros::Duration(1.0).sleep();
162  ros::Rate rate(20);
163  for (size_t i = 0; i < 25; ++i)
164  {
165  publishCmdVel(0.1, 0.2);
166  if (i < 5)
167  publishJoy(0, 0, 0, 0, 0, 0);
168  else if (i < 10)
169  publishJoy(1, 1, 1, 0, 0, 0);
170  else if (i < 15)
171  publishJoy(1, 1, 0, 0, 1, 0);
172  else if (i < 20)
173  publishJoy(1, 1, 0, 1, 0, 0);
174  else
175  publishJoy(1, 1, 0, 0, 0, 1);
176 
177  rate.sleep();
178  ros::spinOnce();
179  if (i < 3)
180  continue;
181  ASSERT_TRUE(static_cast<bool>(cmd_vel_));
182  if (i < 5)
183  {
184  ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
185  ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
186  }
187  else if (i < 15)
188  {
189  ASSERT_NEAR(cmd_vel_->linear.x, 2.0, 1e-3);
190  ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
191  }
192  else
193  {
194  ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
195  ASSERT_NEAR(cmd_vel_->angular.z, 2.0, 1e-3);
196  }
197  }
198 }
199 
200 int main(int argc, char** argv)
201 {
202  testing::InitGoogleTest(&argc, argv);
203  ros::init(argc, argv, "test_joystick_interrupt");
204 
205  return RUN_ALL_TESTS();
206 }
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 cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Twist::ConstPtr cmd_vel_
bool sleep()
static Time now()
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
void publishCmdVel(const float lin, const float ang)
TEST_F(JoystickInterruptTest, NoInterrupt)


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