test_joystick_interrupt.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 #include <sensor_msgs/Joy.h>
00032 #include <geometry_msgs/Twist.h>
00033 
00034 #include <gtest/gtest.h>
00035 
00036 class JoystickInterruptTest : public ::testing::Test
00037 {
00038 protected:
00039   ros::NodeHandle nh_;
00040   ros::Publisher pub_cmd_vel_;
00041   ros::Publisher pub_joy_;
00042   ros::Subscriber sub_cmd_vel_;
00043 
00044   geometry_msgs::Twist::ConstPtr cmd_vel_;
00045 
00046   void cbCmdVel(const geometry_msgs::Twist::ConstPtr& msg)
00047   {
00048     cmd_vel_ = msg;
00049   }
00050 
00051 public:
00052   JoystickInterruptTest()
00053     : nh_()
00054   {
00055     pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel_input", 1);
00056     pub_joy_ = nh_.advertise<sensor_msgs::Joy>("joy", 1);
00057     sub_cmd_vel_ = nh_.subscribe("cmd_vel", 1, &JoystickInterruptTest::cbCmdVel, this);
00058   }
00059   void publishCmdVel(
00060       const float lin,
00061       const float ang)
00062   {
00063     geometry_msgs::Twist cmd_vel_out;
00064     cmd_vel_out.linear.x = lin;
00065     cmd_vel_out.angular.z = ang;
00066     pub_cmd_vel_.publish(cmd_vel_out);
00067   }
00068   void publishJoy(
00069       const int button,
00070       const int high_speed,
00071       const float lin0,
00072       const float ang0,
00073       const float lin1,
00074       const float ang1)
00075   {
00076     sensor_msgs::Joy joy;
00077     joy.header.stamp = ros::Time::now();
00078     joy.buttons.resize(2);
00079     joy.buttons[0] = button;
00080     joy.buttons[1] = high_speed;
00081     joy.axes.resize(4);
00082     joy.axes[0] = lin0;
00083     joy.axes[1] = ang0;
00084     joy.axes[2] = lin1;
00085     joy.axes[3] = ang1;
00086     pub_joy_.publish(joy);
00087   }
00088 };
00089 
00090 TEST_F(JoystickInterruptTest, NoInterrupt)
00091 {
00092   ros::Duration(1.0).sleep();
00093   ros::Rate rate(20);
00094   for (size_t i = 0; i < 25; ++i)
00095   {
00096     publishCmdVel(0.1, 0.2);
00097     if (i < 5)
00098       publishJoy(0, 0, 0, 0, 0, 0);
00099     else if (i < 10)
00100       publishJoy(0, 0, 1, 1, 0, 0);
00101     else if (i < 15)
00102       publishJoy(0, 0, 0, 0, 1, 1);
00103     else if (i < 20)
00104       publishJoy(0, 1, 1, 1, 0, 0);
00105     else
00106       publishJoy(0, 1, 0, 0, 1, 1);
00107 
00108     rate.sleep();
00109     ros::spinOnce();
00110     if (i < 3)
00111       continue;
00112     ASSERT_TRUE(static_cast<bool>(cmd_vel_));
00113     ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
00114     ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
00115   }
00116 }
00117 
00118 TEST_F(JoystickInterruptTest, Interrupt)
00119 {
00120   ros::Duration(1.0).sleep();
00121   ros::Rate rate(20);
00122   for (size_t i = 0; i < 25; ++i)
00123   {
00124     publishCmdVel(0.1, 0.2);
00125     if (i < 5)
00126       publishJoy(0, 0, 0, 0, 0, 0);
00127     else if (i < 10)
00128       publishJoy(1, 0, 1, 0, 0, 0);
00129     else if (i < 15)
00130       publishJoy(1, 0, 0, 0, 1, 0);
00131     else if (i < 20)
00132       publishJoy(1, 0, 0, 1, 0, 0);
00133     else
00134       publishJoy(1, 0, 0, 0, 0, 1);
00135 
00136     rate.sleep();
00137     ros::spinOnce();
00138     if (i < 3)
00139       continue;
00140     ASSERT_TRUE(static_cast<bool>(cmd_vel_));
00141     if (i < 5)
00142     {
00143       ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
00144       ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
00145     }
00146     else if (i < 15)
00147     {
00148       ASSERT_NEAR(cmd_vel_->linear.x, 1.0, 1e-3);
00149       ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
00150     }
00151     else
00152     {
00153       ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
00154       ASSERT_NEAR(cmd_vel_->angular.z, 1.0, 1e-3);
00155     }
00156   }
00157 }
00158 
00159 TEST_F(JoystickInterruptTest, InterruptHighSpeed)
00160 {
00161   ros::Duration(1.0).sleep();
00162   ros::Rate rate(20);
00163   for (size_t i = 0; i < 25; ++i)
00164   {
00165     publishCmdVel(0.1, 0.2);
00166     if (i < 5)
00167       publishJoy(0, 0, 0, 0, 0, 0);
00168     else if (i < 10)
00169       publishJoy(1, 1, 1, 0, 0, 0);
00170     else if (i < 15)
00171       publishJoy(1, 1, 0, 0, 1, 0);
00172     else if (i < 20)
00173       publishJoy(1, 1, 0, 1, 0, 0);
00174     else
00175       publishJoy(1, 1, 0, 0, 0, 1);
00176 
00177     rate.sleep();
00178     ros::spinOnce();
00179     if (i < 3)
00180       continue;
00181     ASSERT_TRUE(static_cast<bool>(cmd_vel_));
00182     if (i < 5)
00183     {
00184       ASSERT_NEAR(cmd_vel_->linear.x, 0.1, 1e-3);
00185       ASSERT_NEAR(cmd_vel_->angular.z, 0.2, 1e-3);
00186     }
00187     else if (i < 15)
00188     {
00189       ASSERT_NEAR(cmd_vel_->linear.x, 2.0, 1e-3);
00190       ASSERT_NEAR(cmd_vel_->angular.z, 0.0, 1e-3);
00191     }
00192     else
00193     {
00194       ASSERT_NEAR(cmd_vel_->linear.x, 0.0, 1e-3);
00195       ASSERT_NEAR(cmd_vel_->angular.z, 2.0, 1e-3);
00196     }
00197   }
00198 }
00199 
00200 int main(int argc, char** argv)
00201 {
00202   testing::InitGoogleTest(&argc, argv);
00203   ros::init(argc, argv, "test_joystick_interrupt");
00204 
00205   return RUN_ALL_TESTS();
00206 }


joystick_interrupt
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:16