@@ -139,7 +139,7 @@ RouteHandler::RouteHandler(const HADMapBin & 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 (
@@ -163,7 +163,7 @@ void RouteHandler::setMap(const HADMapBin & map_msg, const bool & is_enable_diff
163
163
is_map_msg_ready_ = true ;
164
164
is_handler_ready_ = false ;
165
165
166
- setLaneletsFromRouteMsg (is_enable_differantial_lanelet );
166
+ setLaneletsFromRouteMsg (is_enable_differential_lanelet );
167
167
}
168
168
169
169
bool RouteHandler::isRouteLooped (const RouteSections & route_sections)
@@ -181,7 +181,7 @@ bool RouteHandler::isRouteLooped(const RouteSections & route_sections)
181
181
}
182
182
183
183
void RouteHandler::setRoute (
184
- const LaneletRoute & route_msg, const bool & is_enable_differantial_lanelet )
184
+ const LaneletRoute & route_msg, const bool & is_enable_differential_lanelet )
185
185
{
186
186
if (!isRouteLooped (route_msg.segments )) {
187
187
// if get not modified route but new route, reset original start pose
@@ -191,7 +191,7 @@ void RouteHandler::setRoute(
191
191
}
192
192
route_ptr_ = std::make_shared<LaneletRoute>(route_msg);
193
193
is_handler_ready_ = false ;
194
- setLaneletsFromRouteMsg (is_enable_differantial_lanelet );
194
+ setLaneletsFromRouteMsg (is_enable_differential_lanelet );
195
195
} else {
196
196
RCLCPP_ERROR (
197
197
logger_,
@@ -314,14 +314,14 @@ void RouteHandler::clearRoute()
314
314
is_handler_ready_ = false ;
315
315
}
316
316
317
- void RouteHandler::setLaneletsFromRouteMsg (const bool & is_enable_differantial_lanelet )
317
+ void RouteHandler::setLaneletsFromRouteMsg (const bool & is_enable_differential_lanelet )
318
318
{
319
319
if (!route_ptr_ || !is_map_msg_ready_) {
320
320
return ;
321
321
}
322
322
route_lanelets_.clear ();
323
323
preferred_lanelets_.clear ();
324
- if (!is_enable_differantial_lanelet ) {
324
+ if (!is_enable_differential_lanelet ) {
325
325
const bool is_route_valid = lanelet::utils::route::isRouteValid (*route_ptr_, lanelet_map_ptr_);
326
326
if (!is_route_valid) {
327
327
return ;
@@ -344,7 +344,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
344
344
preferred_lanelets_.push_back (llt);
345
345
}
346
346
} catch (const std::exception & e) {
347
- if (!is_enable_differantial_lanelet ) {
347
+ if (!is_enable_differential_lanelet ) {
348
348
std::cerr
349
349
<< e.what ()
350
350
<< " . Maybe the loaded route was created on a different Map from the current one. "
@@ -369,7 +369,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
369
369
const auto & llt = lanelet_map_ptr_->laneletLayer .get (id);
370
370
goal_lanelets_.push_back (llt);
371
371
} catch (const std::exception & e) {
372
- if (!is_enable_differantial_lanelet ) {
372
+ if (!is_enable_differential_lanelet ) {
373
373
std::cerr
374
374
<< e.what ()
375
375
<< " . Maybe the loaded route was created on a different Map from the current one. "
@@ -390,7 +390,7 @@ void RouteHandler::setLaneletsFromRouteMsg(const bool & is_enable_differantial_l
390
390
const auto & llt = lanelet_map_ptr_->laneletLayer .get (id);
391
391
start_lanelets_.push_back (llt);
392
392
} catch (const std::exception & e) {
393
- if (!is_enable_differantial_lanelet ) {
393
+ if (!is_enable_differential_lanelet ) {
394
394
std::cerr
395
395
<< e.what ()
396
396
<< " . Maybe the loaded route was created on a different Map from the current one. "
0 commit comments