mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
6 Commits
mcu-versio
...
4c3a741589
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
4c3a741589 | ||
|
|
44e457bf76 | ||
|
|
6eb4f0041b | ||
|
|
e1cb23ed00 | ||
|
|
358380c23c | ||
|
|
760f6ddd19 |
@@ -1,12 +1,12 @@
|
|||||||
#!/usr/bin/env bash
|
#!/usr/bin/env bash
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
SCRIPT_DIR=$( cd -- "$( dirname -- "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )
|
SCRIPT_DIR=$(cd -- "$(dirname -- "${BASH_SOURCE[0]}")" &>/dev/null && pwd)
|
||||||
|
|
||||||
# Wait for a network interface to be up (not necessarily online)
|
# Wait for a network interface to be up (not necessarily online)
|
||||||
while ! ip link show | grep -q "state UP"; do
|
while ! ip link show | grep -q "state UP"; do
|
||||||
echo "[INFO] Waiting for active network interface..."
|
echo "[INFO] Waiting for active network interface..."
|
||||||
sleep 1
|
sleep 1
|
||||||
done
|
done
|
||||||
|
|
||||||
echo "[INFO] Network interface is up!"
|
echo "[INFO] Network interface is up!"
|
||||||
@@ -16,9 +16,9 @@ echo "[INFO] Starting ROS node..."
|
|||||||
|
|
||||||
# Source ROS 2 Humble setup script
|
# Source ROS 2 Humble setup script
|
||||||
if command -v nixos-rebuild; then
|
if command -v nixos-rebuild; then
|
||||||
echo "[INFO] running on NixOS"
|
echo "[INFO] running on NixOS"
|
||||||
else
|
else
|
||||||
source /opt/ros/humble/setup.bash
|
source /opt/ros/humble/setup.bash
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Source your workspace setup script
|
# Source your workspace setup script
|
||||||
|
|||||||
@@ -1,12 +1,12 @@
|
|||||||
#!/usr/bin/env bash
|
#!/usr/bin/env bash
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
SCRIPT_DIR=$( cd -- "$( dirname -- "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )
|
SCRIPT_DIR=$(cd -- "$(dirname -- "${BASH_SOURCE[0]}")" &>/dev/null && pwd)
|
||||||
|
|
||||||
# Wait for a network interface to be up (not necessarily online)
|
# Wait for a network interface to be up (not necessarily online)
|
||||||
while ! ip link show | grep -q "state UP"; do
|
while ! ip link show | grep -q "state UP"; do
|
||||||
echo "[INFO] Waiting for active network interface..."
|
echo "[INFO] Waiting for active network interface..."
|
||||||
sleep 1
|
sleep 1
|
||||||
done
|
done
|
||||||
|
|
||||||
echo "[INFO] Network interface is up!"
|
echo "[INFO] Network interface is up!"
|
||||||
@@ -16,9 +16,9 @@ echo "[INFO] Starting ROS node..."
|
|||||||
|
|
||||||
# Source ROS 2 Humble setup script
|
# Source ROS 2 Humble setup script
|
||||||
if command -v nixos-rebuild; then
|
if command -v nixos-rebuild; then
|
||||||
echo "[INFO] running on NixOS"
|
echo "[INFO] running on NixOS"
|
||||||
else
|
else
|
||||||
source /opt/ros/humble/setup.bash
|
source /opt/ros/humble/setup.bash
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Source your workspace setup script
|
# Source your workspace setup script
|
||||||
@@ -26,4 +26,3 @@ source $SCRIPT_DIR/../install/setup.bash
|
|||||||
|
|
||||||
# Launch the ROS 2 node
|
# Launch the ROS 2 node
|
||||||
ros2 run headless_pkg headless_full
|
ros2 run headless_pkg headless_full
|
||||||
|
|
||||||
|
|||||||
@@ -1,26 +1,25 @@
|
|||||||
#!/usr/bin/env bash
|
#!/usr/bin/env bash
|
||||||
set -e
|
set -e
|
||||||
|
|
||||||
SCRIPT_DIR=$( cd -- "$( dirname -- "${BASH_SOURCE[0]}" )" &> /dev/null && pwd )
|
SCRIPT_DIR=$(cd -- "$(dirname -- "${BASH_SOURCE[0]}")" &>/dev/null && pwd)
|
||||||
|
|
||||||
[[ -z "$ANCHOR_WS" ]] && ANCHOR_WS="$SCRIPT_DIR/.."
|
[[ -z $ANCHOR_WS ]] && ANCHOR_WS="$SCRIPT_DIR/.."
|
||||||
[[ -z "$AUTONOMY_WS" ]] && AUTONOMY_WS="$HOME/rover-Autonomy"
|
[[ -z $AUTONOMY_WS ]] && AUTONOMY_WS="$HOME/rover-Autonomy"
|
||||||
BAG_LOCATION="$HOME/bags/autostart"
|
BAG_LOCATION="$HOME/bags/autostart"
|
||||||
[[ ! -d "$BAG_LOCATION" ]] && mkdir -p "$BAG_LOCATION"
|
[[ ! -d $BAG_LOCATION ]] && mkdir -p "$BAG_LOCATION"
|
||||||
|
|
||||||
# Wait for a network interface to be up (not necessarily online)
|
# Wait for a network interface to be up (not necessarily online)
|
||||||
while ! ip link show | grep -q "state UP"; do
|
while ! ip link show | grep -q "state UP"; do
|
||||||
echo "[INFO] Waiting for active network interface..."
|
echo "[INFO] Waiting for active network interface..."
|
||||||
sleep 1
|
sleep 1
|
||||||
done
|
done
|
||||||
|
|
||||||
echo "[INFO] Network interface is up!"
|
echo "[INFO] Network interface is up!"
|
||||||
|
|
||||||
|
|
||||||
if command -v nixos-rebuild; then
|
if command -v nixos-rebuild; then
|
||||||
echo "[INFO] running on NixOS"
|
echo "[INFO] running on NixOS"
|
||||||
else
|
else
|
||||||
source /opt/ros/humble/setup.bash
|
source /opt/ros/humble/setup.bash
|
||||||
fi
|
fi
|
||||||
source $ANCHOR_WS/install/setup.bash
|
source $ANCHOR_WS/install/setup.bash
|
||||||
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash
|
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash
|
||||||
|
|||||||
@@ -31,6 +31,8 @@
|
|||||||
name = "ASTRA Anchor";
|
name = "ASTRA Anchor";
|
||||||
packages = with pkgs; [
|
packages = with pkgs; [
|
||||||
colcon
|
colcon
|
||||||
|
socat
|
||||||
|
can-utils
|
||||||
(python313.withPackages (
|
(python313.withPackages (
|
||||||
p: with p; [
|
p: with p; [
|
||||||
pyserial
|
pyserial
|
||||||
|
|||||||
38
scripts/reset-repo.bash
Executable file
38
scripts/reset-repo.bash
Executable file
@@ -0,0 +1,38 @@
|
|||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
repo_root="$(git rev-parse --show-toplevel)"
|
||||||
|
|
||||||
|
if [[ -z $repo_root ]]; then
|
||||||
|
echo "script must be run from within the rover-ros2 repo" >&2
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
cd $repo_root
|
||||||
|
|
||||||
|
echo "this will nuke all of your current un-commited git changes, including any changes to submodules and any gitignored files. is this okay? (y/N)"
|
||||||
|
read okay
|
||||||
|
|
||||||
|
if [[ $okay != "y" ]]; then
|
||||||
|
echo "you didn't say exactly 'y'. aborting." >&2
|
||||||
|
exit 2
|
||||||
|
fi
|
||||||
|
|
||||||
|
echo
|
||||||
|
|
||||||
|
echo "ok say goodbye to everything in this repo"
|
||||||
|
git submodule deinit --all -f && echo "- submodules gone"
|
||||||
|
git clean -fdx && echo "- gitignored changes gone"
|
||||||
|
git add -A
|
||||||
|
git reset HEAD --hard && echo "- everything else gone"
|
||||||
|
git submodule update --init --recursive && echo "- brought the submodules back"
|
||||||
|
echo
|
||||||
|
|
||||||
|
echo "in theory that should've done it. let's make sure"
|
||||||
|
status=$(git status --porcelain)
|
||||||
|
echo $status
|
||||||
|
if [[ -z $status ]]; then
|
||||||
|
echo "nice, all clean!"
|
||||||
|
else
|
||||||
|
echo "uhh that's not supposed to be there. this is probably a bug in this script. good luck!" >&2
|
||||||
|
exit 3
|
||||||
|
fi
|
||||||
463
scripts/test-connectors.bash
Executable file
463
scripts/test-connectors.bash
Executable file
@@ -0,0 +1,463 @@
|
|||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
# test script for anchor connectors (mock, serial, CAN)
|
||||||
|
|
||||||
|
set -o pipefail
|
||||||
|
|
||||||
|
repo_root="$(git rev-parse --show-toplevel)"
|
||||||
|
|
||||||
|
if [[ -z $repo_root ]]; then
|
||||||
|
echo "script must be run from within the rover-ros2 repo" >&2
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
cd "$repo_root"
|
||||||
|
|
||||||
|
# colors
|
||||||
|
BOLD='\033[1m'
|
||||||
|
RED='\033[1;31m'
|
||||||
|
GREEN='\033[1;32m'
|
||||||
|
YELLOW='\033[1;33m'
|
||||||
|
NC='\033[0m'
|
||||||
|
|
||||||
|
TESTS_PASSED=0
|
||||||
|
TESTS_FAILED=0
|
||||||
|
|
||||||
|
log() {
|
||||||
|
echo -e "${BOLD}${YELLOW}info:${NC} ${1}"
|
||||||
|
}
|
||||||
|
|
||||||
|
pass() {
|
||||||
|
echo -e "${BOLD}${GREEN}pass:${NC} ${1}"
|
||||||
|
TESTS_PASSED=$((TESTS_PASSED + 1))
|
||||||
|
}
|
||||||
|
|
||||||
|
fail() {
|
||||||
|
echo -e "${BOLD}${RED}fail:${NC} ${1}"
|
||||||
|
TESTS_FAILED=$((TESTS_FAILED + 1))
|
||||||
|
}
|
||||||
|
|
||||||
|
cleanup() {
|
||||||
|
log "cleaning up"
|
||||||
|
if [[ -n $ANCHOR_PID ]]; then
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
wait "$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
fi
|
||||||
|
if [[ -n $SOCAT_PID ]]; then
|
||||||
|
kill -INT "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
wait "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
fi
|
||||||
|
rm -f /tmp/ttyACM9 /tmp/ttyOUT 2>/dev/null || true
|
||||||
|
}
|
||||||
|
|
||||||
|
trap cleanup EXIT
|
||||||
|
|
||||||
|
source_ros2() {
|
||||||
|
source install/setup.bash
|
||||||
|
}
|
||||||
|
|
||||||
|
wait_for_topic() {
|
||||||
|
local topic="$1"
|
||||||
|
local timeout="${2:-5}"
|
||||||
|
local count=0
|
||||||
|
while ! ros2 topic list 2>/dev/null | grep -q "^${topic}$"; do
|
||||||
|
sleep 0.5
|
||||||
|
count=$((count + 1))
|
||||||
|
if [[ $count -ge $((timeout * 2)) ]]; then
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
done
|
||||||
|
return 0
|
||||||
|
}
|
||||||
|
|
||||||
|
# run a ROS pub/echo test
|
||||||
|
# usage: ros_pubsub_test <echo_topic> <pub_topic> <msg_type> <msg_data>
|
||||||
|
# returns the echo output via stdout
|
||||||
|
ros_pubsub_test() {
|
||||||
|
local echo_topic="$1"
|
||||||
|
local pub_topic="$2"
|
||||||
|
local msg_type="$3"
|
||||||
|
local msg_data="$4"
|
||||||
|
|
||||||
|
timeout 5 bash -c "
|
||||||
|
ros2 topic echo --once $echo_topic &
|
||||||
|
ECHO_PID=\$!
|
||||||
|
sleep 0.5
|
||||||
|
ros2 topic pub --once $pub_topic $msg_type \"$msg_data\" >/dev/null 2>&1
|
||||||
|
wait \$ECHO_PID
|
||||||
|
" 2>/dev/null || true
|
||||||
|
}
|
||||||
|
|
||||||
|
test_mock_connector() {
|
||||||
|
log "testing mock connector"
|
||||||
|
|
||||||
|
log "starting anchor with mock connector"
|
||||||
|
setsid ros2 run anchor_pkg anchor --ros-args -p connector:=mock &
|
||||||
|
ANCHOR_PID=$!
|
||||||
|
sleep 2
|
||||||
|
|
||||||
|
if ! kill -0 "$ANCHOR_PID" 2>/dev/null; then
|
||||||
|
fail "mock connector: anchor failed to start"
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! wait_for_topic "/anchor/to_vic/relay" 10; then
|
||||||
|
fail "mock connector: topics not available"
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
log "anchor started successfully"
|
||||||
|
|
||||||
|
# test: relay -> debug
|
||||||
|
log "testing relay -> debug"
|
||||||
|
local output
|
||||||
|
output=$(ros_pubsub_test "/anchor/to_vic/debug" "/anchor/to_vic/relay" \
|
||||||
|
"astra_msgs/msg/VicCAN" '{mcu_name: \"core\", command_id: 50, data: [1.0, 2.0, 3.0, 4.0]}')
|
||||||
|
|
||||||
|
if [[ -n $output ]] && echo "$output" | grep -q "can_relay_tovic,core,50"; then
|
||||||
|
pass "mock connector: relay -> debug"
|
||||||
|
else
|
||||||
|
fail "mock connector: relay -> debug"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: mock_mcu -> from_vic/core
|
||||||
|
log "testing mock_mcu (core) -> from_vic/core"
|
||||||
|
output=$(ros_pubsub_test "/anchor/from_vic/core" "/anchor/from_vic/mock_mcu" \
|
||||||
|
"astra_msgs/msg/VicCAN" '{mcu_name: \"core\", command_id: 10, data: [100.0, 200.0]}')
|
||||||
|
|
||||||
|
if [[ -n $output ]] && echo "$output" | grep -q "mcu_name: core" && echo "$output" | grep -q "command_id: 10"; then
|
||||||
|
pass "mock connector: mock_mcu -> from_vic/core"
|
||||||
|
else
|
||||||
|
fail "mock connector: mock_mcu -> from_vic/core"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: mock_mcu -> from_vic/arm
|
||||||
|
log "testing mock_mcu (arm) -> from_vic/arm"
|
||||||
|
output=$(ros_pubsub_test "/anchor/from_vic/arm" "/anchor/from_vic/mock_mcu" \
|
||||||
|
"astra_msgs/msg/VicCAN" '{mcu_name: \"arm\", command_id: 55, data: [0.0, 450.0, 900.0, 0.0]}')
|
||||||
|
|
||||||
|
if [[ -n $output ]] && echo "$output" | grep -q "mcu_name: arm" && echo "$output" | grep -q "command_id: 55"; then
|
||||||
|
pass "mock connector: mock_mcu -> from_vic/arm"
|
||||||
|
else
|
||||||
|
fail "mock connector: mock_mcu -> from_vic/arm"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: mock_mcu -> from_vic/bio
|
||||||
|
log "testing mock_mcu (citadel) -> from_vic/bio"
|
||||||
|
output=$(ros_pubsub_test "/anchor/from_vic/bio" "/anchor/from_vic/mock_mcu" \
|
||||||
|
"astra_msgs/msg/VicCAN" '{mcu_name: \"citadel\", command_id: 20, data: [5.0]}')
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: citadel" && echo "$output" | grep -q "command_id: 20"; then
|
||||||
|
pass "mock connector: mock_mcu -> from_vic/bio"
|
||||||
|
else
|
||||||
|
fail "mock connector: mock_mcu -> from_vic/bio"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: relay_string -> debug
|
||||||
|
log "testing relay_string -> debug"
|
||||||
|
output=$(ros_pubsub_test "/anchor/to_vic/debug" "/anchor/to_vic/relay_string" \
|
||||||
|
"std_msgs/msg/String" '{data: \"test_raw_string_data\"}')
|
||||||
|
|
||||||
|
if [[ -n $output ]] && echo "$output" | grep -q "test_raw_string_data"; then
|
||||||
|
pass "mock connector: relay_string -> debug"
|
||||||
|
else
|
||||||
|
fail "mock connector: relay_string -> debug"
|
||||||
|
fi
|
||||||
|
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
wait "$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
ANCHOR_PID=""
|
||||||
|
}
|
||||||
|
|
||||||
|
test_serial_connector() {
|
||||||
|
log "testing serial connector"
|
||||||
|
|
||||||
|
log "creating virtual serial ports with socat"
|
||||||
|
socat pty,raw,echo=0,link=/tmp/ttyACM9 pty,raw,echo=0,link=/tmp/ttyOUT 2>/dev/null &
|
||||||
|
SOCAT_PID=$!
|
||||||
|
sleep 2
|
||||||
|
|
||||||
|
if ! kill -0 "$SOCAT_PID" 2>/dev/null; then
|
||||||
|
fail "serial connector: failed to create virtual serial ports"
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
log "starting anchor with serial connector (override: /tmp/ttyACM9)"
|
||||||
|
setsid ros2 run anchor_pkg anchor --ros-args -p connector:=serial -p serial_override:=/tmp/ttyACM9 &
|
||||||
|
ANCHOR_PID=$!
|
||||||
|
sleep 2
|
||||||
|
|
||||||
|
if ! kill -0 "$ANCHOR_PID" 2>/dev/null; then
|
||||||
|
fail "serial connector: anchor failed to start"
|
||||||
|
kill -INT "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! wait_for_topic "/anchor/to_vic/relay" 10; then
|
||||||
|
fail "serial connector: topics not available"
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
kill -INT "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
pass "serial connector: anchor starts with virtual serial"
|
||||||
|
|
||||||
|
# test: relay -> serial output (VicCAN encoding)
|
||||||
|
log "testing relay -> serial output"
|
||||||
|
|
||||||
|
local serial_out_file
|
||||||
|
serial_out_file=$(mktemp)
|
||||||
|
|
||||||
|
# Start head first (blocks waiting for input), then publish
|
||||||
|
timeout 5 head -n1 /tmp/ttyOUT >"$serial_out_file" &
|
||||||
|
local head_pid=$!
|
||||||
|
sleep 0.3
|
||||||
|
ros2 topic pub --once /anchor/to_vic/relay astra_msgs/msg/VicCAN \
|
||||||
|
'{mcu_name: "core", command_id: 30, data: [1.0, 2.0, 3.0, 4.0]}' >/dev/null 2>&1
|
||||||
|
wait $head_pid 2>/dev/null || true
|
||||||
|
|
||||||
|
local serial_out
|
||||||
|
serial_out=$(cat "$serial_out_file")
|
||||||
|
rm -f "$serial_out_file"
|
||||||
|
|
||||||
|
if [[ -n $serial_out ]] && echo "$serial_out" | grep -q "can_relay_tovic,core,30"; then
|
||||||
|
pass "serial connector: relay -> serial output"
|
||||||
|
else
|
||||||
|
fail "serial connector: relay -> serial output (got: $serial_out)"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: serial input -> from_vic/core
|
||||||
|
log "testing serial input -> from_vic/core"
|
||||||
|
|
||||||
|
local output
|
||||||
|
output=$(timeout 5 bash -c '
|
||||||
|
ros2 topic echo --once /anchor/from_vic/core &
|
||||||
|
ECHO_PID=$!
|
||||||
|
sleep 0.5
|
||||||
|
echo "can_relay_fromvic,core,15,10.0,20.0,30.0,40.0" > /tmp/ttyOUT
|
||||||
|
sleep 0.5
|
||||||
|
echo "can_relay_fromvic,core,15,10.0,20.0,30.0,40.0" > /tmp/ttyOUT
|
||||||
|
wait $ECHO_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: core" && echo "$output" | grep -q "command_id: 15"; then
|
||||||
|
pass "serial connector: serial input -> from_vic/core"
|
||||||
|
else
|
||||||
|
fail "serial connector: serial input -> from_vic/core (got: $output)"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: relay_string -> debug
|
||||||
|
log "testing relay_string -> debug"
|
||||||
|
output=$(ros_pubsub_test "/anchor/to_vic/debug" "/anchor/to_vic/relay_string" \
|
||||||
|
"std_msgs/msg/String" '{data: \"serial_test_string\"}')
|
||||||
|
|
||||||
|
if [[ -n $output ]] && echo "$output" | grep -q "serial_test_string"; then
|
||||||
|
pass "serial connector: relay_string -> debug"
|
||||||
|
else
|
||||||
|
fail "serial connector: relay_string -> debug"
|
||||||
|
fi
|
||||||
|
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
wait "$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
ANCHOR_PID=""
|
||||||
|
kill -INT "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
wait "$SOCAT_PID" 2>/dev/null || true
|
||||||
|
SOCAT_PID=""
|
||||||
|
}
|
||||||
|
|
||||||
|
test_can_connector() {
|
||||||
|
log "testing CAN connector"
|
||||||
|
|
||||||
|
log "starting anchor with CAN connector (override: vcan0)"
|
||||||
|
setsid ros2 run anchor_pkg anchor --ros-args -p connector:=can -p can_override:=vcan0 &
|
||||||
|
ANCHOR_PID=$!
|
||||||
|
sleep 2
|
||||||
|
|
||||||
|
if ! kill -0 "$ANCHOR_PID" 2>/dev/null; then
|
||||||
|
fail "CAN connector: anchor failed to start"
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! wait_for_topic "/anchor/to_vic/relay" 10; then
|
||||||
|
fail "CAN connector: topics not available"
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
return 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
log "anchor started successfully"
|
||||||
|
sleep 1
|
||||||
|
|
||||||
|
# test: relay -> CAN bus
|
||||||
|
# core=1, int16x4=2, cmd=30 -> id = (1<<8)|(2<<6)|30 = 0x19E
|
||||||
|
log "testing relay -> CAN bus"
|
||||||
|
|
||||||
|
local output
|
||||||
|
output=$(timeout 8 bash -c '
|
||||||
|
candump -n 1 vcan0 &
|
||||||
|
DUMP_PID=$!
|
||||||
|
sleep 1
|
||||||
|
ros2 topic pub --once /anchor/to_vic/relay astra_msgs/msg/VicCAN "{mcu_name: \"core\", command_id: 30, data: [1, 2, 3, 4]}" >/dev/null 2>&1
|
||||||
|
sleep 0.5
|
||||||
|
ros2 topic pub --once /anchor/to_vic/relay astra_msgs/msg/VicCAN "{mcu_name: \"core\", command_id: 30, data: [1, 2, 3, 4]}" >/dev/null 2>&1
|
||||||
|
wait $DUMP_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -qi "19E"; then
|
||||||
|
pass "CAN connector: relay -> CAN bus"
|
||||||
|
else
|
||||||
|
fail "CAN connector: relay -> CAN bus (got: $output)"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: CAN -> from_vic/core
|
||||||
|
log "testing CAN bus -> from_vic/core"
|
||||||
|
|
||||||
|
output=$(timeout 5 bash -c '
|
||||||
|
ros2 topic echo --once /anchor/from_vic/core &
|
||||||
|
ECHO_PID=$!
|
||||||
|
sleep 1
|
||||||
|
cansend vcan0 18F#000A0014001E0028
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 18F#000A0014001E0028
|
||||||
|
wait $ECHO_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: core" && echo "$output" | grep -q "command_id: 15"; then
|
||||||
|
pass "CAN connector: CAN -> from_vic/core"
|
||||||
|
else
|
||||||
|
fail "CAN connector: CAN -> from_vic/core"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: CAN -> from_vic/arm
|
||||||
|
log "testing CAN bus -> from_vic/arm"
|
||||||
|
|
||||||
|
output=$(timeout 5 bash -c '
|
||||||
|
ros2 topic echo --once /anchor/from_vic/arm &
|
||||||
|
ECHO_PID=$!
|
||||||
|
sleep 1
|
||||||
|
cansend vcan0 294#00640096012C01F4
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 294#00640096012C01F4
|
||||||
|
wait $ECHO_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: arm" && echo "$output" | grep -q "command_id: 20"; then
|
||||||
|
pass "CAN connector: CAN -> from_vic/arm"
|
||||||
|
else
|
||||||
|
fail "CAN connector: CAN -> from_vic/arm"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: CAN double data type (data_type_key=0)
|
||||||
|
log "testing CAN double data type"
|
||||||
|
|
||||||
|
output=$(timeout 8 bash -c '
|
||||||
|
ros2 topic echo --once /anchor/from_vic/core &
|
||||||
|
ECHO_PID=$!
|
||||||
|
sleep 1
|
||||||
|
cansend vcan0 105#3FF0000000000000
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 105#3FF0000000000000
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 105#3FF0000000000000
|
||||||
|
wait $ECHO_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: core" && echo "$output" | grep -q "command_id: 5"; then
|
||||||
|
pass "CAN connector: double data type"
|
||||||
|
else
|
||||||
|
fail "CAN connector: double data type"
|
||||||
|
fi
|
||||||
|
|
||||||
|
# test: CAN float32x2 data type (data_type_key=1)
|
||||||
|
log "testing CAN float32x2 data type"
|
||||||
|
|
||||||
|
output=$(timeout 8 bash -c '
|
||||||
|
ros2 topic echo --once /anchor/from_vic/core &
|
||||||
|
ECHO_PID=$!
|
||||||
|
sleep 1
|
||||||
|
cansend vcan0 14A#3F80000040000000
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 14A#3F80000040000000
|
||||||
|
sleep 0.5
|
||||||
|
cansend vcan0 14A#3F80000040000000
|
||||||
|
wait $ECHO_PID
|
||||||
|
' 2>/dev/null) || true
|
||||||
|
|
||||||
|
if echo "$output" | grep -q "mcu_name: core" && echo "$output" | grep -q "command_id: 10"; then
|
||||||
|
pass "CAN connector: float32x2 data type"
|
||||||
|
else
|
||||||
|
fail "CAN connector: float32x2 data type"
|
||||||
|
fi
|
||||||
|
|
||||||
|
kill -INT -- -"$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
wait "$ANCHOR_PID" 2>/dev/null || true
|
||||||
|
ANCHOR_PID=""
|
||||||
|
}
|
||||||
|
|
||||||
|
check_prerequisites() {
|
||||||
|
log "checking prerequisites"
|
||||||
|
local missing=0
|
||||||
|
|
||||||
|
if [[ ! -f install/setup.bash ]]; then
|
||||||
|
fail "install/setup.bash not found; run 'colcon build --symlink-install' first"
|
||||||
|
missing=1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! command -v socat &>/dev/null; then
|
||||||
|
fail "socat not found; install it or use 'nix develop'"
|
||||||
|
missing=1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! command -v cansend &>/dev/null || ! command -v candump &>/dev/null; then
|
||||||
|
fail "can-utils (cansend/candump) not found; install it or use 'nix develop'"
|
||||||
|
missing=1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if ! ip link show vcan0 &>/dev/null; then
|
||||||
|
fail "vcan0 interface not found"
|
||||||
|
log " create it with:"
|
||||||
|
log " sudo ip link add dev vcan0 type vcan"
|
||||||
|
log " sudo ip link set vcan0 up"
|
||||||
|
missing=1
|
||||||
|
elif ! ip link show vcan0 | grep -q ",UP"; then
|
||||||
|
fail "vcan0 exists but is not UP"
|
||||||
|
log " enable it with: sudo ip link set vcan0 up"
|
||||||
|
missing=1
|
||||||
|
fi
|
||||||
|
|
||||||
|
if [[ $missing -eq 1 ]]; then
|
||||||
|
echo ""
|
||||||
|
log "prerequisites not met"
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
|
||||||
|
log "all prerequisites met"
|
||||||
|
}
|
||||||
|
|
||||||
|
main() {
|
||||||
|
echo ""
|
||||||
|
log "anchor connector test suite"
|
||||||
|
echo ""
|
||||||
|
|
||||||
|
check_prerequisites
|
||||||
|
|
||||||
|
log "sourcing ROS2 workspace"
|
||||||
|
source_ros2
|
||||||
|
|
||||||
|
test_mock_connector
|
||||||
|
test_serial_connector
|
||||||
|
test_can_connector
|
||||||
|
|
||||||
|
echo ""
|
||||||
|
log "test summary"
|
||||||
|
echo -e "${BOLD}${GREEN}passed:${NC} $TESTS_PASSED"
|
||||||
|
echo -e "${BOLD}${RED}failed:${NC} $TESTS_FAILED"
|
||||||
|
echo ""
|
||||||
|
|
||||||
|
if [[ $TESTS_FAILED -gt 0 ]]; then
|
||||||
|
exit 1
|
||||||
|
fi
|
||||||
|
exit 0
|
||||||
|
}
|
||||||
|
|
||||||
|
main "$@"
|
||||||
@@ -1,11 +1,9 @@
|
|||||||
from warnings import deprecated
|
from warnings import deprecated
|
||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.node import Node
|
from rclpy.node import Node
|
||||||
from rclpy.executors import ExternalShutdownException
|
from rclpy.executors import ExternalShutdownException, SingleThreadedExecutor
|
||||||
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
||||||
|
|
||||||
import atexit
|
|
||||||
|
|
||||||
from .connector import (
|
from .connector import (
|
||||||
Connector,
|
Connector,
|
||||||
MockConnector,
|
MockConnector,
|
||||||
@@ -14,8 +12,7 @@ from .connector import (
|
|||||||
NoValidDeviceException,
|
NoValidDeviceException,
|
||||||
NoWorkingDeviceException,
|
NoWorkingDeviceException,
|
||||||
)
|
)
|
||||||
from .convert import string_to_viccan
|
from .convert import string_to_viccan, viccan_to_string
|
||||||
import threading
|
|
||||||
|
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
from std_msgs.msg import String
|
from std_msgs.msg import String
|
||||||
@@ -25,26 +22,25 @@ class Anchor(Node):
|
|||||||
"""
|
"""
|
||||||
Publishers:
|
Publishers:
|
||||||
* /anchor/from_vic/debug
|
* /anchor/from_vic/debug
|
||||||
- Every string received from the MCU is published here for debugging
|
- Every string received from the MCU is published here for debugging (String)
|
||||||
* /anchor/from_vic/core
|
* /anchor/from_vic/core
|
||||||
- VicCAN messages for Core node
|
- VicCAN messages for Core node
|
||||||
* /anchor/from_vic/arm
|
* /anchor/from_vic/arm
|
||||||
- VicCAN messages for Arm node
|
- VicCAN messages for Arm node (also receives digit messages)
|
||||||
* /anchor/from_vic/bio
|
* /anchor/from_vic/bio
|
||||||
- VicCAN messages for Bio node
|
- VicCAN messages for Bio node (also receives digit messages)
|
||||||
* /anchor/to_vic/debug
|
* /anchor/to_vic/debug
|
||||||
- A string copy of the messages published to ./relay are published here
|
- String copy of all messages sent to the connector
|
||||||
|
|
||||||
Subscribers:
|
Subscribers:
|
||||||
* /anchor/from_vic/mock_mcu
|
* /anchor/from_vic/mock_mcu
|
||||||
- For testing without an actual MCU, publish ViCAN messages here as if they came from an MCU
|
- For testing without an actual MCU, publish VicCAN messages here as if they came from an MCU
|
||||||
* /anchor/to_vic/relay
|
* /anchor/to_vic/relay
|
||||||
- Core, Arm, and Bio publish VicCAN messages to this topic to send to the MCU
|
- Core, Arm, and Bio publish VicCAN messages to this topic to send to the MCU
|
||||||
* /anchor/to_vic/relay_string
|
* /anchor/to_vic/relay_string
|
||||||
- Send raw strings to connectors. Does not work for connectors that require conversion (like CANConnector)
|
- Send raw strings to connectors. Does not work for CANConnector
|
||||||
* /anchor/relay
|
* /anchor/relay
|
||||||
- Legacy method for talking to connectors. Takes String as input, but does not send the raw strings to connectors.
|
- (Deprecated) Legacy topic. Takes String, converts to VicCAN, then sends to connector
|
||||||
Instead, it converts them to VicCAN messages first.
|
|
||||||
"""
|
"""
|
||||||
|
|
||||||
connector: Connector
|
connector: Connector
|
||||||
@@ -54,7 +50,7 @@ class Anchor(Node):
|
|||||||
|
|
||||||
logger = self.get_logger()
|
logger = self.get_logger()
|
||||||
|
|
||||||
# ROS2 Parameter Setup
|
# ROS2 parameter setup
|
||||||
|
|
||||||
self.declare_parameter(
|
self.declare_parameter(
|
||||||
"connector",
|
"connector",
|
||||||
@@ -89,7 +85,7 @@ class Anchor(Node):
|
|||||||
),
|
),
|
||||||
)
|
)
|
||||||
|
|
||||||
# Determine which connector to use. Options are Mock, Serial, and CAN
|
# determine which connector to use. options are Mock, Serial, and CAN
|
||||||
connector_select = (
|
connector_select = (
|
||||||
self.get_parameter("connector").get_parameter_value().string_value
|
self.get_parameter("connector").get_parameter_value().string_value
|
||||||
)
|
)
|
||||||
@@ -129,9 +125,9 @@ class Anchor(Node):
|
|||||||
)
|
)
|
||||||
exit(1)
|
exit(1)
|
||||||
|
|
||||||
# ROS2 Topic Setup
|
# ROS2 topic setup
|
||||||
|
|
||||||
# Publishers
|
# publishers
|
||||||
self.fromvic_debug_pub_ = self.create_publisher( # only used by serial
|
self.fromvic_debug_pub_ = self.create_publisher( # only used by serial
|
||||||
String,
|
String,
|
||||||
"/anchor/from_vic/debug",
|
"/anchor/from_vic/debug",
|
||||||
@@ -152,14 +148,14 @@ class Anchor(Node):
|
|||||||
"/anchor/from_vic/bio",
|
"/anchor/from_vic/bio",
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
# Debug publisher
|
# debug publisher for outgoing messages
|
||||||
self.tovic_debug_pub_ = self.create_publisher(
|
self.tovic_debug_pub_ = self.create_publisher(
|
||||||
VicCAN,
|
String,
|
||||||
"/anchor/to_vic/debug",
|
"/anchor/to_vic/debug",
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Subscribers
|
# subscribers
|
||||||
self.tovic_sub_ = self.create_subscription(
|
self.tovic_sub_ = self.create_subscription(
|
||||||
VicCAN,
|
VicCAN,
|
||||||
"/anchor/to_vic/relay",
|
"/anchor/to_vic/relay",
|
||||||
@@ -173,7 +169,7 @@ class Anchor(Node):
|
|||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
self.mock_mcu_sub_ = self.create_subscription(
|
self.mock_mcu_sub_ = self.create_subscription(
|
||||||
String,
|
VicCAN,
|
||||||
"/anchor/from_vic/mock_mcu",
|
"/anchor/from_vic/mock_mcu",
|
||||||
self.relay_fromvic,
|
self.relay_fromvic,
|
||||||
20,
|
20,
|
||||||
@@ -181,15 +177,17 @@ class Anchor(Node):
|
|||||||
self.tovic_string_sub_ = self.create_subscription(
|
self.tovic_string_sub_ = self.create_subscription(
|
||||||
String,
|
String,
|
||||||
"/anchor/to_vic/relay_string",
|
"/anchor/to_vic/relay_string",
|
||||||
self.connector.write_raw,
|
self.write_connector_raw,
|
||||||
20,
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Close devices on exit
|
# poll at 100Hz for incoming data
|
||||||
atexit.register(self.cleanup)
|
self.read_timer_ = self.create_timer(0.01, self.read_connector)
|
||||||
|
|
||||||
def cleanup(self):
|
def destroy_node(self):
|
||||||
|
self.get_logger().info("closing connector")
|
||||||
self.connector.cleanup()
|
self.connector.cleanup()
|
||||||
|
super().destroy_node()
|
||||||
|
|
||||||
def read_connector(self):
|
def read_connector(self):
|
||||||
"""Check the connector for new data from the MCU, and publish string to appropriate topics"""
|
"""Check the connector for new data from the MCU, and publish string to appropriate topics"""
|
||||||
@@ -204,6 +202,11 @@ class Anchor(Node):
|
|||||||
def write_connector(self, msg: VicCAN):
|
def write_connector(self, msg: VicCAN):
|
||||||
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
|
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
|
||||||
self.connector.write(msg)
|
self.connector.write(msg)
|
||||||
|
self.tovic_debug_pub_.publish(String(data=viccan_to_string(msg)))
|
||||||
|
|
||||||
|
def write_connector_raw(self, msg: String):
|
||||||
|
"""Write raw string to the connector and send a copy to /anchor/to_vic/debug"""
|
||||||
|
self.connector.write_raw(msg)
|
||||||
self.tovic_debug_pub_.publish(msg)
|
self.tovic_debug_pub_.publish(msg)
|
||||||
|
|
||||||
@deprecated(
|
@deprecated(
|
||||||
@@ -226,25 +229,26 @@ class Anchor(Node):
|
|||||||
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
||||||
if msg.mcu_name == "core":
|
if msg.mcu_name == "core":
|
||||||
self.fromvic_core_pub_.publish(msg)
|
self.fromvic_core_pub_.publish(msg)
|
||||||
elif msg.mcu_name == "arm" or msg.mcu_name == "digit":
|
if msg.mcu_name == "arm" or msg.mcu_name == "digit":
|
||||||
self.fromvic_arm_pub_.publish(msg)
|
self.fromvic_arm_pub_.publish(msg)
|
||||||
elif msg.mcu_name == "citadel" or msg.mcu_name == "digit":
|
if msg.mcu_name == "citadel" or msg.mcu_name == "digit":
|
||||||
self.fromvic_bio_pub_.publish(msg)
|
self.fromvic_bio_pub_.publish(msg)
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
anchor_node = Anchor()
|
||||||
|
executor = SingleThreadedExecutor()
|
||||||
|
executor.add_node(anchor_node)
|
||||||
|
|
||||||
try:
|
try:
|
||||||
rclpy.init(args=args)
|
executor.spin()
|
||||||
anchor_node = Anchor()
|
|
||||||
|
|
||||||
thread = threading.Thread(target=rclpy.spin, args=(anchor_node,), daemon=True)
|
|
||||||
thread.start()
|
|
||||||
|
|
||||||
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
|
||||||
while rclpy.ok():
|
|
||||||
anchor_node.read_connector() # Check the connector for updates
|
|
||||||
rate.sleep()
|
|
||||||
except (KeyboardInterrupt, ExternalShutdownException):
|
except (KeyboardInterrupt, ExternalShutdownException):
|
||||||
print("Caught shutdown signal, shutting down...")
|
pass
|
||||||
finally:
|
finally:
|
||||||
|
# don't accept any more jobs
|
||||||
|
executor.shutdown()
|
||||||
|
# make the node quit processing things
|
||||||
|
anchor_node.destroy_node()
|
||||||
|
# shut down everything else
|
||||||
rclpy.try_shutdown()
|
rclpy.try_shutdown()
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
from abc import ABC, abstractmethod
|
from abc import ABC, abstractmethod
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
|
from std_msgs.msg import String
|
||||||
from rclpy.clock import Clock
|
from rclpy.clock import Clock
|
||||||
from rclpy.impl.rcutils_logger import RcutilsLogger
|
from rclpy.impl.rcutils_logger import RcutilsLogger
|
||||||
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
||||||
@@ -77,7 +78,7 @@ class Connector(ABC):
|
|||||||
pass
|
pass
|
||||||
|
|
||||||
@abstractmethod
|
@abstractmethod
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
@@ -199,10 +200,10 @@ class SerialConnector(Connector):
|
|||||||
return (None, None) # pretty much no other error matters
|
return (None, None) # pretty much no other error matters
|
||||||
|
|
||||||
def write(self, msg: VicCAN):
|
def write(self, msg: VicCAN):
|
||||||
self.write_raw(viccan_to_string(msg))
|
self.write_raw(String(data=viccan_to_string(msg)))
|
||||||
|
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
self.serial_interface.write(bytes(msg, "utf8"))
|
self.serial_interface.write(bytes(msg.data, "utf8"))
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
self.logger.info(f"closing serial port if open {self.port}")
|
self.logger.info(f"closing serial port if open {self.port}")
|
||||||
@@ -411,8 +412,10 @@ class CANConnector(Connector):
|
|||||||
self.logger.error(f"CAN error while sending: {e}")
|
self.logger.error(f"CAN error while sending: {e}")
|
||||||
raise DeviceClosedException("CAN bus closed unexpectedly")
|
raise DeviceClosedException("CAN bus closed unexpectedly")
|
||||||
|
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
self.logger.warn(f"write_raw is not supported for CANConnector. msg: {msg}")
|
self.logger.warn(
|
||||||
|
f"write_raw is not supported for CANConnector. msg: {msg.data}"
|
||||||
|
)
|
||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
try:
|
try:
|
||||||
@@ -426,7 +429,7 @@ class CANConnector(Connector):
|
|||||||
class MockConnector(Connector):
|
class MockConnector(Connector):
|
||||||
def __init__(self, logger: RcutilsLogger, clock: Clock):
|
def __init__(self, logger: RcutilsLogger, clock: Clock):
|
||||||
super().__init__(logger, clock)
|
super().__init__(logger, clock)
|
||||||
# No hardware interface for MockConnector. Publish to `/anchor/from_vic/mock_mcu` instead.
|
# no hardware interface for MockConnector. publish to `/anchor/from_vic/mock_mcu` instead
|
||||||
|
|
||||||
def read(self) -> tuple[VicCAN | None, str | None]:
|
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||||
return (None, None)
|
return (None, None)
|
||||||
@@ -434,5 +437,5 @@ class MockConnector(Connector):
|
|||||||
def write(self, msg: VicCAN):
|
def write(self, msg: VicCAN):
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def write_raw(self, msg: str):
|
def write_raw(self, msg: String):
|
||||||
pass
|
pass
|
||||||
|
|||||||
@@ -1,8 +1,9 @@
|
|||||||
{ pkgs, ... }:
|
{ ... }:
|
||||||
{
|
{
|
||||||
projectRootFile = "flake.nix";
|
projectRootFile = "flake.nix";
|
||||||
programs = {
|
programs = {
|
||||||
nixfmt.enable = true;
|
nixfmt.enable = true;
|
||||||
black.enable = true;
|
black.enable = true;
|
||||||
|
shfmt.enable = true;
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user