31 #include <geometry_msgs/Twist.h> 32 #include <sensor_msgs/Joy.h> 33 #include <std_msgs/Int32.h> 35 #include <gtest/gtest.h> 47 void cbCmdVel(
const geometry_msgs::Twist::ConstPtr& msg)
56 pub_cmd_vel_ = nh_.
advertise<geometry_msgs::Twist>(
"cmd_vel_input", 1);
57 pub_joy_ = nh_.
advertise<sensor_msgs::Joy>(
"joy", 1);
61 for (
size_t i = 0; i < 100; ++i)
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);
88 joy.buttons.resize(2);
89 joy.buttons[0] = button;
90 joy.buttons[1] = high_speed;
104 for (
size_t i = 0; i < 25; ++i)
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);
132 for (
size_t i = 0; i < 25; ++i)
150 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
153 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
154 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
158 ASSERT_NEAR(
cmd_vel_->linear.x, 1.0, 1e-3);
159 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
163 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
164 ASSERT_NEAR(
cmd_vel_->angular.z, 1.0, 1e-3);
176 for (
size_t i = 0; i < 20; ++i)
191 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
194 ASSERT_NEAR(
cmd_vel_->linear.x, 0, 1e-3);
195 ASSERT_NEAR(
cmd_vel_->angular.z, 0, 1e-3);
199 ASSERT_NEAR(
cmd_vel_->linear.x, 1.0, 1e-3);
200 ASSERT_NEAR(
cmd_vel_->angular.z, 0.5, 1e-3);
204 ASSERT_NEAR(
cmd_vel_->linear.x, 0, 1e-3);
205 ASSERT_NEAR(
cmd_vel_->angular.z, 0, 1e-3);
214 for (
size_t i = 0; i < 25; ++i)
232 ASSERT_TRUE(static_cast<bool>(
cmd_vel_));
235 ASSERT_NEAR(
cmd_vel_->linear.x, 0.1, 1e-3);
236 ASSERT_NEAR(
cmd_vel_->angular.z, 0.2, 1e-3);
240 ASSERT_NEAR(
cmd_vel_->linear.x, 2.0, 1e-3);
241 ASSERT_NEAR(
cmd_vel_->angular.z, 0.0, 1e-3);
245 ASSERT_NEAR(
cmd_vel_->linear.x, 0.0, 1e-3);
246 ASSERT_NEAR(
cmd_vel_->angular.z, 2.0, 1e-3);
260 std_msgs::Int32::ConstPtr
msg_;
262 void cbMsg(
const std_msgs::Int32::ConstPtr& msg)
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);
276 for (
size_t i = 0; i < 100; ++i)
287 for (
size_t i = 0; i < 100; ++i)
297 std_msgs::Int32 msg_out;
303 std_msgs::Int32 msg_out;
309 sensor_msgs::Joy joy;
311 joy.buttons.resize(1);
312 joy.buttons[0] = button;
317 sensor_msgs::Joy joy;
328 for (
int btn = 0; btn < 2; ++btn)
333 for (
int i = 0; i < 15; ++i)
345 ASSERT_TRUE(static_cast<bool>(msg_)) <<
"button: " << btn;
348 ASSERT_NEAR(-i, msg_->data, 2) <<
"button: " << btn;
352 ASSERT_NEAR(i, msg_->data, 2) <<
"button:" << btn;
412 int main(
int argc,
char** argv)
414 testing::InitGoogleTest(&argc, argv);
415 ros::init(argc, argv,
"test_joystick_interrupt");
417 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)
void cbMsg(const std_msgs::Int32::ConstPtr &msg)
void publish2(const int32_t v)
ros::Subscriber sub_cmd_vel_
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_
uint32_t getNumSubscribers() const
void publishJoy(const int button)
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)