38 #include <gtest/gtest.h> 39 #include "gazebo/SpawnModel.h" 40 #include "gazebo/GetWorldProperties.h" 41 #include "gazebo/DeleteModel.h" 42 #include "geometry_msgs/Pose.h" 43 #include "std_srvs/Empty.h" 55 TEST(SpawnTest, spawnSingleBox)
61 gazebo::SpawnModel spawn_model;
62 spawn_model.request.model_name =
"box1";
65 std::string urdf_filename = std::string(
g_argv[1]);
68 TiXmlDocument xml_in(urdf_filename);
70 std::ostringstream stream;
72 spawn_model.request.model_xml = stream.str();
75 spawn_model.request.robot_namespace =
"";
76 geometry_msgs::Pose pose;
77 pose.position.x = pose.position.y = 0; pose.position.z = 1;
78 pose.orientation.w = 1.0; pose.orientation.x = pose.orientation.y = pose.orientation.z = 0;
79 spawn_model.request.initial_pose = pose;
80 spawn_model.request.reference_frame =
"";
82 ASSERT_TRUE(spawn_model_client.
call(spawn_model));
88 TEST(SpawnTest, spawnBoxStack)
94 gazebo::SpawnModel spawn_model;
97 std::string urdf_filename = std::string(
g_argv[1]);
100 TiXmlDocument xml_in(urdf_filename);
102 std::ostringstream stream;
104 spawn_model.request.model_xml = stream.str();
107 spawn_model.request.robot_namespace =
"";
108 spawn_model.request.reference_frame =
"";
111 for (
int i=0;i<10;i++)
113 std::ostringstream mn_stream;
114 mn_stream <<
"box_" << i;
115 spawn_model.request.model_name = mn_stream.str();
116 geometry_msgs::Pose pose;
117 pose.position.x = pose.position.y = 0; pose.position.z = 1 + 2.0*(i+1);
118 pose.orientation.w = 1.0; pose.orientation.x = pose.orientation.y = pose.orientation.z = 0;
119 spawn_model.request.initial_pose = pose;
120 ASSERT_TRUE(spawn_model_client.
call(spawn_model));
126 TEST(DeleteTest, deleteAllModels)
132 gazebo::DeleteModel delete_model;
137 gazebo::GetWorldProperties world_properties;
139 check_model_client.
call(world_properties);
140 for (std::vector<std::string>::iterator mit = world_properties.response.model_names.begin();
141 mit != world_properties.response.model_names.end();
144 delete_model.request.model_name = *mit;
145 ASSERT_TRUE(delete_model_client.
call(delete_model));
149 check_model_client.
call(world_properties);
150 ASSERT_TRUE(world_properties.response.model_names.empty());
156 int main(
int argc,
char** argv)
159 testing::InitGoogleTest(&argc, argv);
162 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
#define ROS_DEBUG_NAMED(name,...)
int main(int argc, char **argv)
TEST(SpawnTest, spawnSingleBox)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)