25using namespace std::chrono_literals;
31 rclcpp::QoS qos(rclcpp::KeepLast(1));
32 qos.transient_local().reliable();
35 getNode()->create_publisher<std_msgs::msg::String>(
"planner_selector", qos);
37 getNode()->create_publisher<std_msgs::msg::String>(
"controller_selector", qos);
52 RCLCPP_INFO(
getLogger(),
"[PlannerSwitcher] Planner Switcher: Trying to set BackwardPlanner");
62 RCLCPP_INFO(
getLogger(),
"[PlannerSwitcher] Planner Switcher: Trying to set BackwardPlanner");
72 RCLCPP_INFO(
getLogger(),
"[PlannerSwitcher] Planner Switcher: Trying to set ForwardPlanner");
82 RCLCPP_INFO(
getLogger(),
"[PlannerSwitcher] Planner Switcher: Trying to set PureSpinningPlanner");
100 std_msgs::msg::String planner_msg;
104 std_msgs::msg::String controller_msg;
void setDesiredGlobalPlanner(std::string)
void setBackwardPlanner(bool commit=true)
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr controller_selector_pub_
std::string desired_planner_
void setForwardPlanner(bool commit=true)
void setDefaultPlanners(bool commit=true)
void onInitialize() override
void setPureSpinningPlanner(bool commit=true)
void setDesiredController(std::string)
std::string desired_controller_
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr planner_selector_pub_
void setUndoPathBackwardPlanner(bool commit=true)
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()