Skip to content

Commit

Permalink
expect cameras don't subscribe to trigger topic
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters committed Apr 19, 2018
1 parent 42149c1 commit b595d4a
Show file tree
Hide file tree
Showing 3 changed files with 45 additions and 0 deletions.
15 changes: 15 additions & 0 deletions gazebo_plugins/test/camera/camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,21 @@ void CameraTest::subscribeTest()
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 1.0);
cam_sub_.shutdown();

// make sure nothing is subscribing to image_trigger topic
// there is no easy API, so call getSystemState
XmlRpc::XmlRpcValue args, result, payload;
args[0] = ros::this_node::getName();
EXPECT_TRUE(ros::master::execute("getSystemState", args, result, payload, true));
// [publishers, subscribers, services]
// subscribers in index 1 of payload
for (int i = 0; i < payload[1].size(); ++i)
{
// [ [topic1, [topic1Subscriber1...topic1SubscriberN]] ... ]
// topic name i is in index 0
std::string topic = payload[1][i][0];
EXPECT_EQ(topic.find("image_trigger"), std::string::npos);
}
}

#endif
15 changes: 15 additions & 0 deletions gazebo_plugins/test/camera/depth_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,21 @@ TEST_F(DepthCameraTest, cameraSubscribeTest)
cam_sub_.shutdown();
depth_sub_.shutdown();
points_sub_.shutdown();

// make sure nothing is subscribing to image_trigger topic
// there is no easy API, so call getSystemState
XmlRpc::XmlRpcValue args, result, payload;
args[0] = ros::this_node::getName();
EXPECT_TRUE(ros::master::execute("getSystemState", args, result, payload, true));
// [publishers, subscribers, services]
// subscribers in index 1 of payload
for (int i = 0; i < payload[1].size(); ++i)
{
// [ [topic1, [topic1Subscriber1...topic1SubscriberN]] ... ]
// topic name i is in index 0
std::string topic = payload[1][i][0];
EXPECT_EQ(topic.find("image_trigger"), std::string::npos);
}
}

int main(int argc, char** argv)
Expand Down
15 changes: 15 additions & 0 deletions gazebo_plugins/test/camera/multicamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,21 @@ TEST_F(MultiCameraTest, cameraSubscribeTest)
ROS_INFO_STREAM(time_diff);
EXPECT_LT(time_diff, 1.0);
// cam_sub_.shutdown();

// make sure nothing is subscribing to image_trigger topic
// there is no easy API, so call getSystemState
XmlRpc::XmlRpcValue args, result, payload;
args[0] = ros::this_node::getName();
EXPECT_TRUE(ros::master::execute("getSystemState", args, result, payload, true));
// [publishers, subscribers, services]
// subscribers in index 1 of payload
for (int i = 0; i < payload[1].size(); ++i)
{
// [ [topic1, [topic1Subscriber1...topic1SubscriberN]] ... ]
// topic name i is in index 0
std::string topic = payload[1][i][0];
EXPECT_EQ(topic.find("image_trigger"), std::string::npos);
}
}

int main(int argc, char** argv)
Expand Down

0 comments on commit b595d4a

Please sign in to comment.