tango_ros_api_test.cc
Go to the documentation of this file.
1 // Copyright 2016 Intermodalics All Rights Reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 #include <time.h>
15 
16 #include <glog/logging.h>
17 #include <gtest/gtest.h>
19 #include <nodelet/loader.h>
20 #include <pluginlib/class_loader.h>
21 #include <ros/ros.h>
22 #include <tango_ros_messages/TangoConnect.h>
23 
24 std::string master_uri;
25 std::string host_ip;
26 
27 class TangoRosTest : public ::testing::Test {
28  public:
29  constexpr static int TEST_DURATION = 20; // in second.
30 };
31 
32 TEST_F(TangoRosTest, TestPublishingForFixedTime) {
33  int argc = 3;
34  char* argv[] = {"/", &master_uri[0], &host_ip[0]};
35  ros::init(argc, argv, "tango");
36 
37  nodelet::Loader loader;
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.";
44 
45  // Check that all necessary plugins are available.
46  pluginlib::ClassLoader<image_transport::PublisherPlugin> image_transport_pub_loader("image_transport", "image_transport::PublisherPlugin");
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.";
49 
50  ros::NodeHandle nh;
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.";
55 
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);
60  }
61 }
62 
63 // Run all the tests that were declared with TEST()
64 int main(int argc, char **argv) {
65  testing::InitGoogleTest(&argc, argv);
66  master_uri = argv[1];
67  host_ip = argv[2];
68  return RUN_ALL_TESTS();
69 }
int main(int argc, char **argv)
std::string master_uri
std::string host_ip
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)


TangoRosStreamer
Author(s):
autogenerated on Mon Jun 10 2019 15:37:54