31 #include <sensor_msgs/Joy.h> 32 #include <geometry_msgs/Twist.h> 34 #include <gtest/gtest.h> 46 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
55 pub_cmd_vel_ = nh_.
advertise<geometry_msgs::Twist>(
"cmd_vel_input", 1);
56 pub_joy_ = nh_.
advertise<sensor_msgs::Joy>(
"joy", 1);
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);
78 joy.buttons.resize(2);
79 joy.buttons[0] = button;
80 joy.buttons[1] = high_speed;
94 for (
size_t i = 0; i < 25; ++i)
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);
122 for (
size_t i = 0; i < 25; ++i)
140 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
143 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
144 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
148 ASSERT_NEAR(
cmd_vel_->linear.x, 1.0, 1e-3);
149 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
153 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
154 ASSERT_NEAR(
cmd_vel_->angular.z, 1.0, 1e-3);
163 for (
size_t i = 0; i < 25; ++i)
181 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
184 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
185 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
189 ASSERT_NEAR(
cmd_vel_->linear.x, 2.0, 1e-3);
190 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
194 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
195 ASSERT_NEAR(
cmd_vel_->angular.z, 2.0, 1e-3);
200 int main(
int argc,
char** argv)
202 testing::InitGoogleTest(&argc, argv);
203 ros::init(argc, argv,
"test_joystick_interrupt");
205 return RUN_ALL_TESTS();
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher pub_cmd_vel_
void publishJoy(const int button, const int high_speed, const float lin0, const float ang0, const float lin1, const float ang1)
ros::Subscriber sub_cmd_vel_
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_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
void publishCmdVel(const float lin, const float ang)
TEST_F(JoystickInterruptTest, NoInterrupt)