33 #include <geometry_msgs/Twist.h> 34 #include <sensor_msgs/Joy.h> 35 #include <std_msgs/Int32.h> 37 #include <gtest/gtest.h> 49 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
58 pub_cmd_vel_ = nh_.
advertise<geometry_msgs::Twist>(
"cmd_vel_input", 1);
59 pub_joy_ = nh_.
advertise<sensor_msgs::Joy>(
"joy", 1);
63 for (
size_t i = 0; i < 100; ++i)
75 geometry_msgs::Twist cmd_vel_out;
76 cmd_vel_out.linear.x = lin;
77 cmd_vel_out.angular.z = ang;
78 pub_cmd_vel_.
publish(cmd_vel_out);
90 joy.buttons.resize(2);
91 joy.buttons[0] = button;
92 joy.buttons[1] = high_speed;
108 for (
size_t i = 0; i < 25; ++i)
126 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
127 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
128 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
136 for (
size_t i = 0; i < 25; ++i)
154 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
157 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
158 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
162 ASSERT_NEAR(
cmd_vel_->linear.x, 1.0, 1e-3);
163 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
167 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
168 ASSERT_NEAR(
cmd_vel_->angular.z, 1.0, 1e-3);
180 for (
size_t i = 0; i < 20; ++i)
195 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
198 ASSERT_NEAR(
cmd_vel_->linear.x, 0, 1e-3);
199 ASSERT_NEAR(
cmd_vel_->angular.z, 0, 1e-3);
203 ASSERT_NEAR(
cmd_vel_->linear.x, 1.0, 1e-3);
204 ASSERT_NEAR(
cmd_vel_->angular.z, 0.5, 1e-3);
208 ASSERT_NEAR(
cmd_vel_->linear.x, 0, 1e-3);
209 ASSERT_NEAR(
cmd_vel_->angular.z, 0, 1e-3);
218 for (
size_t i = 0; i < 25; ++i)
236 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
239 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
240 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
244 ASSERT_NEAR(
cmd_vel_->linear.x, 2.0, 1e-3);
245 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
249 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
250 ASSERT_NEAR(
cmd_vel_->angular.z, 2.0, 1e-3);
264 const int high_speed,
272 sensor_msgs::Joy joy;
274 joy.buttons.resize(2);
275 joy.buttons[0] = button;
276 joy.buttons[1] = high_speed;
282 joy.axes[4] = lin_y0;
283 joy.axes[5] = lin_y1;
292 for (
size_t i = 0; i < 25; ++i)
314 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
317 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
318 ASSERT_NEAR(
cmd_vel_->linear.y, 0.0, 1e-3);
319 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
323 ASSERT_NEAR(
cmd_vel_->linear.x, 0.5, 1e-3);
324 ASSERT_NEAR(
cmd_vel_->linear.y, 0.0, 1e-3);
325 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
329 ASSERT_NEAR(
cmd_vel_->linear.x, -1.0, 1e-3);
330 ASSERT_NEAR(
cmd_vel_->linear.y, 0.0, 1e-3);
331 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
335 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
336 ASSERT_NEAR(
cmd_vel_->linear.y, 0.15, 1e-3);
337 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
341 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
342 ASSERT_NEAR(
cmd_vel_->linear.y, 0.5, 1e-3);
343 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
347 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
348 ASSERT_NEAR(
cmd_vel_->linear.y, 0.0, 1e-3);
349 ASSERT_NEAR(
cmd_vel_->angular.z, -0.7, 1e-3);
353 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
354 ASSERT_NEAR(
cmd_vel_->linear.y, 0.0, 1e-3);
355 ASSERT_NEAR(
cmd_vel_->angular.z, 1.0, 1e-3);
369 std_msgs::Int32::ConstPtr
msg_;
371 void cbMsg(
const std_msgs::Int32::ConstPtr& msg)
379 pub1_ = nh_.
advertise<std_msgs::Int32>(
"mux_input0", 1);
380 pub2_ = nh_.
advertise<std_msgs::Int32>(
"mux_input1", 1);
381 pub_joy_ = nh_.
advertise<sensor_msgs::Joy>(
"joy", 1);
385 for (
size_t i = 0; i < 100; ++i)
396 for (
size_t i = 0; i < 100; ++i)
406 std_msgs::Int32 msg_out;
412 std_msgs::Int32 msg_out;
418 sensor_msgs::Joy joy;
420 joy.buttons.resize(1);
421 joy.buttons[0] = button;
426 sensor_msgs::Joy joy;
437 for (
int btn = 0; btn < 2; ++btn)
442 for (
int i = 0; i < 15; ++i)
454 ASSERT_TRUE(static_cast<bool>(msg_)) <<
"button: " << btn;
457 ASSERT_NEAR(-i, msg_->data, 2) <<
"button: " << btn;
461 ASSERT_NEAR(i, msg_->data, 2) <<
"button:" << btn;
521 int main(
int argc,
char** argv)
523 testing::InitGoogleTest(&argc, argv);
524 ros::init(argc, argv,
"test_joystick_interrupt");
526 return RUN_ALL_TESTS();
JoystickInterruptTest(const std::string &cmd_vel_topic="cmd_vel")
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)
uint32_t getNumPublishers() const
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)
void publishJoy(const int button, const int high_speed, const float lin0, const float lin_y0, const float ang0, const float lin1, const float lin_y1, const float ang1)
void cbMsg(const std_msgs::Int32::ConstPtr &msg)
void publish2(const int32_t v)
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber sub_cmd_vel_
void cbCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
JoystickInterruptOmniTest()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Twist::ConstPtr cmd_vel_
void publishJoy(const int button)
void publish1(const int32_t v)
int main(int argc, char **argv)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
void publishCmdVel(const float lin, const float ang)
std_msgs::Int32::ConstPtr msg_
TEST_F(JoystickInterruptTest, NoInterrupt)