mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
42 Commits
743744edaa
...
fix-oversi
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
333249677f | ||
|
|
fc2ba5f8d1 | ||
|
|
77d35949e9 | ||
|
|
be4fbf124d | ||
|
|
bfeae04e64 | ||
|
|
7d80ad1ab5 | ||
|
|
dfabd6c330 | ||
|
|
b892bfc631 | ||
|
|
caf61f61a8 | ||
|
|
a96aa6a409 | ||
|
|
8404999369 | ||
|
|
88574524cf | ||
|
|
30bb32a66b | ||
|
|
010d2da0b6 | ||
|
|
0a257abf43 | ||
|
|
b09b55bee0 | ||
|
|
ec7f272934 | ||
|
|
bc9183d59a | ||
|
|
410d3706ed | ||
|
|
89b3194914 | ||
|
|
4ef226c094 | ||
|
|
327539467c | ||
|
|
e570d371c6 | ||
|
|
f7efa604d2 | ||
|
|
fe46a2ab4d | ||
|
|
941e196316 | ||
|
|
7a3c4af1ce | ||
|
|
5e5a52438d | ||
|
|
c814f34ca6 | ||
|
|
ce39d0aeb9 | ||
|
|
9b96244a1b | ||
|
|
e588ff0a7b | ||
|
|
e83642cfe8 | ||
|
|
67b3c5bc8f | ||
|
|
c506a34b37 | ||
|
|
980c08ba4f | ||
|
|
b388275bba | ||
|
|
5c0194c543 | ||
|
|
809ca71208 | ||
|
|
225700bb86 | ||
|
|
4459886fc1 | ||
|
|
18fce2c19b |
52
README.md
52
README.md
@@ -60,6 +60,33 @@ $ ros2 launch anchor_pkg rover.launch.py # Must be run on a computer connected
|
|||||||
$ ros2 run headless_pkg headless_full # Optionally run in a separate shell on the same or different computer.
|
$ ros2 run headless_pkg headless_full # Optionally run in a separate shell on the same or different computer.
|
||||||
```
|
```
|
||||||
|
|
||||||
|
### Using the Mock Connector
|
||||||
|
|
||||||
|
Anchor provides a mock connector meant for testing and scripting purposes. You can select the mock connector by running anchor with this command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ ros2 launch anchor_pkg rover.launch.py connector:="mock"
|
||||||
|
```
|
||||||
|
|
||||||
|
To see all data that would be sent over the CAN network (and thus to the microcontrollers), use this command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ ros2 topic echo /anchor/to_vic/debug
|
||||||
|
```
|
||||||
|
|
||||||
|
To send data to the mock connector (as if you were a ROS2 node), use the normal relay topic:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ ros2 topic pub /anchor/to_vic/relay astra_msgs/msg/VicCAN '{mcu_name: "core", command_id: 50, data: [0.0, 2.0, 0.0, 1.0]}'
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
To send data to the mock connector (as if you were a microcontroller), publish to the dedicated topic:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ ros2 topic pub /anchor/from_vic/mock_mcu astra_msgs/msg/VicCAN '{mcu_name: "arm", command_id: 55, data: [0.0, 450.0, 900.0, 0.0]}'
|
||||||
|
```
|
||||||
|
|
||||||
### Testing Serial
|
### Testing Serial
|
||||||
|
|
||||||
You can fake the presence of a Serial device (i.e., MCU) by using the following command:
|
You can fake the presence of a Serial device (i.e., MCU) by using the following command:
|
||||||
@@ -68,10 +95,31 @@ You can fake the presence of a Serial device (i.e., MCU) by using the following
|
|||||||
$ socat -dd -v pty,rawer,crnl,link=/tmp/ttyACM9 pty,rawer,crnl,link=/tmp/ttyOUT
|
$ socat -dd -v pty,rawer,crnl,link=/tmp/ttyACM9 pty,rawer,crnl,link=/tmp/ttyOUT
|
||||||
```
|
```
|
||||||
|
|
||||||
When you go to run anchor, use the `PORT_OVERRIDE` environment variable to point it to the fake serial port, like so:
|
When you go to run anchor, use the `serial_override` ROS2 parameter to point it to the fake serial port, like so:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
$ PORT_OVERRIDE=/tmp/ttyACM9 ros2 launch anchor_pkg rover.launch.py
|
$ ros2 launch anchor_pkg rover.launch.py connector:=serial serial_override:=/tmp/ttyACM9
|
||||||
|
```
|
||||||
|
|
||||||
|
### Testing CAN
|
||||||
|
|
||||||
|
You can create a virtual CAN network by using the following commands to create and then enable it:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
sudo ip link add dev vcan0 type vcan
|
||||||
|
sudo ip link set vcan0 up
|
||||||
|
```
|
||||||
|
|
||||||
|
When you go to run anchor, use the `can_override` ROS2 parameter to point it to the virtual CAN network, like so:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ ros2 launch anchor_pkg rover.launch.py connector:=can can_override:=vcan0
|
||||||
|
```
|
||||||
|
|
||||||
|
Once you're done, you should delete the virtual network so that anchor doesn't get confused if you plug in a real CAN adapter:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
$ sudo ip link delete vcan0
|
||||||
```
|
```
|
||||||
|
|
||||||
### Connecting the GuliKit Controller
|
### Connecting the GuliKit Controller
|
||||||
|
|||||||
@@ -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
|
||||||
|
|
||||||
|
|||||||
@@ -3,10 +3,10 @@ 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
|
||||||
@@ -16,7 +16,6 @@ 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
|
||||||
|
|||||||
31
flake.lock
generated
31
flake.lock
generated
@@ -24,16 +24,16 @@
|
|||||||
"nixpkgs": "nixpkgs"
|
"nixpkgs": "nixpkgs"
|
||||||
},
|
},
|
||||||
"locked": {
|
"locked": {
|
||||||
"lastModified": 1770108954,
|
"lastModified": 1775216071,
|
||||||
"narHash": "sha256-VBj6bd4LPPSfsZJPa/UPPA92dOs6tmQo0XZKqfz/3W4=",
|
"narHash": "sha256-PrPW70Fh1uLx3JxNV/NLeXjUhgfrZmi7ac8LJOlS0q4=",
|
||||||
"owner": "lopsided98",
|
"owner": "lopsided98",
|
||||||
"repo": "nix-ros-overlay",
|
"repo": "nix-ros-overlay",
|
||||||
"rev": "3d05d46451b376e128a1553e78b8870c75d7753a",
|
"rev": "197a2b55c4ed24f8b885a5b20b65f426fb6d57ca",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
},
|
},
|
||||||
"original": {
|
"original": {
|
||||||
"owner": "lopsided98",
|
"owner": "lopsided98",
|
||||||
"ref": "develop",
|
"ref": "master",
|
||||||
"repo": "nix-ros-overlay",
|
"repo": "nix-ros-overlay",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
}
|
}
|
||||||
@@ -60,7 +60,8 @@
|
|||||||
"nixpkgs": [
|
"nixpkgs": [
|
||||||
"nix-ros-overlay",
|
"nix-ros-overlay",
|
||||||
"nixpkgs"
|
"nixpkgs"
|
||||||
]
|
],
|
||||||
|
"treefmt-nix": "treefmt-nix"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"systems": {
|
"systems": {
|
||||||
@@ -77,6 +78,26 @@
|
|||||||
"repo": "default",
|
"repo": "default",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
}
|
}
|
||||||
|
},
|
||||||
|
"treefmt-nix": {
|
||||||
|
"inputs": {
|
||||||
|
"nixpkgs": [
|
||||||
|
"nixpkgs"
|
||||||
|
]
|
||||||
|
},
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1773297127,
|
||||||
|
"narHash": "sha256-6E/yhXP7Oy/NbXtf1ktzmU8SdVqJQ09HC/48ebEGBpk=",
|
||||||
|
"owner": "numtide",
|
||||||
|
"repo": "treefmt-nix",
|
||||||
|
"rev": "71b125cd05fbfd78cab3e070b73544abe24c5016",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "numtide",
|
||||||
|
"repo": "treefmt-nix",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"root": "root",
|
"root": "root",
|
||||||
|
|||||||
20
flake.nix
20
flake.nix
@@ -2,8 +2,13 @@
|
|||||||
description = "Development environment for ASTRA Anchor";
|
description = "Development environment for ASTRA Anchor";
|
||||||
|
|
||||||
inputs = {
|
inputs = {
|
||||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/master";
|
||||||
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
||||||
|
|
||||||
|
treefmt-nix = {
|
||||||
|
url = "github:numtide/treefmt-nix";
|
||||||
|
inputs.nixpkgs.follows = "nixpkgs";
|
||||||
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
outputs =
|
outputs =
|
||||||
@@ -11,7 +16,8 @@
|
|||||||
self,
|
self,
|
||||||
nix-ros-overlay,
|
nix-ros-overlay,
|
||||||
nixpkgs,
|
nixpkgs,
|
||||||
}:
|
...
|
||||||
|
}@inputs:
|
||||||
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
|
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
|
||||||
system:
|
system:
|
||||||
let
|
let
|
||||||
@@ -25,9 +31,12 @@
|
|||||||
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
|
||||||
|
python-can
|
||||||
pygame
|
pygame
|
||||||
scipy
|
scipy
|
||||||
crccheck
|
crccheck
|
||||||
@@ -83,11 +92,14 @@
|
|||||||
export QT_X11_NO_MITSHM=1
|
export QT_X11_NO_MITSHM=1
|
||||||
'';
|
'';
|
||||||
};
|
};
|
||||||
|
|
||||||
|
formatter = (inputs.treefmt-nix.lib.evalModule pkgs ./treefmt.nix).config.build.wrapper;
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
|
|
||||||
nixConfig = {
|
nixConfig = {
|
||||||
extra-substituters = [ "https://ros.cachix.org" ];
|
# Cache to pull ros packages from
|
||||||
extra-trusted-public-keys = [ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" ];
|
extra-substituters = [ "https://ros.cachix.org" "https://attic.iid.ciirc.cvut.cz/ros" ];
|
||||||
|
extra-trusted-public-keys = [ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" "ros:JR95vUYsShSqfA1VTYoFt1Nz6uXasm5QrcOsGry9f6Q=" ];
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|||||||
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 a git 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,28 +1,21 @@
|
|||||||
|
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 std_srvs.srv import Empty
|
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
||||||
|
|
||||||
import signal
|
from .connector import (
|
||||||
import time
|
Connector,
|
||||||
import atexit
|
MockConnector,
|
||||||
|
SerialConnector,
|
||||||
|
CANConnector,
|
||||||
|
NoValidDeviceException,
|
||||||
|
NoWorkingDeviceException,
|
||||||
|
)
|
||||||
|
from .convert import string_to_viccan, viccan_to_string
|
||||||
|
|
||||||
import serial
|
|
||||||
import serial.tools.list_ports
|
|
||||||
import os
|
|
||||||
import sys
|
|
||||||
import threading
|
|
||||||
import glob
|
|
||||||
|
|
||||||
from std_msgs.msg import String, Header
|
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
|
from std_msgs.msg import String
|
||||||
KNOWN_USBS = [
|
|
||||||
(0x2E8A, 0x00C0), # Raspberry Pi Pico
|
|
||||||
(0x1A86, 0x55D4), # Adafruit Feather ESP32 V2
|
|
||||||
(0x10C4, 0xEA60), # DOIT ESP32 Devkit V1
|
|
||||||
(0x1A86, 0x55D3), # ESP32 S3 Development Board
|
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
class Anchor(Node):
|
class Anchor(Node):
|
||||||
@@ -36,330 +29,227 @@ class Anchor(Node):
|
|||||||
- VicCAN messages for Arm node
|
- VicCAN messages for Arm node
|
||||||
* /anchor/from_vic/bio
|
* /anchor/from_vic/bio
|
||||||
- VicCAN messages for Bio node
|
- VicCAN messages for Bio node
|
||||||
|
* /anchor/to_vic/debug
|
||||||
|
- A string copy of the messages published to ./relay are published here
|
||||||
|
|
||||||
Subscribers:
|
Subscribers:
|
||||||
* /anchor/from_vic/mock_mcu
|
* /anchor/from_vic/mock_mcu
|
||||||
- For testing without an actual MCU, publish strings 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
|
||||||
- Publish raw strings to this topic to send directly to the MCU for debugging
|
- Send raw strings to connectors. Does not work for connectors that require conversion (like CANConnector)
|
||||||
|
* /anchor/relay
|
||||||
|
- Legacy method for talking to connectors. Takes String as input, but does not send the raw strings to connectors.
|
||||||
|
Instead, it converts them to VicCAN messages first.
|
||||||
"""
|
"""
|
||||||
|
|
||||||
|
connector: Connector
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
# Initalize node with name
|
super().__init__("anchor_node")
|
||||||
super().__init__("anchor_node") # previously 'serial_publisher'
|
|
||||||
|
|
||||||
self.serial_port: str | None = None # e.g., "/dev/ttyUSB0"
|
logger = self.get_logger()
|
||||||
|
|
||||||
# Serial port override
|
# ROS2 Parameter Setup
|
||||||
if port_override := os.getenv("PORT_OVERRIDE"):
|
|
||||||
self.serial_port = port_override
|
|
||||||
|
|
||||||
##################################################
|
self.declare_parameter(
|
||||||
# Serial MCU Discovery
|
"connector",
|
||||||
|
"auto",
|
||||||
# If there was not a port override, look for a MCU over USB for Serial.
|
ParameterDescriptor(
|
||||||
if self.serial_port is None:
|
name="connector",
|
||||||
comports = serial.tools.list_ports.comports()
|
description="Declares which MCU connector should be used. Defaults to 'auto'.",
|
||||||
real_ports = list(
|
type=ParameterType.PARAMETER_STRING,
|
||||||
filter(
|
additional_constraints="Must be 'serial', 'can', 'mock', or 'auto'.",
|
||||||
lambda p: p.vid is not None
|
),
|
||||||
and p.pid is not None
|
|
||||||
and p.device is not None,
|
|
||||||
comports,
|
|
||||||
)
|
)
|
||||||
)
|
|
||||||
recog_ports = list(filter(lambda p: (p.vid, p.pid) in KNOWN_USBS, comports))
|
|
||||||
|
|
||||||
if len(recog_ports) == 1: # Found singular recognized MCU
|
self.declare_parameter(
|
||||||
found_port = recog_ports[0]
|
"can_override",
|
||||||
self.get_logger().info(
|
"",
|
||||||
f"Selecting MCU '{found_port.description}' at {found_port.device}."
|
ParameterDescriptor(
|
||||||
|
name="can_override",
|
||||||
|
description="Overrides which CAN channel will be used. Defaults to ''.",
|
||||||
|
type=ParameterType.PARAMETER_STRING,
|
||||||
|
additional_constraints="Must be a valid CAN network that shows up in `ip link show`.",
|
||||||
|
),
|
||||||
)
|
)
|
||||||
self.serial_port = found_port.device # String, location of device file; e.g., '/dev/ttyACM0'
|
|
||||||
elif len(recog_ports) > 1: # Found multiple recognized MCUs
|
|
||||||
# Kinda jank log message
|
|
||||||
self.get_logger().error(
|
|
||||||
f"Found multiple recognized MCUs: {[p.device for p in recog_ports].__str__()}"
|
|
||||||
)
|
|
||||||
# Don't set self.serial_port; later if-statement will exit()
|
|
||||||
elif (
|
|
||||||
len(recog_ports) == 0 and len(real_ports) > 0
|
|
||||||
): # Found real ports but none recognized; i.e. maybe found an IMU or camera but not a MCU
|
|
||||||
self.get_logger().error(
|
|
||||||
f"No recognized MCUs found; instead found {[p.device for p in real_ports].__str__()}."
|
|
||||||
)
|
|
||||||
# Don't set self.serial_port; later if-statement will exit()
|
|
||||||
else: # Found jack shit
|
|
||||||
self.get_logger().error("No valid Serial ports specified or found.")
|
|
||||||
# Don't set self.serial_port; later if-statement will exit()
|
|
||||||
|
|
||||||
# We still don't have a serial port; fall back to legacy discovery (Areeb's code)
|
self.declare_parameter(
|
||||||
# Loop through all serial devices on the computer to check for the MCU
|
"serial_override",
|
||||||
if self.serial_port is None:
|
"",
|
||||||
self.get_logger().warning("Falling back to legacy MCU discovery...")
|
ParameterDescriptor(
|
||||||
ports = Anchor.list_serial_ports()
|
name="serial_override",
|
||||||
for _ in range(4):
|
description="Overrides which serial port will be used. Defaults to ''.",
|
||||||
if self.serial_port is not None:
|
type=ParameterType.PARAMETER_STRING,
|
||||||
break
|
additional_constraints="Must be a valid path to a serial device file that shows up in `ls /dev/tty*`.",
|
||||||
for port in ports:
|
),
|
||||||
|
)
|
||||||
|
|
||||||
|
# Determine which connector to use. Options are Mock, Serial, and CAN
|
||||||
|
connector_select = (
|
||||||
|
self.get_parameter("connector").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
can_override = (
|
||||||
|
self.get_parameter("can_override").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
serial_override = (
|
||||||
|
self.get_parameter("serial_override").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
match connector_select:
|
||||||
|
case "serial":
|
||||||
|
logger.info("using serial connector")
|
||||||
|
self.connector = SerialConnector(
|
||||||
|
logger, self.get_clock(), serial_override
|
||||||
|
)
|
||||||
|
case "can":
|
||||||
|
logger.info("using CAN connector")
|
||||||
|
self.connector = CANConnector(logger, self.get_clock(), can_override)
|
||||||
|
case "mock":
|
||||||
|
logger.info("using mock connector")
|
||||||
|
self.connector = MockConnector(logger, self.get_clock())
|
||||||
|
case "auto":
|
||||||
|
logger.info("automatically determining connector")
|
||||||
try:
|
try:
|
||||||
# connect and send a ping command
|
logger.info("trying CAN connector")
|
||||||
ser = serial.Serial(port, 115200, timeout=1)
|
self.connector = CANConnector(
|
||||||
# (f"Checking port {port}...")
|
logger, self.get_clock(), can_override
|
||||||
ser.write(b"ping\n")
|
|
||||||
response = ser.read_until(bytes("\n", "utf8"))
|
|
||||||
|
|
||||||
# if pong is in response, then we are talking with the MCU
|
|
||||||
if b"pong" in response:
|
|
||||||
self.serial_port = port
|
|
||||||
self.get_logger().info(f"Found MCU at {self.serial_port}!")
|
|
||||||
break
|
|
||||||
except:
|
|
||||||
pass
|
|
||||||
|
|
||||||
# If port is still None then we ain't finding no mcu
|
|
||||||
if self.serial_port is None:
|
|
||||||
self.get_logger().error("Unable to find MCU. Exiting...")
|
|
||||||
time.sleep(1)
|
|
||||||
sys.exit(1)
|
|
||||||
# Found a Serial port, try to open it; above code has not officially opened a Serial port
|
|
||||||
else:
|
|
||||||
self.get_logger().debug(
|
|
||||||
f"Attempting to open Serial port '{self.serial_port}'..."
|
|
||||||
)
|
)
|
||||||
try:
|
except (NoValidDeviceException, NoWorkingDeviceException, TypeError):
|
||||||
self.serial_interface = serial.Serial(
|
logger.info("CAN connector failed, trying serial connector")
|
||||||
self.serial_port, 115200, timeout=1
|
self.connector = SerialConnector(
|
||||||
|
logger, self.get_clock(), serial_override
|
||||||
)
|
)
|
||||||
|
case _:
|
||||||
# Attempt to get name of connected MCU
|
logger.fatal(
|
||||||
self.serial_interface.write(
|
f"invalid value for connector parameter: {connector_select}"
|
||||||
b"can_relay_mode,on\n"
|
|
||||||
) # can_relay_ready,[mcu]
|
|
||||||
mcu_name: str = ""
|
|
||||||
for _ in range(4):
|
|
||||||
response = self.serial_interface.read_until(bytes("\n", "utf8"))
|
|
||||||
try:
|
|
||||||
if b"can_relay_ready" in response:
|
|
||||||
args: list[str] = response.decode("utf8").strip().split(",")
|
|
||||||
if len(args) == 2:
|
|
||||||
mcu_name = args[1]
|
|
||||||
break
|
|
||||||
except UnicodeDecodeError:
|
|
||||||
pass # ignore malformed responses
|
|
||||||
self.get_logger().info(
|
|
||||||
f"MCU '{mcu_name}' is ready at '{self.serial_port}'."
|
|
||||||
)
|
)
|
||||||
|
exit(1)
|
||||||
|
|
||||||
except serial.SerialException as e:
|
|
||||||
self.get_logger().error(
|
|
||||||
f"Could not open Serial port '{self.serial_port}' for reason:"
|
|
||||||
)
|
|
||||||
self.get_logger().error(e.strerror)
|
|
||||||
time.sleep(1)
|
|
||||||
sys.exit(1)
|
|
||||||
|
|
||||||
# Close serial port on exit
|
|
||||||
atexit.register(self.cleanup)
|
|
||||||
|
|
||||||
##################################################
|
|
||||||
# ROS2 Topic Setup
|
# ROS2 Topic Setup
|
||||||
|
|
||||||
# New pub/sub with VicCAN
|
# Publishers
|
||||||
self.fromvic_debug_pub_ = self.create_publisher(
|
self.fromvic_debug_pub_ = self.create_publisher( # only used by serial
|
||||||
String, "/anchor/from_vic/debug", 20
|
String,
|
||||||
|
"/anchor/from_vic/debug",
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
self.fromvic_core_pub_ = self.create_publisher(
|
self.fromvic_core_pub_ = self.create_publisher(
|
||||||
VicCAN, "/anchor/from_vic/core", 20
|
VicCAN,
|
||||||
|
"/anchor/from_vic/core",
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
self.fromvic_arm_pub_ = self.create_publisher(
|
self.fromvic_arm_pub_ = self.create_publisher(
|
||||||
VicCAN, "/anchor/from_vic/arm", 20
|
VicCAN,
|
||||||
|
"/anchor/from_vic/arm",
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
self.fromvic_bio_pub_ = self.create_publisher(
|
self.fromvic_bio_pub_ = self.create_publisher(
|
||||||
VicCAN, "/anchor/from_vic/bio", 20
|
VicCAN,
|
||||||
|
"/anchor/from_vic/bio",
|
||||||
|
20,
|
||||||
|
)
|
||||||
|
# Debug publisher
|
||||||
|
self.tovic_debug_pub_ = self.create_publisher(
|
||||||
|
String,
|
||||||
|
"/anchor/to_vic/debug",
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
self.mock_mcu_sub_ = self.create_subscription(
|
# Subscribers
|
||||||
String, "/anchor/from_vic/mock_mcu", self.on_mock_fromvic, 20
|
|
||||||
)
|
|
||||||
self.tovic_sub_ = self.create_subscription(
|
self.tovic_sub_ = self.create_subscription(
|
||||||
VicCAN, "/anchor/to_vic/relay", self.on_relay_tovic_viccan, 20
|
VicCAN,
|
||||||
|
"/anchor/to_vic/relay",
|
||||||
|
self.write_connector,
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
self.tovic_debug_sub_ = self.create_subscription(
|
self.tovic_sub_legacy_ = self.create_subscription(
|
||||||
String, "/anchor/to_vic/relay_string", self.on_relay_tovic_string, 20
|
String,
|
||||||
|
"/anchor/relay",
|
||||||
|
self.write_connector_legacy,
|
||||||
|
20,
|
||||||
|
)
|
||||||
|
self.mock_mcu_sub_ = self.create_subscription(
|
||||||
|
VicCAN,
|
||||||
|
"/anchor/from_vic/mock_mcu",
|
||||||
|
self.relay_fromvic,
|
||||||
|
20,
|
||||||
|
)
|
||||||
|
self.tovic_string_sub_ = self.create_subscription(
|
||||||
|
String,
|
||||||
|
"/anchor/to_vic/relay_string",
|
||||||
|
self.write_connector_raw,
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Create publishers
|
# poll at 100Hz for incoming data
|
||||||
self.arm_pub = self.create_publisher(String, "/anchor/arm/feedback", 10)
|
self.read_timer_ = self.create_timer(0.01, self.read_connector)
|
||||||
self.core_pub = self.create_publisher(String, "/anchor/core/feedback", 10)
|
|
||||||
self.bio_pub = self.create_publisher(String, "/anchor/bio/feedback", 10)
|
|
||||||
|
|
||||||
self.debug_pub = self.create_publisher(String, "/anchor/debug", 10)
|
def destroy_node(self):
|
||||||
|
self.get_logger().info("closing connector")
|
||||||
|
self.connector.cleanup()
|
||||||
|
super().destroy_node()
|
||||||
|
|
||||||
# Create a subscriber
|
def read_connector(self):
|
||||||
self.relay_sub = self.create_subscription(
|
"""Check the connector for new data from the MCU, and publish string to appropriate topics"""
|
||||||
String, "/anchor/relay", self.on_relay_tovic_string, 10
|
viccan, raw = self.connector.read()
|
||||||
|
|
||||||
|
if raw:
|
||||||
|
self.fromvic_debug_pub_.publish(String(data=raw))
|
||||||
|
|
||||||
|
if viccan:
|
||||||
|
self.relay_fromvic(viccan)
|
||||||
|
|
||||||
|
def write_connector(self, msg: VicCAN):
|
||||||
|
"""Write to the connector and send a copy to /anchor/to_vic/debug"""
|
||||||
|
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)
|
||||||
|
|
||||||
|
@deprecated(
|
||||||
|
"Use /anchor/to_vic/relay or /anchor/to_vic/relay_string instead of /anchor/relay"
|
||||||
)
|
)
|
||||||
|
def write_connector_legacy(self, msg: String):
|
||||||
def read_MCU(self):
|
"""Write to the connector by first attempting to convert String to VicCAN"""
|
||||||
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
# please do not reference this code. ~riley
|
||||||
try:
|
for cmd in msg.data.split("\n"):
|
||||||
output = str(self.serial_interface.readline(), "utf8")
|
viccan = string_to_viccan(
|
||||||
|
cmd,
|
||||||
if output:
|
"anchor",
|
||||||
self.relay_fromvic(output)
|
self.get_logger(),
|
||||||
# All output over debug temporarily
|
self.get_clock().now().to_msg(),
|
||||||
# self.get_logger().info(f"[MCU] {output}")
|
|
||||||
msg = String()
|
|
||||||
msg.data = output
|
|
||||||
self.debug_pub.publish(msg)
|
|
||||||
if output.startswith("can_relay_fromvic,core"):
|
|
||||||
self.core_pub.publish(msg)
|
|
||||||
elif output.startswith("can_relay_fromvic,arm") or output.startswith(
|
|
||||||
"can_relay_fromvic,digit"
|
|
||||||
): # digit for voltage readings
|
|
||||||
self.arm_pub.publish(msg)
|
|
||||||
if output.startswith("can_relay_fromvic,citadel") or output.startswith(
|
|
||||||
"can_relay_fromvic,digit"
|
|
||||||
): # digit for SHT sensor
|
|
||||||
self.bio_pub.publish(msg)
|
|
||||||
# msg = String()
|
|
||||||
# msg.data = output
|
|
||||||
# self.debug_pub.publish(msg)
|
|
||||||
return
|
|
||||||
except serial.SerialException as e:
|
|
||||||
print(f"SerialException: {e}")
|
|
||||||
print("Closing serial port.")
|
|
||||||
try:
|
|
||||||
if self.serial_interface.is_open:
|
|
||||||
self.serial_interface.close()
|
|
||||||
except:
|
|
||||||
pass
|
|
||||||
exit(1)
|
|
||||||
except TypeError as e:
|
|
||||||
print(f"TypeError: {e}")
|
|
||||||
print("Closing serial port.")
|
|
||||||
try:
|
|
||||||
if self.serial_interface.is_open:
|
|
||||||
self.serial_interface.close()
|
|
||||||
except:
|
|
||||||
pass
|
|
||||||
exit(1)
|
|
||||||
except Exception as e:
|
|
||||||
print(f"Exception: {e}")
|
|
||||||
# print("Closing serial port.")
|
|
||||||
# if self.ser.is_open:
|
|
||||||
# self.ser.close()
|
|
||||||
# exit(1)
|
|
||||||
|
|
||||||
def on_mock_fromvic(self, msg: String):
|
|
||||||
"""For testing without an actual MCU, publish strings here as if they came from an MCU"""
|
|
||||||
# self.get_logger().info(f"Got command from mock MCU: {msg}")
|
|
||||||
self.relay_fromvic(msg.data)
|
|
||||||
|
|
||||||
def on_relay_tovic_viccan(self, msg: VicCAN):
|
|
||||||
"""Relay a VicCAN message to the MCU"""
|
|
||||||
output: str = f"can_relay_tovic,{msg.mcu_name},{msg.command_id}"
|
|
||||||
for num in msg.data:
|
|
||||||
output += f",{round(num, 7)}" # limit to 7 decimal places
|
|
||||||
output += "\n"
|
|
||||||
# self.get_logger().info(f"VicCAN relay to MCU: {output}")
|
|
||||||
self.serial_interface.write(bytes(output, "utf8"))
|
|
||||||
|
|
||||||
def relay_fromvic(self, msg: str):
|
|
||||||
"""Relay a string message from the MCU to the appropriate VicCAN topic"""
|
|
||||||
self.fromvic_debug_pub_.publish(String(data=msg))
|
|
||||||
parts = msg.strip().split(",")
|
|
||||||
if len(parts) > 0 and parts[0] != "can_relay_fromvic":
|
|
||||||
self.get_logger().debug(f"Ignoring non-VicCAN message: '{msg.strip()}'")
|
|
||||||
return
|
|
||||||
|
|
||||||
# String validation
|
|
||||||
malformed: bool = False
|
|
||||||
malformed_reason: str = ""
|
|
||||||
if len(parts) < 3 or len(parts) > 7:
|
|
||||||
malformed = True
|
|
||||||
malformed_reason = (
|
|
||||||
f"invalid argument count (expected [3,7], got {len(parts)})"
|
|
||||||
)
|
)
|
||||||
elif parts[1] not in ["core", "arm", "digit", "citadel", "broadcast"]:
|
if viccan:
|
||||||
malformed = True
|
self.write_connector(viccan)
|
||||||
malformed_reason = f"invalid mcu_name '{parts[1]}'"
|
|
||||||
elif not (parts[2].isnumeric()) or int(parts[2]) < 0:
|
|
||||||
malformed = True
|
|
||||||
malformed_reason = f"command_id '{parts[2]}' is not a non-negative integer"
|
|
||||||
else:
|
|
||||||
for x in parts[3:]:
|
|
||||||
try:
|
|
||||||
float(x)
|
|
||||||
except ValueError:
|
|
||||||
malformed = True
|
|
||||||
malformed_reason = f"data '{x}' is not a float"
|
|
||||||
break
|
|
||||||
|
|
||||||
if malformed:
|
def relay_fromvic(self, msg: VicCAN):
|
||||||
self.get_logger().warning(
|
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
||||||
f"Ignoring malformed from_vic message: '{msg.strip()}'; reason: {malformed_reason}"
|
if msg.mcu_name == "core":
|
||||||
)
|
self.fromvic_core_pub_.publish(msg)
|
||||||
return
|
if msg.mcu_name == "arm" or msg.mcu_name == "digit":
|
||||||
|
self.fromvic_arm_pub_.publish(msg)
|
||||||
# Have valid VicCAN message
|
if msg.mcu_name == "citadel" or msg.mcu_name == "digit":
|
||||||
|
self.fromvic_bio_pub_.publish(msg)
|
||||||
output = VicCAN()
|
|
||||||
output.mcu_name = parts[1]
|
|
||||||
output.command_id = int(parts[2])
|
|
||||||
if len(parts) > 3:
|
|
||||||
output.data = [float(x) for x in parts[3:]]
|
|
||||||
output.header = Header(
|
|
||||||
stamp=self.get_clock().now().to_msg(), frame_id="from_vic"
|
|
||||||
)
|
|
||||||
|
|
||||||
# self.get_logger().info(f"Relaying from MCU: {output}")
|
|
||||||
if output.mcu_name == "core":
|
|
||||||
self.fromvic_core_pub_.publish(output)
|
|
||||||
elif output.mcu_name == "arm" or output.mcu_name == "digit":
|
|
||||||
self.fromvic_arm_pub_.publish(output)
|
|
||||||
elif output.mcu_name == "citadel" or output.mcu_name == "digit":
|
|
||||||
self.fromvic_bio_pub_.publish(output)
|
|
||||||
|
|
||||||
def on_relay_tovic_string(self, msg: String):
|
|
||||||
"""Relay a raw string message to the MCU for debugging"""
|
|
||||||
message = msg.data
|
|
||||||
# self.get_logger().info(f"Sending command to MCU: {msg}")
|
|
||||||
self.serial_interface.write(bytes(message, "utf8"))
|
|
||||||
|
|
||||||
@staticmethod
|
|
||||||
def list_serial_ports():
|
|
||||||
return glob.glob("/dev/ttyUSB*") + glob.glob("/dev/ttyACM*")
|
|
||||||
|
|
||||||
def cleanup(self):
|
|
||||||
print("Cleaning up before terminating...")
|
|
||||||
if self.serial_interface.is_open:
|
|
||||||
self.serial_interface.close()
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
try:
|
|
||||||
rclpy.init(args=args)
|
rclpy.init(args=args)
|
||||||
anchor_node = Anchor()
|
anchor_node = Anchor()
|
||||||
|
executor = SingleThreadedExecutor()
|
||||||
|
executor.add_node(anchor_node)
|
||||||
|
|
||||||
thread = threading.Thread(target=rclpy.spin, args=(anchor_node,), daemon=True)
|
try:
|
||||||
thread.start()
|
executor.spin()
|
||||||
|
|
||||||
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
|
||||||
while rclpy.ok():
|
|
||||||
anchor_node.read_MCU() # Check the MCU 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()
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
|
||||||
signal.signal(
|
|
||||||
signal.SIGTERM, lambda signum, frame: sys.exit(0)
|
|
||||||
) # Catch termination signals and exit cleanly
|
|
||||||
main()
|
|
||||||
|
|||||||
441
src/anchor_pkg/anchor_pkg/connector.py
Normal file
441
src/anchor_pkg/anchor_pkg/connector.py
Normal file
@@ -0,0 +1,441 @@
|
|||||||
|
from abc import ABC, abstractmethod
|
||||||
|
from astra_msgs.msg import VicCAN
|
||||||
|
from std_msgs.msg import String
|
||||||
|
from rclpy.clock import Clock
|
||||||
|
from rclpy.impl.rcutils_logger import RcutilsLogger
|
||||||
|
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
||||||
|
|
||||||
|
# CAN
|
||||||
|
import can
|
||||||
|
import can.interfaces.socketcan
|
||||||
|
import struct
|
||||||
|
|
||||||
|
# Serial
|
||||||
|
import serial
|
||||||
|
import serial.tools.list_ports
|
||||||
|
|
||||||
|
KNOWN_USBS = [
|
||||||
|
(0x2E8A, 0x00C0), # Raspberry Pi Pico
|
||||||
|
(0x1A86, 0x55D4), # Adafruit Feather ESP32 V2
|
||||||
|
(0x10C4, 0xEA60), # DOIT ESP32 Devkit V1
|
||||||
|
(0x1A86, 0x55D3), # ESP32 S3 Development Board
|
||||||
|
]
|
||||||
|
BAUD_RATE = 115200
|
||||||
|
|
||||||
|
MCU_IDS = [
|
||||||
|
"broadcast",
|
||||||
|
"core",
|
||||||
|
"arm",
|
||||||
|
"digit",
|
||||||
|
"faerie",
|
||||||
|
"citadel",
|
||||||
|
"libs",
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
class NoValidDeviceException(Exception):
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
class NoWorkingDeviceException(Exception):
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
class MultipleValidDevicesException(Exception):
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
class DeviceClosedException(Exception):
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
class Connector(ABC):
|
||||||
|
logger: RcutilsLogger
|
||||||
|
clock: Clock
|
||||||
|
|
||||||
|
def string_to_viccan(self, msg: str, mcu_name: str):
|
||||||
|
"""function currying so that we do not need to pass logger and clock every time"""
|
||||||
|
return _string_to_viccan(
|
||||||
|
msg,
|
||||||
|
mcu_name,
|
||||||
|
self.logger,
|
||||||
|
self.clock.now().to_msg(),
|
||||||
|
)
|
||||||
|
|
||||||
|
def __init__(self, logger: RcutilsLogger, clock: Clock):
|
||||||
|
self.logger = logger
|
||||||
|
self.clock = clock
|
||||||
|
|
||||||
|
@abstractmethod
|
||||||
|
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||||
|
"""
|
||||||
|
Must return a tuple of (VicCAN, debug message or string repr of VicCAN)
|
||||||
|
"""
|
||||||
|
pass
|
||||||
|
|
||||||
|
@abstractmethod
|
||||||
|
def write(self, msg: VicCAN):
|
||||||
|
pass
|
||||||
|
|
||||||
|
@abstractmethod
|
||||||
|
def write_raw(self, msg: String):
|
||||||
|
pass
|
||||||
|
|
||||||
|
def cleanup(self):
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
class SerialConnector(Connector):
|
||||||
|
port: str
|
||||||
|
mcu_name: str
|
||||||
|
serial_interface: serial.Serial
|
||||||
|
|
||||||
|
def __init__(self, logger: RcutilsLogger, clock: Clock, serial_override: str = ""):
|
||||||
|
super().__init__(logger, clock)
|
||||||
|
|
||||||
|
ports = self._find_ports()
|
||||||
|
mcu_name: str | None = None
|
||||||
|
|
||||||
|
if serial_override:
|
||||||
|
logger.warn(
|
||||||
|
f"using serial_override: `{serial_override}`! this will bypass several checks."
|
||||||
|
)
|
||||||
|
ports = [serial_override]
|
||||||
|
mcu_name = "override"
|
||||||
|
|
||||||
|
if len(ports) <= 0:
|
||||||
|
raise NoValidDeviceException("no valid serial device found")
|
||||||
|
if (l := len(ports)) > 1:
|
||||||
|
raise MultipleValidDevicesException(
|
||||||
|
f"too many ({l}) valid serial devices found"
|
||||||
|
)
|
||||||
|
|
||||||
|
# check each of our ports to make sure one of them is responding
|
||||||
|
port = ports[0]
|
||||||
|
# we might already have a name by now if we overrode earlier
|
||||||
|
mcu_name = mcu_name or self._get_name(port)
|
||||||
|
if not mcu_name:
|
||||||
|
raise NoWorkingDeviceException(
|
||||||
|
f"found {port}, but it did not respond with its name"
|
||||||
|
)
|
||||||
|
|
||||||
|
self.port = port
|
||||||
|
self.mcu_name = mcu_name
|
||||||
|
|
||||||
|
# if we fail at this point, it should crash because we've already tested the port
|
||||||
|
self.serial_interface = serial.Serial(self.port, BAUD_RATE, timeout=1)
|
||||||
|
|
||||||
|
def _find_ports(self) -> list[str]:
|
||||||
|
"""
|
||||||
|
Finds all valid ports but does not test them
|
||||||
|
|
||||||
|
returns: all valid ports
|
||||||
|
"""
|
||||||
|
comports = serial.tools.list_ports.comports()
|
||||||
|
valid_ports = list(
|
||||||
|
map( # get just device strings
|
||||||
|
lambda p: p.device,
|
||||||
|
filter( # make sure we have a known device
|
||||||
|
lambda p: (p.vid, p.pid) in KNOWN_USBS and p.device is not None,
|
||||||
|
comports,
|
||||||
|
),
|
||||||
|
)
|
||||||
|
)
|
||||||
|
self.logger.info(f"found valid MCU ports: [ {', '.join(valid_ports)} ]")
|
||||||
|
return valid_ports
|
||||||
|
|
||||||
|
def _get_name(self, port: str) -> str | None:
|
||||||
|
"""
|
||||||
|
Get the name of the MCU (if it works)
|
||||||
|
|
||||||
|
returns: str name of the MCU, None if it doesn't work
|
||||||
|
"""
|
||||||
|
# attempt to open the serial port
|
||||||
|
serial_interface: serial.Serial
|
||||||
|
try:
|
||||||
|
self.logger.info(f"asking {port} for its name")
|
||||||
|
serial_interface = serial.Serial(port, BAUD_RATE, timeout=1)
|
||||||
|
|
||||||
|
serial_interface.write(b"can_relay_mode,on\n")
|
||||||
|
|
||||||
|
for i in range(4):
|
||||||
|
self.logger.debug(f"attempt {i + 1} of 4 asking {port} for its name")
|
||||||
|
response = serial_interface.read_until(bytes("\n", "utf8"))
|
||||||
|
try:
|
||||||
|
if b"can_relay_ready" in response:
|
||||||
|
args: list[str] = response.decode("utf8").strip().split(",")
|
||||||
|
if len(args) == 2:
|
||||||
|
self.logger.info(f"we are talking to {args[1]}")
|
||||||
|
return args[1]
|
||||||
|
break
|
||||||
|
except UnicodeDecodeError as e:
|
||||||
|
self.logger.info(
|
||||||
|
f"ignoring UnicodeDecodeError when asking for MCU name: {e}"
|
||||||
|
)
|
||||||
|
|
||||||
|
if serial_interface.is_open:
|
||||||
|
# turn relay mode off if it failed to respond with its name
|
||||||
|
serial_interface.write(b"can_relay_mode,off\n")
|
||||||
|
serial_interface.close()
|
||||||
|
except serial.SerialException as e:
|
||||||
|
self.logger.error(f"SerialException when asking for MCU name: {e}")
|
||||||
|
|
||||||
|
return None
|
||||||
|
|
||||||
|
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||||
|
try:
|
||||||
|
raw = str(self.serial_interface.readline(), "utf8")
|
||||||
|
|
||||||
|
if not raw:
|
||||||
|
return (None, None)
|
||||||
|
|
||||||
|
return (
|
||||||
|
self.string_to_viccan(raw, self.mcu_name),
|
||||||
|
raw,
|
||||||
|
)
|
||||||
|
except serial.SerialException as e:
|
||||||
|
self.logger.error(f"SerialException: {e}")
|
||||||
|
raise DeviceClosedException(f"serial port {self.port} closed unexpectedly")
|
||||||
|
except Exception:
|
||||||
|
return (None, None) # pretty much no other error matters
|
||||||
|
|
||||||
|
def write(self, msg: VicCAN):
|
||||||
|
self.write_raw(String(data=viccan_to_string(msg)))
|
||||||
|
|
||||||
|
def write_raw(self, msg: String):
|
||||||
|
self.serial_interface.write(bytes(msg.data, "utf8"))
|
||||||
|
|
||||||
|
def cleanup(self):
|
||||||
|
self.logger.info(f"closing serial port if open {self.port}")
|
||||||
|
try:
|
||||||
|
if self.serial_interface.is_open:
|
||||||
|
self.serial_interface.close()
|
||||||
|
except Exception as e:
|
||||||
|
self.logger.error(e)
|
||||||
|
|
||||||
|
|
||||||
|
class CANConnector(Connector):
|
||||||
|
def __init__(self, logger: RcutilsLogger, clock: Clock, can_override: str):
|
||||||
|
super().__init__(logger, clock)
|
||||||
|
|
||||||
|
self.can_channel: str | None = None
|
||||||
|
self.can_bus: can.BusABC | None = None
|
||||||
|
|
||||||
|
avail = can.interfaces.socketcan.SocketcanBus._detect_available_configs()
|
||||||
|
|
||||||
|
if len(avail) == 0:
|
||||||
|
raise NoValidDeviceException("no CAN interfaces found")
|
||||||
|
|
||||||
|
# filter to busses whose channel matches the can_override
|
||||||
|
if can_override:
|
||||||
|
self.logger.info(f"overrode can interface with {can_override}")
|
||||||
|
avail = list(
|
||||||
|
filter(
|
||||||
|
lambda b: b.get("channel") == can_override,
|
||||||
|
avail,
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
if (l := len(avail)) > 1:
|
||||||
|
channels = ", ".join(str(b.get("channel")) for b in avail)
|
||||||
|
raise MultipleValidDevicesException(
|
||||||
|
f"too many ({l}) CAN interfaces found: [{channels}]"
|
||||||
|
)
|
||||||
|
|
||||||
|
bus = avail[0]
|
||||||
|
self.can_channel = str(bus.get("channel"))
|
||||||
|
self.logger.info(f"found CAN interface '{self.can_channel}'")
|
||||||
|
|
||||||
|
try:
|
||||||
|
self.can_bus = can.Bus(
|
||||||
|
interface="socketcan",
|
||||||
|
channel=self.can_channel,
|
||||||
|
bitrate=1_000_000,
|
||||||
|
)
|
||||||
|
except can.CanError as e:
|
||||||
|
raise NoWorkingDeviceException(
|
||||||
|
f"could not open CAN channel '{self.can_channel}': {e}"
|
||||||
|
)
|
||||||
|
|
||||||
|
if self.can_channel and self.can_channel.startswith("v"):
|
||||||
|
self.logger.warn("CAN interface is likely virtual")
|
||||||
|
|
||||||
|
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||||
|
if not self.can_bus:
|
||||||
|
raise DeviceClosedException("CAN bus not initialized")
|
||||||
|
|
||||||
|
try:
|
||||||
|
message = self.can_bus.recv(timeout=0.0)
|
||||||
|
except can.CanError as e:
|
||||||
|
self.logger.error(f"CAN error while receiving: {e}")
|
||||||
|
raise DeviceClosedException("CAN bus closed unexpectedly")
|
||||||
|
|
||||||
|
if message is None:
|
||||||
|
return (None, None)
|
||||||
|
|
||||||
|
arbitration_id = message.arbitration_id & 0x7FF
|
||||||
|
data_bytes = bytes(message.data)
|
||||||
|
|
||||||
|
mcu_key = (arbitration_id >> 8) & 0b111
|
||||||
|
data_type_key = (arbitration_id >> 6) & 0b11
|
||||||
|
command = arbitration_id & 0x3F
|
||||||
|
|
||||||
|
try:
|
||||||
|
mcu_name = MCU_IDS[mcu_key]
|
||||||
|
except IndexError:
|
||||||
|
self.logger.warn(
|
||||||
|
f"received CAN frame with unknown MCU key {mcu_key}; id=0x{arbitration_id:X}"
|
||||||
|
)
|
||||||
|
return (None, None)
|
||||||
|
|
||||||
|
data: list[float] = []
|
||||||
|
|
||||||
|
try:
|
||||||
|
if data_type_key == 3:
|
||||||
|
data = []
|
||||||
|
elif data_type_key == 0:
|
||||||
|
if len(data_bytes) < 8:
|
||||||
|
self.logger.warn(
|
||||||
|
f"received double payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
|
)
|
||||||
|
return (None, None)
|
||||||
|
(value,) = struct.unpack(">d", data_bytes[:8])
|
||||||
|
data = [float(value)]
|
||||||
|
elif data_type_key == 1:
|
||||||
|
if len(data_bytes) < 8:
|
||||||
|
self.logger.warn(
|
||||||
|
f"received float32x2 payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
|
)
|
||||||
|
return (None, None)
|
||||||
|
v1, v2 = struct.unpack(">ff", data_bytes[:8])
|
||||||
|
data = [float(v1), float(v2)]
|
||||||
|
elif data_type_key == 2:
|
||||||
|
if len(data_bytes) < 8:
|
||||||
|
self.logger.warn(
|
||||||
|
f"received int16x4 payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||||
|
)
|
||||||
|
return (None, None)
|
||||||
|
i1, i2, i3, i4 = struct.unpack(">hhhh", data_bytes[:8])
|
||||||
|
data = [float(i1), float(i2), float(i3), float(i4)]
|
||||||
|
else:
|
||||||
|
self.logger.warn(
|
||||||
|
f"received CAN frame with unknown data_type_key {data_type_key}; id=0x{arbitration_id:X}"
|
||||||
|
)
|
||||||
|
return (None, None)
|
||||||
|
except struct.error as e:
|
||||||
|
self.logger.error(f"error unpacking CAN payload: {e}")
|
||||||
|
return (None, None)
|
||||||
|
|
||||||
|
viccan = VicCAN(
|
||||||
|
mcu_name=mcu_name,
|
||||||
|
command_id=int(command),
|
||||||
|
data=data,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.logger.debug(
|
||||||
|
f"received CAN frame id=0x{message.arbitration_id:X}, "
|
||||||
|
f"decoded as VicCAN(mcu_name={viccan.mcu_name}, command_id={viccan.command_id}, data={viccan.data})"
|
||||||
|
)
|
||||||
|
|
||||||
|
return (
|
||||||
|
viccan,
|
||||||
|
f"{viccan.mcu_name},{viccan.command_id},"
|
||||||
|
+ ",".join(map(str, list(viccan.data))),
|
||||||
|
)
|
||||||
|
|
||||||
|
def write(self, msg: VicCAN):
|
||||||
|
if not self.can_bus:
|
||||||
|
raise DeviceClosedException("CAN bus not initialized")
|
||||||
|
|
||||||
|
# build 11-bit arbitration ID according to VicCAN spec:
|
||||||
|
# bits 10..8: targeted MCU key
|
||||||
|
# bits 7..6: data type key
|
||||||
|
# bits 5..0: command
|
||||||
|
|
||||||
|
# map MCU name to 3-bit key.
|
||||||
|
try:
|
||||||
|
mcu_id = MCU_IDS.index((msg.mcu_name or "").lower())
|
||||||
|
except ValueError:
|
||||||
|
self.logger.error(
|
||||||
|
f"unknown VicCAN mcu_name '{msg.mcu_name}' for CAN frame; dropping message"
|
||||||
|
)
|
||||||
|
return
|
||||||
|
|
||||||
|
# determine data type from length:
|
||||||
|
# 0: double x1, 1: float32 x2, 2: int16 x4, 3: empty
|
||||||
|
match data_len := len(msg.data):
|
||||||
|
case 0:
|
||||||
|
data_type = 3
|
||||||
|
data = bytes()
|
||||||
|
case 1:
|
||||||
|
data_type = 0
|
||||||
|
data = struct.pack(">d", *msg.data)
|
||||||
|
case 2:
|
||||||
|
data_type = 1
|
||||||
|
data = struct.pack(">ff", *msg.data)
|
||||||
|
case 3 | 4: # 3 gets treated as 4
|
||||||
|
data_type = 2
|
||||||
|
if data_len == 3:
|
||||||
|
msg.data.append(0)
|
||||||
|
data = struct.pack(">hhhh", *[int(x) for x in msg.data])
|
||||||
|
case _:
|
||||||
|
self.logger.error(
|
||||||
|
f"unexpected VicCAN data length: {data_len}; dropping message"
|
||||||
|
)
|
||||||
|
return
|
||||||
|
|
||||||
|
# command is limited to 6 bits.
|
||||||
|
command = int(msg.command_id)
|
||||||
|
if command < 0 or command > 0x3F:
|
||||||
|
self.logger.error(
|
||||||
|
f"invalid command_id for CAN frame: {command}; dropping message"
|
||||||
|
)
|
||||||
|
return
|
||||||
|
|
||||||
|
try:
|
||||||
|
can_message = can.Message(
|
||||||
|
arbitration_id=(mcu_id << 8) | (data_type << 6) | command,
|
||||||
|
data=data,
|
||||||
|
is_extended_id=False,
|
||||||
|
)
|
||||||
|
except Exception as e:
|
||||||
|
self.logger.error(f"failed to construct CAN message: {e}")
|
||||||
|
return
|
||||||
|
|
||||||
|
try:
|
||||||
|
self.can_bus.send(can_message)
|
||||||
|
self.logger.debug(
|
||||||
|
f"sent CAN frame id=0x{can_message.arbitration_id:X}, "
|
||||||
|
f"data={list(can_message.data)}"
|
||||||
|
)
|
||||||
|
except can.CanError as e:
|
||||||
|
self.logger.error(f"CAN error while sending: {e}")
|
||||||
|
raise DeviceClosedException("CAN bus closed unexpectedly")
|
||||||
|
|
||||||
|
def write_raw(self, msg: String):
|
||||||
|
self.logger.warn(
|
||||||
|
f"write_raw is not supported for CANConnector. msg: {msg.data}"
|
||||||
|
)
|
||||||
|
|
||||||
|
def cleanup(self):
|
||||||
|
try:
|
||||||
|
if self.can_bus is not None:
|
||||||
|
self.logger.info("shutting down CAN bus")
|
||||||
|
self.can_bus.shutdown()
|
||||||
|
except Exception as e:
|
||||||
|
self.logger.error(e)
|
||||||
|
|
||||||
|
|
||||||
|
class MockConnector(Connector):
|
||||||
|
def __init__(self, logger: RcutilsLogger, clock: Clock):
|
||||||
|
super().__init__(logger, clock)
|
||||||
|
# No hardware interface for MockConnector. Publish to `/anchor/from_vic/mock_mcu` instead.
|
||||||
|
|
||||||
|
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||||
|
return (None, None)
|
||||||
|
|
||||||
|
def write(self, msg: VicCAN):
|
||||||
|
pass
|
||||||
|
|
||||||
|
def write_raw(self, msg: String):
|
||||||
|
pass
|
||||||
65
src/anchor_pkg/anchor_pkg/convert.py
Normal file
65
src/anchor_pkg/anchor_pkg/convert.py
Normal file
@@ -0,0 +1,65 @@
|
|||||||
|
from astra_msgs.msg import VicCAN
|
||||||
|
from std_msgs.msg import Header
|
||||||
|
from builtin_interfaces.msg import Time
|
||||||
|
from rclpy.impl.rcutils_logger import RcutilsLogger
|
||||||
|
|
||||||
|
|
||||||
|
def string_to_viccan(
|
||||||
|
msg: str, mcu_name: str, logger: RcutilsLogger, time: Time
|
||||||
|
) -> VicCAN | None:
|
||||||
|
"""
|
||||||
|
Converts the serial string VicCAN format to a ROS2 VicCAN message.
|
||||||
|
Does not fill out the Header of the message.
|
||||||
|
On a failure, it will log at a debug level why it failed and return None.
|
||||||
|
"""
|
||||||
|
|
||||||
|
parts: list[str] = msg.strip().split(",")
|
||||||
|
|
||||||
|
# don't need an extra check because len of .split output is always >= 1
|
||||||
|
if not parts[0].startswith("can_relay_"):
|
||||||
|
logger.debug(f"got non-CAN data from {mcu_name}: {msg}")
|
||||||
|
return None
|
||||||
|
elif len(parts) < 3:
|
||||||
|
logger.debug(f"got garbage (not enough parts) CAN data from {mcu_name}: {msg}")
|
||||||
|
return None
|
||||||
|
elif len(parts) > 7:
|
||||||
|
logger.debug(f"got garbage (too many parts) CAN data from {mcu_name}: {msg}")
|
||||||
|
return None
|
||||||
|
|
||||||
|
try:
|
||||||
|
command_id = int(parts[2])
|
||||||
|
except ValueError:
|
||||||
|
logger.debug(
|
||||||
|
f"got garbage (non-integer command id) CAN data from {mcu_name}: {msg}"
|
||||||
|
)
|
||||||
|
return None
|
||||||
|
|
||||||
|
if command_id not in range(64):
|
||||||
|
logger.debug(
|
||||||
|
f"got garbage (wrong command id {command_id}) CAN data from {mcu_name}: {msg}"
|
||||||
|
)
|
||||||
|
return None
|
||||||
|
|
||||||
|
try:
|
||||||
|
return VicCAN(
|
||||||
|
header=Header(
|
||||||
|
stamp=time,
|
||||||
|
frame_id="from_vic",
|
||||||
|
),
|
||||||
|
mcu_name=parts[1],
|
||||||
|
command_id=command_id,
|
||||||
|
data=[float(x) for x in parts[3:]],
|
||||||
|
)
|
||||||
|
except ValueError:
|
||||||
|
logger.debug(f"got garbage (non-numerical) CAN data from {mcu_name}: {msg}")
|
||||||
|
return None
|
||||||
|
|
||||||
|
|
||||||
|
def viccan_to_string(viccan: VicCAN) -> str:
|
||||||
|
"""Converts a ROS2 VicCAN message to the serial string VicCAN format."""
|
||||||
|
# make sure we accept 3 digits and treat it as 4
|
||||||
|
if len(viccan.data) == 3:
|
||||||
|
viccan.data.append(0)
|
||||||
|
# go from [ w, x, y, z ] -> ",w,x,y,z" & round to 7 digits max
|
||||||
|
data = "".join([f",{round(val,7)}" for val in viccan.data])
|
||||||
|
return f"can_relay_tovic,{viccan.mcu_name},{viccan.command_id}{data}\n"
|
||||||
@@ -1,138 +1,111 @@
|
|||||||
#!/usr/bin/env python3
|
|
||||||
|
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, Shutdown
|
from launch.actions import DeclareLaunchArgument, Shutdown
|
||||||
from launch.substitutions import (
|
|
||||||
LaunchConfiguration,
|
|
||||||
ThisLaunchFileDir,
|
|
||||||
PathJoinSubstitution,
|
|
||||||
)
|
|
||||||
from launch_ros.actions import Node
|
|
||||||
from launch.conditions import IfCondition
|
from launch.conditions import IfCondition
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
# Prevent making __pycache__ directories
|
def generate_launch_description():
|
||||||
from sys import dont_write_bytecode
|
connector = LaunchConfiguration("connector")
|
||||||
|
serial_override = LaunchConfiguration("serial_override")
|
||||||
|
can_override = LaunchConfiguration("can_override")
|
||||||
|
use_ptz = LaunchConfiguration("use_ptz")
|
||||||
|
|
||||||
dont_write_bytecode = True
|
ld = LaunchDescription()
|
||||||
|
|
||||||
|
# arguments
|
||||||
|
ld.add_action(
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
"connector",
|
||||||
|
default_value="auto",
|
||||||
|
description="Connector parameter for anchor node (default: 'auto')",
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
ld.add_action(
|
||||||
# Retrieve the resolved value of the launch argument 'mode'
|
DeclareLaunchArgument(
|
||||||
mode = LaunchConfiguration("mode").perform(context)
|
"serial_override",
|
||||||
nodes = []
|
default_value="",
|
||||||
|
description="Serial port override parameter for anchor node (default: '')",
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
if mode == "anchor":
|
ld.add_action(
|
||||||
# Launch every node and pass "anchor" as the parameter
|
DeclareLaunchArgument(
|
||||||
|
"can_override",
|
||||||
|
default_value="",
|
||||||
|
description="CAN network override parameter for anchor node (default: '')",
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
nodes.append(
|
ld.add_action(
|
||||||
Node(
|
DeclareLaunchArgument(
|
||||||
package="arm_pkg",
|
"use_ptz",
|
||||||
executable="arm", # change as needed
|
default_value="true", # must be string for launch system
|
||||||
name="arm",
|
description="Whether to launch PTZ node (default: true)",
|
||||||
output="both",
|
|
||||||
parameters=[{"launch_mode": mode}],
|
|
||||||
on_exit=Shutdown(),
|
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
nodes.append(
|
|
||||||
Node(
|
# nodes
|
||||||
package="core_pkg",
|
ld.add_action(
|
||||||
executable="core", # change as needed
|
|
||||||
name="core",
|
|
||||||
output="both",
|
|
||||||
parameters=[{"launch_mode": mode}],
|
|
||||||
on_exit=Shutdown(),
|
|
||||||
)
|
|
||||||
)
|
|
||||||
nodes.append(
|
|
||||||
Node(
|
|
||||||
package="core_pkg",
|
|
||||||
executable="ptz", # change as needed
|
|
||||||
name="ptz",
|
|
||||||
output="both",
|
|
||||||
condition=IfCondition(LaunchConfiguration("use_ptz", default="true")),
|
|
||||||
# Currently don't shutdown all nodes if the PTZ node fails, as it is not critical
|
|
||||||
# on_exit=Shutdown() # Uncomment if you want to shutdown on PTZ failure
|
|
||||||
)
|
|
||||||
)
|
|
||||||
nodes.append(
|
|
||||||
Node(
|
|
||||||
package="bio_pkg",
|
|
||||||
executable="bio", # change as needed
|
|
||||||
name="bio",
|
|
||||||
output="both",
|
|
||||||
parameters=[{"launch_mode": mode}],
|
|
||||||
on_exit=Shutdown(),
|
|
||||||
)
|
|
||||||
)
|
|
||||||
nodes.append(
|
|
||||||
Node(
|
|
||||||
package="anchor_pkg",
|
|
||||||
executable="anchor", # change as needed
|
|
||||||
name="anchor",
|
|
||||||
output="both",
|
|
||||||
parameters=[{"launch_mode": mode}],
|
|
||||||
on_exit=Shutdown(),
|
|
||||||
)
|
|
||||||
)
|
|
||||||
elif mode in ["arm", "core", "bio", "ptz"]:
|
|
||||||
# Only launch the node corresponding to the provided mode.
|
|
||||||
if mode == "arm":
|
|
||||||
nodes.append(
|
|
||||||
Node(
|
Node(
|
||||||
package="arm_pkg",
|
package="arm_pkg",
|
||||||
executable="arm",
|
executable="arm",
|
||||||
name="arm",
|
name="arm",
|
||||||
output="both",
|
output="both",
|
||||||
parameters=[{"launch_mode": mode}],
|
parameters=[{"launch_mode": "anchor"}],
|
||||||
on_exit=Shutdown(),
|
on_exit=Shutdown(),
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
elif mode == "core":
|
|
||||||
nodes.append(
|
ld.add_action(
|
||||||
Node(
|
Node(
|
||||||
package="core_pkg",
|
package="core_pkg",
|
||||||
executable="core",
|
executable="core",
|
||||||
name="core",
|
name="core",
|
||||||
output="both",
|
output="both",
|
||||||
parameters=[{"launch_mode": mode}],
|
parameters=[{"launch_mode": "anchor"}],
|
||||||
on_exit=Shutdown(),
|
on_exit=Shutdown(),
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
elif mode == "bio":
|
|
||||||
nodes.append(
|
ld.add_action(
|
||||||
Node(
|
|
||||||
package="bio_pkg",
|
|
||||||
executable="bio",
|
|
||||||
name="bio",
|
|
||||||
output="both",
|
|
||||||
parameters=[{"launch_mode": mode}],
|
|
||||||
on_exit=Shutdown(),
|
|
||||||
)
|
|
||||||
)
|
|
||||||
elif mode == "ptz":
|
|
||||||
nodes.append(
|
|
||||||
Node(
|
Node(
|
||||||
package="core_pkg",
|
package="core_pkg",
|
||||||
executable="ptz",
|
executable="ptz",
|
||||||
name="ptz",
|
name="ptz",
|
||||||
output="both",
|
output="both",
|
||||||
on_exit=Shutdown(), # on fail, shutdown if this was the only node to be launched
|
condition=IfCondition(use_ptz),
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
else:
|
|
||||||
# If an invalid mode is provided, print an error.
|
|
||||||
print("Invalid mode provided. Choose one of: arm, core, bio, anchor, ptz.")
|
|
||||||
|
|
||||||
return nodes
|
ld.add_action(
|
||||||
|
Node(
|
||||||
|
package="bio_pkg",
|
||||||
def generate_launch_description():
|
executable="bio",
|
||||||
declare_arg = DeclareLaunchArgument(
|
name="bio",
|
||||||
"mode",
|
output="both",
|
||||||
default_value="anchor",
|
parameters=[{"launch_mode": "anchor"}],
|
||||||
description="Launch mode: arm, core, bio, anchor, or ptz",
|
on_exit=Shutdown(),
|
||||||
|
)
|
||||||
)
|
)
|
||||||
|
|
||||||
return LaunchDescription([declare_arg, OpaqueFunction(function=launch_setup)])
|
ld.add_action(
|
||||||
|
Node(
|
||||||
|
package="anchor_pkg",
|
||||||
|
executable="anchor",
|
||||||
|
name="anchor",
|
||||||
|
output="both",
|
||||||
|
parameters=[
|
||||||
|
{
|
||||||
|
"launch_mode": "anchor",
|
||||||
|
"connector": connector,
|
||||||
|
"serial_override": serial_override,
|
||||||
|
"can_override": can_override,
|
||||||
|
}
|
||||||
|
],
|
||||||
|
on_exit=Shutdown(),
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
return ld
|
||||||
|
|||||||
@@ -3,13 +3,14 @@
|
|||||||
<package format="3">
|
<package format="3">
|
||||||
<name>anchor_pkg</name>
|
<name>anchor_pkg</name>
|
||||||
<version>0.0.0</version>
|
<version>0.0.0</version>
|
||||||
<description>TODO: Package description</description>
|
<description>Anchor -- ROS and CAN relay node</description>
|
||||||
<maintainer email="tristanmcginnis26@gmail.com">tristan</maintainer>
|
<maintainer email="rjm0037@uah.edu">Riley</maintainer>
|
||||||
<license>AGPL-3.0-only</license>
|
<license>AGPL-3.0-only</license>
|
||||||
|
|
||||||
<depend>rclpy</depend>
|
<depend>rclpy</depend>
|
||||||
<depend>common_interfaces</depend>
|
<depend>common_interfaces</depend>
|
||||||
<depend>python3-serial</depend>
|
<depend>python3-serial</depend>
|
||||||
|
<depend>python3-can</depend>
|
||||||
|
|
||||||
<build_depend>black</build_depend>
|
<build_depend>black</build_depend>
|
||||||
|
|
||||||
|
|||||||
@@ -1,279 +0,0 @@
|
|||||||
import rclpy
|
|
||||||
from rclpy.node import Node
|
|
||||||
|
|
||||||
import pygame
|
|
||||||
|
|
||||||
import time
|
|
||||||
|
|
||||||
import serial
|
|
||||||
import sys
|
|
||||||
import threading
|
|
||||||
import glob
|
|
||||||
import os
|
|
||||||
|
|
||||||
from std_msgs.msg import String
|
|
||||||
from astra_msgs.msg import ControllerState
|
|
||||||
from astra_msgs.msg import ArmManual
|
|
||||||
from astra_msgs.msg import ArmIK
|
|
||||||
|
|
||||||
|
|
||||||
os.environ["SDL_AUDIODRIVER"] = (
|
|
||||||
"dummy" # Force pygame to use a dummy audio driver before pygame.init()
|
|
||||||
)
|
|
||||||
os.environ["SDL_VIDEODRIVER"] = "dummy" # Prevents pygame from trying to open a display
|
|
||||||
|
|
||||||
|
|
||||||
class Headless(Node):
|
|
||||||
def __init__(self):
|
|
||||||
# Initalize node with name
|
|
||||||
super().__init__("arm_headless")
|
|
||||||
|
|
||||||
# Depricated, kept temporarily for reference
|
|
||||||
# self.create_timer(0.20, self.send_controls)#read and send controls
|
|
||||||
|
|
||||||
self.create_timer(0.1, self.send_manual)
|
|
||||||
|
|
||||||
# Create a publisher to publish any output the pico sends
|
|
||||||
|
|
||||||
# Depricated, kept temporarily for reference
|
|
||||||
# self.publisher = self.create_publisher(ControllerState, '/astra/arm/control', 10)
|
|
||||||
self.manual_pub = self.create_publisher(ArmManual, "/arm/control/manual", 10)
|
|
||||||
|
|
||||||
# Create a subscriber to listen to any commands sent for the pico
|
|
||||||
|
|
||||||
# Depricated, kept temporarily for reference
|
|
||||||
# self.subscriber = self.create_subscription(String, '/astra/arm/feedback', self.read_feedback, 10)
|
|
||||||
|
|
||||||
# self.debug_sub = self.create_subscription(String, '/arm/feedback/debug', self.read_feedback, 10)
|
|
||||||
|
|
||||||
self.laser_status = 0
|
|
||||||
|
|
||||||
# Initialize pygame
|
|
||||||
pygame.init()
|
|
||||||
|
|
||||||
# Initialize the gamepad module
|
|
||||||
pygame.joystick.init()
|
|
||||||
|
|
||||||
# Check if any gamepad is connected
|
|
||||||
if pygame.joystick.get_count() == 0:
|
|
||||||
print("No gamepad found.")
|
|
||||||
pygame.quit()
|
|
||||||
exit()
|
|
||||||
for event in pygame.event.get():
|
|
||||||
if event.type == pygame.QUIT:
|
|
||||||
pygame.quit()
|
|
||||||
exit()
|
|
||||||
|
|
||||||
# Initialize the first gamepad, print name to terminal
|
|
||||||
self.gamepad = pygame.joystick.Joystick(0)
|
|
||||||
self.gamepad.init()
|
|
||||||
print(f"Gamepad Found: {self.gamepad.get_name()}")
|
|
||||||
#
|
|
||||||
#
|
|
||||||
|
|
||||||
def run(self):
|
|
||||||
# This thread makes all the update processes run in the background
|
|
||||||
thread = threading.Thread(target=rclpy.spin, args={self}, daemon=True)
|
|
||||||
thread.start()
|
|
||||||
|
|
||||||
try:
|
|
||||||
while rclpy.ok():
|
|
||||||
# Check the pico for updates
|
|
||||||
|
|
||||||
# self.read_feedback()
|
|
||||||
if (
|
|
||||||
pygame.joystick.get_count() == 0
|
|
||||||
): # if controller disconnected, wait for it to be reconnected
|
|
||||||
print(f"Gamepad disconnected: {self.gamepad.get_name()}")
|
|
||||||
|
|
||||||
while pygame.joystick.get_count() == 0:
|
|
||||||
# self.send_controls() #depricated, kept for reference temporarily
|
|
||||||
self.send_manual()
|
|
||||||
# self.read_feedback()
|
|
||||||
self.gamepad = pygame.joystick.Joystick(0)
|
|
||||||
self.gamepad.init() # re-initialized gamepad
|
|
||||||
print(f"Gamepad reconnected: {self.gamepad.get_name()}")
|
|
||||||
|
|
||||||
except KeyboardInterrupt:
|
|
||||||
sys.exit(0)
|
|
||||||
|
|
||||||
def send_manual(self):
|
|
||||||
for event in pygame.event.get():
|
|
||||||
if event.type == pygame.QUIT:
|
|
||||||
pygame.quit()
|
|
||||||
exit()
|
|
||||||
input = ArmManual()
|
|
||||||
|
|
||||||
# Triggers for gripper control
|
|
||||||
if self.gamepad.get_axis(2) > 0: # left trigger
|
|
||||||
input.gripper = -1
|
|
||||||
elif self.gamepad.get_axis(5) > 0: # right trigger
|
|
||||||
input.gripper = 1
|
|
||||||
|
|
||||||
# Toggle Laser
|
|
||||||
if self.gamepad.get_button(7): # Start
|
|
||||||
self.laser_status = 1
|
|
||||||
elif self.gamepad.get_button(6): # Back
|
|
||||||
self.laser_status = 0
|
|
||||||
input.laser = self.laser_status
|
|
||||||
|
|
||||||
if self.gamepad.get_button(5): # right bumper, control effector
|
|
||||||
|
|
||||||
# Left stick X-axis for effector yaw
|
|
||||||
if self.gamepad.get_axis(0) > 0:
|
|
||||||
input.effector_yaw = 1
|
|
||||||
elif self.gamepad.get_axis(0) < 0:
|
|
||||||
input.effector_yaw = -1
|
|
||||||
|
|
||||||
# Right stick X-axis for effector roll
|
|
||||||
if self.gamepad.get_axis(3) > 0:
|
|
||||||
input.effector_roll = 1
|
|
||||||
elif self.gamepad.get_axis(3) < 0:
|
|
||||||
input.effector_roll = -1
|
|
||||||
|
|
||||||
else: # Control arm axis
|
|
||||||
dpad_input = self.gamepad.get_hat(0)
|
|
||||||
input.axis0 = 0
|
|
||||||
if dpad_input[0] == 1:
|
|
||||||
input.axis0 = 1
|
|
||||||
elif dpad_input[0] == -1:
|
|
||||||
input.axis0 = -1
|
|
||||||
|
|
||||||
if self.gamepad.get_axis(0) > 0.15 or self.gamepad.get_axis(0) < -0.15:
|
|
||||||
input.axis1 = round(self.gamepad.get_axis(0))
|
|
||||||
|
|
||||||
if self.gamepad.get_axis(1) > 0.15 or self.gamepad.get_axis(1) < -0.15:
|
|
||||||
input.axis2 = -1 * round(self.gamepad.get_axis(1))
|
|
||||||
|
|
||||||
if self.gamepad.get_axis(4) > 0.15 or self.gamepad.get_axis(4) < -0.15:
|
|
||||||
input.axis3 = -1 * round(self.gamepad.get_axis(4))
|
|
||||||
|
|
||||||
# input.axis1 = -1 * round(self.gamepad.get_axis(0))#left x-axis
|
|
||||||
# input.axis2 = -1 * round(self.gamepad.get_axis(1))#left y-axis
|
|
||||||
# input.axis3 = -1 * round(self.gamepad.get_axis(4))#right y-axis
|
|
||||||
|
|
||||||
# Button Mappings
|
|
||||||
# axis2 -> LT
|
|
||||||
# axis5 -> RT
|
|
||||||
# Buttons0 -> A
|
|
||||||
# Buttons1 -> B
|
|
||||||
# Buttons2 -> X
|
|
||||||
# Buttons3 -> Y
|
|
||||||
# Buttons4 -> LB
|
|
||||||
# Buttons5 -> RB
|
|
||||||
# Buttons6 -> Back
|
|
||||||
# Buttons7 -> Start
|
|
||||||
|
|
||||||
input.linear_actuator = 0
|
|
||||||
|
|
||||||
if pygame.joystick.get_count() != 0:
|
|
||||||
|
|
||||||
self.get_logger().info(
|
|
||||||
f"[Ctrl] {input.axis0}, {input.axis1}, {input.axis2}, {input.axis3}\n"
|
|
||||||
)
|
|
||||||
self.manual_pub.publish(input)
|
|
||||||
else:
|
|
||||||
pass
|
|
||||||
|
|
||||||
pass
|
|
||||||
|
|
||||||
# Depricated, kept temporarily for reference
|
|
||||||
# def send_controls(self):
|
|
||||||
|
|
||||||
# for event in pygame.event.get():
|
|
||||||
# if event.type == pygame.QUIT:
|
|
||||||
# pygame.quit()
|
|
||||||
# exit()
|
|
||||||
# input = ControllerState()
|
|
||||||
|
|
||||||
# input.lt = self.gamepad.get_axis(2)#left trigger
|
|
||||||
# input.rt = self.gamepad.get_axis(5)#right trigger
|
|
||||||
|
|
||||||
# #input.lb = self.gamepad.get_button(9)#Value must be converted to bool
|
|
||||||
# if(self.gamepad.get_button(4)):#left bumper
|
|
||||||
# input.lb = True
|
|
||||||
# else:
|
|
||||||
# input.lb = False
|
|
||||||
|
|
||||||
# #input.rb = self.gamepad.get_button(10)#Value must be converted to bool
|
|
||||||
# if(self.gamepad.get_button(5)):#right bumper
|
|
||||||
# input.rb = True
|
|
||||||
# else:
|
|
||||||
# input.rb = False
|
|
||||||
|
|
||||||
# #input.plus = self.gamepad.get_button(6)#plus button
|
|
||||||
# if(self.gamepad.get_button(7)):#plus button
|
|
||||||
# input.plus = True
|
|
||||||
# else:
|
|
||||||
# input.plus = False
|
|
||||||
|
|
||||||
# #input.minus = self.gamepad.get_button(4)#minus button
|
|
||||||
# if(self.gamepad.get_button(6)):#minus button
|
|
||||||
# input.minus = True
|
|
||||||
# else:
|
|
||||||
# input.minus = False
|
|
||||||
|
|
||||||
# input.ls_x = round(self.gamepad.get_axis(0),2)#left x-axis
|
|
||||||
# input.ls_y = round(self.gamepad.get_axis(1),2)#left y-axis
|
|
||||||
# input.rs_x = round(self.gamepad.get_axis(3),2)#right x-axis
|
|
||||||
# input.rs_y = round(self.gamepad.get_axis(4),2)#right y-axis
|
|
||||||
|
|
||||||
# #input.a = self.gamepad.get_button(1)#A button
|
|
||||||
# if(self.gamepad.get_button(0)):#A button
|
|
||||||
# input.a = True
|
|
||||||
# else:
|
|
||||||
# input.a = False
|
|
||||||
# #input.b = self.gamepad.get_button(0)#B button
|
|
||||||
# if(self.gamepad.get_button(1)):#B button
|
|
||||||
# input.b = True
|
|
||||||
# else:
|
|
||||||
# input.b = False
|
|
||||||
# #input.x = self.gamepad.get_button(3)#X button
|
|
||||||
# if(self.gamepad.get_button(2)):#X button
|
|
||||||
# input.x = True
|
|
||||||
# else:
|
|
||||||
# input.x = False
|
|
||||||
# #input.y = self.gamepad.get_button(2)#Y button
|
|
||||||
# if(self.gamepad.get_button(3)):#Y button
|
|
||||||
# input.y = True
|
|
||||||
# else:
|
|
||||||
# input.y = False
|
|
||||||
|
|
||||||
# dpad_input = self.gamepad.get_hat(0)#D-pad input
|
|
||||||
|
|
||||||
# #not using up/down on DPad
|
|
||||||
# input.d_up = False
|
|
||||||
# input.d_down = False
|
|
||||||
|
|
||||||
# if(dpad_input[0] == 1):#D-pad right
|
|
||||||
# input.d_right = True
|
|
||||||
# else:
|
|
||||||
# input.d_right = False
|
|
||||||
# if(dpad_input[0] == -1):#D-pad left
|
|
||||||
# input.d_left = True
|
|
||||||
# else:
|
|
||||||
# input.d_left = False
|
|
||||||
|
|
||||||
# if pygame.joystick.get_count() != 0:
|
|
||||||
|
|
||||||
# self.get_logger().info(f"[Ctrl] Updated Controller State\n")
|
|
||||||
|
|
||||||
# self.publisher.publish(input)
|
|
||||||
# else:
|
|
||||||
# pass
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
|
||||||
rclpy.init(args=args)
|
|
||||||
|
|
||||||
node = Headless()
|
|
||||||
|
|
||||||
rclpy.spin(node)
|
|
||||||
rclpy.shutdown()
|
|
||||||
|
|
||||||
# tb_bs = BaseStation()
|
|
||||||
# node.run()
|
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
|
||||||
main()
|
|
||||||
@@ -2,6 +2,7 @@ import sys
|
|||||||
import threading
|
import threading
|
||||||
import signal
|
import signal
|
||||||
import math
|
import math
|
||||||
|
from warnings import deprecated
|
||||||
|
|
||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.node import Node
|
from rclpy.node import Node
|
||||||
@@ -11,7 +12,7 @@ from rclpy import qos
|
|||||||
from std_msgs.msg import String, Header
|
from std_msgs.msg import String, Header
|
||||||
from sensor_msgs.msg import JointState
|
from sensor_msgs.msg import JointState
|
||||||
from control_msgs.msg import JointJog
|
from control_msgs.msg import JointJog
|
||||||
from astra_msgs.msg import SocketFeedback, DigitFeedback, ArmManual
|
from astra_msgs.msg import SocketFeedback, DigitFeedback, ArmManual # TODO: Old topics
|
||||||
from astra_msgs.msg import ArmFeedback, VicCAN, RevMotorState
|
from astra_msgs.msg import ArmFeedback, VicCAN, RevMotorState
|
||||||
|
|
||||||
control_qos = qos.QoSProfile(
|
control_qos = qos.QoSProfile(
|
||||||
@@ -68,7 +69,9 @@ class ArmNode(Node):
|
|||||||
# Parameters
|
# Parameters
|
||||||
|
|
||||||
self.declare_parameter("use_old_topics", True)
|
self.declare_parameter("use_old_topics", True)
|
||||||
self.use_old_topics = self.get_parameter("use_old_topics").get_parameter_value().bool_value
|
self.use_old_topics = (
|
||||||
|
self.get_parameter("use_old_topics").get_parameter_value().bool_value
|
||||||
|
)
|
||||||
|
|
||||||
##################################################
|
##################################################
|
||||||
# Old topics
|
# Old topics
|
||||||
@@ -85,7 +88,9 @@ class ArmNode(Node):
|
|||||||
SocketFeedback, "/arm/feedback/socket", 10
|
SocketFeedback, "/arm/feedback/socket", 10
|
||||||
)
|
)
|
||||||
self.arm_feedback = SocketFeedback()
|
self.arm_feedback = SocketFeedback()
|
||||||
self.digit_pub = self.create_publisher(DigitFeedback, "/arm/feedback/digit", 10)
|
self.digit_pub = self.create_publisher(
|
||||||
|
DigitFeedback, "/arm/feedback/digit", 10
|
||||||
|
)
|
||||||
self.digit_feedback = DigitFeedback()
|
self.digit_feedback = DigitFeedback()
|
||||||
self.feedback_timer = self.create_timer(0.25, self.publish_feedback)
|
self.feedback_timer = self.create_timer(0.25, self.publish_feedback)
|
||||||
|
|
||||||
@@ -110,13 +115,19 @@ class ArmNode(Node):
|
|||||||
|
|
||||||
# Control
|
# Control
|
||||||
|
|
||||||
# Manual: /arm/manual_new is published by Servo or Basestation
|
# Manual: /arm/manual/joint_jog is published by Basestation or Headless
|
||||||
self.jointjog_pub_ = self.create_subscription(
|
self.man_jointjog_sub_ = self.create_subscription(
|
||||||
JointJog, "/arm/manual_new", self.jointjog_callback, qos_profile=control_qos
|
JointJog,
|
||||||
|
"/arm/manual/joint_jog",
|
||||||
|
self.jointjog_callback,
|
||||||
|
qos_profile=control_qos,
|
||||||
)
|
)
|
||||||
# IK: /joint_commands is published by JointTrajectoryController via topic_based_control
|
# IK: /joint_commands is published by JointTrajectoryController via topic_based_control
|
||||||
self.joint_command_sub_ = self.create_subscription(
|
self.joint_command_sub_ = self.create_subscription(
|
||||||
JointState, "/joint_commands", self.joint_command_callback, qos_profile=control_qos
|
JointState,
|
||||||
|
"/joint_commands",
|
||||||
|
self.joint_command_callback,
|
||||||
|
qos_profile=control_qos,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Feedback
|
# Feedback
|
||||||
@@ -124,12 +135,12 @@ class ArmNode(Node):
|
|||||||
# Combined Socket and Digit feedback
|
# Combined Socket and Digit feedback
|
||||||
self.arm_feedback_pub_ = self.create_publisher(
|
self.arm_feedback_pub_ = self.create_publisher(
|
||||||
ArmFeedback,
|
ArmFeedback,
|
||||||
"/arm/feedback/new_feedback",
|
"/arm/feedback",
|
||||||
qos_profile=qos.qos_profile_sensor_data,
|
qos_profile=qos.qos_profile_sensor_data,
|
||||||
)
|
)
|
||||||
# IK arm pose: /joint_states is published from here to topic_based_control
|
# IK arm pose: /joint_states is published from here to topic_based_control
|
||||||
self.joint_state_pub_ = self.create_publisher(
|
self.joint_state_pub_ = self.create_publisher(
|
||||||
JointState, "joint_states", qos_profile=qos.qos_profile_sensor_data
|
JointState, "/joint_states", qos_profile=qos.qos_profile_sensor_data
|
||||||
)
|
)
|
||||||
|
|
||||||
###################################################
|
###################################################
|
||||||
@@ -146,12 +157,9 @@ class ArmNode(Node):
|
|||||||
self.saved_joint_state.velocity = [0.0] * len(self.saved_joint_state.name)
|
self.saved_joint_state.velocity = [0.0] * len(self.saved_joint_state.name)
|
||||||
|
|
||||||
def jointjog_callback(self, msg: JointJog):
|
def jointjog_callback(self, msg: JointJog):
|
||||||
if (
|
if len(msg.joint_names) != len(msg.velocities):
|
||||||
len(msg.joint_names) == 0
|
self.get_logger().debug("Ignoring malformed /arm/manual/joint_jog message.")
|
||||||
or len(msg.velocities) == 0
|
return
|
||||||
or len(msg.joint_names) != len(msg.velocities)
|
|
||||||
):
|
|
||||||
return # Malformed message
|
|
||||||
|
|
||||||
# Grab velocities from message
|
# Grab velocities from message
|
||||||
velocities = [
|
velocities = [
|
||||||
@@ -164,62 +172,51 @@ class ArmNode(Node):
|
|||||||
]
|
]
|
||||||
# Deadzone
|
# Deadzone
|
||||||
velocities = [vel if abs(vel) > 0.05 else 0.0 for vel in velocities]
|
velocities = [vel if abs(vel) > 0.05 else 0.0 for vel in velocities]
|
||||||
# ROS2's rad/s to VicCAN's deg/s*10; don't convert gripper's m/s
|
|
||||||
velocities = [
|
|
||||||
math.degrees(vel) * 10 if i < 6 else vel for i, vel in enumerate(velocities)
|
|
||||||
]
|
|
||||||
# Axis 2 & 3 URDF direction is inverted
|
|
||||||
velocities[2] = -velocities[2]
|
|
||||||
velocities[3] = -velocities[3]
|
|
||||||
|
|
||||||
# Send Axis 0-3
|
self.send_velocities(velocities, msg.header)
|
||||||
self.anchor_tovic_pub_.publish(
|
|
||||||
VicCAN(
|
|
||||||
mcu_name="arm", command_id=43, data=velocities[0:3], header=msg.header
|
|
||||||
)
|
|
||||||
)
|
|
||||||
# Send Wrist yaw and roll
|
|
||||||
# TODO: Verify embedded
|
|
||||||
self.anchor_tovic_pub_.publish(
|
|
||||||
VicCAN(
|
|
||||||
mcu_name="digit", command_id=43, data=velocities[4:5], header=msg.header
|
|
||||||
)
|
|
||||||
)
|
|
||||||
# Send End Effector Gripper
|
|
||||||
# TODO: Verify m/s received correctly by embedded
|
|
||||||
self.anchor_tovic_pub_.publish(
|
|
||||||
VicCAN(
|
|
||||||
mcu_name="digit", command_id=26, data=[velocities[6]], header=msg.header
|
|
||||||
)
|
|
||||||
)
|
|
||||||
# TODO: use msg.duration
|
# TODO: use msg.duration
|
||||||
|
|
||||||
def joint_command_callback(self, msg: JointState):
|
def joint_command_callback(self, msg: JointState):
|
||||||
if len(msg.position) < 7 and len(msg.velocity) < 7:
|
if len(msg.position) < 7 and len(msg.velocity) < 7:
|
||||||
|
self.get_logger().debug("Ignoring malformed /joint_command message.")
|
||||||
return # command needs either position or velocity for all 7 joints
|
return # command needs either position or velocity for all 7 joints
|
||||||
|
|
||||||
# Assumed order: Axis0, Axis1, Axis2, Axis3, Wrist_Yaw, Wrist_Roll, Gripper
|
# Grab velocities from message
|
||||||
# TODO: refactor to depend on joint names
|
|
||||||
# Embedded takes deg*10, ROS2 uses Radians
|
|
||||||
velocities = [
|
velocities = [
|
||||||
math.degrees(vel) * 10 if abs(vel) > 0.05 else 0.0 for vel in msg.velocity
|
(
|
||||||
|
msg.velocity[msg.name.index(joint_name)] # type: ignore
|
||||||
|
if joint_name in msg.name
|
||||||
|
else 0.0
|
||||||
|
)
|
||||||
|
for joint_name in self.all_joint_names
|
||||||
]
|
]
|
||||||
# Axis 2 & 3 URDF direction is inverted
|
|
||||||
velocities[2] = -velocities[2]
|
|
||||||
velocities[3] = -velocities[3]
|
|
||||||
|
|
||||||
# Axis 0-3
|
self.send_velocities(velocities, msg.header)
|
||||||
arm_cmd = VicCAN(mcu_name="arm", command_id=43, data=velocities[0:3])
|
|
||||||
arm_cmd.header = Header(stamp=self.get_clock().now().to_msg())
|
|
||||||
# Wrist yaw and roll, gripper included for future use when have adequate hardware
|
|
||||||
digit_cmd = VicCAN(mcu_name="digit", command_id=43, data=velocities[4:6])
|
|
||||||
digit_cmd.header = Header(stamp=self.get_clock().now().to_msg())
|
|
||||||
|
|
||||||
self.anchor_tovic_pub_.publish(arm_cmd)
|
def send_velocities(self, velocities: list[float], header: Header):
|
||||||
self.anchor_tovic_pub_.publish(digit_cmd)
|
# ROS2's rad/s to VicCAN's deg/s*10; don't convert gripper's m/s
|
||||||
|
velocities = [
|
||||||
|
math.degrees(vel) * 10 if i < 6 else vel for i, vel in enumerate(velocities)
|
||||||
|
]
|
||||||
|
|
||||||
|
# Send Axis 0-3
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(mcu_name="arm", command_id=43, data=velocities[0:3], header=header)
|
||||||
|
)
|
||||||
|
# Send Wrist yaw and roll
|
||||||
|
# TODO: Verify embedded
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(mcu_name="digit", command_id=43, data=velocities[4:5], header=header)
|
||||||
|
)
|
||||||
|
# Send End Effector Gripper
|
||||||
|
# TODO: Verify m/s received correctly by embedded
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(mcu_name="digit", command_id=26, data=[velocities[6]], header=header)
|
||||||
|
)
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def send_manual(self, msg: ArmManual):
|
def send_manual(self, msg: ArmManual):
|
||||||
"""TODO: Old"""
|
|
||||||
axis0 = msg.axis0
|
axis0 = msg.axis0
|
||||||
axis1 = -1 * msg.axis1
|
axis1 = -1 * msg.axis1
|
||||||
axis2 = msg.axis2
|
axis2 = msg.axis2
|
||||||
@@ -243,13 +240,13 @@ class ArmNode(Node):
|
|||||||
|
|
||||||
return
|
return
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def send_cmd(self, msg: str):
|
def send_cmd(self, msg: str):
|
||||||
"""TODO: Old"""
|
|
||||||
output = String(data=msg)
|
output = String(data=msg)
|
||||||
self.anchor_pub.publish(output)
|
self.anchor_pub.publish(output)
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def anchor_feedback(self, msg: String):
|
def anchor_feedback(self, msg: String):
|
||||||
"""TODO: Old"""
|
|
||||||
output = msg.data
|
output = msg.data
|
||||||
if output.startswith("can_relay_fromvic,arm,55"):
|
if output.startswith("can_relay_fromvic,arm,55"):
|
||||||
self.updateAngleFeedback(output)
|
self.updateAngleFeedback(output)
|
||||||
@@ -282,8 +279,7 @@ class ArmNode(Node):
|
|||||||
self.process_fromvic_digit(msg)
|
self.process_fromvic_digit(msg)
|
||||||
|
|
||||||
def process_fromvic_arm(self, msg: VicCAN):
|
def process_fromvic_arm(self, msg: VicCAN):
|
||||||
if msg.mcu_name != "arm":
|
assert msg.mcu_name == "arm"
|
||||||
return
|
|
||||||
|
|
||||||
# Check message len to prevent crashing on bad data
|
# Check message len to prevent crashing on bad data
|
||||||
if msg.command_id in self.viccan_socket_msg_len_dict:
|
if msg.command_id in self.viccan_socket_msg_len_dict:
|
||||||
@@ -326,12 +322,8 @@ class ArmNode(Node):
|
|||||||
# Joint state publisher for URDF visualization
|
# Joint state publisher for URDF visualization
|
||||||
self.saved_joint_state.position[0] = math.radians(angles[0]) # Axis 0
|
self.saved_joint_state.position[0] = math.radians(angles[0]) # Axis 0
|
||||||
self.saved_joint_state.position[1] = math.radians(angles[1]) # Axis 1
|
self.saved_joint_state.position[1] = math.radians(angles[1]) # Axis 1
|
||||||
self.saved_joint_state.position[2] = math.radians(
|
self.saved_joint_state.position[2] = math.radians(angles[2]) # Axis 2
|
||||||
-angles[2]
|
self.saved_joint_state.position[3] = math.radians(angles[3]) # Axis 3
|
||||||
) # Axis 2 (inverted)
|
|
||||||
self.saved_joint_state.position[3] = math.radians(
|
|
||||||
-angles[3]
|
|
||||||
) # Axis 3 (inverted)
|
|
||||||
# Wrist is handled by digit feedback
|
# Wrist is handled by digit feedback
|
||||||
self.saved_joint_state.header.stamp = msg.header.stamp
|
self.saved_joint_state.header.stamp = msg.header.stamp
|
||||||
self.joint_state_pub_.publish(self.saved_joint_state)
|
self.joint_state_pub_.publish(self.saved_joint_state)
|
||||||
@@ -363,18 +355,17 @@ class ArmNode(Node):
|
|||||||
velocities[1]
|
velocities[1]
|
||||||
) # Axis 1
|
) # Axis 1
|
||||||
self.saved_joint_state.velocity[2] = math.radians(
|
self.saved_joint_state.velocity[2] = math.radians(
|
||||||
-velocities[2]
|
velocities[2]
|
||||||
) # Axis 2 (-)
|
) # Axis 2
|
||||||
self.saved_joint_state.velocity[3] = math.radians(
|
self.saved_joint_state.velocity[3] = math.radians(
|
||||||
-velocities[3]
|
velocities[3]
|
||||||
) # Axis 3 (-)
|
) # Axis 3
|
||||||
# Wrist is handled by digit feedback
|
# Wrist is handled by digit feedback
|
||||||
self.saved_joint_state.header.stamp = msg.header.stamp
|
self.saved_joint_state.header.stamp = msg.header.stamp
|
||||||
self.joint_state_pub_.publish(self.saved_joint_state)
|
self.joint_state_pub_.publish(self.saved_joint_state)
|
||||||
|
|
||||||
def process_fromvic_digit(self, msg: VicCAN):
|
def process_fromvic_digit(self, msg: VicCAN):
|
||||||
if msg.mcu_name != "digit":
|
assert msg.mcu_name == "digit"
|
||||||
return
|
|
||||||
|
|
||||||
# Check message len to prevent crashing on bad data
|
# Check message len to prevent crashing on bad data
|
||||||
if msg.command_id in self.viccan_digit_msg_len_dict:
|
if msg.command_id in self.viccan_digit_msg_len_dict:
|
||||||
@@ -398,13 +389,13 @@ class ArmNode(Node):
|
|||||||
msg.data[1]
|
msg.data[1]
|
||||||
) # Wrist yaw
|
) # Wrist yaw
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def publish_feedback(self):
|
def publish_feedback(self):
|
||||||
"""TODO: Old"""
|
|
||||||
self.socket_pub.publish(self.arm_feedback)
|
self.socket_pub.publish(self.arm_feedback)
|
||||||
self.digit_pub.publish(self.digit_feedback)
|
self.digit_pub.publish(self.digit_feedback)
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def updateAngleFeedback(self, msg: str):
|
def updateAngleFeedback(self, msg: str):
|
||||||
"""TODO: Old"""
|
|
||||||
# Angle feedbacks,
|
# Angle feedbacks,
|
||||||
# split the msg.data by commas
|
# split the msg.data by commas
|
||||||
parts = msg.split(",")
|
parts = msg.split(",")
|
||||||
@@ -422,8 +413,8 @@ class ArmNode(Node):
|
|||||||
else:
|
else:
|
||||||
self.get_logger().info("Invalid angle feedback input format")
|
self.get_logger().info("Invalid angle feedback input format")
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def updateBusVoltage(self, msg: str):
|
def updateBusVoltage(self, msg: str):
|
||||||
"""TODO: Old"""
|
|
||||||
# Bus Voltage feedbacks
|
# Bus Voltage feedbacks
|
||||||
parts = msg.split(",")
|
parts = msg.split(",")
|
||||||
if len(parts) >= 7:
|
if len(parts) >= 7:
|
||||||
@@ -437,8 +428,8 @@ class ArmNode(Node):
|
|||||||
else:
|
else:
|
||||||
self.get_logger().info("Invalid voltage feedback input format")
|
self.get_logger().info("Invalid voltage feedback input format")
|
||||||
|
|
||||||
|
@deprecated("Uses an old message type. Will be removed at some point.")
|
||||||
def updateMotorFeedback(self, msg: str):
|
def updateMotorFeedback(self, msg: str):
|
||||||
"""TODO: Old"""
|
|
||||||
parts = str(msg.strip()).split(",")
|
parts = str(msg.strip()).split(",")
|
||||||
motorId = round(float(parts[3]))
|
motorId = round(float(parts[3]))
|
||||||
temp = float(parts[4]) / 10.0
|
temp = float(parts[4]) / 10.0
|
||||||
@@ -462,15 +453,22 @@ class ArmNode(Node):
|
|||||||
self.arm_feedback.axis0_current = current
|
self.arm_feedback.axis0_current = current
|
||||||
|
|
||||||
|
|
||||||
|
def exit_handler(signum, frame):
|
||||||
|
print("Caught SIGTERM. Exiting...")
|
||||||
|
rclpy.try_shutdown()
|
||||||
|
sys.exit(0)
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
rclpy.init(args=args)
|
rclpy.init(args=args)
|
||||||
|
|
||||||
|
# Catch termination signals and exit cleanly
|
||||||
|
signal.signal(signal.SIGTERM, exit_handler)
|
||||||
|
|
||||||
arm_node = ArmNode()
|
arm_node = ArmNode()
|
||||||
thread = threading.Thread(target=rclpy.spin, args=(arm_node,), daemon=True)
|
|
||||||
thread.start()
|
|
||||||
|
|
||||||
try:
|
try:
|
||||||
thread.join()
|
rclpy.spin(arm_node)
|
||||||
except (KeyboardInterrupt, ExternalShutdownException):
|
except (KeyboardInterrupt, ExternalShutdownException):
|
||||||
pass
|
pass
|
||||||
finally:
|
finally:
|
||||||
@@ -478,8 +476,4 @@ def main(args=None):
|
|||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
# signal.signal(signal.SIGTSTP, lambda signum, frame: sys.exit(0)) # Catch Ctrl+Z and exit cleanly
|
|
||||||
signal.signal(
|
|
||||||
signal.SIGTERM, lambda signum, frame: sys.exit(0)
|
|
||||||
) # Catch termination signals and exit cleanly
|
|
||||||
main()
|
main()
|
||||||
|
|||||||
@@ -1,27 +1,22 @@
|
|||||||
from setuptools import find_packages, setup
|
from setuptools import setup
|
||||||
import os
|
|
||||||
from glob import glob
|
|
||||||
|
|
||||||
package_name = "arm_pkg"
|
package_name = "arm_pkg"
|
||||||
|
|
||||||
setup(
|
setup(
|
||||||
name=package_name,
|
name=package_name,
|
||||||
version="1.0.0",
|
version="1.0.0",
|
||||||
packages=find_packages(exclude=["test"]),
|
packages=[package_name],
|
||||||
data_files=[
|
data_files=[
|
||||||
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
||||||
("share/" + package_name, ["package.xml"]),
|
("share/" + package_name, ["package.xml"]),
|
||||||
],
|
],
|
||||||
install_requires=["setuptools"],
|
install_requires=["setuptools"],
|
||||||
zip_safe=True,
|
zip_safe=True,
|
||||||
maintainer="tristan",
|
maintainer="David",
|
||||||
maintainer_email="tristanmcginnis26@gmail.com",
|
maintainer_email="ds0196@uah.edu",
|
||||||
description="TODO: Package description",
|
description="Relays topics related to the arm between VicCAN (through Anchor) and basestation.",
|
||||||
license="All Rights Reserved",
|
license="AGPL-3.0-only",
|
||||||
entry_points={
|
entry_points={
|
||||||
"console_scripts": [
|
"console_scripts": ["arm = arm_pkg.arm_node:main"],
|
||||||
"arm = arm_pkg.arm_node:main",
|
|
||||||
"headless = arm_pkg.arm_headless:main",
|
|
||||||
],
|
|
||||||
},
|
},
|
||||||
)
|
)
|
||||||
|
|||||||
Submodule src/astra_descriptions updated: 72d3c223af...c36bd8233d
@@ -262,7 +262,7 @@ class PtzNode(Node):
|
|||||||
f"[{self.get_clock().now().nanoseconds / 1e9:.2f}] PTZ Node: {message_text}"
|
f"[{self.get_clock().now().nanoseconds / 1e9:.2f}] PTZ Node: {message_text}"
|
||||||
)
|
)
|
||||||
self.debug_pub.publish(msg)
|
self.debug_pub.publish(msg)
|
||||||
self.get_logger().info(message_text)
|
self.get_logger().debug(message_text)
|
||||||
|
|
||||||
def run_async_func(self, coro):
|
def run_async_func(self, coro):
|
||||||
"""Run an async function in the event loop."""
|
"""Run an async function in the event loop."""
|
||||||
|
|||||||
@@ -39,9 +39,9 @@ os.environ["SDL_AUDIODRIVER"] = (
|
|||||||
CORE_STOP_MSG = CoreControl() # All zeros by default
|
CORE_STOP_MSG = CoreControl() # All zeros by default
|
||||||
CORE_STOP_TWIST_MSG = Twist() # "
|
CORE_STOP_TWIST_MSG = Twist() # "
|
||||||
ARM_STOP_MSG = ArmManual() # "
|
ARM_STOP_MSG = ArmManual() # "
|
||||||
ARM_IK_STOP_MSG = TwistStamped() # "
|
|
||||||
BIO_STOP_MSG = BioControl() # "
|
BIO_STOP_MSG = BioControl() # "
|
||||||
|
|
||||||
|
|
||||||
control_qos = qos.QoSProfile(
|
control_qos = qos.QoSProfile(
|
||||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||||
depth=2,
|
depth=2,
|
||||||
@@ -75,15 +75,7 @@ class Headless(Node):
|
|||||||
# Initialize pygame first
|
# Initialize pygame first
|
||||||
pygame.init()
|
pygame.init()
|
||||||
pygame.joystick.init()
|
pygame.joystick.init()
|
||||||
super().__init__("headless")
|
super().__init__("headless_node")
|
||||||
|
|
||||||
# TODO: move the STOP_MSGs somewhere better
|
|
||||||
global ARM_STOP_JOG_MSG
|
|
||||||
ARM_STOP_JOG_MSG = JointJog(
|
|
||||||
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()),
|
|
||||||
joint_names=self.all_joint_names,
|
|
||||||
velocities=[0.0] * len(self.all_joint_names),
|
|
||||||
)
|
|
||||||
|
|
||||||
##################################################
|
##################################################
|
||||||
# Preamble
|
# Preamble
|
||||||
@@ -247,9 +239,9 @@ class Headless(Node):
|
|||||||
else:
|
else:
|
||||||
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG)
|
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG)
|
||||||
if self.use_arm_ik:
|
if self.use_arm_ik:
|
||||||
self.arm_ik_twist_publisher.publish(ARM_IK_STOP_MSG)
|
self.arm_ik_twist_publisher.publish(self.arm_ik_twist_stop_msg())
|
||||||
else:
|
else:
|
||||||
self.arm_manual_pub_.publish(ARM_STOP_JOG_MSG)
|
self.arm_manual_pub_.publish(self.arm_manual_stop_msg())
|
||||||
# TODO: add bio here after implementing new topics
|
# TODO: add bio here after implementing new topics
|
||||||
|
|
||||||
def send_controls(self):
|
def send_controls(self):
|
||||||
@@ -519,14 +511,12 @@ class Headless(Node):
|
|||||||
# X: _
|
# X: _
|
||||||
# Y: linear actuator out
|
# Y: linear actuator out
|
||||||
|
|
||||||
ARM_THRESHOLD = 0.2
|
|
||||||
|
|
||||||
# Right stick: EF yaw and axis 3
|
# Right stick: EF yaw and axis 3
|
||||||
arm_input.velocities[self.all_joint_names.index("wrist_yaw_joint")] = float(
|
arm_input.velocities[self.all_joint_names.index("wrist_yaw_joint")] = float(
|
||||||
stick_to_arm_direction(right_stick_x)
|
stick_to_arm_direction(right_stick_x)
|
||||||
)
|
)
|
||||||
arm_input.velocities[self.all_joint_names.index("axis_3_joint")] = float(
|
arm_input.velocities[self.all_joint_names.index("axis_3_joint")] = float(
|
||||||
-1 * stick_to_arm_direction(right_stick_y)
|
stick_to_arm_direction(right_stick_y)
|
||||||
)
|
)
|
||||||
|
|
||||||
# Left stick: axis 1 and 2
|
# Left stick: axis 1 and 2
|
||||||
@@ -534,7 +524,7 @@ class Headless(Node):
|
|||||||
stick_to_arm_direction(left_stick_x)
|
stick_to_arm_direction(left_stick_x)
|
||||||
)
|
)
|
||||||
arm_input.velocities[self.all_joint_names.index("axis_2_joint")] = float(
|
arm_input.velocities[self.all_joint_names.index("axis_2_joint")] = float(
|
||||||
-1 * stick_to_arm_direction(left_stick_y)
|
stick_to_arm_direction(left_stick_y)
|
||||||
)
|
)
|
||||||
|
|
||||||
# D-pad: axis 0 and _
|
# D-pad: axis 0 and _
|
||||||
@@ -653,6 +643,18 @@ class Headless(Node):
|
|||||||
else:
|
else:
|
||||||
pass # TODO: implement new bio control topics
|
pass # TODO: implement new bio control topics
|
||||||
|
|
||||||
|
def arm_manual_stop_msg(self):
|
||||||
|
return JointJog(
|
||||||
|
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()),
|
||||||
|
joint_names=self.all_joint_names,
|
||||||
|
velocities=[0.0] * len(self.all_joint_names),
|
||||||
|
)
|
||||||
|
|
||||||
|
def arm_ik_twist_stop_msg(self):
|
||||||
|
return TwistStamped(
|
||||||
|
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg())
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
def stick_deadzone(value: float, threshold=STICK_DEADZONE) -> float:
|
def stick_deadzone(value: float, threshold=STICK_DEADZONE) -> float:
|
||||||
"""Apply a deadzone to a joystick input so the motors don't sound angry"""
|
"""Apply a deadzone to a joystick input so the motors don't sound angry"""
|
||||||
|
|||||||
9
treefmt.nix
Normal file
9
treefmt.nix
Normal file
@@ -0,0 +1,9 @@
|
|||||||
|
{ ... }:
|
||||||
|
{
|
||||||
|
projectRootFile = "flake.nix";
|
||||||
|
programs = {
|
||||||
|
nixfmt.enable = true;
|
||||||
|
black.enable = true;
|
||||||
|
shfmt.enable = true;
|
||||||
|
};
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user