Skip to content

Commit 78de185

Browse files
author
dkuenster
committed
mpc_local_planner: fix typos when reading footprint params
1 parent f3923a2 commit 78de185

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

mpc_local_planner/src/mpc_local_planner_ros.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -822,7 +822,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
822822
double radius;
823823
if (!nh->get_parameter(_name + "." + "footprint_model.radius", radius))
824824
{
825-
RCLCPP_ERROR_STREAM(_logger, "Footprint model 'circular' cannot be loaded for trajectory optimization, since param '/footprint_model/radius' does not exist. Using point-model instead.");
825+
RCLCPP_ERROR_STREAM(_logger, "Footprint model 'circular' cannot be loaded for trajectory optimization, since param '/footprint_model.radius' does not exist. Using point-model instead.");
826826
return std::make_shared<teb_local_planner::PointRobotFootprint>();
827827
}
828828
RCLCPP_INFO_STREAM(_logger, "Footprint model 'circular' (radius: " << radius << "m) loaded for trajectory optimization.");
@@ -833,9 +833,9 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
833833
if (model_name.compare("line") == 0)
834834
{
835835
// check parameters
836-
if (!nh->has_parameter(_name + "." + "footprint_model.line_start") || !nh->has_parameter(_name + "." + "footprint_model/line_end"))
836+
if (!nh->has_parameter(_name + "." + "footprint_model.line_start") || !nh->has_parameter(_name + "." + "footprint_model.line_end"))
837837
{
838-
RCLCPP_ERROR_STREAM(_logger, "Footprint model 'line' cannot be loaded for trajectory optimization, since param '/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
838+
RCLCPP_ERROR_STREAM(_logger, "Footprint model 'line' cannot be loaded for trajectory optimization, since param '/footprint_model.line_start' and/or '/footprint_model.line_end' do not exist. Using point-model instead.");
839839
return std::make_shared<teb_local_planner::PointRobotFootprint>();
840840
}
841841
// get line coordinates
@@ -845,7 +845,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
845845
if (line_start.size() != 2 || line_end.size() != 2)
846846
{
847847
RCLCPP_ERROR_STREAM(_logger,
848-
"Footprint model 'line' cannot be loaded for trajectory optimization, since param '/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
848+
"Footprint model 'line' cannot be loaded for trajectory optimization, since param '/footprint_model.line_start' and/or '/footprint_model.line_end' do not contain x and y coordinates (2D). Using point-model instead.");
849849
return std::make_shared<teb_local_planner::PointRobotFootprint>();
850850
}
851851

@@ -862,7 +862,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
862862
if (!nh->has_parameter(_name + "." + "footprint_model.front_offset") || !nh->has_parameter(_name + "." + "footprint_model.front_radius") ||
863863
!nh->has_parameter(_name + "." + "footprint_model.rear_offset") || !nh->has_parameter(_name + "." + "footprint_model.rear_radius"))
864864
{
865-
RCLCPP_ERROR_STREAM(_logger,"Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using "
865+
RCLCPP_ERROR_STREAM(_logger,"Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '/footprint_model.front_offset', '/footprint_model.front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using "
866866
"point-model instead.");
867867
return std::make_shared<teb_local_planner::PointRobotFootprint>();
868868
}
@@ -914,7 +914,7 @@ teb_local_planner::RobotFootprintModelPtr MpcLocalPlannerROS::getRobotFootprintF
914914

915915
}
916916
// otherwise
917-
RCLCPP_WARN_STREAM(_logger, "Unknown robot footprint model specified with parameter '/footprint_model/type'. Using point model instead.");
917+
RCLCPP_WARN_STREAM(_logger, "Unknown robot footprint model specified with parameter '/footprint_model.type'. Using point model instead.");
918918
return std::make_shared<teb_local_planner::PointRobotFootprint>();
919919
}
920920

0 commit comments

Comments
 (0)