SMACC2
|
#include <cp_planner_switcher.hpp>
Public Member Functions | |
CpPlannerSwitcher () | |
void | onInitialize () override |
void | setDesiredGlobalPlanner (std::string) |
void | setDesiredController (std::string) |
void | commitPublish () |
void | setBackwardPlanner (bool commit=true) |
void | setUndoPathBackwardPlanner (bool commit=true) |
void | setForwardPlanner (bool commit=true) |
void | setPureSpinningPlanner (bool commit=true) |
void | setDefaultPlanners (bool commit=true) |
Public Member Functions inherited from smacc2::ISmaccComponent | |
ISmaccComponent () | |
virtual | ~ISmaccComponent () |
virtual std::string | getName () const |
Private Attributes | |
std::string | desired_planner_ |
std::string | desired_controller_ |
bool | set_planners_mode_flag_ |
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr | planner_selector_pub_ |
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr | controller_selector_pub_ |
rclcpp::Publisher< std_msgs::msg::String >::SharedPtr | goal_checker_selector_pub_ |
Definition at line 31 of file cp_planner_switcher.hpp.
cl_nitrosz::CpPlannerSwitcher::CpPlannerSwitcher | ( | ) |
Definition at line 27 of file cp_planner_switcher.cpp.
void cl_nitrosz::CpPlannerSwitcher::commitPublish | ( | ) |
Definition at line 99 of file cp_planner_switcher.cpp.
References controller_selector_pub_, desired_controller_, desired_planner_, and planner_selector_pub_.
Referenced by setBackwardPlanner(), setDefaultPlanners(), setForwardPlanner(), setPureSpinningPlanner(), and setUndoPathBackwardPlanner().
|
overridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 29 of file cp_planner_switcher.cpp.
References controller_selector_pub_, smacc2::ISmaccComponent::getNode(), and planner_selector_pub_.
void cl_nitrosz::CpPlannerSwitcher::setBackwardPlanner | ( | bool | commit = true | ) |
Definition at line 60 of file cp_planner_switcher.cpp.
References commitPublish(), desired_controller_, desired_planner_, and smacc2::ISmaccComponent::getLogger().
Referenced by cl_nitrosz::CbNavigateBackwards::onEntry().
void cl_nitrosz::CpPlannerSwitcher::setDefaultPlanners | ( | bool | commit = true | ) |
Definition at line 91 of file cp_planner_switcher.cpp.
References commitPublish(), desired_controller_, and desired_planner_.
Referenced by cl_nitrosz::CpWaypointNavigator::sendNextGoal().
void cl_nitrosz::CpPlannerSwitcher::setDesiredController | ( | std::string | controllerName | ) |
Definition at line 45 of file cp_planner_switcher.cpp.
References desired_controller_.
void cl_nitrosz::CpPlannerSwitcher::setDesiredGlobalPlanner | ( | std::string | plannerName | ) |
Definition at line 40 of file cp_planner_switcher.cpp.
References desired_planner_.
void cl_nitrosz::CpPlannerSwitcher::setForwardPlanner | ( | bool | commit = true | ) |
Definition at line 70 of file cp_planner_switcher.cpp.
References commitPublish(), desired_controller_, desired_planner_, and smacc2::ISmaccComponent::getLogger().
Referenced by cl_nitrosz::CbNavigateForward::onEntry().
void cl_nitrosz::CpPlannerSwitcher::setPureSpinningPlanner | ( | bool | commit = true | ) |
Definition at line 80 of file cp_planner_switcher.cpp.
References commitPublish(), desired_controller_, desired_planner_, and smacc2::ISmaccComponent::getLogger().
Referenced by cl_nitrosz::CbAbsoluteRotate::onEntry(), and cl_nitrosz::CbRotate::onEntry().
void cl_nitrosz::CpPlannerSwitcher::setUndoPathBackwardPlanner | ( | bool | commit = true | ) |
Definition at line 50 of file cp_planner_switcher.cpp.
References commitPublish(), desired_controller_, desired_planner_, and smacc2::ISmaccComponent::getLogger().
|
private |
Definition at line 66 of file cp_planner_switcher.hpp.
Referenced by commitPublish(), and onInitialize().
|
private |
Definition at line 60 of file cp_planner_switcher.hpp.
Referenced by commitPublish(), setBackwardPlanner(), setDefaultPlanners(), setDesiredController(), setForwardPlanner(), setPureSpinningPlanner(), and setUndoPathBackwardPlanner().
|
private |
Definition at line 58 of file cp_planner_switcher.hpp.
Referenced by commitPublish(), setBackwardPlanner(), setDefaultPlanners(), setDesiredGlobalPlanner(), setForwardPlanner(), setPureSpinningPlanner(), and setUndoPathBackwardPlanner().
|
private |
Definition at line 68 of file cp_planner_switcher.hpp.
|
private |
Definition at line 64 of file cp_planner_switcher.hpp.
Referenced by commitPublish(), and onInitialize().
|
private |
Definition at line 62 of file cp_planner_switcher.hpp.