check_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: John Hsu */
36 
37 #include <string>
38 #include <gtest/gtest.h>
39 #include "gazebo/GetWorldProperties.h"
40 #include "geometry_msgs/Pose.h"
41 #include "std_srvs/Empty.h"
42 
43 #include <sstream>
44 #include <tinyxml.h>
45 #include <boost/lexical_cast.hpp>
46 
47 // Including ros, just to be able to call ros::init(), to remove unwanted
48 // args from command-line.
49 #include <ros/ros.h>
50 
51 int g_argc;
52 char** g_argv;
53 
54 TEST(SpawnTest, spawnSingleBox)
55 {
56  ros::NodeHandle nh("");
57  // make the service call to spawn model
58  ros::service::waitForService("gazebo/get_world_properties");
59  ros::ServiceClient check_model_client = nh.serviceClient<gazebo::GetWorldProperties>("gazebo/get_world_properties");
60  gazebo::GetWorldProperties world_properties;
61 
62 
63  bool found = false;
64 
65  // test duration
66  double test_duration = 10.0; // default to 10 seconds sim time
67  try
68  {
69  test_duration = boost::lexical_cast<double>(g_argv[1]);
70  }
71  catch (boost::bad_lexical_cast &e)
72  {
73  ROS_ERROR_NAMED("check_model", "first argument of check_model should be timeout");
74  return;
75  }
76  ros::Time timeout = ros::Time::now() + ros::Duration(test_duration);
77 
78  // model name to look for
79  std::string model_name = std::string(g_argv[2]);
80  ROS_INFO_NAMED("check_model", "looking for model: %s",model_name.c_str());
81 
82  while (!found && ros::Time::now() < timeout)
83  {
84  check_model_client.call(world_properties);
85  for (std::vector<std::string>::iterator mit = world_properties.response.model_names.begin();
86  mit != world_properties.response.model_names.end();
87  mit++)
88  {
89  if (*mit == model_name)
90  {
91  found = true;
92  break;
93  }
94  }
95  }
96 
97  ASSERT_TRUE(found);
98 
99  SUCCEED();
100 }
101 
102 
103 
104 
105 int main(int argc, char** argv)
106 {
107  ros::init(argc, argv, "test", ros::init_options::AnonymousName);
108  testing::InitGoogleTest(&argc, argv);
109  g_argc = argc;
110  g_argv = argv;
111  return RUN_ALL_TESTS();
112 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
TEST(SpawnTest, spawnSingleBox)
Definition: check_model.cpp:54
#define ROS_INFO_NAMED(name,...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int g_argc
Definition: check_model.cpp:51
int SUCCEED
#define ROS_ERROR_NAMED(name,...)
static Time now()
int main(int argc, char **argv)
char ** g_argv
Definition: check_model.cpp:52
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27