00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #ifdef HAVE_CONFIG_H
00014 #include <config.h>
00015 #endif
00016
00017 #ifndef CONFIGXMLPARSER_H_
00018 #define CONFIGXMLPARSER_H_
00019
00020 #include "SimulatedDevices.h"
00021 #include <libxml++/libxml++.h>
00022 #include <urdf/model.h>
00023
00024 #include <iostream>
00025 using namespace std;
00026 #include <cstdlib>
00027 #include <list>
00028
00029 struct ROSInterfaceInfo
00030 {
00031 typedef enum
00032 {
00033 Unknown, ROSOdomToPAT, PATToROSOdom, ROSJointStateToArm, ArmToROSJointState, VirtualCameraToROSImage,
00034 RangeSensorToROSRange, ROSImageToHUD, ROSTwistToPAT, ROSPoseToPAT, ImuToROSImu, PressureSensorToROS, GPSSensorToROS,
00035 DVLSensorToROS, RangeImageSensorToROSImage, multibeamSensorToLaserScan, SimulatedDevice, contactSensorToROS, WorldToROSTF
00036 } type_t;
00037 string subtype;
00038 std::map<std::string, std::string> values;
00039 string topic, infoTopic, targetName, rootName;
00040 type_t type;
00041 int rate;
00042 unsigned int w, h;
00043 unsigned int posx, posy, depth, blackWhite, enableObjects;
00044 double scale;
00045 };
00046
00047 struct Parameters
00048 {
00049 double fx, fy, x0, y0, f, n, k;
00050 };
00051
00052 struct Vcam
00053 {
00054 string name;
00055 string linkName, roscam, roscaminfo;
00056 std::string frameId;
00057 int resw, resh, link, range, bw;
00058 double showpath;
00059 double position[3], orientation[3];
00060 double baseLine;
00061 boost::shared_ptr<Parameters> parameters;
00062 void init()
00063 {
00064 name = "";
00065 linkName = "";
00066 roscam = "";
00067 roscaminfo = "";
00068 resw = 160;
00069 resh = 120;
00070 position[0] = 0;
00071 position[1] = 0;
00072 position[2] = 0;
00073 orientation[0] = 0;
00074 orientation[1] = 0;
00075 orientation[2] = 0;
00076 baseLine = 0.0;
00077 frameId = "";
00078 showpath = 0;
00079 parameters.reset();
00080 range = 0;
00081 bw = 0;
00082 }
00083 };
00084
00085 struct slProjector
00086 {
00087 string name;
00088 string linkName;
00089 string image_name;
00090 double position[3], orientation[3];
00091 double fov;
00092 int laser;
00093 int link;
00094 void init()
00095 {
00096 name = "";
00097 linkName = "";
00098 image_name = "";
00099 position[0] = 0;
00100 position[1] = 0;
00101 position[2] = 0;
00102 orientation[0] = 0;
00103 orientation[1] = 0;
00104 orientation[2] = 0;
00105 fov = 0;
00106 laser = 1;
00107 }
00108 };
00109
00110 struct rangeSensor
00111 {
00112 string name;
00113 string linkName;
00114 double position[3], orientation[3];
00115 double range;
00116 int visible;
00117 int link;
00118 void init()
00119 {
00120 name = "";
00121 linkName = "";
00122 position[0] = 0;
00123 position[1] = 0;
00124 position[2] = 0;
00125 orientation[0] = 0;
00126 orientation[1] = 0;
00127 orientation[2] = 0;
00128 range = 0;
00129 visible = 0;
00130 }
00131 };
00132
00133 struct Imu
00134 {
00135 string name;
00136 string linkName;
00137 double std;
00138 double position[3], orientation[3];
00139 int link;
00140 void init()
00141 {
00142 name = "";
00143 linkName = "";
00144 std = 0.0;
00145 position[0] = 0;
00146 position[1] = 0;
00147 position[2] = 0;
00148 orientation[0] = 0;
00149 orientation[1] = 0;
00150 orientation[2] = 0;
00151 }
00152 };
00153
00154 struct XMLPressureSensor
00155 {
00156 string name;
00157 string linkName;
00158 double std;
00159 double position[3], orientation[3];
00160 int link;
00161 void init()
00162 {
00163 name = "";
00164 linkName = "";
00165 std = 0.0;
00166 position[0] = 0;
00167 position[1] = 0;
00168 position[2] = 0;
00169 orientation[0] = 0;
00170 orientation[1] = 0;
00171 orientation[2] = 0;
00172 }
00173 };
00174
00175 struct XMLGPSSensor
00176 {
00177 string name;
00178 string linkName;
00179 double std;
00180 double position[3], orientation[3];
00181 int link;
00182 void init()
00183 {
00184 name = "";
00185 linkName = "";
00186 std = 0.0;
00187 position[0] = 0;
00188 position[1] = 0;
00189 position[2] = 0;
00190 orientation[0] = 0;
00191 orientation[1] = 0;
00192 orientation[2] = 0;
00193 }
00194 };
00195
00196 struct XMLDVLSensor
00197 {
00198 string name;
00199 string linkName;
00200 double std;
00201 double position[3], orientation[3];
00202 int link;
00203 void init()
00204 {
00205 name = "";
00206 linkName = "";
00207 std = 0.0;
00208 position[0] = 0;
00209 position[1] = 0;
00210 position[2] = 0;
00211 orientation[0] = 0;
00212 orientation[1] = 0;
00213 orientation[2] = 0;
00214 }
00215 };
00216
00217 struct XMLMultibeamSensor
00218 {
00219 string name;
00220 string linkName;
00221 double position[3], orientation[3];
00222 int link;
00223 double initAngle, finalAngle, angleIncr, range;
00224 void init()
00225 {
00226 name = "";
00227 linkName = "";
00228 position[0] = 0;
00229 position[1] = 0;
00230 position[2] = 0;
00231 orientation[0] = 0;
00232 orientation[1] = 0;
00233 orientation[2] = 0;
00234 }
00235 };
00236
00237 struct Mimic
00238 {
00239 string jointName;
00240 double offset, multiplier;
00241 };
00242
00243 struct Geometry
00244 {
00245 int type;
00246 double boxSize[3];
00247 double length, radius;
00248 string file;
00249 };
00250
00251 struct Link
00252 {
00253 string name;
00254 double position[3];
00255 double rpy[3];
00256 double quat[4];
00257 std::string material;
00258 boost::shared_ptr<Geometry> cs, geom;
00259 double mass;
00260 };
00261
00262 struct Joint
00263 {
00264 string name;
00265 int parent, child;
00266 int mimicp, type;
00267 float lowLimit, upLimit;
00268 boost::shared_ptr<Mimic> mimic;
00269 double position[3];
00270 double rpy[3];
00271 double axis[3];
00272 double quat[4];
00273 };
00274
00275 struct Material
00276 {
00277 string name;
00278 double r, g, b, a;
00279 };
00280
00281 struct Vehicle
00282 {
00283 string name;
00284 std::vector<Link> links;
00285 std::vector<Joint> joints;
00286 int nlinks;
00287 int njoints;
00288 int ninitJoints;
00289 double position[3];
00290 double orientation[3];
00291 std::vector<double> jointValues;
00292 std::map<std::string, Material> materials;
00293 std::list<Vcam> Vcams;
00294 std::list<Vcam> VRangecams;
00295 std::list<slProjector> sls_projectors;
00296 std::list<rangeSensor> range_sensors, object_pickers;
00297 std::list<Imu> imus;
00298 std::list<XMLPressureSensor> pressure_sensors;
00299 std::list<XMLGPSSensor> gps_sensors;
00300 std::list<XMLDVLSensor> dvl_sensors;
00301 std::list<XMLMultibeamSensor> multibeam_sensors;
00302 std::vector<uwsim::SimulatedDeviceConfig::Ptr> simulated_devices;
00303 std::string URDFFile;
00304 };
00305
00306 struct PhysicProperties
00307 {
00308 double mass;
00309 double inertia[3];
00310 double linearDamping;
00311 double angularDamping;
00312 double minLinearLimit[3];
00313 double maxLinearLimit[3];
00314 double minAngularLimit[3];
00315 double maxAngularLimit[3];
00316 int isKinematic;
00317 std::string csType, cs;
00318 void init()
00319 {
00320 mass = 1;
00321 inertia[0] = 0;
00322 inertia[1] = 0;
00323 inertia[2] = 0;
00324 csType = "box";
00325 cs = "";
00326 linearDamping = 0;
00327 angularDamping = 0;
00328 minLinearLimit[0] = 1;
00329 minLinearLimit[1] = 1;
00330 minLinearLimit[2] = 1;
00331 maxLinearLimit[0] = 0;
00332 maxLinearLimit[1] = 0;
00333 maxLinearLimit[2] = 0;
00334 isKinematic = 0;
00335 minAngularLimit[0] = 1;
00336 minAngularLimit[1] = 1;
00337 minAngularLimit[2] = 1;
00338 maxAngularLimit[0] = 0;
00339 maxAngularLimit[1] = 0;
00340 maxAngularLimit[2] = 0;
00341 }
00342 ;
00343 };
00344
00345 struct Object
00346 {
00347 string name, file;
00348 double position[3];
00349 double orientation[3];
00350 double offsetp[3];
00351 double offsetr[3];
00352 boost::shared_ptr<PhysicProperties> physicProperties;
00353 };
00354
00355 struct PhysicsWater
00356 {
00357 int enable;
00358 double position[3];
00359 double resolution;
00360 double size[6];
00361 void init()
00362 {
00363 enable = 0;
00364 resolution = 0.25;
00365 position[0] = position[1] = position[2] = 0;
00366 size[0] = size[2] = size[4] = -10;
00367 size[1] = size[3] = size[5] = 10;
00368 }
00369 ;
00370 };
00371
00372 struct ShowTrajectory
00373 {
00374 std::string target;
00375 double color[3];
00376 int lineStyle;
00377 void init()
00378 {
00379 target="";
00380 color[0]= 1; color[1]= 0; color[2] = 0;
00381 lineStyle=1;
00382 }
00383 };
00384
00385 class ConfigFile
00386 {
00387 public:
00388
00389
00390 void esPi(string in, double ¶m);
00391
00392 void extractFloatChar(const xmlpp::Node* node, double ¶m);
00393 void extractIntChar(const xmlpp::Node* node, int ¶m);
00394 void extractUIntChar(const xmlpp::Node* node, unsigned int ¶m);
00395 void extractStringChar(const xmlpp::Node* node, string ¶m);
00396 void extractPositionOrColor(const xmlpp::Node* node, double param[3]);
00397 void extractOrientation(const xmlpp::Node* node, double param[3]);
00398
00399 void processFog(const xmlpp::Node* node);
00400 void processOceanState(const xmlpp::Node* node);
00401 void processSimParams(const xmlpp::Node* node);
00402 void processPhysicsWater(const xmlpp::Node* node);
00403 void processSize(const xmlpp::Node* node);
00404 void processShowTrajectory(const xmlpp::Node* node, ShowTrajectory & trajectory);
00405 void processParameters(const xmlpp::Node*, Parameters *params);
00406 void processVcam(const xmlpp::Node* node, Vcam &vcam);
00407 void processSLProjector(const xmlpp::Node* node, slProjector &slp);
00408 void processRangeSensor(const xmlpp::Node* node, rangeSensor &rs);
00409 void processImu(const xmlpp::Node* node, Imu &rs);
00410 void processPressureSensor(const xmlpp::Node* node, XMLPressureSensor &ps);
00411 void processDVLSensor(const xmlpp::Node* node, XMLDVLSensor &s);
00412 void processGPSSensor(const xmlpp::Node* node, XMLGPSSensor &s);
00413 void processMultibeamSensor(const xmlpp::Node* node, XMLMultibeamSensor &s);
00414 void processCamera(const xmlpp::Node* node);
00415 void processJointValues(const xmlpp::Node* node, std::vector<double> &jointValues, int &ninitJoints);
00416 void processVehicle(const xmlpp::Node* node, Vehicle &vehicle);
00417 void processPhysicProperties(const xmlpp::Node* node, PhysicProperties &pp);
00418 void processObject(const xmlpp::Node* node, Object &object);
00419 void processROSInterface(const xmlpp::Node* node, ROSInterfaceInfo &rosInterface);
00420 void processROSInterfaces(const xmlpp::Node* node);
00421 void processXML(const xmlpp::Node* node);
00422
00423 void processGeometry(urdf::Geometry * geometry, Geometry * geom);
00424 void processPose(urdf::Pose pose, double position[3], double rpy[3], double quat[4]);
00425 void processVisual(boost::shared_ptr<const urdf::Visual> visual, Link &link,
00426 std::map<std::string, Material> &materials);
00427 void processJoint(boost::shared_ptr<const urdf::Joint> joint, Joint &jointVehicle, int parentLink, int childLink);
00428 int processLink(boost::shared_ptr<const urdf::Link> link, Vehicle &vehicle, int nlink, int njoint,
00429 std::map<std::string, Material> &materials);
00430 int processURDFFile(string file, Vehicle &vehicle);
00431
00432 void postprocessVehicle(Vehicle &vehicle);
00433
00434 public:
00435 double windx, windy, windSpeed, depth, reflectionDamping, waveScale, choppyFactor, crestFoamHeight,
00436 oceanSurfaceHeight, fogDensity;
00437 int isNotChoppy, disableShaders, eye_in_hand, freeMotion, resw, resh, enablePhysics;
00438 string arm, vehicleToTrack;
00439 double camPosition[3], camLookAt[3], fogColor[3], color[3], attenuation[3], offsetr[3], offsetp[3], gravity[3];
00440 double camFov, camAspectRatio, camNear, camFar;
00441 list<Vehicle> vehicles;
00442 list<Object> objects;
00443 list<ROSInterfaceInfo> ROSInterfaces;
00444 list<ROSInterfaceInfo> ROSPhysInterfaces;
00445 list<ShowTrajectory> trajectories;
00446 PhysicsWater physicsWater;
00447 double physicsFrequency;
00448 int physicsSubSteps;
00449
00450 ConfigFile(const std::string &fName);
00451 };
00452
00453 #endif