mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 23:07:34 +08:00
174 lines
5.0 KiB
Bash
Executable File
174 lines
5.0 KiB
Bash
Executable File
#!/bin/bash
|
|
#
|
|
# Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@zubax.com>
|
|
#
|
|
|
|
HELP="Register slcan-enabled Serial-to-CAN adapters as network interfaces.
|
|
Usage:
|
|
`basename $0` [options] <tty0> [[options] <tty1> ...]
|
|
|
|
Interface indexes will be assigned automatically in ascending order, i.e.
|
|
first device will be mapped to the interface slcan0, second will be mapped to
|
|
slcan1, and so on. Each added option affects only the interfaces that follow
|
|
it, which means that options must be properly ordered (see examples below).
|
|
This tool requires superuser priveleges.
|
|
|
|
The package 'can-utils' must be installed. On Debian/Ubuntu-based systems it
|
|
can be installed via APT: apt-get install can-utils
|
|
|
|
Options:
|
|
--speed-code <X> (where X is a number in range [0, 8]; default: 8)
|
|
-s<X>
|
|
Set CAN speed to:
|
|
0 - 10 Kbps
|
|
1 - 20 Kbps
|
|
2 - 50 Kbps
|
|
3 - 100 Kbps
|
|
4 - 125 Kbps (UAVCAN recommended)
|
|
5 - 250 Kbps (UAVCAN recommended)
|
|
6 - 500 Kbps (UAVCAN recommended)
|
|
7 - 800 Kbps
|
|
8 - 1 Mbps (UAVCAN recommended, default)
|
|
|
|
--remove-all
|
|
-r
|
|
Remove all SLCAN interfaces.
|
|
If this option is used, it MUST be provided FIRST, otherwise it
|
|
will remove the interfaces added earlier.
|
|
|
|
--basename <X> (where X is a string containing [a-z], default: slcan)
|
|
-b<X>
|
|
Base name to use for the interfaces that follow this option.
|
|
Default value is 'slcan'. This option can be provided multiple times,
|
|
it will only affect the interfaces that were provided after it. If you
|
|
want to affect all added interfaces, provide this option first (see
|
|
examples below).
|
|
|
|
--baudrate <X> (where X is an integer, default: 921600)
|
|
-S<X>
|
|
Configure baud rate to use on the interface.
|
|
This option is mostly irrelevant for USB to CAN adapters.
|
|
|
|
Example 1:
|
|
`basename $0` --remove-all /dev/ttyUSB3 --basename can --baudrate 115200 \\
|
|
/dev/ttyUSB0 --speed-code 4 /dev/ttyACM0
|
|
The example above initializes the interfaces as follows:
|
|
/dev/ttyUSB3 --> slcan0 1 Mbps baudrate 921600
|
|
/dev/ttyUSB0 --> can0 1 Mbps baudrate 115200
|
|
/dev/ttyACM0 --> can1 125 kbps baudrate 115200
|
|
|
|
Example 2:
|
|
`basename $0` --remove-all
|
|
The example above only removes all SLCAN interfaces without adding new ones."
|
|
|
|
function die() { echo $@ >&2; exit 1; }
|
|
|
|
if [ "$1" == '--help' ] || [ "$1" == '-h' ]; then echo "$HELP"; exit; fi
|
|
|
|
[ -n "$1" ] || die "Invalid usage. Use --help to get help."
|
|
|
|
[ "$(id -u)" == "0" ] || die "Must be root."
|
|
|
|
which slcan_attach > /dev/null || die "Please install can-utils first."
|
|
|
|
# ---------------------------------------------------------
|
|
|
|
function deinitialize() {
|
|
echo "Stopping slcand..." >&2
|
|
# Trying SIGINT first
|
|
killall -INT slcand &> /dev/null
|
|
sleep 0.3
|
|
# Then trying the default signal, which is SIGTERM, if SIGINT didn't help
|
|
slcand_kill_retries=10
|
|
while killall slcand &> /dev/null
|
|
do
|
|
(( slcand_kill_retries -= 1 ))
|
|
[[ "$slcand_kill_retries" > 0 ]] || die "Failed to stop slcand"
|
|
sleep 1
|
|
done
|
|
}
|
|
|
|
function handle_tty() {
|
|
tty=$(readlink -f $1)
|
|
tty=${tty/'/dev/'}
|
|
|
|
iface_index=0
|
|
while ifconfig "$IFACE_BASENAME$iface_index" &> /dev/null
|
|
do
|
|
iface_index=$((iface_index + 1))
|
|
done
|
|
|
|
slcan_iface_index=0
|
|
while ifconfig "slcan$slcan_iface_index" &> /dev/null
|
|
do
|
|
slcan_iface_index=$((slcan_iface_index + 1))
|
|
done
|
|
|
|
iface="$IFACE_BASENAME$iface_index"
|
|
slcan_iface="slcan$slcan_iface_index"
|
|
|
|
echo "Attaching $tty to $iface speed code $SPEED_CODE baudrate $BAUDRATE" >&2
|
|
|
|
# Configuring the baudrate
|
|
stty -F /dev/$tty ispeed $BAUDRATE ospeed $BAUDRATE || return 1
|
|
|
|
# Attaching the line discipline. Note that slcan_attach has option -n but it doesn't work.
|
|
slcan_attach -f -o -s$SPEED_CODE /dev/$tty > /dev/null || return 2
|
|
slcand $tty || return 3
|
|
sleep 1 # FIXME
|
|
|
|
# ...therefore we need to rename the interface manually
|
|
ip link set $slcan_iface name $iface
|
|
|
|
ifconfig $iface up || return 4
|
|
}
|
|
|
|
IFACE_BASENAME='slcan'
|
|
SPEED_CODE=8
|
|
BAUDRATE=921600
|
|
|
|
next_option=''
|
|
while [ -n "$1" ]; do
|
|
case $1 in
|
|
-r | --remove-all)
|
|
deinitialize
|
|
;;
|
|
|
|
-b*)
|
|
IFACE_BASENAME=${1:2}
|
|
;;
|
|
|
|
-S*)
|
|
BAUDRATE=${1:2}
|
|
;;
|
|
|
|
-s[0-8])
|
|
SPEED_CODE=${1:2}
|
|
;;
|
|
|
|
--*)
|
|
next_option=${1:2}
|
|
;;
|
|
|
|
-*)
|
|
die "Invalid option: $1"
|
|
;;
|
|
|
|
*)
|
|
if [ "$next_option" = 'basename' ]; then IFACE_BASENAME=$1
|
|
elif [ "$next_option" = 'speed-code' ]; then SPEED_CODE=$1
|
|
elif [ "$next_option" = 'baudrate' ]; then BAUDRATE=$1
|
|
elif [ "$next_option" = '' ]
|
|
then
|
|
handle_tty $1 || die "Failed to configure the interface $1"
|
|
else
|
|
die "Invalid option '$next_option'"
|
|
fi
|
|
next_option=''
|
|
;;
|
|
esac
|
|
shift
|
|
done
|
|
|
|
[ "$next_option" = '' ] || die "Expected argument for option '$next_option'"
|