6 _plugin_loader(
"rsm_core",
"rsm::BaseState") {
8 private_nh.
param<std::string>(
"calculate_goal_plugin",
11 "rsm::NavigationState");
13 "rsm::MappingDummyState");
21 "startStopExploration",
24 "startStopWaypointFollowing",
46 int plugin_type, std::string routine) {
48 switch (plugin_type) {
63 s <<
"rsm::" << routine <<
"RoutineState";
68 if (!routine.empty()) {
70 s <<
"rsm::" << routine;
74 "No matching plugin type found, return to Idle State");
75 return boost::make_shared<IdleState>();
80 }
catch (
const std::exception &e) {
81 ROS_ERROR(
"Plugin state could not be created, return to Idle State");
82 return boost::make_shared<IdleState>();
109 std_msgs::String state_info;
118 if (nextState != NULL && nextState->getStateInterface() == NULL) {
124 "Next state instance invalid. Either NULL or already assigned state passed.");
130 const rsm_msgs::OperationMode::ConstPtr &operation_mode) {
131 if (operation_mode->emergencyStop) {
136 }
else if (operation_mode->mode == 2) {
152 const geometry_msgs::PoseStamped::ConstPtr &goal) {
157 rsm_msgs::SetNavigationGoal srv;
158 srv.request.goal = goal->pose;
162 ROS_ERROR(
"Failed to call Set Navigation Goal service");
167 std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
176 res.success = success;
177 res.message = message;
180 res.message =
"No active state";
186 std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
195 res.success = success;
196 res.message = message;
199 res.message =
"No active state";
205 std_srvs::Trigger::Response &res) {
213 std_srvs::Trigger::Response &res) {
ros::ServiceServer _start_stop_waypoint_following_service
ros::Publisher _state_info_publisher
virtual ~StateInterface()
bool stop2dNavGoal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
boost::shared_ptr< rsm::BaseState > getPluginState(int plugin_type, std::string routine="")
Returns a plugin-state corresponding to the given type.
#define SIMPLE_GOAL_STOP_INTERRUPT
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
std::string _navigation_plugin
Navigation state plugin name for plugin loader.
bool call(MReq &req, MRes &res)
ros::ServiceServer _start_stop_exploration_service
void transitionToVolatileState(boost::shared_ptr< rsm::BaseState > next_state)
pluginlib::ClassLoader< rsm::BaseState > _plugin_loader
Plugin loader for state plugins.
bool startStopWaypointFollowingService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
bool stateInfoService(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
#define TELEOPERATION_INTERRUPT
ros::ServiceServer _state_info_service
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber _simple_goal_sub
bool startStopExplorationService(std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res)
ros::Subscriber _operation_mode_sub
ros::ServiceClient _set_navigation_goal_client
#define EMERGENCY_STOP_INTERRUPT
std::string _mapping_plugin
Mapping state plugin name for plugin loader.
boost::shared_ptr< rsm::BaseState > _next_state
Upcoming state.
void simpleGoalCallback(const geometry_msgs::PoseStamped::ConstPtr &goal)
void operationModeCallback(const rsm_msgs::OperationMode::ConstPtr &operation_mode)
boost::shared_ptr< rsm::BaseState > _current_state
Currently active state.
std::string _calculate_goal_plugin
Calculate goal state plugin name for plugin loader.
#define SIMPLE_GOAL_INTERRUPT
ros::ServiceServer _stop_2d_nav_goal_service