Robot Control Library
start_stop.h
Go to the documentation of this file.
1/**
2 * <rc/start_stop.h>
3 *
4 * @brief cleanly start and stop a process, signal handling, program flow
5 *
6 * It can be tricky to manage the starting and stopping of mutiple threads and
7 * loops. Since the robot control library has several background threads in
8 * addition to any user-created threads, we encourage the use of the
9 * consolidated high-level process control method described here. These
10 * functions allow easy implementation of good-practice process handling
11 * including a global shutdown flag, a signal handler, making & deleting a PID
12 * file, stopping previously running copies of a program, and stopping a program
13 * when it's in the background.
14 *
15 * The rc_state_t struct tries to cover the majority of use cases in the context
16 * of a robotics application. The user should start their program main()
17 * function by setting the state to UNINITIALIZED and enabling the signal
18 * handler before doing hardware initialization and starting threads. When the
19 * user's own initialization sequence is complete they should set the flow state
20 * to PAUSED or RUNNING to indicate to the newly created threads that the
21 * program should now behave in normal ongoing operational mode.
22 *
23 * During normal operation, the user may elect to implement a PAUSED state where
24 * the user's threads may keep running to read sensors but do not actuate
25 * motors, leaving their robot in a safe state. For example, pressing the pause
26 * button could be assigned to change this state back and forth between RUNNING
27 * and PAUSED. This is entirely optional.
28 *
29 * The most important state here is EXITING. The signal handler described here
30 * intercepts the SIGINT signal when the user presses Ctrl-C and sets the state
31 * to EXITING. It is then up to the user's threads to watch for this condition
32 * and exit cleanly. The user may also set the state to EXITING at any time to
33 * trigger the closing of their own threads and robot control library's own
34 * background threads.
35 *
36 * The flow state variable is kept in the robot control library's memory space
37 * and should be read and modified by the rc_get_state() and rc_set_state()
38 * functions above. The user may optionally use the rc_print_state() function to
39 * print a human readable version of the state enum to the screen.
40 *
41 *
42 * @addtogroup start_stop
43 * @{
44 */
45
46#ifndef RC_START_STOP_H
47#define RC_START_STOP_H
48
49#ifdef __cplusplus
50extern "C" {
51#endif
52
53#define RC_PID_DIR "/run/shm/"
54#define RC_PID_FILE "/run/shm/robotcontrol.pid"
55
56/**
57 * @brief process state variable, read and modify by rc_get_state,
58 * rc_set_state, and rc_print_state. Starts as UNINITIALIZED.
59 */
60typedef enum rc_state_t {
66
67
68/**
69 * @brief fetches the current process state as set by the user or signal
70 * handler
71 *
72 * @return current process state
73 */
75
76
77/**
78 * @brief sets the current process state.
79 *
80 * Except for the signal handler setting the state to EXITING, this is the only
81 * way that the process state can be changed.
82 *
83 * @param[in] new_state The new state
84 */
85void rc_set_state(rc_state_t new_state);
86
87
88/**
89 * @brief prints the process state to stdout in human-readble form
90 *
91 * @return 0 on success, -1 on failure
92 */
94
95
96/**
97 * @brief Makes a PID file RC_PID_FILE (/run/shm/robotcontrol.pid)
98 * containing the current PID of your process
99 *
100 * @return Returns 0 if successful. If that file already exists then it is
101 * not touched and this function returns 1 at which point we suggest you run
102 * rc_kill_exising_process() to kill that process. Returns -1 if there is some
103 * other problem writing to the file.
104 */
106
107
108/**
109 * @brief This function is used to make sure any existing program using the
110 * PID file is stopped.
111 *
112 * The user doesn't need to integrate this in their own program However, the
113 * user may call the rc_kill example program from the command line to close
114 * whatever program is running in the background.
115 *
116 * @param[in] timeout_s timeout period to wait for process to close cleanly,
117 * must be >=0.1
118 *
119 * @return return values:
120 * - -4: invalid argument or other error
121 * - -3: insufficient privileges to kill existing process
122 * - -2: unreadable or invalid contents in RC_PID_FILE
123 * - -1: existing process failed to close cleanly and had to be killed
124 * - 0: No existing process was running
125 * - 1: An existing process was running but it shut down cleanly.
126 */
127int rc_kill_existing_process(float timeout_s);
128
129
130/**
131 * @brief Removes the PID file created by rc_make_pid_file().
132 *
133 * This should be called before your program closes to make sure it's not left
134 * behind.
135 *
136 * @return Returns 0 whether or not the file was actually there. Returns -1
137 * if there was a file system error.
138 */
140
141
142/**
143 * @brief Enables a generic signal handler. Optional but recommended.
144 *
145 * This catches SIGINT, SIGTERM, SIGHUP, and SIGSEGV and does the following:
146 *
147 * - SIGINT (ctrl-c) Sets process state to EXITING indicating to the user
148 * threads to shut down cleanly. All user threads should check rc_get_state to
149 * catch this.
150 * - SITERM: Same as SIGINT above
151 * - SIGHUP: Ignored to prevent process from stopping due to loose USB network
152 * connection. Also allows robot control programs to keep running after USB
153 * cable in intentionally removed.
154 * - SIGSEGV: Segfaults will be caught and print some debugging info to the
155 * screen before setting rc_state to EXITING. Behavior with segfaults is no
156 * guaranteed to be predictable.
157 *
158 * @return Returns 0 on success or -1 on error
159 */
161
162
163/**
164 * @brief resets the system signal callbacks to defualt, generally this is
165 * never needed unless you are intentionally changing signal handlers in the
166 * middle of a program.
167 *
168 * @return Returns 0 on success or -1 on error
169 */
171
172
173#ifdef __cplusplus
174}
175#endif
176
177#endif // RC_START_STOP_H
178
179/** @} end group start_stop*/
180
rc_state_t rc_get_state(void)
fetches the current process state as set by the user or signal handler
int rc_remove_pid_file(void)
Removes the PID file created by rc_make_pid_file().
void rc_set_state(rc_state_t new_state)
sets the current process state.
int rc_print_state(void)
prints the process state to stdout in human-readble form
int rc_make_pid_file(void)
Makes a PID file RC_PID_FILE (/run/shm/robotcontrol.pid) containing the current PID of your process.
int rc_enable_signal_handler(void)
Enables a generic signal handler. Optional but recommended.
int rc_disable_signal_handler(void)
resets the system signal callbacks to defualt, generally this is never needed unless you are intentio...
rc_state_t
process state variable, read and modify by rc_get_state, rc_set_state, and rc_print_state....
Definition: start_stop.h:60
int rc_kill_existing_process(float timeout_s)
This function is used to make sure any existing program using the PID file is stopped.
@ RUNNING
Definition: start_stop.h:62
@ EXITING
Definition: start_stop.h:64
@ PAUSED
Definition: start_stop.h:63
@ UNINITIALIZED
Definition: start_stop.h:61