User Tools

Site Tools


getting_started:practical_problems:abort

Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revisionPrevious revision
Next revision
Previous revision
Next revisionBoth sides next revision
getting_started:practical_problems:abort [2017/09/25 07:39] grafgetting_started:practical_problems:abort [2017/11/05 13:37] – [Define Signal Handler when using ROS] graf
Line 7: Line 7:
  
 void signalHandler(int signum) { void signalHandler(int signum) {
- SafetySystem::exitHandler();+  SafetySystem::exitHandler();
 } }
  
Line 35: Line 35:
 The system will stay in the level as long as the shutting down will take. This could include a whole sequence of steps such as applying brakes or driving to a safe position. As soon as this point is reached another safety event, ''seSwitchingOff'' is triggered which leads to a safety level change to ''slOff''. The action to be taken in this level is stopping the executor. Therefore, you have to assign a level action in your safety properties as follows: The system will stay in the level as long as the shutting down will take. This could include a whole sequence of steps such as applying brakes or driving to a safe position. As soon as this point is reached another safety event, ''seSwitchingOff'' is triggered which leads to a safety level change to ''slOff''. The action to be taken in this level is stopping the executor. Therefore, you have to assign a level action in your safety properties as follows:
 <code cpp> <code cpp>
-slOff.setLevelAction([&](SafetyContext* privateContext) {Executor::stop();});+slOff.setLevelAction([&](SafetyContext* privateContext) { 
 +  Executor::stop(); 
 +  Sequencer::instance().abort(); 
 +}); 
 +</code> 
 +This will cause the executor to stop running and return control to the main programm. Further, any running sequences will terminate and the main program will exit. 
 + 
 +===== Define Signal Handler when using ROS ===== 
 +If you use ROS you have to keep in mind to register the signal handler only after the ROS node is created and initialized, otherwise the registration will be overwritten by ROS. 
 +<code cpp> 
 + 
 +int main() { 
 +  ... 
 +  // init ROS node 
 +   
 +  signal(SIGINT, signalHandler); 
 +  ... 
 +}
 </code> </code>
-This will cause the executor to stop running and return control to the main programm which in turns will exit. 
getting_started/practical_problems/abort.txt · Last modified: 2024/02/16 08:16 by ursgraf