Skip to content
Snippets Groups Projects
Commit e40d31f2 authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Added road_sclae as argument

parent 8a085494
No related branches found
No related tags found
1 merge request!1Opendrive lib
...@@ -13,7 +13,6 @@ ...@@ -13,7 +13,6 @@
#define SIGNS_LAUNCH_FILE "spawn_signs.launch" #define SIGNS_LAUNCH_FILE "spawn_signs.launch"
#define OBJECTS_LAUNCH_FILE "spawn_objects.launch" #define OBJECTS_LAUNCH_FILE "spawn_objects.launch"
#define ROAD_SCALE 10
/** /**
* \class CAdcCircuit * \class CAdcCircuit
...@@ -27,6 +26,7 @@ class CAdcCircuit ...@@ -27,6 +26,7 @@ class CAdcCircuit
{ {
private: private:
std::vector<CAdcRoad*> roads;///< Variable to store an access each road data. std::vector<CAdcRoad*> roads;///< Variable to store an access each road data.
double road_scale;///< The scale of the road to divide by the objects and signals poses.
/** /**
* \brief Function to add a road. * \brief Function to add a road.
...@@ -108,6 +108,14 @@ class CAdcCircuit ...@@ -108,6 +108,14 @@ class CAdcCircuit
* *
*/ */
void load(std::unique_ptr<OpenDRIVE> &open_drive); void load(std::unique_ptr<OpenDRIVE> &open_drive);
/**
* \brief Function to set road_Scale.
*
* \param road_scale The scale of the road to divide by the objects and signals poses.
*
*/
void set_road_scale(double road_scale=1.0);
}; };
#endif #endif
...@@ -18,9 +18,11 @@ class COpenDriveFormat ...@@ -18,9 +18,11 @@ class COpenDriveFormat
public: public:
/** /**
* \brief Default constructor. * \brief Default constructor.
*
* \param road_scale The scale of the road to divide by the objects and signals poses.
* *
*/ */
COpenDriveFormat(); COpenDriveFormat(double road_scale);
/** /**
* \brief Function to store on adc_circuit the useful information of a .xodr file. * \brief Function to store on adc_circuit the useful information of a .xodr file.
......
...@@ -6,11 +6,12 @@ ...@@ -6,11 +6,12 @@
CAdcCircuit::CAdcCircuit() CAdcCircuit::CAdcCircuit()
{ {
this->road_scale = 1.0;
} }
CAdcCircuit::~CAdcCircuit() CAdcCircuit::~CAdcCircuit()
{ {
this->road_scale = 1.0;
clear_roads(); clear_roads();
} }
...@@ -77,11 +78,11 @@ void CAdcCircuit::generate_spawn_launch_files(std::string &dir) ...@@ -77,11 +78,11 @@ void CAdcCircuit::generate_spawn_launch_files(std::string &dir)
//sign info //sign info
for (unsigned int i = 0; i < this->roads.size(); i++) for (unsigned int i = 0; i < this->roads.size(); i++)
this->roads[i]->append_signs_spawn(signs_filename, ROAD_SCALE); this->roads[i]->append_signs_spawn(signs_filename, this->road_scale);
//object info //object info
for (unsigned int i = 0; i < this->roads.size(); i++) for (unsigned int i = 0; i < this->roads.size(); i++)
this->roads[i]->append_objects_spawn(objects_filename, ROAD_SCALE); this->roads[i]->append_objects_spawn(objects_filename, this->road_scale);
//End //End
oss.str(""); oss.str("");
...@@ -112,3 +113,8 @@ void CAdcCircuit::load(std::unique_ptr<OpenDRIVE> &open_drive) ...@@ -112,3 +113,8 @@ void CAdcCircuit::load(std::unique_ptr<OpenDRIVE> &open_drive)
add_road(road); add_road(road);
} }
} }
void CAdcCircuit::set_road_scale(double road_scale)
{
this->road_scale = road_scale;
}
...@@ -3,25 +3,43 @@ ...@@ -3,25 +3,43 @@
#include <iostream> #include <iostream>
#include <vector> #include <vector>
#include "adc_signals.h" #include "adc_signals.h"
#include <stdexcept>
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
if (argc != 3) if (argc != 3 && argc != 4)
{ {
std::cerr << "ERROR: Missing input arguments.The usage of this program is:" << std::endl; std::cerr << "ERROR: Missing input arguments.The usage of this program is:" << std::endl;
std::cerr << "opendrive_to_gazebo_test <xodr input file path> <output launch file direcctory>" << std::endl; std::cerr << "opendrive_to_gazebo_test <xodr input file path> <output launch file direcctory> [optional]<road_scale>" << std::endl;
return -1; return -1;
} }
COpenDriveFormat open_drive_format;
std::string xml_file = argv[1]; std::string xml_file = argv[1];
std::string launch_dir = argv[2]; std::string launch_dir = argv[2];
double road_scale;
int slash_index, point_index; int slash_index, point_index;
slash_index = xml_file.find_last_of("/"); slash_index = xml_file.find_last_of("/");
point_index = xml_file.find_last_of("."); point_index = xml_file.find_last_of(".");
std::string file_name = xml_file.substr(xml_file.find_last_of("/")+1, point_index - slash_index -1); std::string file_name = xml_file.substr(xml_file.find_last_of("/")+1, point_index - slash_index -1);
std::cout << "file name " << file_name << std::endl;
std::string launch_base_name = launch_dir + file_name; std::string launch_base_name = launch_dir + file_name;
if (argc == 4)
{
try
{
road_scale = std::stod(argv[3]);
}
catch (const std::invalid_argument& e)
{
std::cerr << "ERROR: Invalid road_scale, it must be a double: " << e.what() << std::endl;
return -1;
}
}
else
{
road_scale = 1.0;
}
COpenDriveFormat open_drive_format(road_scale);
try try
{ {
open_drive_format.load(xml_file, false); open_drive_format.load(xml_file, false);
......
...@@ -16,8 +16,9 @@ ...@@ -16,8 +16,9 @@
#include "xml/OpenDRIVE_1.4H.hxx" #include "xml/OpenDRIVE_1.4H.hxx"
#endif #endif
COpenDriveFormat::COpenDriveFormat() COpenDriveFormat::COpenDriveFormat(double road_scale)
{ {
adc_circuit.set_road_scale(road_scale);
} }
void COpenDriveFormat::load(std::string &filename, bool debug) void COpenDriveFormat::load(std::string &filename, bool debug)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment