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

refactor(mission_planner): apply clang-tidy #1737

Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -21,12 +21,12 @@ GoalPoseVisualizer::GoalPoseVisualizer(const rclcpp::NodeOptions & node_options)
{
sub_route_ = create_subscription<autoware_auto_planning_msgs::msg::HADMapRoute>(
"input/route", rclcpp::QoS{1}.transient_local(),
std::bind(&GoalPoseVisualizer::echoBackRouteCallback, this, std::placeholders::_1));
std::bind(&GoalPoseVisualizer::echo_back_route_callback, this, std::placeholders::_1));
pub_goal_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>(
"output/goal_pose", rclcpp::QoS{1}.transient_local());
}

void GoalPoseVisualizer::echoBackRouteCallback(
void GoalPoseVisualizer::echo_back_route_callback(
const autoware_auto_planning_msgs::msg::HADMapRoute::ConstSharedPtr msg)
{
geometry_msgs::msg::PoseStamped goal_pose;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class GoalPoseVisualizer : public rclcpp::Node
rclcpp::Subscription<autoware_auto_planning_msgs::msg::HADMapRoute>::SharedPtr sub_route_;
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_goal_pose_;

void echoBackRouteCallback(
void echo_back_route_callback(
const autoware_auto_planning_msgs::msg::HADMapRoute::ConstSharedPtr msg);
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ bool MissionPlanner::getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_veh

bool MissionPlanner::transformPose(
const geometry_msgs::msg::PoseStamped & input_pose, geometry_msgs::msg::PoseStamped * output_pose,
const std::string target_frame)
const std::string & target_frame)
{
geometry_msgs::msg::TransformStamped transform;
try {
Expand Down
19 changes: 10 additions & 9 deletions planning/mission_planner/src/mission_planner/mission_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,11 @@ class MissionPlanner : public rclcpp::Node

rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr marker_publisher_;

virtual bool isRoutingGraphReady() const = 0;
virtual autoware_auto_planning_msgs::msg::HADMapRoute planRoute() = 0;
virtual void visualizeRoute(
virtual bool is_routing_graph_ready() const = 0;
virtual autoware_auto_planning_msgs::msg::HADMapRoute plan_route() = 0;
virtual void visualize_route(
const autoware_auto_planning_msgs::msg::HADMapRoute & route) const = 0;
virtual void publishRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const;
virtual void publish_route(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const;

private:
rclcpp::Publisher<autoware_auto_planning_msgs::msg::HADMapRoute>::SharedPtr route_publisher_;
Expand All @@ -61,12 +61,13 @@ class MissionPlanner : public rclcpp::Node
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

bool getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose);
void goalPoseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr);
void checkpointCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr);
bool transformPose(
bool get_ego_vehicle_pose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose);
void goal_pose_callback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr);
void checkpoint_callback(
const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr);
bool transform_pose(
const geometry_msgs::msg::PoseStamped & input_pose,
geometry_msgs::msg::PoseStamped * output_pose, const std::string target_frame);
geometry_msgs::msg::PoseStamped * output_pose, const std::string & target_frame);
};

} // namespace mission_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
namespace
{
using RouteSections = std::vector<autoware_auto_mapping_msgs::msg::HADMapSegment>;
RouteSections combineConsecutiveRouteSections(
RouteSections combine_consecutive_route_sections(
const RouteSections & route_sections1, const RouteSections & route_sections2)
{
RouteSections route_sections;
Expand All @@ -53,7 +53,7 @@ RouteSections combineConsecutiveRouteSections(
return route_sections;
}

bool isRouteLooped(const RouteSections & route_sections)
bool is_route_looped(const RouteSections & route_sections)
{
for (std::size_t i = 0; i < route_sections.size(); i++) {
const auto & route_section = route_sections.at(i);
Expand All @@ -69,17 +69,16 @@ bool isRouteLooped(const RouteSections & route_sections)
return false;
}

double normalizeRadian(const double rad, const double min_rad = -M_PI, const double max_rad = M_PI)
double normalize_radian(const double rad, const double min_rad = -M_PI, const double max_rad = M_PI)
{
const auto value = std::fmod(rad, 2 * M_PI);
if (min_rad < value && value <= max_rad) {
return value;
} else {
return value - std::copysign(2 * M_PI, value);
}
return value - std::copysign(2 * M_PI, value);
}

bool isInLane(const lanelet::ConstLanelet & lanelet, const lanelet::ConstPoint3d & point)
bool is_in_lane(const lanelet::ConstLanelet & lanelet, const lanelet::ConstPoint3d & point)
{
// check if goal is on a lane at appropriate angle
const auto distance = boost::geometry::distance(
Expand All @@ -88,7 +87,7 @@ bool isInLane(const lanelet::ConstLanelet & lanelet, const lanelet::ConstPoint3d
return distance < th_distance;
}

bool isInParkingSpace(
bool is_in_parking_space(
const lanelet::ConstLineStrings3d & parking_spaces, const lanelet::ConstPoint3d & point)
{
for (const auto & parking_space : parking_spaces) {
Expand All @@ -108,7 +107,7 @@ bool isInParkingSpace(
return false;
}

bool isInParkingLot(
bool is_in_parking_lot(
const lanelet::ConstPolygons3d & parking_lots, const lanelet::ConstPoint3d & point)
{
for (const auto & parking_lot : parking_lots) {
Expand All @@ -122,7 +121,7 @@ bool isInParkingLot(
return false;
}

double projectGoalToMap(
double project_goal_to_map(
const lanelet::Lanelet & lanelet_component, const lanelet::ConstPoint3d & goal_point)
{
const lanelet::ConstLineString3d center_line =
Expand Down Expand Up @@ -179,7 +178,11 @@ void MissionPlannerLanelet2::visualizeRoute(
}
}

std_msgs::msg::ColorRGBA cl_route, cl_ll_borders, cl_end, cl_normal, cl_goal;
std_msgs::msg::ColorRGBA cl_route;
std_msgs::msg::ColorRGBA cl_ll_borders;
std_msgs::msg::ColorRGBA cl_end;
std_msgs::msg::ColorRGBA cl_normal;
std_msgs::msg::ColorRGBA cl_goal;
setColor(&cl_route, 0.2, 0.4, 0.2, 0.05);
setColor(&cl_goal, 0.2, 0.4, 0.4, 0.05);
setColor(&cl_end, 0.2, 0.2, 0.4, 0.05);
Expand Down Expand Up @@ -214,11 +217,11 @@ bool MissionPlannerLanelet2::isGoalValid() const
}
const auto goal_lanelet_pt = lanelet::utils::conversion::toLaneletPoint(goal_pose_.pose.position);

if (isInLane(closest_lanelet, goal_lanelet_pt)) {
if (is_in_lane(closest_lanelet, goal_lanelet_pt)) {
const auto lane_yaw =
lanelet::utils::getLaneletAngle(closest_lanelet, goal_pose_.pose.position);
const auto goal_yaw = tf2::getYaw(goal_pose_.pose.orientation);
const auto angle_diff = normalizeRadian(lane_yaw - goal_yaw);
const auto angle_diff = normalize_radian(lane_yaw - goal_yaw);

constexpr double th_angle = M_PI / 4;

Expand All @@ -229,13 +232,13 @@ bool MissionPlannerLanelet2::isGoalValid() const

// check if goal is in parking space
const auto parking_spaces = lanelet::utils::query::getAllParkingSpaces(lanelet_map_ptr_);
if (isInParkingSpace(parking_spaces, goal_lanelet_pt)) {
if (is_in_parking_space(parking_spaces, goal_lanelet_pt)) {
return true;
}

// check if goal is in parking lot
const auto parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_);
if (isInParkingLot(parking_lots, goal_lanelet_pt)) {
if (is_in_parking_lot(parking_lots, goal_lanelet_pt)) {
return true;
}

Expand All @@ -246,11 +249,11 @@ bool MissionPlannerLanelet2::isGoalValid() const
return false;
}
// check if goal pose is in shoulder lane
if (isInLane(closest_shoulder_lanelet, goal_lanelet_pt)) {
if (is_in_lane(closest_shoulder_lanelet, goal_lanelet_pt)) {
const auto lane_yaw =
lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal_pose_.pose.position);
const auto goal_yaw = tf2::getYaw(goal_pose_.pose.orientation);
const auto angle_diff = normalizeRadian(lane_yaw - goal_yaw);
const auto angle_diff = normalize_radian(lane_yaw - goal_yaw);

constexpr double th_angle = M_PI / 4;
if (std::abs(angle_diff) < th_angle) {
Expand Down Expand Up @@ -291,10 +294,10 @@ autoware_auto_planning_msgs::msg::HADMapRoute MissionPlannerLanelet2::planRoute(
// create local route sections
route_handler_.setRouteLanelets(path_lanelets);
const auto local_route_sections = route_handler_.createMapSegments(path_lanelets);
route_sections = combineConsecutiveRouteSections(route_sections, local_route_sections);
route_sections = combine_consecutive_route_sections(route_sections, local_route_sections);
}

if (isRouteLooped(route_sections)) {
if (is_route_looped(route_sections)) {
RCLCPP_WARN(
get_logger(), "Loop detected within route! Be aware that looped route is not debugged!");
}
Expand All @@ -315,7 +318,7 @@ void MissionPlannerLanelet2::refineGoalHeight(const RouteSections & route_sectio
const auto goal_lane_id = route_sections.back().preferred_primitive_id;
lanelet::Lanelet goal_lanelet = lanelet_map_ptr_->laneletLayer.get(goal_lane_id);
const auto goal_lanelet_pt = lanelet::utils::conversion::toLaneletPoint(goal_pose_.pose.position);
double goal_height = projectGoalToMap(goal_lanelet, goal_lanelet_pt);
double goal_height = project_goal_to_map(goal_lanelet, goal_lanelet_pt);
goal_pose_.pose.position.z = goal_height;
checkpoints_.back().pose.position.z = goal_height;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,14 +56,14 @@ class MissionPlannerLanelet2 : public MissionPlanner

rclcpp::Subscription<autoware_auto_mapping_msgs::msg::HADMapBin>::SharedPtr map_subscriber_;

void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
bool isGoalValid() const;
void refineGoalHeight(const RouteSections & route_sections);
void map_callback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg);
bool is_goal_valid() const;
void refine_goal_height(const RouteSections & route_sections);

// virtual functions
bool isRoutingGraphReady() const;
autoware_auto_planning_msgs::msg::HADMapRoute planRoute();
void visualizeRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const;
bool isRoutingGraphReady() const override;
autoware_auto_planning_msgs::msg::HADMapRoute planRoute() override;
void visualizeRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const override;
};
} // namespace mission_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ void insertMarkerArray(
a1->markers.insert(a1->markers.end(), a2.markers.begin(), a2.markers.end());
}

std::vector<std::pair<double, lanelet::Lanelet>> excludeSubtypeLaneletsWithDistance(
std::vector<std::pair<double, lanelet::Lanelet>> exclude_subtype_lanelets_with_distance(
const std::vector<std::pair<double, lanelet::Lanelet>> & lls, const char subtype[])
{
std::vector<std::pair<double, lanelet::Lanelet>> exclude_subtype_lanelets;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ bool exists(const std::vector<T> & vectors, const T & item)
return false;
}

void setColor(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, double a);
void insertMarkerArray(
void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, double a);
void insert_marker_array(
visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2);
std::string toString(const geometry_msgs::msg::Pose & pose);
std::string to_string(const geometry_msgs::msg::Pose & pose);
#endif // MISSION_PLANNER_LANELET2__UTILITY_FUNCTIONS_HPP_