@@ -139,7 +139,7 @@ RouteHandler::RouteHandler(const LaneletMapBin & map_msg)
139
139
route_ptr_ = nullptr ;
140
140
}
141
141
142
- void RouteHandler::setMap (const HADMapBin & map_msg, const bool & is_enable_differantial_lanelet )
142
+ void RouteHandler::setMap (const HADMapBin & map_msg, const bool & is_enable_differential_lanelet )
143
143
{
144
144
lanelet_map_ptr_ = std::make_shared<lanelet::LaneletMap>();
145
145
lanelet::utils::conversion::fromBinMsg (
@@ -161,7 +161,7 @@ void RouteHandler::setMap(const HADMapBin & map_msg, const bool & is_enable_diff
161
161
is_map_msg_ready_ = true ;
162
162
is_handler_ready_ = false ;
163
163
164
- setLaneletsFromRouteMsg (is_enable_differantial_lanelet );
164
+ setLaneletsFromRouteMsg (is_enable_differential_lanelet );
165
165
}
166
166
167
167
bool RouteHandler::isRouteLooped (const RouteSections & route_sections)
@@ -179,7 +179,7 @@ bool RouteHandler::isRouteLooped(const RouteSections & route_sections)
179
179
}
180
180
181
181
void RouteHandler::setRoute (
182
- const LaneletRoute & route_msg, const bool & is_enable_differantial_lanelet )
182
+ const LaneletRoute & route_msg, const bool & is_enable_differential_lanelet )
183
183
{
184
184
if (!isRouteLooped (route_msg.segments )) {
185
185
// if get not modified route but new route, reset original start pose
@@ -189,7 +189,7 @@ void RouteHandler::setRoute(
189
189
}
190
190
route_ptr_ = std::make_shared<LaneletRoute>(route_msg);
191
191
is_handler_ready_ = false ;
192
- setLaneletsFromRouteMsg (is_enable_differantial_lanelet );
192
+ setLaneletsFromRouteMsg (is_enable_differential_lanelet );
193
193
} else {
194
194
RCLCPP_ERROR (
195
195
logger_,
@@ -312,14 +312,14 @@ void RouteHandler::clearRoute()
312
312
is_handler_ready_ = false ;
313
313
}
314
314
315
- void RouteHandler::setLaneletsFromRouteMsg (const bool & is_enable_differantial_lanelet )
315
+ void RouteHandler::setLaneletsFromRouteMsg (const bool & is_enable_differential_lanelet )
316
316
{
317
317
if (!route_ptr_ || !is_map_msg_ready_) {
318
318
return ;
319
319
}
320
320
route_lanelets_.clear ();
321
321
preferred_lanelets_.clear ();
322
- if (!is_enable_differantial_lanelet ) {
322
+ if (!is_enable_differential_lanelet ) {
323
323
const bool is_route_valid = lanelet::utils::route::isRouteValid (*route_ptr_, lanelet_map_ptr_);
324
324
if (!is_route_valid) {
325
325
return ;
@@ -342,7 +342,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
342
342
preferred_lanelets_.push_back (llt);
343
343
}
344
344
} catch (const std::exception & e) {
345
- if (!is_enable_differantial_lanelet ) {
345
+ if (!is_enable_differential_lanelet ) {
346
346
std::cerr
347
347
<< e.what ()
348
348
<< " . Maybe the loaded route was created on a different Map from the current one. "
@@ -367,7 +367,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
367
367
const auto & llt = lanelet_map_ptr_->laneletLayer .get (id);
368
368
goal_lanelets_.push_back (llt);
369
369
} catch (const std::exception & e) {
370
- if (!is_enable_differantial_lanelet ) {
370
+ if (!is_enable_differential_lanelet ) {
371
371
std::cerr
372
372
<< e.what ()
373
373
<< " . Maybe the loaded route was created on a different Map from the current one. "
@@ -388,7 +388,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
388
388
const auto & llt = lanelet_map_ptr_->laneletLayer .get (id);
389
389
start_lanelets_.push_back (llt);
390
390
} catch (const std::exception & e) {
391
- if (!is_enable_differantial_lanelet ) {
391
+ if (!is_enable_differential_lanelet ) {
392
392
std::cerr
393
393
<< e.what ()
394
394
<< " . Maybe the loaded route was created on a different Map from the current one. "
0 commit comments