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 #include <cstdio>
00036 #include <cstdlib>
00037
00038 #include <vector>
00039 #include <string>
00040 #include <sstream>
00041
00042 #include <gazebo/gazebo.h>
00043 #include <gazebo/GazeboError.hh>
00044 #include <gazebo/World.hh>
00045 #include <gazebo/Model.hh>
00046
00047 #include "ros/ros.h"
00048 #include <boost/program_options.hpp>
00049
00050 #include <gazebo_tools/urdf2gazebo.h>
00051
00052 void usage(const char *progname)
00053 {
00054 printf("\nUsage: %s [options] <spawn|kill> <model_name>\n", progname);
00055 printf(" Example: %s --help\n",progname);
00056 printf(" Example: %s -p robot_description -x 10 spawn pr2\n",progname);
00057 printf(" Example: %s -f my_urdf_file.urdf -o gazebo_model.xml -x 10\n",progname);
00058 printf(" Example: %s kill pr2_model\n",progname);
00059 }
00060
00061 void remove_model(std::string model_name)
00062 {
00063
00064
00065 libgazebo::Client *client = new libgazebo::Client();
00066 libgazebo::FactoryIface *factoryIface = new libgazebo::FactoryIface();
00067
00068 int serverId = 0;
00069
00071 bool connected_to_server = false;
00072 while (!connected_to_server)
00073 {
00074 try
00075 {
00076 client->ConnectWait(serverId, GZ_CLIENT_ID_USER_FIRST);
00077 connected_to_server = true;
00078 }
00079 catch (gazebo::GazeboError e)
00080 {
00081 ROS_ERROR("Gazebo error: Unable to connect\n %s\n",e.GetErrorStr().c_str());
00082 usleep(1000000);
00083 connected_to_server = false;
00084 }
00085 }
00086
00088 try
00089 {
00090 factoryIface->Open(client, "default");
00091 }
00092 catch (gazebo::GazeboError e)
00093 {
00094 ROS_ERROR("Gazebo error: Unable to connect to the factory interface\n%s\n",e.GetErrorStr().c_str());
00095 exit(2);
00096 }
00097
00099 bool writing_iface = true;
00100 while (writing_iface)
00101 {
00102 factoryIface->Lock(1);
00103 if (strcmp((char*)factoryIface->data->deleteEntity,"")==0)
00104 {
00105 ROS_INFO("Deleting Robot Model Name:%s in Gazebo\n",model_name.c_str());
00106
00107 strcpy((char*)factoryIface->data->deleteEntity, model_name.c_str());
00108 writing_iface = false;
00109 }
00110 factoryIface->Unlock();
00111 }
00112 }
00113
00114 void spawn_model(TiXmlDocument gazebo_model_xml)
00115 {
00116
00117 libgazebo::Client *client = new libgazebo::Client();
00118 libgazebo::FactoryIface *factoryIface = new libgazebo::FactoryIface();
00119
00120 int serverId = 0;
00121
00122 bool connected_to_server = false;
00124 while (!connected_to_server)
00125 {
00126 try
00127 {
00128 ROS_DEBUG("gazebo_model: waiting for gazebo factory, usually launched by 'roslaunch `rospack find gazebo_worlds`/launch/empty_world.launch'");
00129 client->ConnectWait(serverId, GZ_CLIENT_ID_USER_FIRST);
00130 connected_to_server = true;
00131 }
00132 catch (gazebo::GazeboError e)
00133 {
00134 ROS_ERROR("Gazebo error: Unable to connect\n %s\n",e.GetErrorStr().c_str());
00135 usleep(1000000);
00136 connected_to_server = false;
00137 }
00138 }
00139
00140
00141 try
00142 {
00143 factoryIface->Open(client, "default");
00144 }
00145 catch (gazebo::GazeboError e)
00146 {
00147 ROS_ERROR("Gazebo error: Unable to connect to the factory interface\n%s\n",e.GetErrorStr().c_str());
00148 exit(2);
00149 }
00150
00151 std::ostringstream stream;
00152 stream << gazebo_model_xml;
00153 std::string gazebo_model_xml_string = stream.str();
00154 ROS_DEBUG("Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
00155
00156 bool writing_iface = true;
00157 while (writing_iface)
00158 {
00159 factoryIface->Lock(1);
00160 if (strcmp((char*)factoryIface->data->newModel,"")==0)
00161 {
00162
00163 strcpy((char*)factoryIface->data->newModel, gazebo_model_xml_string.c_str());
00164 writing_iface = false;
00165 }
00166 factoryIface->Unlock();
00167 }
00168 }
00169 namespace po = boost::program_options;
00170
00171 int main(int argc, char **argv)
00172 {
00173 ros::init(argc,argv,"gazebo_model",ros::init_options::AnonymousName);
00174
00175 ROS_WARN("SUPPORT FOR gazebo_model IS BEING DEPRECATED, PLEASE USE spawn_model IN THE FUTURE.\n\nrosrun gazebo spawn_model\n\nfor usage information.");
00176
00177
00178 if (argc < 2)
00179 {
00180 usage(argv[0]);
00181 exit(1);
00182 }
00183
00184 double initial_x = 0;
00185 double initial_y = 0;
00186 double initial_z = 0;
00187 double initial_rx = 0;
00188 double initial_ry = 0;
00189 double initial_rz = 0;
00190
00191
00192 po::options_description v_desc("Allowed options");
00193 v_desc.add_options()
00194 ("help,h" , "produce this help message")
00195 ("param-name,p" , po::value<std::string>() , "Name of parameter on parameter server containing the model XML.")
00196 ("namespace,n" , po::value<std::string>() , "ROS namespace of the model spawned in simulation. If not specified, the namespace of this node is used.")
00197 ("input-filename,f" , po::value<std::string>() , "read input model from file, not from the parameter server, exclusive with -p option.")
00198 ("output-filename,o" , po::value<std::string>() , "write converted gazebo model xml to a file instead, model is not spawned in simulation.")
00199 ("skip-joint-limits,s" , "do not enforce joint limits during urdf-->gazebo conversion.")
00200 ("init-x,x" , po::value<double>() , "set initial x position of model, defaults to 0.")
00201 ("init-y,y" , po::value<double>() , "set initial y position of model, defaults to 0.")
00202 ("init-z,z" , po::value<double>() , "set initial z position of model, defaults to 0.")
00203 ("init-roll,R" , po::value<double>() , "set initial roll (rx) of model in radians, defaults to 0. application orders are r-p-y.")
00204 ("init-pitch,P" , po::value<double>() , "set initial pitch (ry) of model in radians, defaults to 0. application orders are r-p-y.")
00205 ("init-yaw,Y" , po::value<double>() , "set initial yaw (rz) of model in radians, defaults to 0. application orders are r-p-y.");
00206
00207 po::options_description h_desc("Hidden options");
00208 h_desc.add_options()
00209 ("command" , po::value< std::vector<std::string> >(), "<spawn|kill>")
00210 ("model-name" , po::value< std::vector<std::string> >(), "overwrite name of the gazebo model in simulation. If not specified, the model name defaults to the name in urdf.");
00211
00212 po::options_description desc("Allowed options");
00213 desc.add(v_desc).add(h_desc);
00214
00215 po::positional_options_description p_desc;
00216 p_desc.add("command", 1);
00217 p_desc.add("model-name", 2);
00218
00219 po::variables_map vm;
00220
00221 po::store(po::command_line_parser(argc, argv).options(desc).positional(p_desc).run(), vm);
00222 po::notify(vm);
00223
00224 if (vm.count("help"))
00225 {
00226 usage(argv[0]);
00227 std::cout << v_desc << std::endl;
00228 exit(1);
00229 }
00230
00231
00232
00233 bool enforce_limits = true;
00234 if (vm.count("skip-joint-limits"))
00235 enforce_limits = false;
00236
00237
00238
00239 bool do_conversion = true;
00240
00241 std::string file_in;
00242 if (vm.count("input-filename"))
00243 file_in = vm["input-filename"].as<std::string>();
00244 else
00245 file_in.clear();
00246
00247 std::string file_out;
00248 if (vm.count("output-filename"))
00249 {
00250 file_out = vm["output-filename"].as<std::string>();
00251 }
00252
00253 std::string robot_namespace;
00254 if (vm.count("namespace"))
00255 {
00256 robot_namespace = vm["namespace"].as<std::string>();
00257 }
00258 else
00259 {
00260 robot_namespace = ros::this_node::getNamespace();
00261 ROS_DEBUG("NOTE: %s is called under namespace %s, this namespace is passed to gazebo so all Gazebo plugins (e.g.ros_time, gazebo_mechanism_control,etc.) will start up under this namespace. User can overwrite by passing in argument -namespace, for example: %s /prf/robot_description -n /prf",argv[0],argv[0],robot_namespace.c_str());
00262 }
00263 ROS_DEBUG("namespace: %s",robot_namespace.c_str());
00264
00265
00266 if (vm.count("init-x"))
00267 {
00268 initial_x = vm["init-x"].as<double>();
00269 ROS_DEBUG("x: %f",initial_x);
00270 }
00271 if (vm.count("init-y"))
00272 {
00273 initial_y = vm["init-y"].as<double>();
00274 ROS_DEBUG("y: %f",initial_y);
00275 }
00276 if (vm.count("init-z"))
00277 {
00278 initial_z = vm["init-z"].as<double>();
00279 ROS_DEBUG("z: %f",initial_z);
00280 }
00281 if (vm.count("init-roll"))
00282 {
00283 initial_rx = vm["init-roll"].as<double>();
00284 ROS_DEBUG("init-roll: %f",initial_rx);
00285 }
00286 if (vm.count("init-pitch"))
00287 {
00288 initial_ry = vm["init-pitch"].as<double>();
00289 ROS_DEBUG("init-pitch: %f",initial_ry);
00290 }
00291 if (vm.count("init-yaw"))
00292 {
00293 initial_rz = vm["init-yaw"].as<double>();
00294 ROS_DEBUG("init-yaw: %f",initial_rz);
00295 }
00296
00297 std::string command;
00298 if (vm.count("command"))
00299 {
00300 std::vector<std::string> str_vec = vm["command"].as<std::vector<std::string> >();
00301 if (str_vec.size() == 1)
00302 command = str_vec[0];
00303 else
00304 command.clear();
00305 }
00306
00307 std::string param_name;
00308 if (vm.count("param-name"))
00309 {
00310 param_name = vm["param-name"].as<std::string>();
00311 if (!file_in.empty())
00312 {
00313 ROS_ERROR("Both param-name and input-filename are specified. Only one input source is allowed.\n");
00314 exit(2);
00315 }
00316 }
00317 else if (command == "spawn" && file_in.empty())
00318 {
00319 ROS_ERROR("Either param-name or input-filename must be specified for spawn to work. Need one input source.\n");
00320 exit(2);
00321 }
00322
00323
00324
00325 std::string model_name;
00326 if (vm.count("model-name"))
00327 {
00328 std::vector<std::string> str_vec = vm["model-name"].as<std::vector<std::string> >();
00329 if (str_vec.size() == 1)
00330 {
00331 model_name = str_vec[0];
00332
00333 std::replace(model_name.begin(),model_name.end(),'/','_');
00334 ROS_DEBUG("model name will be: %s",model_name.c_str());
00335 }
00336 else
00337 model_name.clear();
00338 }
00339
00340
00341
00342 urdf::Vector3 initial_xyz(initial_x,initial_y,initial_z);
00343 urdf::Vector3 initial_rpy(initial_rx*180/M_PI,initial_ry*180/M_PI,initial_rz*180/M_PI);
00344
00345 if (command == "kill" && !model_name.empty())
00346 {
00347
00348 remove_model(model_name);
00349 }
00350 else
00351 {
00352
00353 std::string xml_string;
00354 if (file_in.empty())
00355 {
00356
00357 ros::NodeHandle rosnode("~");
00358 std::string full_param_name;
00359 rosnode.searchParam(param_name,full_param_name);
00360 rosnode.getParam(full_param_name.c_str(),xml_string);
00361 ROS_DEBUG("%s content\n%s\n", full_param_name.c_str(), xml_string.c_str());
00362 if (xml_string.c_str()==NULL)
00363 {
00364 ROS_ERROR("Unable to load robot model from param server robot_description\n");
00365 exit(2);
00366 }
00367 }
00368 else
00369 {
00370
00371 TiXmlDocument xml_in(file_in);
00372 xml_in.LoadFile();
00373
00374 std::ostringstream stream;
00375 stream << xml_in;
00376 xml_string = stream.str();
00377 }
00378
00379
00380 TiXmlDocument xml_doc;
00381 xml_doc.Parse(xml_string.c_str());
00382
00383
00384 TiXmlDocument gazebo_model_xml;
00385
00386
00387 if (xml_doc.FirstChild("robot"))
00388 do_conversion = true;
00389 else if (xml_doc.FirstChild("model:physical"))
00390 do_conversion = false;
00391 else
00392 {
00393 ROS_ERROR("Unable to determine input xml type: input urdf xml must begin with <robot>, input gazebo model xml must begin with <model:physical>\n");
00394 exit(2);
00395 }
00396
00397
00398 if (do_conversion)
00399 {
00400
00401 urdf2gazebo::URDF2Gazebo u2g;
00402 u2g.convert(xml_doc, gazebo_model_xml, enforce_limits, initial_xyz, initial_rpy, model_name, robot_namespace);
00403 }
00404 else
00405 {
00409 std::string open_bracket("<?");
00410 std::string close_bracket("?>");
00411 size_t pos1 = xml_string.find(open_bracket,0);
00412 size_t pos2 = xml_string.find(close_bracket,0);
00413 if (pos1 != std::string::npos && pos2 != std::string::npos)
00414 xml_string.replace(pos1,pos2-pos1+2,std::string(""));
00415
00416
00417 gazebo_model_xml.Parse(xml_string.c_str());
00418
00419
00420
00421
00422 TiXmlElement* model;
00423 model = gazebo_model_xml.FirstChildElement("model:physical");
00424 if (model)
00425 {
00426
00427
00428 TiXmlElement* xyz_key = model->FirstChildElement("xyz");
00429 if (xyz_key)
00430 model->RemoveChild(xyz_key);
00431 TiXmlElement* rpy_key = model->FirstChildElement("rpy");
00432 if (rpy_key)
00433 model->RemoveChild(rpy_key);
00434
00435 xyz_key = new TiXmlElement("xyz");
00436 rpy_key = new TiXmlElement("rpy");
00437
00438 std::ostringstream xyz_stream, rpy_stream;
00439 xyz_stream << initial_x << " " << initial_y << " " << initial_z;
00440 rpy_stream << initial_rx << " " << initial_ry << " " << initial_rz;
00441
00442 TiXmlText* xyz_txt = new TiXmlText(xyz_stream.str());
00443 TiXmlText* rpy_txt = new TiXmlText(rpy_stream.str());
00444
00445 xyz_key->LinkEndChild(xyz_txt);
00446 rpy_key->LinkEndChild(rpy_txt);
00447
00448 model->LinkEndChild(xyz_key);
00449 model->LinkEndChild(rpy_key);
00450
00451
00452
00453 if (!model_name.empty())
00454 {
00455
00456 model->RemoveAttribute("name");
00457 model->SetAttribute("name",model_name);
00458 }
00459 else
00460 {
00461
00462 model_name = model->Attribute("name");
00463 }
00464
00465 }
00466
00467 }
00468
00469 if (command == "spawn" && file_out.empty())
00470 {
00471
00472 spawn_model(gazebo_model_xml);
00473 }
00474 else if (!file_out.empty())
00475 {
00476
00477 if (!gazebo_model_xml.SaveFile(file_out))
00478 {
00479 printf("Unable to save gazebo model in %s\n", file_out.c_str());
00480 exit(3);
00481 }
00482 }
00483 else
00484 {
00485 ROS_ERROR("command must be either spawn, kill or use -o option to do file conversion.");
00486 }
00487 }
00488
00489 return 0;
00490 }
00491