Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
O
opendrive_to_gazebo
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
mobile_robotics
ADC
libraries
opendrive_to_gazebo
Commits
ce92e0af
Commit
ce92e0af
authored
5 years ago
by
Alejandro Lopez Gestoso
Browse files
Options
Downloads
Patches
Plain Diff
Adapted to road pointers
parent
3becee28
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
include/adc_circuit.h
+2
-2
2 additions, 2 deletions
include/adc_circuit.h
src/adc_circuit.cpp
+8
-6
8 additions, 6 deletions
src/adc_circuit.cpp
src/open_drive_format.cpp
+7
-7
7 additions, 7 deletions
src/open_drive_format.cpp
with
17 additions
and
15 deletions
include/adc_circuit.h
+
2
−
2
View file @
ce92e0af
...
...
@@ -18,7 +18,7 @@
class
CAdcCircuit
{
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.
public:
/**
...
...
@@ -47,7 +47,7 @@ class CAdcCircuit
* \param road The road to add.
*
*/
void
add_road
(
CAdcRoad
&
road
);
void
add_road
(
CAdcRoad
*
&
road
);
/**
* \brief Function to print each road info.
...
...
This diff is collapsed.
Click to expand it.
src/adc_circuit.cpp
+
8
−
6
View file @
ce92e0af
...
...
@@ -16,10 +16,12 @@ CAdcCircuit::~CAdcCircuit()
void
CAdcCircuit
::
clear_roads
(
void
)
{
std
::
vector
<
CAdcRoad
>
().
swap
(
this
->
roads
);
for
(
unsigned
int
i
=
0
;
i
<
this
->
roads
.
size
();
i
++
)
delete
this
->
roads
[
i
];
std
::
vector
<
CAdcRoad
*>
().
swap
(
this
->
roads
);
}
void
CAdcCircuit
::
add_road
(
CAdcRoad
&
road
)
void
CAdcCircuit
::
add_road
(
CAdcRoad
*
&
road
)
{
this
->
roads
.
push_back
(
road
);
}
...
...
@@ -27,20 +29,20 @@ void CAdcCircuit::add_road(CAdcRoad &road)
void
CAdcCircuit
::
debug
(
void
)
{
for
(
unsigned
int
i
=
0
;
i
<
this
->
roads
.
size
();
i
++
)
this
->
roads
[
i
]
.
debug
();
this
->
roads
[
i
]
->
debug
();
}
void
CAdcCircuit
::
calculate_signals_pose
(
bool
debug
)
{
for
(
unsigned
int
i
=
0
;
i
<
this
->
roads
.
size
();
i
++
)
this
->
roads
[
i
]
.
calculate_signals_pose
(
debug
);
this
->
roads
[
i
]
->
calculate_signals_pose
(
debug
);
}
void
CAdcCircuit
::
get_signals
(
std
::
vector
<
CAdcSignals
*>
&
signals
)
{
std
::
vector
<
CAdcSignals
*>
().
swap
(
signals
);
for
(
unsigned
int
i
=
0
;
i
<
this
->
roads
.
size
();
i
++
)
this
->
roads
[
i
]
.
get_signals
(
signals
);
this
->
roads
[
i
]
->
get_signals
(
signals
);
}
void
CAdcCircuit
::
generate_spwan_launch_file
(
std
::
string
&
filename
)
...
...
@@ -62,7 +64,7 @@ void CAdcCircuit::generate_spwan_launch_file(std::string &filename)
//sign info
for
(
unsigned
int
i
=
0
;
i
<
this
->
roads
.
size
();
i
++
)
this
->
roads
[
i
]
.
append_signs_spawn
(
filename
);
this
->
roads
[
i
]
->
append_signs_spawn
(
filename
);
//End
oss
.
str
(
""
);
...
...
This diff is collapsed.
Click to expand it.
src/open_drive_format.cpp
+
7
−
7
View file @
ce92e0af
...
...
@@ -39,7 +39,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
ss
>>
road_id
;
double
road_length
=
road_it
->
length
().
get
();
std
::
string
name
=
road_it
->
name
().
get
();
CAdcRoad
r
oad
(
road_id
,
road_length
,
name
);
CAdcRoad
*
road
=
new
CAdcR
oad
(
road_id
,
road_length
,
name
);
///////////////////// link atributes
...
...
@@ -54,20 +54,20 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
if
(
geo_it
->
line
().
present
())
{
CAdcGeoLine
*
line
=
new
CAdcGeoLine
(
min_s
,
max_s
,
x
,
y
,
heading
);
road
.
add_geometry
(
line
);
road
->
add_geometry
(
line
);
}
else
if
(
geo_it
->
spiral
().
present
())
{
double
curv_start
=
(
geo_it
->
spiral
().
get
().
curvStart
().
present
()
?
geo_it
->
spiral
().
get
().
curvStart
().
get
()
:
0.0
);
double
curv_end
=
(
geo_it
->
spiral
().
get
().
curvEnd
().
present
()
?
geo_it
->
spiral
().
get
().
curvEnd
().
get
()
:
0.0
);
CAdcGeoSpiral
*
spi
=
new
CAdcGeoSpiral
(
min_s
,
max_s
,
x
,
y
,
heading
,
curv_start
,
curv_end
);
road
.
add_geometry
(
spi
);
road
->
add_geometry
(
spi
);
}
else
if
(
geo_it
->
arc
().
present
())
{
double
curvature
=
(
geo_it
->
arc
().
get
().
curvature
().
present
()
?
geo_it
->
arc
().
get
().
curvature
().
get
()
:
0.0
);
CAdcGeoArc
*
arc
=
new
CAdcGeoArc
(
min_s
,
max_s
,
x
,
y
,
heading
,
curvature
);
road
.
add_geometry
(
arc
);
road
->
add_geometry
(
arc
);
}
else
if
(
geo_it
->
poly3
().
present
())
{
...
...
@@ -77,7 +77,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
param
.
c
=
(
geo_it
->
poly3
().
get
().
c
().
present
()
?
geo_it
->
poly3
().
get
().
c
().
get
()
:
0.0
);
param
.
d
=
(
geo_it
->
poly3
().
get
().
d
().
present
()
?
geo_it
->
poly3
().
get
().
d
().
get
()
:
0.0
);
CAdcGeoPoly3
*
poly3
=
new
CAdcGeoPoly3
(
min_s
,
max_s
,
x
,
y
,
heading
,
param
);
road
.
add_geometry
(
poly3
);
road
->
add_geometry
(
poly3
);
}
else
if
(
geo_it
->
paramPoly3
().
present
())
{
...
...
@@ -95,7 +95,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
if
(
geo_it
->
paramPoly3
().
get
().
pRange
().
present
()
&&
geo_it
->
paramPoly3
().
get
().
pRange
().
get
()
==
pRange
::
arcLength
)
normalized
=
false
;
CAdcGeoParamPoly3
*
parampoly3
=
new
CAdcGeoParamPoly3
(
min_s
,
max_s
,
x
,
y
,
heading
,
u_param
,
v_param
,
normalized
);
road
.
add_geometry
(
parampoly3
);
road
->
add_geometry
(
parampoly3
);
}
}
...
...
@@ -118,7 +118,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
if
(
signal_it
->
orientation
().
present
()
&&
signal_it
->
orientation
().
get
()
==
orientation
::
cxx_1
)
reverse
=
true
;
CAdcSignals
*
sign
=
new
CAdcSignals
(
id
,
s
,
t
,
heading
,
type
,
sub_type
,
value
,
text
,
reverse
);
road
.
add_signal
(
sign
);
road
->
add_signal
(
sign
);
}
}
this
->
adc_circuit
.
add_road
(
road
);
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment