Automatic startup and shutdown for a ROS robot

5 mins

Updated:

While going through some design improvements for our rover, I decided to implement a simpler method of turning the rover on and off. Here is what we ultimately want to achieve:

  • Our roslaunch file should run automatically once the host PC boots up (launching ROS normally requires use of the command line)
  • A single toggle switch should control the on/off state of both the PC and the motor controllers
  • The PC should be given ample time to shutdown properly and not just have it’s ‘plug pulled’ when the toggle switch is opened

By the way: We are using a Jetson Xavier NX developer kit as our PC (with ROS Kinetic), and a pair of ODrives for our motor controllers. These instructions should still be relevant for similar hardware configurations, although the software steps may be quite different for a non-Linux setup.

ros_upstart

ros_upstart is a ROS package which configures a Linux daemon (background) service to run your chosen roslaunch file. The service starts automatically once the OS is booted, but can also be started and stopped manually just like any other daemon. Here is the guide I used to configure ros_upstart.

You may also need to consider the permissions granted to the service. By default the service is run without user privileges, which may cause problems if your ROS nodes need to access hardware interfaces e.g. GPIO, UART. In Linux, use of these interfaces is typically controlled using groups. A group is granted access to a particular interface via a udev rule, and users who belong to that group are able to use the interface.

The solution is to specify a user – who is a member of all the necessary groups - while configuring ros_upstart:

rosrun robot_upstart install my_robot_bringup/launch/my_robot.launch --job my_robot_ros --symlink --user patrick

This ensures the target roslaunch file runs with the permissions of user “patrick”. I also had to modify one of the files generated by ros_upstart (my_robot_ros-start in /usr/sbin) to get everything working, but I’d only recommend this if the prior steps are insufficient:

# Replace this line:
setuidgid patrick roslaunch $LAUNCH_FILENAME & PID=$!

# With this one:
envuidgid patrick roslaunch $LAUNCH_FILENAME & PID=$!

You can use the command rosnode list to verify that all your nodes have been loaded successfully by the service.

Switch detection

While ros_upstart takes care of the start-up procedure, we still need a way of turning the system off. As one of our primary aims is to control everything using a single toggle switch, we need some way of detecting the state of this switch and running the shutdown command when it is in the off state. Running this command ensures all services (including ROS) are stopped in a controlled manner, and protects against filesystem corruption.

In our rover the toggle switch is used to connect / disconnect the high side of a 24V battery, so the first obstacle we face is translating a 24V signal into a 3.3V signal compatible with the TTL level of our PC’s GPIO pins. We achieve this using an optocoupler (an IS2801-1 from Isocom Components to be exact, although most optocouplers should be OK).

Optocouplers have the additional benefit of galvanic isolation, therefore there is no need for the battery negative and signal negative to be tied together, as would be the case for a normal level translation circuit. This, along with the fact we are using an isolated DC/DC converter to power our PC from the 24V battery, keeps high currents from the motor controllers away from the PC’s ground connections.

Detecting the switch state and initiating shut down can be achieved in a few lines of code within a ROS node:

#!/usr/bin/env python

import Jetson.GPIO as GPIO
import rospy
import os

# initialise GPIO (switch signal connected to pin 37)
GPIO.setmode(GPIO.BOARD)
GPIO.setup(37, GPIO.IN)

# how many seconds the switch must be in the 'off' position before calling shutdown
shutdown_count = 3

def main():

	# node setup
	rospy.init_node('shutdown_input')
	r = rospy.Rate(1)

	counter = 0

	# ensure this node closes down if ROS exits
	while not rospy.is_shutdown():

		# switch in 'off' position
		if GPIO.input(37):

			counter += 1

		# switch in 'on' position
		else:

			counter = 0

		if counter >= shutdown_count:
			
			os.system("shutdown now -h")

		r.sleep()

	# release GPIO on exit
	GPIO.cleanup()

if __name__ == '__main__':

	main()						

Delay off timer

There is one extra thing we need to ensure the shutdown function can work effectively. While the toggle switch is sufficient to power off the motor controllers and signal the PC to shutdown, there needs to a way to keep the PC powered while it is shutting down, as a toggle switch by it’s nature causes a break in the circuit. This can be achieved using a ‘delay off’ timer relay. The complete circuit, including the aforementioned optocoupler is shown below:

The delay timer here keeps the coil energised for a fixed interval once the switch has been opened (about 30 seconds in our case), allowing current to flow through the relay contacts and thus keep the DC/DC converter powered while the shutdown is completed. After this delay the coil de-energises and the DC/DC converter is switched off, preventing anything from draining the 24V battery while the rover is switched off.

Finishing up

With everything wired up and working, it’s just a case of adding the shutdown node to the list of nodes that are launched on startup via ros_upstart. It’s definitely worth testing this node independently before adding it to your roslaunch file, as you may end up with the PC shutting itself down instantly on startup, which could be an annoying problem to fix.

Leave a Comment

Loading...