diff --git a/core/start-blueos-core b/core/start-blueos-core index 2a53b8602..33391da1c 100755 --- a/core/start-blueos-core +++ b/core/start-blueos-core @@ -88,10 +88,10 @@ fi # From that 1min30s, the startup time is about ~25s, and originally, ~37s, meaning that the # remaining (~65 seconds) is the docker shutting down, and the Linux booting up. PRIORITY_SERVICES=( - 'autopilot',250,"nice --19 $SERVICES_PATH/ardupilot_manager/main.py" - 'cable_guy',250,"$SERVICES_PATH/cable_guy/main.py" + 'autopilot',0,"nice --19 $SERVICES_PATH/ardupilot_manager/main.py" + 'cable_guy',0,"$SERVICES_PATH/cable_guy/main.py" 'video',0,"nice --19 mavlink-camera-manager --default-settings BlueROVUDP --mavlink tcpout:127.0.0.1:5777 --mavlink-system-id $MAV_SYSTEM_ID --gst-feature-rank omxh264enc=0,v4l2h264enc=250,x264enc=260 --log-path /var/logs/blueos/services/mavlink-camera-manager --verbose" - 'mavlink2rest',250,"mavlink2rest --connect=udpin:127.0.0.1:14000 --server 0.0.0.0:6040 --system-id $MAV_SYSTEM_ID --component-id $MAV_COMPONENT_ID_ONBOARD_COMPUTER4" + 'mavlink2rest',0,"mavlink2rest --connect=udpin:127.0.0.1:14000 --server 0.0.0.0:6040 --system-id $MAV_SYSTEM_ID --component-id $MAV_COMPONENT_ID_ONBOARD_COMPUTER4" ) SERVICES=(