Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <string>
00038 #include <gtest/gtest.h>
00039 #include "gazebo/SpawnModel.h"
00040 #include "gazebo/GetWorldProperties.h"
00041 #include "gazebo/DeleteModel.h"
00042 #include "geometry_msgs/Pose.h"
00043 #include "std_srvs/Empty.h"
00044
00045 #include <sstream>
00046 #include <tinyxml.h>
00047
00048
00049
00050 #include <ros/ros.h>
00051
00052 int g_argc;
00053 char** g_argv;
00054
00055 TEST(SpawnTest, spawnSingleBox)
00056 {
00057 ros::NodeHandle nh("");
00058
00059 ros::service::waitForService("gazebo/spawn_urdf_model");
00060 ros::ServiceClient spawn_model_client = nh.serviceClient<gazebo::SpawnModel>("gazebo/spawn_urdf_model");
00061 gazebo::SpawnModel spawn_model;
00062 spawn_model.request.model_name = "box1";
00063
00064
00065 std::string urdf_filename = std::string(g_argv[1]);
00066 ROS_DEBUG("loading file: %s",urdf_filename.c_str());
00067
00068 TiXmlDocument xml_in(urdf_filename);
00069 xml_in.LoadFile();
00070 std::ostringstream stream;
00071 stream << xml_in;
00072 spawn_model.request.model_xml = stream.str();
00073 ROS_DEBUG("XML string: %s",stream.str().c_str());
00074
00075 spawn_model.request.robot_namespace = "";
00076 geometry_msgs::Pose pose;
00077 pose.position.x = pose.position.y = 0; pose.position.z = 1;
00078 pose.orientation.w = 1.0; pose.orientation.x = pose.orientation.y = pose.orientation.z = 0;
00079 spawn_model.request.initial_pose = pose;
00080 spawn_model.request.reference_frame = "";
00081
00082 ASSERT_TRUE(spawn_model_client.call(spawn_model));
00083
00084 SUCCEED();
00085 }
00086
00087
00088 TEST(SpawnTest, spawnBoxStack)
00089 {
00090 ros::NodeHandle nh("");
00091
00092 ros::service::waitForService("gazebo/spawn_urdf_model");
00093 ros::ServiceClient spawn_model_client = nh.serviceClient<gazebo::SpawnModel>("gazebo/spawn_urdf_model");
00094 gazebo::SpawnModel spawn_model;
00095
00096
00097 std::string urdf_filename = std::string(g_argv[1]);
00098 ROS_DEBUG("loading file: %s",urdf_filename.c_str());
00099
00100 TiXmlDocument xml_in(urdf_filename);
00101 xml_in.LoadFile();
00102 std::ostringstream stream;
00103 stream << xml_in;
00104 spawn_model.request.model_xml = stream.str();
00105 ROS_DEBUG("XML string: %s",stream.str().c_str());
00106
00107 spawn_model.request.robot_namespace = "";
00108 spawn_model.request.reference_frame = "";
00109
00110
00111 for (int i=0;i<10;i++)
00112 {
00113 std::ostringstream mn_stream;
00114 mn_stream << "box_" << i;
00115 spawn_model.request.model_name = mn_stream.str();
00116 geometry_msgs::Pose pose;
00117 pose.position.x = pose.position.y = 0; pose.position.z = 1 + 2.0*(i+1);
00118 pose.orientation.w = 1.0; pose.orientation.x = pose.orientation.y = pose.orientation.z = 0;
00119 spawn_model.request.initial_pose = pose;
00120 ASSERT_TRUE(spawn_model_client.call(spawn_model));
00121 }
00122
00123 SUCCEED();
00124 }
00125
00126 TEST(DeleteTest, deleteAllModels)
00127 {
00128 ros::NodeHandle nh("");
00129
00130 ros::service::waitForService("gazebo/delete_model");
00131 ros::ServiceClient delete_model_client = nh.serviceClient<gazebo::DeleteModel>("gazebo/delete_model");
00132 gazebo::DeleteModel delete_model;
00133
00134
00135 ros::service::waitForService("gazebo/get_world_properties");
00136 ros::ServiceClient check_model_client = nh.serviceClient<gazebo::GetWorldProperties>("gazebo/get_world_properties");
00137 gazebo::GetWorldProperties world_properties;
00138
00139 check_model_client.call(world_properties);
00140 for (std::vector<std::string>::iterator mit = world_properties.response.model_names.begin();
00141 mit != world_properties.response.model_names.end();
00142 mit++)
00143 {
00144 delete_model.request.model_name = *mit;
00145 ASSERT_TRUE(delete_model_client.call(delete_model));
00146 }
00147
00148
00149 check_model_client.call(world_properties);
00150 ASSERT_TRUE(world_properties.response.model_names.empty());
00151
00152 SUCCEED();
00153 }
00154
00155
00156 int main(int argc, char** argv)
00157 {
00158 ros::init(argc, argv, "test", ros::init_options::AnonymousName);
00159 testing::InitGoogleTest(&argc, argv);
00160 g_argc = argc;
00161 g_argv = argv;
00162 return RUN_ALL_TESTS();
00163 }