Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(autoware_behavior_velocity_stop_line_module): resolve warnings of clangd #8382

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/behavior_velocity_planner_common/utilization/util.hpp"
#include "autoware/motion_utils/marker/virtual_wall_marker_creator.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/ros/marker_helper.hpp"
#include "scene.hpp"

#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/marker_helper.hpp>
#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
Expand All @@ -44,7 +44,7 @@
visualization_msgs::msg::Marker marker;
marker.header.frame_id = "map";
marker.ns = "search_segments";
marker.id = module_id;
marker.id = static_cast<int>(module_id);

Check warning on line 47 in planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp#L47

Added line #L47 was not covered by tests
marker.lifetime = rclcpp::Duration::from_seconds(0.5);
marker.type = visualization_msgs::msg::Marker::SPHERE_LIST;
marker.action = visualization_msgs::msg::Marker::ADD;
Expand All @@ -64,7 +64,8 @@
visualization_msgs::msg::Marker marker;
marker.header.frame_id = "map";
marker.ns = "search_stopline";
marker.id = module_id;
marker.id = static_cast<int>(module_id);

Check warning on line 67 in planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp#L67

Added line #L67 was not covered by tests
;
marker.lifetime = rclcpp::Duration::from_seconds(0.5);
marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
marker.action = visualization_msgs::msg::Marker::ADD;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@

#include "manager.hpp"

#include "autoware/behavior_velocity_planner_common/plugin_interface.hpp"
#include "autoware/universe_utils/ros/parameter.hpp"
#include "lanelet2_core/primitives/BasicRegulatoryElements.h"

#include <memory>
#include <set>
Expand All @@ -27,7 +29,7 @@ using autoware::universe_utils::getOrDeclareParameter;
using lanelet::TrafficSign;

StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
: SceneModuleManagerInterface(node, getModuleName()), planner_param_()
{
const std::string ns(getModuleName());
auto & p = planner_param_;
Expand Down Expand Up @@ -57,7 +59,7 @@ std::vector<StopLineWithLaneId> StopLineModuleManager::getStopLinesWithLaneIdOnP
}

for (const auto & stop_line : traffic_sign_reg_elem->refLines()) {
stop_lines_with_lane_id.push_back(std::make_pair(stop_line, lane_id));
stop_lines_with_lane_id.emplace_back(stop_line, lane_id);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,10 @@
#ifndef MANAGER_HPP_
#define MANAGER_HPP_

#include "autoware/behavior_velocity_planner_common/plugin_wrapper.hpp"
#include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp"
#include "scene.hpp"

#include <autoware/behavior_velocity_planner_common/plugin_interface.hpp>
#include <autoware/behavior_velocity_planner_common/plugin_wrapper.hpp>
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
#include <rclcpp/rclcpp.hpp>

#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,32 +14,34 @@

#include "scene.hpp"

#include <autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp>
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/universe_utils/system/time_keeper.hpp>

#include <algorithm>
#include <vector>
#include "autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp"
#include "autoware/behavior_velocity_planner_common/utilization/util.hpp"
#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/universe_utils/system/time_keeper.hpp"

namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;

StopLineModule::StopLineModule(
const int64_t module_id, const size_t lane_id, const lanelet::ConstLineString3d & stop_line,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const int64_t module_id, const int64_t lane_id, const lanelet::ConstLineString3d & stop_line,
const PlannerParam & planner_param, const rclcpp::Logger & logger,
const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock),
lane_id_(lane_id),
stop_line_(stop_line),
state_(State::APPROACH),
planner_param_(planner_param),

Check warning on line 33 in planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp#L33

Added line #L33 was not covered by tests
debug_data_()
{
velocity_factor_.init(PlanningBehavior::STOP_SIGN);
planner_param_ = planner_param;
}

struct SegmentIndexWithPose
{
size_t index = 0;
geometry_msgs::msg::Pose pose;
};

bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
{
universe_utils::ScopedTimeTrack st(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,23 +15,17 @@
#ifndef SCENE_HPP_
#define SCENE_HPP_

#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>
#include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp"
#include "autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp"
#include "autoware/behavior_velocity_planner_common/utilization/util.hpp"
#include "lanelet2_core/primitives/LineString.h"

#define EIGEN_MPL2_ONLY
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <autoware/behavior_velocity_planner_common/scene_module_interface.hpp>
#include <autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp>
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <rclcpp/rclcpp.hpp>

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <cstdint>
#include <memory>
#include <utility>
#include <vector>

namespace autoware::behavior_velocity_planner
{
Expand All @@ -40,24 +34,13 @@ class StopLineModule : public SceneModuleInterface
using StopLineWithLaneId = std::pair<lanelet::ConstLineString3d, int64_t>;

public:
enum class State { APPROACH, STOPPED, START };

struct SegmentIndexWithPose
{
size_t index;
geometry_msgs::msg::Pose pose;
};

struct SegmentIndexWithPoint2d
{
size_t index;
Point2d point;
};

struct SegmentIndexWithOffset
struct PlannerParam
{
size_t index;
double offset;
double stop_margin;
double stop_duration_sec;
double hold_stop_margin_distance;
bool use_initialization_stop_line_state;
bool show_stop_line_collision_check;
};

struct DebugData
Expand All @@ -68,19 +51,9 @@ class StopLineModule : public SceneModuleInterface
LineString2d search_stopline;
};

struct PlannerParam
{
double stop_margin;
double stop_duration_sec;
double hold_stop_margin_distance;
bool use_initialization_stop_line_state;
bool show_stop_line_collision_check;
};

public:
StopLineModule(
const int64_t module_id, const size_t lane_id, const lanelet::ConstLineString3d & stop_line,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const int64_t module_id, const int64_t lane_id, const lanelet::ConstLineString3d & stop_line,
const PlannerParam & planner_param, const rclcpp::Logger & logger,
const rclcpp::Clock::SharedPtr clock);

bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override;
Expand All @@ -89,9 +62,12 @@ class StopLineModule : public SceneModuleInterface
autoware::motion_utils::VirtualWalls createVirtualWalls() override;

private:
enum class State { APPROACH, STOPPED, START };

std::shared_ptr<const rclcpp::Time> stopped_time_;

geometry_msgs::msg::Point getCenterOfStopLine(const lanelet::ConstLineString3d & stop_line);
static geometry_msgs::msg::Point getCenterOfStopLine(
const lanelet::ConstLineString3d & stop_line);

int64_t lane_id_;

Expand Down
Loading