Skip to content

Commit a6ffb3e

Browse files
authored
refactor(mission_planner): apply clang-tidy (autowarefoundation#1737)
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp> Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
1 parent 4b8cf17 commit a6ffb3e

File tree

8 files changed

+83
-78
lines changed

8 files changed

+83
-78
lines changed

planning/mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,12 +21,12 @@ GoalPoseVisualizer::GoalPoseVisualizer(const rclcpp::NodeOptions & node_options)
2121
{
2222
sub_route_ = create_subscription<autoware_auto_planning_msgs::msg::HADMapRoute>(
2323
"input/route", rclcpp::QoS{1}.transient_local(),
24-
std::bind(&GoalPoseVisualizer::echoBackRouteCallback, this, std::placeholders::_1));
24+
std::bind(&GoalPoseVisualizer::echo_back_route_callback, this, std::placeholders::_1));
2525
pub_goal_pose_ = create_publisher<geometry_msgs::msg::PoseStamped>(
2626
"output/goal_pose", rclcpp::QoS{1}.transient_local());
2727
}
2828

29-
void GoalPoseVisualizer::echoBackRouteCallback(
29+
void GoalPoseVisualizer::echo_back_route_callback(
3030
const autoware_auto_planning_msgs::msg::HADMapRoute::ConstSharedPtr msg)
3131
{
3232
geometry_msgs::msg::PoseStamped goal_pose;

planning/mission_planner/src/goal_pose_visualizer/goal_pose_visualizer.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ class GoalPoseVisualizer : public rclcpp::Node
3131
rclcpp::Subscription<autoware_auto_planning_msgs::msg::HADMapRoute>::SharedPtr sub_route_;
3232
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pub_goal_pose_;
3333

34-
void echoBackRouteCallback(
34+
void echo_back_route_callback(
3535
const autoware_auto_planning_msgs::msg::HADMapRoute::ConstSharedPtr msg);
3636
};
3737

planning/mission_planner/src/mission_planner/mission_planner.cpp

+19-18
Original file line numberDiff line numberDiff line change
@@ -40,9 +40,9 @@ MissionPlanner::MissionPlanner(
4040
using std::placeholders::_1;
4141

4242
goal_subscriber_ = create_subscription<geometry_msgs::msg::PoseStamped>(
43-
"input/goal_pose", 10, std::bind(&MissionPlanner::goalPoseCallback, this, _1));
43+
"input/goal_pose", 10, std::bind(&MissionPlanner::goal_pose_callback, this, _1));
4444
checkpoint_subscriber_ = create_subscription<geometry_msgs::msg::PoseStamped>(
45-
"input/checkpoint", 10, std::bind(&MissionPlanner::checkpointCallback, this, _1));
45+
"input/checkpoint", 10, std::bind(&MissionPlanner::checkpoint_callback, this, _1));
4646

4747
rclcpp::QoS durable_qos{1};
4848
durable_qos.transient_local();
@@ -52,7 +52,7 @@ MissionPlanner::MissionPlanner(
5252
create_publisher<visualization_msgs::msg::MarkerArray>("debug/route_marker", durable_qos);
5353
}
5454

55-
bool MissionPlanner::getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose)
55+
bool MissionPlanner::get_ego_vehicle_pose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose)
5656
{
5757
geometry_msgs::msg::PoseStamped base_link_origin;
5858
base_link_origin.header.frame_id = base_link_frame_;
@@ -65,12 +65,12 @@ bool MissionPlanner::getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_veh
6565
base_link_origin.pose.orientation.w = 1;
6666

6767
// transform base_link frame origin to map_frame to get vehicle positions
68-
return transformPose(base_link_origin, ego_vehicle_pose, map_frame_);
68+
return transform_pose(base_link_origin, ego_vehicle_pose, map_frame_);
6969
}
7070

71-
bool MissionPlanner::transformPose(
71+
bool MissionPlanner::transform_pose(
7272
const geometry_msgs::msg::PoseStamped & input_pose, geometry_msgs::msg::PoseStamped * output_pose,
73-
const std::string target_frame)
73+
const std::string & target_frame)
7474
{
7575
geometry_msgs::msg::TransformStamped transform;
7676
try {
@@ -84,17 +84,17 @@ bool MissionPlanner::transformPose(
8484
}
8585
}
8686

87-
void MissionPlanner::goalPoseCallback(
87+
void MissionPlanner::goal_pose_callback(
8888
const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr)
8989
{
9090
// set start pose
91-
if (!getEgoVehiclePose(&start_pose_)) {
91+
if (!get_ego_vehicle_pose(&start_pose_)) {
9292
RCLCPP_ERROR(
9393
get_logger(), "Failed to get ego vehicle pose in map frame. Aborting mission planning");
9494
return;
9595
}
9696
// set goal pose
97-
if (!transformPose(*goal_msg_ptr, &goal_pose_, map_frame_)) {
97+
if (!transform_pose(*goal_msg_ptr, &goal_pose_, map_frame_)) {
9898
RCLCPP_ERROR(get_logger(), "Failed to get goal pose in map frame. Aborting mission planning");
9999
return;
100100
}
@@ -104,16 +104,16 @@ void MissionPlanner::goalPoseCallback(
104104
checkpoints_.push_back(start_pose_);
105105
checkpoints_.push_back(goal_pose_);
106106

107-
if (!isRoutingGraphReady()) {
107+
if (!is_routing_graph_ready()) {
108108
RCLCPP_ERROR(get_logger(), "RoutingGraph is not ready. Aborting mission planning");
109109
return;
110110
}
111111

112-
autoware_auto_planning_msgs::msg::HADMapRoute route = planRoute();
113-
publishRoute(route);
112+
autoware_auto_planning_msgs::msg::HADMapRoute route = plan_route();
113+
publish_route(route);
114114
} // namespace mission_planner
115115

116-
void MissionPlanner::checkpointCallback(
116+
void MissionPlanner::checkpoint_callback(
117117
const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr)
118118
{
119119
if (checkpoints_.size() < 2) {
@@ -124,7 +124,7 @@ void MissionPlanner::checkpointCallback(
124124
}
125125

126126
geometry_msgs::msg::PoseStamped transformed_checkpoint;
127-
if (!transformPose(*checkpoint_msg_ptr, &transformed_checkpoint, map_frame_)) {
127+
if (!transform_pose(*checkpoint_msg_ptr, &transformed_checkpoint, map_frame_)) {
128128
RCLCPP_ERROR(
129129
get_logger(), "Failed to get checkpoint pose in map frame. Aborting mission planning");
130130
return;
@@ -133,16 +133,17 @@ void MissionPlanner::checkpointCallback(
133133
// insert checkpoint before goal
134134
checkpoints_.insert(checkpoints_.end() - 1, transformed_checkpoint);
135135

136-
autoware_auto_planning_msgs::msg::HADMapRoute route = planRoute();
137-
publishRoute(route);
136+
autoware_auto_planning_msgs::msg::HADMapRoute route = plan_route();
137+
publish_route(route);
138138
}
139139

140-
void MissionPlanner::publishRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const
140+
void MissionPlanner::publish_route(
141+
const autoware_auto_planning_msgs::msg::HADMapRoute & route) const
141142
{
142143
if (!route.segments.empty()) {
143144
RCLCPP_INFO(get_logger(), "Route successfully planned. Publishing...");
144145
route_publisher_->publish(route);
145-
visualizeRoute(route);
146+
visualize_route(route);
146147
} else {
147148
RCLCPP_ERROR(get_logger(), "Calculated route is empty!");
148149
}

planning/mission_planner/src/mission_planner/mission_planner.hpp

+10-9
Original file line numberDiff line numberDiff line change
@@ -47,11 +47,11 @@ class MissionPlanner : public rclcpp::Node
4747

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

50-
virtual bool isRoutingGraphReady() const = 0;
51-
virtual autoware_auto_planning_msgs::msg::HADMapRoute planRoute() = 0;
52-
virtual void visualizeRoute(
50+
virtual bool is_routing_graph_ready() const = 0;
51+
virtual autoware_auto_planning_msgs::msg::HADMapRoute plan_route() = 0;
52+
virtual void visualize_route(
5353
const autoware_auto_planning_msgs::msg::HADMapRoute & route) const = 0;
54-
virtual void publishRoute(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const;
54+
virtual void publish_route(const autoware_auto_planning_msgs::msg::HADMapRoute & route) const;
5555

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

64-
bool getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose);
65-
void goalPoseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr);
66-
void checkpointCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr);
67-
bool transformPose(
64+
bool get_ego_vehicle_pose(geometry_msgs::msg::PoseStamped * ego_vehicle_pose);
65+
void goal_pose_callback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr);
66+
void checkpoint_callback(
67+
const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr);
68+
bool transform_pose(
6869
const geometry_msgs::msg::PoseStamped & input_pose,
69-
geometry_msgs::msg::PoseStamped * output_pose, const std::string target_frame);
70+
geometry_msgs::msg::PoseStamped * output_pose, const std::string & target_frame);
7071
};
7172

7273
} // namespace mission_planner

0 commit comments

Comments
 (0)