Skip to content

Commit

Permalink
refactor(mission_planner): use snake case instead of camel case (#4565)
Browse files Browse the repository at this point in the history
* feat(mission_planner): add a guard for rerouting while not follwoing lane

Signed-off-by: yutaka <purewater0901@gmail.com>

* refactor(mission_planner): use snake case instead of camel case

Signed-off-by: yutaka <purewater0901@gmail.com>

---------

Signed-off-by: yutaka <purewater0901@gmail.com>
  • Loading branch information
purewater0901 authored Aug 8, 2023
1 parent 1c529ae commit 7502305
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,8 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
plugin_loader_("mission_planner", "mission_planner::PlannerPlugin"),
tf_buffer_(get_clock()),
tf_listener_(tf_buffer_),
odometry_(nullptr),
map_ptr_(nullptr),
reroute_availability_(nullptr),
normal_route_(nullptr),
mrm_route_(nullptr)
Expand All @@ -86,7 +88,6 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
planner_ = plugin_loader_.createSharedInstance("mission_planner::lanelet2::DefaultPlanner");
planner_->initialize(this);

odometry_ = nullptr;
sub_odometry_ = create_subscription<Odometry>(
"/localization/kinematic_state", rclcpp::QoS(1),
std::bind(&MissionPlanner::on_odometry, this, std::placeholders::_1));
Expand All @@ -97,9 +98,9 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options)
std::bind(&MissionPlanner::on_reroute_availability, this, std::placeholders::_1));

auto qos_transient_local = rclcpp::QoS{1}.transient_local();
vector_map_subscriber_ = create_subscription<HADMapBin>(
sub_vector_map_ = create_subscription<HADMapBin>(
"input/vector_map", qos_transient_local,
std::bind(&MissionPlanner::onMap, this, std::placeholders::_1));
std::bind(&MissionPlanner::on_map, this, std::placeholders::_1));

const auto durable_qos = rclcpp::QoS(1).transient_local();
pub_marker_ = create_publisher<MarkerArray>("debug/route_marker", durable_qos);
Expand Down Expand Up @@ -141,7 +142,7 @@ void MissionPlanner::on_reroute_availability(const RerouteAvailability::ConstSha
reroute_availability_ = msg;
}

void MissionPlanner::onMap(const HADMapBin::ConstSharedPtr msg)
void MissionPlanner::on_map(const HADMapBin::ConstSharedPtr msg)
{
map_ptr_ = msg;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,11 +73,13 @@ class MissionPlanner : public rclcpp::Node
PoseStamped transform_pose(const PoseStamped & input);

rclcpp::Subscription<Odometry>::SharedPtr sub_odometry_;
rclcpp::Subscription<HADMapBin>::SharedPtr vector_map_subscriber_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_vector_map_;
rclcpp::Subscription<RerouteAvailability>::SharedPtr sub_reroute_availability_;
Odometry::ConstSharedPtr odometry_;
HADMapBin::ConstSharedPtr map_ptr_;
RerouteAvailability::ConstSharedPtr reroute_availability_;
void on_odometry(const Odometry::ConstSharedPtr msg);
void on_map(const HADMapBin::ConstSharedPtr msg);
void on_reroute_availability(const RerouteAvailability::ConstSharedPtr msg);

rclcpp::Publisher<MarkerArray>::SharedPtr pub_marker_;
Expand Down Expand Up @@ -126,9 +128,6 @@ class MissionPlanner : public rclcpp::Node
const ClearMrmRoute::Service::Request::SharedPtr req,
const ClearMrmRoute::Service::Response::SharedPtr res);

HADMapBin::ConstSharedPtr map_ptr_{nullptr};
void onMap(const HADMapBin::ConstSharedPtr msg);

component_interface_utils::Subscription<ModifiedGoal>::SharedPtr sub_modified_goal_;
void on_modified_goal(const ModifiedGoal::Message::ConstSharedPtr msg);
void on_change_route(
Expand Down

0 comments on commit 7502305

Please sign in to comment.