16 #include <glog/logging.h> 17 #include <gtest/gtest.h> 22 #include <tango_ros_messages/TangoConnect.h> 29 constexpr
static int TEST_DURATION = 20;
38 std::map<std::string, std::string> remappings;
39 std::vector<std::string> nodelet_argv;
40 LOG(INFO) <<
"Start loading nodelets.";
41 const bool result = loader.
load(
"/tango",
"tango_ros_native/TangoRosNodelet", remappings, nodelet_argv);
42 ASSERT_TRUE(result) <<
"Problem loading Tango ROS nodelet!";
43 LOG(INFO) <<
"Finished loading nodelets.";
47 ASSERT_TRUE(image_transport_pub_loader.
isClassAvailable(
"image_transport/raw_pub")) <<
"Plugin image_transport/raw_pub is not available.";
48 ASSERT_TRUE(image_transport_pub_loader.
isClassAvailable(
"image_transport/compressed_pub")) <<
"Plugin image_transport/compressed_pub is not available.";
51 ros::ServiceClient tango_connect_service = nh.serviceClient<tango_ros_messages::TangoConnect>(
"/tango/connect");
52 tango_ros_messages::TangoConnect srv;
53 srv.request.request = tango_ros_messages::TangoConnect::Request::CONNECT;
54 ASSERT_TRUE(tango_connect_service.
call(srv)) <<
"Call to tango connect failed.";
56 time_t current_time = time(NULL);
57 time_t end = current_time + TEST_DURATION;
58 while(current_time < end) {
59 current_time = time(NULL);
64 int main(
int argc,
char **argv) {
65 testing::InitGoogleTest(&argc, argv);
68 return RUN_ALL_TESTS();
int main(int argc, char **argv)
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
TEST_F(TangoRosTest, TestPublishingForFixedTime)
virtual bool isClassAvailable(const std::string &lookup_name)