@@ -40,9 +40,9 @@ MissionPlanner::MissionPlanner(
40
40
using std::placeholders::_1;
41
41
42
42
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));
44
44
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));
46
46
47
47
rclcpp::QoS durable_qos{1 };
48
48
durable_qos.transient_local ();
@@ -52,7 +52,7 @@ MissionPlanner::MissionPlanner(
52
52
create_publisher<visualization_msgs::msg::MarkerArray>(" debug/route_marker" , durable_qos);
53
53
}
54
54
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)
56
56
{
57
57
geometry_msgs::msg::PoseStamped base_link_origin;
58
58
base_link_origin.header .frame_id = base_link_frame_;
@@ -65,12 +65,12 @@ bool MissionPlanner::getEgoVehiclePose(geometry_msgs::msg::PoseStamped * ego_veh
65
65
base_link_origin.pose .orientation .w = 1 ;
66
66
67
67
// 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_);
69
69
}
70
70
71
- bool MissionPlanner::transformPose (
71
+ bool MissionPlanner::transform_pose (
72
72
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)
74
74
{
75
75
geometry_msgs::msg::TransformStamped transform;
76
76
try {
@@ -84,17 +84,17 @@ bool MissionPlanner::transformPose(
84
84
}
85
85
}
86
86
87
- void MissionPlanner::goalPoseCallback (
87
+ void MissionPlanner::goal_pose_callback (
88
88
const geometry_msgs::msg::PoseStamped::ConstSharedPtr goal_msg_ptr)
89
89
{
90
90
// set start pose
91
- if (!getEgoVehiclePose (&start_pose_)) {
91
+ if (!get_ego_vehicle_pose (&start_pose_)) {
92
92
RCLCPP_ERROR (
93
93
get_logger (), " Failed to get ego vehicle pose in map frame. Aborting mission planning" );
94
94
return ;
95
95
}
96
96
// set goal pose
97
- if (!transformPose (*goal_msg_ptr, &goal_pose_, map_frame_)) {
97
+ if (!transform_pose (*goal_msg_ptr, &goal_pose_, map_frame_)) {
98
98
RCLCPP_ERROR (get_logger (), " Failed to get goal pose in map frame. Aborting mission planning" );
99
99
return ;
100
100
}
@@ -104,16 +104,16 @@ void MissionPlanner::goalPoseCallback(
104
104
checkpoints_.push_back (start_pose_);
105
105
checkpoints_.push_back (goal_pose_);
106
106
107
- if (!isRoutingGraphReady ()) {
107
+ if (!is_routing_graph_ready ()) {
108
108
RCLCPP_ERROR (get_logger (), " RoutingGraph is not ready. Aborting mission planning" );
109
109
return ;
110
110
}
111
111
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);
114
114
} // namespace mission_planner
115
115
116
- void MissionPlanner::checkpointCallback (
116
+ void MissionPlanner::checkpoint_callback (
117
117
const geometry_msgs::msg::PoseStamped::ConstSharedPtr checkpoint_msg_ptr)
118
118
{
119
119
if (checkpoints_.size () < 2 ) {
@@ -124,7 +124,7 @@ void MissionPlanner::checkpointCallback(
124
124
}
125
125
126
126
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_)) {
128
128
RCLCPP_ERROR (
129
129
get_logger (), " Failed to get checkpoint pose in map frame. Aborting mission planning" );
130
130
return ;
@@ -133,16 +133,17 @@ void MissionPlanner::checkpointCallback(
133
133
// insert checkpoint before goal
134
134
checkpoints_.insert (checkpoints_.end () - 1 , transformed_checkpoint);
135
135
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);
138
138
}
139
139
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
141
142
{
142
143
if (!route.segments .empty ()) {
143
144
RCLCPP_INFO (get_logger (), " Route successfully planned. Publishing..." );
144
145
route_publisher_->publish (route);
145
- visualizeRoute (route);
146
+ visualize_route (route);
146
147
} else {
147
148
RCLCPP_ERROR (get_logger (), " Calculated route is empty!" );
148
149
}
0 commit comments