StateInterface.cpp
Go to the documentation of this file.
2 
3 namespace rsm {
4 
6  _plugin_loader("rsm_core", "rsm::BaseState") {
7  ros::NodeHandle private_nh("~");
8  private_nh.param<std::string>("calculate_goal_plugin",
9  _calculate_goal_plugin, "rsm::CalculateGoalState");
10  private_nh.param<std::string>("navigation_plugin", _navigation_plugin,
11  "rsm::NavigationState");
12  private_nh.param<std::string>("mapping_plugin", _mapping_plugin,
13  "rsm::MappingDummyState");
14 
15  ros::NodeHandle nh("rsm");
16  _operation_mode_sub = nh.subscribe<rsm_msgs::OperationMode>("operationMode",
18  _simple_goal_sub = nh.subscribe<geometry_msgs::PoseStamped>("simpleGoal", 1,
20  _start_stop_exploration_service = nh.advertiseService(
21  "startStopExploration",
23  _start_stop_waypoint_following_service = nh.advertiseService(
24  "startStopWaypointFollowing",
26  _stop_2d_nav_goal_service = nh.advertiseService("stop2DNavGoal",
28  _state_info_publisher = nh.advertise<std_msgs::String>("stateInfo", 10);
29  _state_info_service = nh.advertiseService("stateInfo",
31  _set_navigation_goal_client = nh.serviceClient<rsm_msgs::SetNavigationGoal>(
32  "setNavigationGoal");
33 
34  _current_state = NULL;
35  _next_state = NULL;
36  _on_interrupt = false;
37 }
38 
40  if (_current_state) {
41  _current_state->onExit();
42  }
43 }
44 
46  int plugin_type, std::string routine) {
47  try {
48  switch (plugin_type) {
49  case 1: {
51  break;
52  }
53  case 2: {
55  break;
56  }
57  case 3: {
59  break;
60  }
61  case 4: {
62  std::ostringstream s;
63  s << "rsm::" << routine << "RoutineState";
64  return _plugin_loader.createInstance(s.str());
65  break;
66  }
67  default: {
68  if (!routine.empty()) {
69  std::ostringstream s;
70  s << "rsm::" << routine;
71  return _plugin_loader.createInstance(s.str());
72  } else {
73  ROS_ERROR(
74  "No matching plugin type found, return to Idle State");
75  return boost::make_shared<IdleState>();
76  }
77  break;
78  }
79  }
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>();
83  }
84 }
85 
87  // check 1st time awake
88  if (!_current_state && _next_state) {
90  _current_state->onEntry();
91  _next_state = NULL;
92  }
93  if (_current_state) {
94  _current_state->onActive();
95 
96  if (_next_state) // do transition
97  {
98  // do de-initialization of current state
99  _current_state->onExit();
100  }
101  }
102 
103  if (_next_state) // do transition
104  {
105  // do transition to next state
107  _next_state.reset();
108  _current_state->onEntry();
109  std_msgs::String state_info;
110  state_info.data = _current_state->getName();
111  _state_info_publisher.publish(state_info);
112  }
113 }
114 
117  if (_current_state != nextState) {
118  if (nextState != NULL && nextState->getStateInterface() == NULL) {
119  _next_state = nextState;
120  _next_state->setStateInterface(this);
121  _next_state->onSetup();
122  } else {
123  ROS_ERROR(
124  "Next state instance invalid. Either NULL or already assigned state passed.");
125  }
126  }
127 }
128 
130  const rsm_msgs::OperationMode::ConstPtr &operation_mode) {
131  if (operation_mode->emergencyStop) {
132  _on_interrupt = true;
133  if (_current_state) {
135  }
136  } else if (operation_mode->mode == 2) {
137  _on_interrupt = true;
138  if (_current_state) {
140  }
141  } else {
142  if (_on_interrupt) {
143  _on_interrupt = false;
144  if (_current_state) {
145  _current_state->onInterrupt(INTERRUPT_END);
146  }
147  }
148  }
149 }
150 
152  const geometry_msgs::PoseStamped::ConstPtr &goal) {
153  _on_interrupt = true;
154  if (_current_state) {
156  }
157  rsm_msgs::SetNavigationGoal srv;
158  srv.request.goal = goal->pose;
159  srv.request.navigationMode = SIMPLE_GOAL;
161  } else {
162  ROS_ERROR("Failed to call Set Navigation Goal service");
163  }
164 }
165 
167  std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
168  if (_current_state) {
169  bool success;
170  std::string message;
171  if (req.data) {
172  _current_state->onExplorationStart(success, message);
173  } else {
174  _current_state->onExplorationStop(success, message);
175  }
176  res.success = success;
177  res.message = message;
178  } else {
179  res.success = false;
180  res.message = "No active state";
181  }
182  return true;
183 }
184 
186  std_srvs::SetBool::Request &req, std_srvs::SetBool::Response &res) {
187  if (_current_state) {
188  bool success;
189  std::string message;
190  if (req.data) {
191  _current_state->onWaypointFollowingStart(success, message);
192  } else {
193  _current_state->onWaypointFollowingStop(success, message);
194  }
195  res.success = success;
196  res.message = message;
197  } else {
198  res.success = false;
199  res.message = "No active state";
200  }
201  return true;
202 }
203 
204 bool StateInterface::stop2dNavGoal(std_srvs::Trigger::Request &req,
205  std_srvs::Trigger::Response &res) {
206  if (_current_state) {
208  }
209  return true;
210 }
211 
212 bool StateInterface::stateInfoService(std_srvs::Trigger::Request &req,
213  std_srvs::Trigger::Response &res) {
214  res.success = true;
215  res.message = _current_state->getName();
216  return true;
217 }
218 
219 }
ros::ServiceServer _start_stop_waypoint_following_service
ros::Publisher _state_info_publisher
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
Definition: BaseState.h:14
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
std::string _navigation_plugin
Navigation state plugin name for plugin loader.
XmlRpcServer s
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
Definition: BaseState.h:12
ros::ServiceServer _state_info_service
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
Definition: BaseState.h:8
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
Definition: BaseState.h:11
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.
#define INTERRUPT_END
Definition: BaseState.h:10
std::string _calculate_goal_plugin
Calculate goal state plugin name for plugin loader.
#define SIMPLE_GOAL_INTERRUPT
Definition: BaseState.h:13
#define SIMPLE_GOAL
Definition: BaseState.h:18
#define ROS_ERROR(...)
ros::ServiceServer _stop_2d_nav_goal_service


rsm_core
Author(s): Marco Steinbrink
autogenerated on Mon Feb 28 2022 23:28:16