diff --git a/include/adc_circuit.h b/include/adc_circuit.h index 63ecdf6535ef92de857786c2829e307f95e30555..afa5cb63fb85fdb73ba02eb1f26a31fdbeace8a2 100644 --- a/include/adc_circuit.h +++ b/include/adc_circuit.h @@ -106,7 +106,7 @@ class CAdcCircuit * \param open_drive The objects generated with XSD. * */ - void load(std::auto_ptr<OpenDRIVE> &open_drive); + void load(std::unique_ptr<OpenDRIVE> &open_drive); }; -#endif \ No newline at end of file +#endif diff --git a/include/adc_geometries.h b/include/adc_geometries.h index 7fcc89f1028ccd2d6f022d3dc68a8f2e0f53b3b9..e398c7c792a6b56fd44e72a7d8733b9c0c9b9912 100644 --- a/include/adc_geometries.h +++ b/include/adc_geometries.h @@ -55,7 +55,7 @@ class CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - virtual void load_param(std::auto_ptr<planView::geometry_type> &geometry_info) = 0; + virtual void load_param(std::unique_ptr<planView::geometry_type> &geometry_info) = 0; public: /** @@ -152,7 +152,7 @@ class CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load(std::auto_ptr<planView::geometry_type> &geometry_info); + void load(std::unique_ptr<planView::geometry_type> &geometry_info); /** * \brief Function to set the common geometry parameters. @@ -268,7 +268,7 @@ class CAdcGeoLine: public CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load_param(std::auto_ptr<planView::geometry_type> &geometry_info); + void load_param(std::unique_ptr<planView::geometry_type> &geometry_info); }; @@ -402,7 +402,7 @@ class CAdcGeoSpiral: public CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load_param(std::auto_ptr<planView::geometry_type> &geometry_info); + void load_param(std::unique_ptr<planView::geometry_type> &geometry_info); }; @@ -528,7 +528,7 @@ class CAdcGeoArc: public CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load_param(std::auto_ptr<planView::geometry_type> &geometry_info); + void load_param(std::unique_ptr<planView::geometry_type> &geometry_info); }; @@ -669,7 +669,7 @@ class CAdcGeoPoly3: public CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load_param(std::auto_ptr<planView::geometry_type> &geometry_info); + void load_param(std::unique_ptr<planView::geometry_type> &geometry_info); }; @@ -806,6 +806,6 @@ class CAdcGeoParamPoly3: public CAdcGeometry * \param geometry_info The objects generated with XSD. * */ - void load_param(std::auto_ptr<planView::geometry_type> &geometry_info); + void load_param(std::unique_ptr<planView::geometry_type> &geometry_info); }; -#endif \ No newline at end of file +#endif diff --git a/include/adc_object.h b/include/adc_object.h index f73774e205ff07d14eb2d4e158a301bd10264517..65492234afd4270a9af65842a5f659b65dc66883 100644 --- a/include/adc_object.h +++ b/include/adc_object.h @@ -278,7 +278,7 @@ class CAdcObject * \param object_info The object generated with XSD. * */ - void load(std::auto_ptr<objects::object_type> &object_info); + void load(std::unique_ptr<objects::object_type> &object_info); }; #endif diff --git a/include/adc_road.h b/include/adc_road.h index b0cf8a66701137f0b78e506f9f7d95eac79de695..b19be20fc2c9de7b0b76b7ba0817ec29c592d162 100644 --- a/include/adc_road.h +++ b/include/adc_road.h @@ -205,7 +205,7 @@ class CAdcRoad * \param road_info The objects generated with XSD. * */ - void load(std::auto_ptr<OpenDRIVE::road_type> &road_info); + void load(std::unique_ptr<OpenDRIVE::road_type> &road_info); }; #endif diff --git a/include/adc_signals.h b/include/adc_signals.h index d1347b60bf611e536373a568899e3d0707ea857d..5e02050aadd74333e9d1d89f1d71be0a85ad885e 100644 --- a/include/adc_signals.h +++ b/include/adc_signals.h @@ -205,7 +205,7 @@ class CAdcSignals * \param signal_info The objects generated with XSD. * */ - void load(std::auto_ptr<signals::signal_type> &signal_info); + void load(std::unique_ptr<signals::signal_type> &signal_info); }; #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 513a54beb7aea38ca81df4022bd3c75ee975dce0..48007ea2e824c3409a6a29dbefb1d80438a684c9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,4 +1,5 @@ # driver source files +SET(CMAKE_CXX_STANDARD 11) SET(sources opendrive_to_gazebo.cpp adc_circuit.cpp adc_road.cpp adc_geometries.cpp adc_signals.cpp adc_object.cpp) # application header files SET(headers ../include/opendrive_to_gazebo.h ../include/adc_circuit.h ../include/adc_road.h ../include/adc_geometries.h ../include/adc_signals.h ../include/adc_object.h) diff --git a/src/adc_circuit.cpp b/src/adc_circuit.cpp index aa320b392ab8df6ac9460d4b858e21e5f9d2224c..cf7b6a08841825c7b78c789fb594c9e12561b9b2 100644 --- a/src/adc_circuit.cpp +++ b/src/adc_circuit.cpp @@ -101,14 +101,14 @@ void CAdcCircuit::generate_spawn_launch_files(std::string &dir) objects_out_file.close(); } -void CAdcCircuit::load(std::auto_ptr<OpenDRIVE> &open_drive) +void CAdcCircuit::load(std::unique_ptr<OpenDRIVE> &open_drive) { ////////////////// Access road atributes for (OpenDRIVE::road_iterator road_it(open_drive->road().begin()); road_it != open_drive->road().end(); ++road_it) { CAdcRoad *road = new CAdcRoad(); - std::auto_ptr<OpenDRIVE::road_type> road_info(new OpenDRIVE::road_type(*road_it)); + std::unique_ptr<OpenDRIVE::road_type> road_info(new OpenDRIVE::road_type(*road_it)); road->load(road_info); add_road(road); } -} \ No newline at end of file +} diff --git a/src/adc_geometries.cpp b/src/adc_geometries.cpp index 7875ae76430737e365744bbd2e3f2ba13421d5fa..3a351000ff956107c28427fa0f731103191ca82a 100644 --- a/src/adc_geometries.cpp +++ b/src/adc_geometries.cpp @@ -75,7 +75,7 @@ void CAdcGeometry::debug(void) debug_param(); } -void CAdcGeometry::load(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeometry::load(std::unique_ptr<planView::geometry_type> &geometry_info) { this->min_s = (geometry_info->s().present() ? geometry_info->s().get() : 0.0); this->max_s = min_s + (geometry_info->length().present() ? geometry_info->length().get() : 0.0); @@ -141,7 +141,7 @@ void CAdcGeoLine::debug_param(void) } -void CAdcGeoLine::load_param(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeoLine::load_param(std::unique_ptr<planView::geometry_type> &geometry_info) { } @@ -212,7 +212,7 @@ void CAdcGeoSpiral::debug_param(void) std::cout << " params: start_curvature = " << this->curv_start << ", end_curvature = " << this->curv_end << std::endl; } -void CAdcGeoSpiral::load_param(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeoSpiral::load_param(std::unique_ptr<planView::geometry_type> &geometry_info) { this->curv_start = (geometry_info->spiral().get().curvStart().present() ? geometry_info->spiral().get().curvStart().get() : 0.0); this->curv_end = (geometry_info->spiral().get().curvEnd().present() ? geometry_info->spiral().get().curvEnd().get() : 0.0); @@ -280,7 +280,7 @@ void CAdcGeoArc::debug_param(void) std::cout << " params: curvature = " << this->curvature << std::endl; } -void CAdcGeoArc::load_param(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeoArc::load_param(std::unique_ptr<planView::geometry_type> &geometry_info) { this->curvature = (geometry_info->arc().get().curvature().present() ? geometry_info->arc().get().curvature().get() : 0.0); } @@ -363,7 +363,7 @@ void CAdcGeoPoly3::debug_param(void) std::cout << " params: a = " << this->param.a << ", b = " << this->param.b << ", c = " << this->param.c << ", d = " << this->param.d << std::endl; } -void CAdcGeoPoly3::load_param(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeoPoly3::load_param(std::unique_ptr<planView::geometry_type> &geometry_info) { this->param.a = (geometry_info->poly3().get().a().present() ? geometry_info->poly3().get().a().get() : 0.0); this->param.b = (geometry_info->poly3().get().b().present() ? geometry_info->poly3().get().b().get() : 0.0); @@ -485,7 +485,7 @@ void CAdcGeoParamPoly3::debug_param(void) std::cout << " V params: a = " << this->v_param.a << ", b = " << this->v_param.b << ", c = " << this->v_param.c << ", d = " << this->v_param.d << std::endl; } -void CAdcGeoParamPoly3::load_param(std::auto_ptr<planView::geometry_type> &geometry_info) +void CAdcGeoParamPoly3::load_param(std::unique_ptr<planView::geometry_type> &geometry_info) { this->u_param.a = (geometry_info->paramPoly3().get().aU().present() ? geometry_info->paramPoly3().get().aU().get() : 0.0); this->u_param.b = (geometry_info->paramPoly3().get().bU().present() ? geometry_info->paramPoly3().get().bU().get() : 0.0); diff --git a/src/adc_object.cpp b/src/adc_object.cpp index 12bbb0b04d1667c3940bb0883e7b7677c0555948..65419ffd944bb6a563cd3f45753aaed282ba6c05 100644 --- a/src/adc_object.cpp +++ b/src/adc_object.cpp @@ -69,16 +69,16 @@ CAdcObject::CAdcObject(const CAdcObject & object) this->repeat = object.repeat; std::vector<std::vector<Object_corner> >().swap(this->corners); - for (int i = 0; i < object.corners.size(); i++) + for (unsigned int i = 0; i < object.corners.size(); i++) { std::vector<Object_corner> corner_aux; - for (int j = 0; j < object.corners[i].size(); j++) + for (unsigned int j = 0; j < object.corners[i].size(); j++) corner_aux.push_back(object.corners[i][j]); this->corners.push_back(corner_aux); } std::vector<Object_repeat>().swap(this->repeat_info); - for (int i = 0; i < object.repeat_info.size(); i++) + for (unsigned int i = 0; i < object.repeat_info.size(); i++) this->repeat_info.push_back(object.repeat_info[i]); } @@ -145,10 +145,10 @@ CAdcObject::CAdcObject(int id, double s, double t, double heading, std::string t this->outline = true; this->repeat = false; std::vector<std::vector<Object_corner> >().swap(this->corners); - for (int i = 0; i < corners.size(); i++) + for (unsigned int i = 0; i < corners.size(); i++) { std::vector<Object_corner> corner_aux; - for (int j = 0; j < corners[i].size(); j++) + for (unsigned int j = 0; j < corners[i].size(); j++) corner_aux.push_back(corners[i][j]); this->corners.push_back(corner_aux); } @@ -174,15 +174,15 @@ void CAdcObject::operator = (const CAdcObject &object) this->outline = object.outline; this->repeat = object.repeat; std::vector<std::vector<Object_corner> >().swap(this->corners); - for (int i = 0; i < object.corners.size(); i++) + for (unsigned int i = 0; i < object.corners.size(); i++) { std::vector<Object_corner> corner_aux; - for (int j = 0; j < object.corners[i].size(); j++) + for (unsigned int j = 0; j < object.corners[i].size(); j++) corner_aux.push_back(object.corners[i][j]); this->corners.push_back(corner_aux); } std::vector<Object_repeat>().swap(this->repeat_info); - for (int i = 0; i < object.repeat_info.size(); i++) + for (unsigned int i = 0; i < object.repeat_info.size(); i++) this->repeat_info.push_back(object.repeat_info[i]); } @@ -210,10 +210,10 @@ void CAdcObject::get_corners(std::vector<std::vector<Object_corner> > &corners) { std::vector<std::vector<Object_corner> >().swap(corners); //resize better than push_back - for (int i = 0; i < this->corners.size(); i++) + for (unsigned int i = 0; i < this->corners.size(); i++) { std::vector<Object_corner> corner_aux; - for (int j = 0; j < this->corners[i].size(); j++) + for (unsigned int j = 0; j < this->corners[i].size(); j++) corner_aux.push_back(this->corners[i][j]); corners.push_back(corner_aux); } @@ -232,7 +232,7 @@ bool CAdcObject::is_repeat(void) void CAdcObject::get_repeat_info(std::vector<Object_repeat> &repeat_info) { std::vector<Object_repeat>().swap(this->repeat_info); - for (int i = 0; i < this->repeat_info.size(); i++) + for (unsigned int i = 0; i < this->repeat_info.size(); i++) repeat_info.push_back(this->repeat_info[i]); } @@ -252,10 +252,10 @@ void CAdcObject::debug(bool world_pose) std::cout << " world pose: x = " << this->world_x << ", y = " << this->world_y << ", yaw = " << this->world_yaw << std::endl; if (this->outline) { - for (int i = 0; i < this->corners.size(); i++) + for (unsigned int i = 0; i < this->corners.size(); i++) { std::cout << " Subobject_" << i << ":" << std::endl; - for (int j = 0; j < this->corners[i].size(); j++) + for (unsigned int j = 0; j < this->corners[i].size(); j++) { std::cout << " corner_" << j << ": s = " << this->corners[i][j].s << ", t = " << this->corners[i][j].t << ", height = " << this->corners[i][j].height << std::endl; if (world_pose) @@ -266,7 +266,7 @@ void CAdcObject::debug(bool world_pose) if (this->repeat) { int count = 0; - for (int i = 0; i < this->repeat_info.size(); i++) + for (unsigned int i = 0; i < this->repeat_info.size(); i++) { for (int j = 0; j < this->repeat_info[i].n; j++) { @@ -315,7 +315,7 @@ void CAdcObject::append_objects_spawn(std::string &filename) out_file.close(); } -void CAdcObject::load(std::auto_ptr<objects::object_type> &object_info) +void CAdcObject::load(std::unique_ptr<objects::object_type> &object_info) { std::stringstream ss(object_info->id().get()); ss >> this->id; @@ -401,4 +401,4 @@ void CAdcObject::load(std::auto_ptr<objects::object_type> &object_info) this->repeat_info.push_back(repeat_aux); } } -} \ No newline at end of file +} diff --git a/src/adc_road.cpp b/src/adc_road.cpp index 18bed174f256829f259cd25ba7a5c3854d36fbdb..230f438a12fda7435c431b0f009ab0de69f29965 100644 --- a/src/adc_road.cpp +++ b/src/adc_road.cpp @@ -227,7 +227,7 @@ void CAdcRoad::append_objects_spawn(std::string &filename) this->objects[i]->append_objects_spawn(filename); } -void CAdcRoad::load(std::auto_ptr<OpenDRIVE::road_type> &road_info) +void CAdcRoad::load(std::unique_ptr<OpenDRIVE::road_type> &road_info) { std::stringstream ss(road_info->id().get()); ss >> this->id; @@ -240,35 +240,35 @@ void CAdcRoad::load(std::auto_ptr<OpenDRIVE::road_type> &road_info) if (geo_it->line().present()) { CAdcGeoLine *line = new CAdcGeoLine(); - std::auto_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); + std::unique_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); line->load(geo_info); add_geometry(line); } else if (geo_it->spiral().present()) { CAdcGeoSpiral *spi = new CAdcGeoSpiral(); - std::auto_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); + std::unique_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); spi->load(geo_info); add_geometry(spi); } else if (geo_it->arc().present()) { CAdcGeoArc *arc = new CAdcGeoArc(); - std::auto_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); + std::unique_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); arc->load(geo_info); add_geometry(arc); } else if (geo_it->poly3().present()) { CAdcGeoPoly3 *poly3 = new CAdcGeoPoly3(); - std::auto_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); + std::unique_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); poly3->load(geo_info); add_geometry(poly3); } else if (geo_it->paramPoly3().present()) { CAdcGeoParamPoly3 *parampoly3 = new CAdcGeoParamPoly3(); - std::auto_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); + std::unique_ptr<planView::geometry_type> geo_info(new planView::geometry_type(*geo_it)); parampoly3->load(geo_info); add_geometry(parampoly3); } @@ -280,7 +280,7 @@ void CAdcRoad::load(std::auto_ptr<OpenDRIVE::road_type> &road_info) for (signals::signal_iterator signal_it(road_info->signals().get().signal().begin()); signal_it != road_info->signals().get().signal().end(); ++signal_it) { CAdcSignals *sign = new CAdcSignals(); - std::auto_ptr<signals::signal_type> signal_info(new signals::signal_type(*signal_it)); + std::unique_ptr<signals::signal_type> signal_info(new signals::signal_type(*signal_it)); sign->load(signal_info); add_signal(sign); } @@ -292,9 +292,9 @@ void CAdcRoad::load(std::auto_ptr<OpenDRIVE::road_type> &road_info) for (objects::object_iterator object_it(road_info->objects().get().object().begin()); object_it != road_info->objects().get().object().end(); ++object_it) { CAdcObject *obj = new CAdcObject(); - std::auto_ptr<objects::object_type> object_info(new objects::object_type(*object_it)); + std::unique_ptr<objects::object_type> object_info(new objects::object_type(*object_it)); obj->load(object_info); add_object(obj); } } -} \ No newline at end of file +} diff --git a/src/adc_signals.cpp b/src/adc_signals.cpp index 0e7f176590b00487fd05b61d53d33309930cad0c..0bbee83ebc0782fa41239becf229b7333fac19e5 100644 --- a/src/adc_signals.cpp +++ b/src/adc_signals.cpp @@ -217,7 +217,7 @@ void CAdcSignals::append_sign_spawn(std::string &filename) out_file.close(); } -void CAdcSignals::load(std::auto_ptr<signals::signal_type> &signal_info) +void CAdcSignals::load(std::unique_ptr<signals::signal_type> &signal_info) { std::stringstream ss(signal_info->id().get()); ss >> this->id; @@ -232,4 +232,4 @@ void CAdcSignals::load(std::auto_ptr<signals::signal_type> &signal_info) if (signal_info->orientation().present() && signal_info->orientation().get() == orientation::cxx_1) reverse = true; this->heading += (reverse != DEFAULT_REVERSE_ORIENTATION ? M_PI : 0.0); -} \ No newline at end of file +} diff --git a/src/opendrive_to_gazebo.cpp b/src/opendrive_to_gazebo.cpp index 5ddf4768243b04a586283e12358e50d6993d4e52..5bc308b8f9fca8dd0ca99bdcdd897a70ddd94ba6 100644 --- a/src/opendrive_to_gazebo.cpp +++ b/src/opendrive_to_gazebo.cpp @@ -30,7 +30,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug) { // try to open the specified file try{ - std::auto_ptr<OpenDRIVE> open_drive(OpenDRIVE_(filename.c_str(), xml_schema::flags::dont_validate)); + std::unique_ptr<OpenDRIVE> open_drive(OpenDRIVE_(filename.c_str(), xml_schema::flags::dont_validate)); this->adc_circuit.load(open_drive); diff --git a/src/xml/CMakeLists.txt b/src/xml/CMakeLists.txt index 7f45af687503c4883281e597e1d4f3ece3d5817d..c2bf844af25b7e1ddef8d7e80338e9cb283169db 100644 --- a/src/xml/CMakeLists.txt +++ b/src/xml/CMakeLists.txt @@ -36,7 +36,7 @@ IF(XSD_FOUND) ADD_CUSTOM_TARGET(xsd_files_gen DEPENDS ${XSD_SOURCES_INT}) ADD_CUSTOM_COMMAND( OUTPUT ${XSD_SOURCES_INT} - COMMAND xsdcxx cxx-tree --generate-serialization --reserved-name access=parkingSpace_access --reserved-name link=lane_link ${XSD_FILES} + COMMAND xsdcxx cxx-tree --std c++11 --generate-serialization --reserved-name access=parkingSpace_access --reserved-name link=lane_link ${XSD_FILES} WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} DEPENDS ${XSD_PATH_FILES} COMMENT "Parsing the xml template file ${XSD_FILES}")