Skip to content

Commit e87b2bd

Browse files
committed
Rename use_lane_level_specification_for_waypoints to use_lane_ids_for_routing
1 parent b712753 commit e87b2bd

File tree

4 files changed

+8
-8
lines changed

4 files changed

+8
-8
lines changed

openscenario/openscenario_interpreter/src/syntax/assign_route_action.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,8 @@ auto AssignRouteAction::start() -> void
8181
};
8282

8383
traffic_simulator::v2::RouteOption route_option;
84-
route_option.use_lane_level_specification_for_waypoints =
85-
get_from_parameter("RoutingAction.use_lane_level_specification_for_waypoints", false);
84+
route_option.use_lane_ids_for_routing =
85+
get_from_parameter("RoutingAction.use_lane_ids_for_routing", false);
8686

8787
for (const auto & actor : actors) {
8888
actor.apply([&](const auto & object) {

simulation/traffic_simulator/include/traffic_simulator/data_type/route_option.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ inline namespace v2
2424
struct RouteOption
2525
{
2626
bool allow_goal_modification = false;
27-
bool use_lane_level_specification_for_waypoints = false;
27+
bool use_lane_ids_for_routing = false;
2828
};
2929
} // namespace v2
3030

@@ -39,7 +39,7 @@ struct RouteOption
3939
{
4040
v2::RouteOption v2;
4141
v2.allow_goal_modification = allow_goal_modification;
42-
v2.use_lane_level_specification_for_waypoints = false;
42+
v2.use_lane_ids_for_routing = false;
4343
return v2;
4444
}
4545
};

simulation/traffic_simulator/src/entity/ego_entity.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -243,7 +243,7 @@ void EgoEntity::requestAssignRoute(
243243
const std::vector<CanonicalizedLaneletPose> & route,
244244
const traffic_simulator::RouteOption & option)
245245
{
246-
if (option.use_lane_level_specification_for_waypoints) {
246+
if (option.use_lane_ids_for_routing) {
247247
concealer::FieldOperatorApplication::RouteOption route_option;
248248
route_option.allow_goal_modification = option.allow_goal_modification;
249249

@@ -311,7 +311,7 @@ void EgoEntity::requestAssignRoute(
311311
const std::vector<geometry_msgs::msg::Pose> & route,
312312
const traffic_simulator::RouteOption & option)
313313
{
314-
if (option.use_lane_level_specification_for_waypoints) {
314+
if (option.use_lane_ids_for_routing) {
315315
std::vector<CanonicalizedLaneletPose> lanelet_poses;
316316
for (const auto & pose : route) {
317317
if (auto lanelet_pose = pose::toCanonicalizedLaneletPose(pose, false)) {
@@ -395,7 +395,7 @@ auto EgoEntity::requestReplanRoute(
395395
clearRoute();
396396
/*
397397
NOTE:
398-
This function does not support use_lane_level_specification_for_waypoints option.
398+
This function does not support use_lane_ids_for_routing option.
399399
The developers should consider manual override simulation to determine whether support it or not.
400400
*/
401401
{
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ OpenSCENARIO:
6767
- name: ''
6868
ParameterDeclarations:
6969
ParameterDeclaration:
70-
- name: RoutingAction.use_lane_level_specification_for_waypoints
70+
- name: RoutingAction.use_lane_ids_for_routing
7171
parameterType: boolean
7272
value: true
7373
Event:

0 commit comments

Comments
 (0)