Multi-computer reboot/shutdown setup

Hi, I’m trying to implement the backend to make the Reboot and Turn off button of the UI work for both computers on my LeoRover.

So far, I’ve managed to make a pre-shutdown topic that calls a routine that calls the /stop_motor service of the RPLidar, and publish a data: True msg on the relay1 and relay2 topics.

I can’t seem to be able to make the actual reboot/shutdown command work on my Jetson Nano. It seems that the command is never received on the Jetson. The Pi is shutdown before that. I tried adding a time.sleep(3) to the two callbacks in the leo_system python script and sudo service leo restart but it doesn’t work either.

Does anyone have an idea on how I could make it work?

Could you share your code?

I would probably do something like:

ssh -t jetson 'shutdown -h now` 

to shutdown jetson remotely.

Hi,

I was actually trying to run a modified version of leo_system on the Jetson. The only modification I made in LeoOS, is to add a time.sleep(1) in the shutdown and reboot callbacks. To test my setup I published an Empty msg on the new system/preshutdown topic.

But the Pi is shutting down before the msg reaches the Jetson and therefore it stays on while the Pi shutdown as intended.

#!/usr/bin/env python
import rospy
import os
import time

from std_msgs.msg import Bool, Empty
from std_srvs import srv
from ros_jetson_stats.srv import fan


def rebootCallback(x):
    rospy.loginfo("Reboot command invoked")
    time.sleep(1)
    os.system("shutdown -r now")

def preshutdownCallback(x):
    rospy.loginfo("pre-shutdown command invoked")
    relay1_pub = rospy.Publisher("relay1", Bool, queue_size=1)
    relay2_pub = rospy.Publisher("relay2", Bool, queue_size=1)
    relay_msg = Bool()
    relay_msg.data = True
    relay1_pub.publish(relay_msg)
    relay2_pub.publish(relay_msg)
    try:
        rospy.wait_for_service("/ros_jetson_stats/fan", 2)
        fan_srv = rospy.ServiceProxy("/ros_jetson_stats/fan", fan)
        msg = fan()
        msg.mode = "manual"
        msg.fanSpeed = 0
        resp = fan_srv(msg)
    except rospy.ROSException as e:
        rospy.logerr(e)
    try:
        rospy.wait_for_service('/stop_motor', 2)
        stop_motor = rospy.ServiceProxy('/stop_motor', srv.Empty)
        resp = stop_motor(srv.EmptyRequest())
    except rospy.ROSException as e:
        rospy.logerr(e)
    shutdown_pub = rospy.Publisher("system/shutdown", Empty, queue_size=5)
    shutdown_pub.publish(Empty())

def shutdownCallback(x):
    rospy.loginfo("Shutdown command invoked")
    time.sleep(1)
    os.system("shutdown -h now")

try:
    rospy.init_node("leo_system_jetson")
    preshutdown_pub = rospy.Subscriber("system/preshutdown", Empty, preshutdownCallback)
    shutdown_pub = rospy.Subscriber("system/shutdown", Empty, shutdownCallback)
    rospy.loginfo("Jetson system node started!")
except rospy.ROSInterruptException as e:
    rospy.logerr(e)

rospy.spin()

I could try the method you suggested, using ssh. I could run the preshutdown routine in another script. The thing I can’t quite figure out is, I need to send the ssh -t jetson 'shutdown -h now' command before the Pi is shutdown, but how can I do that without modifiying the leo_system script? If using the ssh method, I think I’ll need to setup ssh certificates for authentication, it that right?

Why not just do something like this:

#!/usr/bin/env python
import rospy
import os
import time

from std_msgs.msg import Bool, Empty
from std_srv import srv
from ros_jetson_stats.srv import fan

def preshutdownCallback(x):
    rospy.loginfo("pre-shutdown command invoked")
    relay1_pub = rospy.Publisher("relay1", Bool, queue_size=1)
    relay2_pub = rospy.Publisher("relay2", Bool, queue_size=1)
    relay_msg = Bool()
    relay_msg.data = True
    relay1_pub.publish(relay_msg)
    relay2_pub.publish(relay_msg)
    try:
        rospy.wait_for_service("/ros_jetson_stats/fan", 2)
        fan_srv = rospy.ServiceProxy("/ros_jetson_stats/fan", fan)
        msg = fan()
        msg.mode = "manual"
        msg.fanSpeed = 0
        resp = fan_srv(msg)
    except rospy.ROSException as e:
        rospy.logerr(e)
    try:
        rospy.wait_for_service('/stop_motor', 2)
        stop_motor = rospy.ServiceProxy('/stop_motor', srv.Empty)
        resp = stop_motor(srv.EmptyRequest())
    except rospy.ROSException as e:
        rospy.logerr(e)
    shutdown_pub = rospy.Publisher("system/shutdown", Empty, queue_size=5)
    shutdown_pub.publish(Empty())
    time.sleep(1)
    os.system("shutdown -h now")

try:
    rospy.init_node("leo_system_jetson")
    preshutdown_sub = rospy.Subscriber("system/preshutdown", Empty, preshutdownCallback)
    rospy.loginfo("Jetson system node started!")
except rospy.ROSInterruptException as e:
    rospy.logerr(e)

rospy.spin()

This won’t work because my Pi is connected to the network through the Ethernet connection from the Jetson. If the jetson is shutdown, I can’t shutdown the Pi.

I have a similar issue when the Pi is shutdown before the Jetson. Since the Pi runs the ros master, I can’t call the ros service nor publish on the ros topics. It’s not an easy problem to tackle.

The expected behaviour is:

  • Shutdown: Pre-Shutdown procedure (Turn jetson fan off, pub to set the relays off) shutdown Pi then shutdown Jetson
  • Reboot: Reboot Pi then after a few seconds Reboot Jetson.

As I mentionned earlier, it looks like the issue comes from the Pi being shutdown before sending the reboot/shutdown msg to the Jetson. It seems quite hard to make sure that both the Pi and the Jetson are shutdown in the right order.

EDIT: Thinking about it, maybe I could run my pre-shutdown procedure, publish on the system/shutdown or system/reboot topic and then run the os.system("shutdown -h now") locally.

The shutdown procedure can be quite challenging due to different race conditions. Here’s how I would do it:

On Jetson, add system/jetson_shutdown ROS service that runs the preshutdown procedure and sets a timer that will shutdown the computer after a couple of seconds (so it could reply to the service request). It would look like this:

#!/usr/bin/env python
import rospy
import os
import time
from threading import Timer

from std_msgs.msg import Bool, Empty
from std_srv import srv
from ros_jetson_stats.srv import fan

def preshutdown():
    rospy.loginfo("pre-shutdown command invoked")
    relay1_pub = rospy.Publisher("relay1", Bool, queue_size=1)
    relay2_pub = rospy.Publisher("relay2", Bool, queue_size=1)
    relay_msg = Bool()
    relay_msg.data = True
    relay1_pub.publish(relay_msg)
    relay2_pub.publish(relay_msg)
    try:
        rospy.wait_for_service("/ros_jetson_stats/fan", 2)
        fan_srv = rospy.ServiceProxy("/ros_jetson_stats/fan", fan)
        msg = fan()
        msg.mode = "manual"
        msg.fanSpeed = 0
        resp = fan_srv(msg)
    except rospy.ROSException as e:
        rospy.logerr(e)
    try:
        rospy.wait_for_service('/stop_motor', 2)
        stop_motor = rospy.ServiceProxy('/stop_motor', srv.Empty)
        resp = stop_motor(srv.EmptyRequest())
    except rospy.ROSException as e:
        rospy.logerr(e)

def jetson_shutdown(req):
    preshutdown()
    shutdown_timer.start()
    return srv.EmptyResponse()

def do_shutdown():
    os.system("shutdown -h now")


shutdown_timer = Timer(3.0, do_shutdown)

rospy.init_node("leo_system_jetson")
shutdown_srv = rospy.Service("system/jetson_shutdown", srv.Empty, jetson_shutdown)
rospy.loginfo("Jetson system node started!")

rospy.spin()

(It can have some syntax errors)

On RPi, I would modify the shutdownCallback to call the jetson_shutdown service before doing the shutdown itself. The service calls are blocking, so it should be guaranteed to start the shutdown timer on the jetson.

That’s a neat solution! I’ll try it asap.

I might also modify the firmware to replace the relay topics by services to make the calls blocking.

I’m currently testing the new script you provided. I modified it a little.

#!/usr/bin/env python
import rospy
import os
from threading import Timer

from std_msgs.msg import Bool
from std_srvs.srv import Empty, EmptyRequest, EmptyResponse
from ros_jetson_stats.srv import fan, fanRequest

def preshutdown():
    rospy.loginfo("pre-shutdown command invoked")
    relay1_pub = rospy.Publisher("relay1", Bool, queue_size=1)
    relay2_pub = rospy.Publisher("relay2", Bool, queue_size=1)
    relay_msg = Bool()
    relay_msg.data = True
    relay1_pub.publish(relay_msg)
    relay2_pub.publish(relay_msg)
    try:
        rospy.logdebug("Setting fan to manual speed: 0")
        rospy.wait_for_service("/jtop/fan", 2)
        msg = fanRequest()
        msg.mode = "manual"
        msg.fanSpeed = 0
        resp = fan_srv(msg)
    except rospy.ROSException as e:
        rospy.logerr(e)
    try:
        rospy.logdebug("Stopping the LiDAR motor")
        rospy.wait_for_service('/stop_motor', 2)
        stop_motor = rospy.ServiceProxy('/stop_motor', Empty)
        resp = stop_motor(EmptyRequest())
    except rospy.ROSException as e:
        rospy.logerr(e)

def jetson_reboot(req):
    rospy.logdebug("Reboot timer starting")
    reboot_timer.start()
    return EmptyResponse()

def jetson_shutdown(req):
    preshutdown()
    rospy.logdebug("Shutdown timer starting")
    shutdown_timer.start()
    return EmptyResponse()

def do_reboot():
    os.system("shutdown -r now")

def do_shutdown():
    os.system("shutdown -h now")

def initialise():
    rospy.wait_for_service("/jtop/fan", 5)
    global fan_srv
    fan_srv = rospy.ServiceProxy("/jtop/fan", fan)
    msg = fanRequest()
    msg.mode = "default"
    resp = fan_srv(msg)

reboot_timer = Timer(3.0, do_reboot)
shutdown_timer = Timer(3.0, do_shutdown)

rospy.init_node("leo_system_jetson", log_level=rospy.DEBUG)
initialise()
reboot_srv = rospy.Service("/leo_system/jetson_reboot", Empty, jetson_reboot)
shutdown_srv = rospy.Service("/leo_system/jetson_shutdown", Empty, jetson_shutdown)
rospy.loginfo("Jetson system node started!")

rospy.spin()

I get the following error when my script gets to the os.system("shutdown -r now") call.

Failed to set wall message, ignoring: Interactive authentication required.
Failed to reboot system via logind: Interactive authentication required.
Failed to open /dev/initctl: Permission denied
Failed to talk to init daemon.

I’m guessing there’s a permission error somewhere but I can’t seem to locate where.

EDIT: I found part of the solution here: Non-interactive shutdown from ssh - #10 by alciregi - Ask Fedora.
I then needed to add sudo in the reboot and shutdown service of my jetson script.

To perform shutdown and reboot operations from inactive session without sudo, you need to add rules to PolKit Local Authority. In LeoOS it is done by adding this file to the /etc/polkit-1/localauthority/50-local.d/ directory:

1 Like