Skip to content

Commit 38e6e07

Browse files
pre-commit-ci[bot]Ahmed Ebrahim
authored and
Ahmed Ebrahim
committed
style(pre-commit): autofix
1 parent a55197f commit 38e6e07

File tree

4 files changed

+24
-19
lines changed

4 files changed

+24
-19
lines changed

planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,9 @@
3333
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
3434
#include <autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp>
3535
#include <autoware_planning_msgs/msg/remaining_distance_eta.hpp>
36+
#include <geometry_msgs/msg/pose.hpp>
3637
#include <nav_msgs/msg/occupancy_grid.hpp>
3738
#include <nav_msgs/msg/odometry.hpp>
38-
#include <geometry_msgs/msg/pose.hpp>
3939
#include <tier4_planning_msgs/msg/approval.hpp>
4040
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
4141
#include <tier4_planning_msgs/msg/path_change_module.hpp>
@@ -65,9 +65,9 @@ using autoware_perception_msgs::msg::TrafficSignalArray;
6565
using autoware_planning_msgs::msg::LaneletRoute;
6666
using autoware_planning_msgs::msg::PoseWithUuidStamped;
6767
using autoware_planning_msgs::msg::RemainingDistanceETA;
68+
using geometry_msgs::msg::Pose;
6869
using nav_msgs::msg::OccupancyGrid;
6970
using nav_msgs::msg::Odometry;
70-
using geometry_msgs::msg::Pose;
7171
using rcl_interfaces::msg::SetParametersResult;
7272
using steering_factor_interface::SteeringFactorInterface;
7373
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
@@ -191,7 +191,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node
191191
*/
192192
void publishRemainingDistanceETA(
193193
const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const;
194-
194+
195195
/**
196196
* @brief publish reroute availability
197197
*/

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,9 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
6262

6363
// publisher
6464
path_publisher_ = create_publisher<PathWithLaneId>("~/output/path", 1);
65-
remaining_distance_eta_publisher_ = create_publisher<RemainingDistanceETA>("~/output/remaining_distance_eta", rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable());
65+
remaining_distance_eta_publisher_ = create_publisher<RemainingDistanceETA>(
66+
"~/output/remaining_distance_eta",
67+
rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable());
6668
turn_signal_publisher_ =
6769
create_publisher<TurnIndicatorsCommand>("~/output/turn_indicators_cmd", 1);
6870
hazard_signal_publisher_ = create_publisher<HazardLightsCommand>("~/output/hazard_lights_cmd", 1);
@@ -542,7 +544,8 @@ void BehaviorPathPlannerNode::publish_reroute_availability() const
542544
reroute_availability_publisher_->publish(is_reroute_available);
543545
}
544546

545-
void BehaviorPathPlannerNode::publishRemainingDistanceETA(const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const
547+
void BehaviorPathPlannerNode::publishRemainingDistanceETA(
548+
const double & remaining_distance, const route_handler::EstimatedTimeOfArrival & eta) const
546549
{
547550
RemainingDistanceETA remaining_distance_eta;
548551
remaining_distance_eta.remaining_distance = remaining_distance;
@@ -551,7 +554,6 @@ void BehaviorPathPlannerNode::publishRemainingDistanceETA(const double & remaini
551554
remaining_distance_eta.seconds = eta.seconds;
552555

553556
remaining_distance_eta_publisher_->publish(remaining_distance_eta);
554-
555557
}
556558

557559
void BehaviorPathPlannerNode::publish_turn_signal_debug_data(const TurnSignalDebugData & debug_data)

planning/route_handler/include/route_handler/route_handler.hpp

+6-2
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,8 @@ using RouteSections = std::vector<autoware_planning_msgs::msg::LaneletSegment>;
5050
enum class Direction { NONE, LEFT, RIGHT };
5151
enum class PullOverDirection { NONE, LEFT, RIGHT };
5252
enum class PullOutDirection { NONE, LEFT, RIGHT };
53-
struct EstimatedTimeOfArrival {
53+
struct EstimatedTimeOfArrival
54+
{
5455
uint8_t hours;
5556
uint8_t minutes;
5657
uint8_t seconds;
@@ -362,7 +363,10 @@ class RouteHandler
362363
bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const;
363364
lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const;
364365
double getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_);
365-
EstimatedTimeOfArrival getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity);
366+
EstimatedTimeOfArrival getEstimatedTimeOfArrival(
367+
const double & remaining_distance,
368+
const geometry_msgs::msg::Vector3 & current_vehicle_velocity);
369+
366370
private:
367371
// MUST
368372
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;

planning/route_handler/src/route_handler.cpp

+10-11
Original file line numberDiff line numberDiff line change
@@ -2261,13 +2261,13 @@ bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath &
22612261
}
22622262

22632263
double RouteHandler::getRemainingDistance(const Pose & current_pose, const Pose & goal_pose_)
2264-
{/**
2264+
{ /**
22652265
2266-
double dist_to_goal = lanelet::geometry::toArcCoordinates(
2267-
lanelet::utils::to2D(lanelet.centerline()),
2268-
lanelet::utils::to2D(target_goal_position).basicPoint())
2269-
.length;
2270-
*/
2266+
double dist_to_goal = lanelet::geometry::toArcCoordinates(
2267+
lanelet::utils::to2D(lanelet.centerline()),
2268+
lanelet::utils::to2D(target_goal_position).basicPoint())
2269+
.length;
2270+
*/
22712271
static bool is_first_time{true};
22722272
double length = 0.0;
22732273
size_t counter = 0;
@@ -2294,10 +2294,9 @@ double dist_to_goal = lanelet::geometry::toArcCoordinates(
22942294
break;
22952295
}
22962296

2297-
if(shortest_path.size() == 1 && !is_first_time) {
2297+
if (shortest_path.size() == 1 && !is_first_time) {
22982298
length += tier4_autoware_utils::calcDistance2d(current_pose.position, goal_pose_.position);
22992299
break;
2300-
23012300
}
23022301

23032302
if (counter == 0) {
@@ -2323,14 +2322,14 @@ double dist_to_goal = lanelet::geometry::toArcCoordinates(
23232322
return length;
23242323
}
23252324

2326-
EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity)
2325+
EstimatedTimeOfArrival RouteHandler::getEstimatedTimeOfArrival(
2326+
const double & remaining_distance, const geometry_msgs::msg::Vector3 & current_vehicle_velocity)
23272327
{
2328-
23292328
double current_velocity_norm = std::sqrt(
23302329
current_vehicle_velocity.x * current_vehicle_velocity.x +
23312330
current_vehicle_velocity.y * current_vehicle_velocity.y);
23322331

2333-
if(remaining_distance < 0.0001 || current_velocity_norm < 0.0001){
2332+
if (remaining_distance < 0.0001 || current_velocity_norm < 0.0001) {
23342333
eta.hours = 0;
23352334
eta.minutes = 0;
23362335
eta.seconds = 0;

0 commit comments

Comments
 (0)