Skip to content

Commit

Permalink
fix(behavior_velocity_planner): fix cppcheck warnings of virtualCallI…
Browse files Browse the repository at this point in the history
…nConstructor (autowarefoundation#8376)

Co-authored-by: Ryuta Kambe <[email protected]>
  • Loading branch information
taisa1 and veqcc authored Aug 20, 2024
1 parent daa04dc commit 9a461b4
Show file tree
Hide file tree
Showing 14 changed files with 14 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
const std::string ns(BlindSpotModuleManager::getModuleName());
planner_param_.use_pass_judge_line =
getOrDeclareParameter<bool>(node, ns + ".use_pass_judge_line");
planner_param_.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".stop_line_margin");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".common.enable_rtc"))
{
const std::string ns(getModuleName());
const std::string ns(CrosswalkModuleManager::getModuleName());

// for crosswalk parameters
auto & cp = crosswalk_planner_param_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
const std::string ns(DetectionAreaModuleManager::getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
planner_param_.use_dead_line = getOrDeclareParameter<bool>(node, ns + ".use_dead_line");
planner_param_.dead_line_margin = getOrDeclareParameter<double>(node, ns + ".dead_line_margin");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
&node, "intersection_occlusion",
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
{
const std::string ns(getModuleName());
const std::string ns(IntersectionModuleManager::getModuleName());
auto & ip = intersection_param_;

// common
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ using autoware::universe_utils::getOrDeclareParameter;
NoDrivableLaneModuleManager::NoDrivableLaneModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
const std::string ns(NoDrivableLaneModuleManager::getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
planner_param_.print_debug_info = getOrDeclareParameter<bool>(node, ns + ".print_debug_info");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ NoStoppingAreaModuleManager::NoStoppingAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
const std::string ns(NoStoppingAreaModuleManager::getModuleName());
auto & pp = planner_param_;
const auto & vi = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
pp.state_clear_time = getOrDeclareParameter<double>(node, ns + ".state_clear_time");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ using occlusion_spot_utils::PASS_JUDGE;
OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
const std::string ns(OcclusionSpotModuleManager::getModuleName());
auto & pp = planner_param_;
// for detection type
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node)
p.left_overhang = vehicle_info.left_overhang_m;
}

const std::string ns(getModuleName());
const std::string ns(RunOutModuleManager::getModuleName());

{
auto & p = planner_param_.smoother;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ using lanelet::autoware::SpeedBump;
SpeedBumpModuleManager::SpeedBumpModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
std::string ns(getModuleName());
std::string ns(SpeedBumpModuleManager::getModuleName());
planner_param_.slow_start_margin = getOrDeclareParameter<double>(node, ns + ".slow_start_margin");
planner_param_.slow_end_margin = getOrDeclareParameter<double>(node, ns + ".slow_end_margin");
planner_param_.print_debug_info = getOrDeclareParameter<bool>(node, ns + ".print_debug_info");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using lanelet::TrafficSign;
StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
const std::string ns(StopLineModuleManager::getModuleName());
auto & p = planner_param_;
p.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
p.hold_stop_margin_distance =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ using autoware::universe_utils::getOrDeclareParameter;
TemplateModuleManager::TemplateModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
std::string ns(getModuleName());
std::string ns(TemplateModuleManager::getModuleName());
dummy_parameter_ = getOrDeclareParameter<double>(node, ns + ".dummy");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ TrafficLightModuleManager::TrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
{
const std::string ns(getModuleName());
const std::string ns(TrafficLightModuleManager::getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
planner_param_.tl_state_timeout = getOrDeclareParameter<double>(node, ns + ".tl_state_timeout");
planner_param_.stop_time_hysteresis =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ using lanelet::autoware::VirtualTrafficLight;
VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
const std::string ns(VirtualTrafficLightModuleManager::getModuleName());

{
auto & p = planner_param_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ using lanelet::autoware::Crosswalk;
WalkwayModuleManager::WalkwayModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
const std::string ns(WalkwayModuleManager::getModuleName());

// for walkway parameters
auto & wp = walkway_planner_param_;
Expand Down

0 comments on commit 9a461b4

Please sign in to comment.