mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-02-11 17:30:36 +00:00
Compare commits
27 Commits
gazebo-doc
...
bio-topic-
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
7e6a53b7f1 | ||
|
|
9510270272 | ||
|
|
3f68052144 | ||
|
|
c72f72dc32 | ||
|
|
d4042f8744 | ||
|
|
61f5f1fc3e | ||
|
|
d46bb81ed1 | ||
|
|
87a764e616 | ||
|
|
f99b9e6f96 | ||
|
|
65aab7f179 | ||
|
|
697efa7b9d | ||
|
|
b70a0d27c3 | ||
|
|
2d48361b8f | ||
|
|
d9355f16e9 | ||
|
|
9fc120b09e | ||
|
|
4a98c3d435 | ||
|
|
b5be93e5f6 | ||
|
|
0e775c65c6 | ||
|
|
14141651bf | ||
|
|
c10a2a5cca | ||
|
|
df78575206 | ||
|
|
40fa0d0ab8 | ||
|
|
3bb3771dce | ||
|
|
5e7776631d | ||
|
|
b84ca6757d | ||
|
|
96f5eda005 | ||
|
|
4c1416851e |
3
.gitmodules
vendored
3
.gitmodules
vendored
@@ -1,6 +1,3 @@
|
|||||||
[submodule "src/astra_description"]
|
[submodule "src/astra_description"]
|
||||||
path = src/astra_descriptions
|
path = src/astra_descriptions
|
||||||
url = ../astra_descriptions
|
url = ../astra_descriptions
|
||||||
[submodule "src/astra_msgs"]
|
|
||||||
path = src/astra_msgs
|
|
||||||
url = git@github.com:SHC-ASTRA/astra_msgs.git
|
|
||||||
|
|||||||
@@ -14,8 +14,8 @@ echo "[INFO] Network interface is up!"
|
|||||||
# Your actual ROS node start command goes here
|
# Your actual ROS node start command goes here
|
||||||
echo "[INFO] Starting ROS node..."
|
echo "[INFO] Starting ROS node..."
|
||||||
|
|
||||||
# Source ROS 2 Humble setup script
|
# Source ROS 2 Humble setup script (if we aren't using nix)
|
||||||
source /opt/ros/humble/setup.bash
|
command -v ros2 || source /opt/ros/humble/setup.bash
|
||||||
|
|
||||||
# Source your workspace setup script
|
# Source your workspace setup script
|
||||||
source $SCRIPT_DIR/../install/setup.bash
|
source $SCRIPT_DIR/../install/setup.bash
|
||||||
|
|||||||
@@ -15,7 +15,7 @@ echo "[INFO] Network interface is up!"
|
|||||||
echo "[INFO] Starting ROS node..."
|
echo "[INFO] Starting ROS node..."
|
||||||
|
|
||||||
# Source ROS 2 Humble setup script
|
# Source ROS 2 Humble setup script
|
||||||
source /opt/ros/humble/setup.bash
|
command -v ros2 || source /opt/ros/humble/setup.bash
|
||||||
|
|
||||||
# Source your workspace setup script
|
# Source your workspace setup script
|
||||||
source $SCRIPT_DIR/../install/setup.bash
|
source $SCRIPT_DIR/../install/setup.bash
|
||||||
|
|||||||
@@ -17,7 +17,7 @@ done
|
|||||||
echo "[INFO] Network interface is up!"
|
echo "[INFO] Network interface is up!"
|
||||||
|
|
||||||
|
|
||||||
source /opt/ros/humble/setup.bash
|
command -v ros2 || source /opt/ros/humble/setup.bash
|
||||||
source $ANCHOR_WS/install/setup.bash
|
source $ANCHOR_WS/install/setup.bash
|
||||||
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash
|
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash
|
||||||
|
|
||||||
|
|||||||
112
flake.lock
generated
112
flake.lock
generated
@@ -1,5 +1,29 @@
|
|||||||
{
|
{
|
||||||
"nodes": {
|
"nodes": {
|
||||||
|
"astra-msgs": {
|
||||||
|
"inputs": {
|
||||||
|
"nix-ros-overlay": "nix-ros-overlay",
|
||||||
|
"nixpkgs": [
|
||||||
|
"astra-msgs",
|
||||||
|
"nix-ros-overlay",
|
||||||
|
"nixpkgs"
|
||||||
|
]
|
||||||
|
},
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1770693861,
|
||||||
|
"narHash": "sha256-8NBtSsKVYtd+NYt51tJ1EteC0nOTemDUBoRXbDoQAuA=",
|
||||||
|
"owner": "SHC-ASTRA",
|
||||||
|
"repo": "astra_msgs",
|
||||||
|
"rev": "60bbb53085b09fbdb7e848b1dd168d526d9af281",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "SHC-ASTRA",
|
||||||
|
"ref": "60bbb53085b09fbdb7e848b1dd168d526d9af281",
|
||||||
|
"repo": "astra_msgs",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
|
},
|
||||||
"flake-utils": {
|
"flake-utils": {
|
||||||
"inputs": {
|
"inputs": {
|
||||||
"systems": "systems"
|
"systems": "systems"
|
||||||
@@ -18,33 +42,87 @@
|
|||||||
"type": "github"
|
"type": "github"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
"flake-utils_2": {
|
||||||
|
"inputs": {
|
||||||
|
"systems": "systems_2"
|
||||||
|
},
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1731533236,
|
||||||
|
"narHash": "sha256-l0KFg5HjrsfsO/JpG+r7fRrqm12kzFHyUHqHCVpMMbI=",
|
||||||
|
"owner": "numtide",
|
||||||
|
"repo": "flake-utils",
|
||||||
|
"rev": "11707dc2f618dd54ca8739b309ec4fc024de578b",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "numtide",
|
||||||
|
"repo": "flake-utils",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
|
},
|
||||||
"nix-ros-overlay": {
|
"nix-ros-overlay": {
|
||||||
"inputs": {
|
"inputs": {
|
||||||
"flake-utils": "flake-utils",
|
"flake-utils": "flake-utils",
|
||||||
"nixpkgs": "nixpkgs"
|
"nixpkgs": "nixpkgs"
|
||||||
},
|
},
|
||||||
"locked": {
|
"locked": {
|
||||||
"lastModified": 1761810010,
|
"lastModified": 1770408708,
|
||||||
"narHash": "sha256-o0wJKW603SiOO373BTgeZaF6nDxegMA/cRrzSC2Cscg=",
|
"narHash": "sha256-E7ZQRgGrsiuswgXnG7337ZR5s4SdZlheZjxKOQdVoH8=",
|
||||||
"owner": "lopsided98",
|
"owner": "lopsided98",
|
||||||
"repo": "nix-ros-overlay",
|
"repo": "nix-ros-overlay",
|
||||||
"rev": "e277df39e3bc6b372a5138c0bcf10198857c55ab",
|
"rev": "e78ba91032c7f8bdd823fbf43937cbf0f4f09747",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
},
|
},
|
||||||
"original": {
|
"original": {
|
||||||
"owner": "lopsided98",
|
"owner": "lopsided98",
|
||||||
"ref": "master",
|
"ref": "develop",
|
||||||
|
"repo": "nix-ros-overlay",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"nix-ros-overlay_2": {
|
||||||
|
"inputs": {
|
||||||
|
"flake-utils": "flake-utils_2",
|
||||||
|
"nixpkgs": "nixpkgs_2"
|
||||||
|
},
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1770108954,
|
||||||
|
"narHash": "sha256-VBj6bd4LPPSfsZJPa/UPPA92dOs6tmQo0XZKqfz/3W4=",
|
||||||
|
"owner": "lopsided98",
|
||||||
|
"repo": "nix-ros-overlay",
|
||||||
|
"rev": "3d05d46451b376e128a1553e78b8870c75d7753a",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "lopsided98",
|
||||||
|
"ref": "develop",
|
||||||
"repo": "nix-ros-overlay",
|
"repo": "nix-ros-overlay",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"nixpkgs": {
|
"nixpkgs": {
|
||||||
"locked": {
|
"locked": {
|
||||||
"lastModified": 1744849697,
|
"lastModified": 1759381078,
|
||||||
"narHash": "sha256-S9hqvanPSeRu6R4cw0OhvH1rJ+4/s9xIban9C4ocM/0=",
|
"narHash": "sha256-gTrEEp5gEspIcCOx9PD8kMaF1iEmfBcTbO0Jag2QhQs=",
|
||||||
"owner": "lopsided98",
|
"owner": "NixOS",
|
||||||
"repo": "nixpkgs",
|
"repo": "nixpkgs",
|
||||||
"rev": "6318f538166fef9f5118d8d78b9b43a04bb049e4",
|
"rev": "7df7ff7d8e00218376575f0acdcc5d66741351ee",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "lopsided98",
|
||||||
|
"ref": "nix-ros",
|
||||||
|
"repo": "nixpkgs",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"nixpkgs_2": {
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1759381078,
|
||||||
|
"narHash": "sha256-gTrEEp5gEspIcCOx9PD8kMaF1iEmfBcTbO0Jag2QhQs=",
|
||||||
|
"owner": "NixOS",
|
||||||
|
"repo": "nixpkgs",
|
||||||
|
"rev": "7df7ff7d8e00218376575f0acdcc5d66741351ee",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
},
|
},
|
||||||
"original": {
|
"original": {
|
||||||
@@ -56,7 +134,8 @@
|
|||||||
},
|
},
|
||||||
"root": {
|
"root": {
|
||||||
"inputs": {
|
"inputs": {
|
||||||
"nix-ros-overlay": "nix-ros-overlay",
|
"astra-msgs": "astra-msgs",
|
||||||
|
"nix-ros-overlay": "nix-ros-overlay_2",
|
||||||
"nixpkgs": [
|
"nixpkgs": [
|
||||||
"nix-ros-overlay",
|
"nix-ros-overlay",
|
||||||
"nixpkgs"
|
"nixpkgs"
|
||||||
@@ -77,6 +156,21 @@
|
|||||||
"repo": "default",
|
"repo": "default",
|
||||||
"type": "github"
|
"type": "github"
|
||||||
}
|
}
|
||||||
|
},
|
||||||
|
"systems_2": {
|
||||||
|
"locked": {
|
||||||
|
"lastModified": 1681028828,
|
||||||
|
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
|
||||||
|
"owner": "nix-systems",
|
||||||
|
"repo": "default",
|
||||||
|
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
|
||||||
|
"type": "github"
|
||||||
|
},
|
||||||
|
"original": {
|
||||||
|
"owner": "nix-systems",
|
||||||
|
"repo": "default",
|
||||||
|
"type": "github"
|
||||||
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"root": "root",
|
"root": "root",
|
||||||
|
|||||||
15
flake.nix
15
flake.nix
@@ -2,8 +2,10 @@
|
|||||||
description = "Development environment for ASTRA Anchor";
|
description = "Development environment for ASTRA Anchor";
|
||||||
|
|
||||||
inputs = {
|
inputs = {
|
||||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/master";
|
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
||||||
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
||||||
|
# specify astra_msgs commit hash to the one we support
|
||||||
|
astra-msgs.url = "github:SHC-ASTRA/astra_msgs?ref=60bbb53085b09fbdb7e848b1dd168d526d9af281";
|
||||||
};
|
};
|
||||||
|
|
||||||
outputs =
|
outputs =
|
||||||
@@ -11,6 +13,7 @@
|
|||||||
self,
|
self,
|
||||||
nix-ros-overlay,
|
nix-ros-overlay,
|
||||||
nixpkgs,
|
nixpkgs,
|
||||||
|
astra-msgs,
|
||||||
}:
|
}:
|
||||||
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
|
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
|
||||||
system:
|
system:
|
||||||
@@ -24,8 +27,9 @@
|
|||||||
devShells.default = pkgs.mkShell {
|
devShells.default = pkgs.mkShell {
|
||||||
name = "ASTRA Anchor";
|
name = "ASTRA Anchor";
|
||||||
packages = with pkgs; [
|
packages = with pkgs; [
|
||||||
|
astra-msgs.packages.${system}.astra-msgs
|
||||||
colcon
|
colcon
|
||||||
(python312.withPackages (
|
(python313.withPackages (
|
||||||
p: with p; [
|
p: with p; [
|
||||||
pyserial
|
pyserial
|
||||||
pygame
|
pygame
|
||||||
@@ -39,6 +43,7 @@
|
|||||||
buildEnv {
|
buildEnv {
|
||||||
paths = [
|
paths = [
|
||||||
ros-core
|
ros-core
|
||||||
|
rqt-graph
|
||||||
ros2cli
|
ros2cli
|
||||||
ros2run
|
ros2run
|
||||||
ros2bag
|
ros2bag
|
||||||
@@ -56,10 +61,12 @@
|
|||||||
control-msgs
|
control-msgs
|
||||||
control-toolbox
|
control-toolbox
|
||||||
moveit-core
|
moveit-core
|
||||||
|
moveit-planners
|
||||||
moveit-common
|
moveit-common
|
||||||
moveit-msgs
|
moveit-msgs
|
||||||
moveit-ros-planning
|
moveit-ros-planning
|
||||||
moveit-ros-planning-interface
|
moveit-ros-planning-interface
|
||||||
|
moveit-ros-visualization
|
||||||
moveit-configs-utils
|
moveit-configs-utils
|
||||||
moveit-ros-move-group
|
moveit-ros-move-group
|
||||||
moveit-servo
|
moveit-servo
|
||||||
@@ -68,9 +75,9 @@
|
|||||||
pilz-industrial-motion-planner
|
pilz-industrial-motion-planner
|
||||||
pick-ik
|
pick-ik
|
||||||
ompl
|
ompl
|
||||||
chomp-motion-planner
|
|
||||||
joy
|
joy
|
||||||
# ros2-controllers nixpkg does not build :(
|
ros2-controllers
|
||||||
|
chomp-motion-planner
|
||||||
];
|
];
|
||||||
}
|
}
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.node import Node
|
from rclpy.node import Node
|
||||||
|
from rclpy.executors import ExternalShutdownException
|
||||||
from std_srvs.srv import Empty
|
from std_srvs.srv import Empty
|
||||||
|
|
||||||
import signal
|
import signal
|
||||||
@@ -7,6 +8,7 @@ import time
|
|||||||
import atexit
|
import atexit
|
||||||
|
|
||||||
import serial
|
import serial
|
||||||
|
import serial.tools.list_ports
|
||||||
import os
|
import os
|
||||||
import sys
|
import sys
|
||||||
import threading
|
import threading
|
||||||
@@ -15,70 +17,156 @@ import glob
|
|||||||
from std_msgs.msg import String, Header
|
from std_msgs.msg import String, Header
|
||||||
from astra_msgs.msg import VicCAN
|
from astra_msgs.msg import VicCAN
|
||||||
|
|
||||||
serial_pub = None
|
KNOWN_USBS = [
|
||||||
thread = None
|
(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):
|
||||||
Publishers:
|
"""
|
||||||
* /anchor/from_vic/debug
|
Publishers:
|
||||||
- Every string received from the MCU is published here for debugging
|
* /anchor/from_vic/debug
|
||||||
* /anchor/from_vic/core
|
- Every string received from the MCU is published here for debugging
|
||||||
- VicCAN messages for Core node
|
* /anchor/from_vic/core
|
||||||
* /anchor/from_vic/arm
|
- VicCAN messages for Core node
|
||||||
- VicCAN messages for Arm node
|
* /anchor/from_vic/arm
|
||||||
* /anchor/from_vic/bio
|
- VicCAN messages for Arm node
|
||||||
- VicCAN messages for Bio node
|
* /anchor/from_vic/bio
|
||||||
|
- VicCAN messages for Bio node
|
||||||
|
|
||||||
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 strings 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
|
- Publish raw strings to this topic to send directly to the MCU for debugging
|
||||||
"""
|
"""
|
||||||
|
|
||||||
|
|
||||||
class SerialRelay(Node):
|
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
# Initalize node with name
|
# Initalize node with name
|
||||||
super().__init__("anchor_node") # previously 'serial_publisher'
|
super().__init__("anchor_node") # previously 'serial_publisher'
|
||||||
|
|
||||||
# Loop through all serial devices on the computer to check for the MCU
|
self.serial_port: str | None = None # e.g., "/dev/ttyUSB0"
|
||||||
self.port = None
|
|
||||||
|
# Serial port override
|
||||||
if port_override := os.getenv("PORT_OVERRIDE"):
|
if port_override := os.getenv("PORT_OVERRIDE"):
|
||||||
self.port = port_override
|
self.serial_port = port_override
|
||||||
ports = SerialRelay.list_serial_ports()
|
|
||||||
for i in range(4):
|
|
||||||
if self.port is not None:
|
|
||||||
break
|
|
||||||
for port in ports:
|
|
||||||
try:
|
|
||||||
# connect and send a ping command
|
|
||||||
ser = serial.Serial(port, 115200, timeout=1)
|
|
||||||
# (f"Checking port {port}...")
|
|
||||||
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:
|
# Serial MCU Discovery
|
||||||
self.port = port
|
|
||||||
self.get_logger().info(f"Found MCU at {self.port}!")
|
|
||||||
break
|
|
||||||
except:
|
|
||||||
pass
|
|
||||||
|
|
||||||
if self.port is None:
|
# If there was not a port override, look for a MCU over USB for Serial.
|
||||||
self.get_logger().info("Unable to find MCU...")
|
if self.serial_port is None:
|
||||||
|
comports = serial.tools.list_ports.comports()
|
||||||
|
real_ports = list(
|
||||||
|
filter(
|
||||||
|
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
|
||||||
|
found_port = recog_ports[0]
|
||||||
|
self.get_logger().info(
|
||||||
|
f"Selecting MCU '{found_port.description}' at {found_port.device}."
|
||||||
|
)
|
||||||
|
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)
|
||||||
|
# Loop through all serial devices on the computer to check for the MCU
|
||||||
|
if self.serial_port is None:
|
||||||
|
self.get_logger().warning("Falling back to legacy MCU discovery...")
|
||||||
|
ports = Anchor.list_serial_ports()
|
||||||
|
for _ in range(4):
|
||||||
|
if self.serial_port is not None:
|
||||||
|
break
|
||||||
|
for port in ports:
|
||||||
|
try:
|
||||||
|
# connect and send a ping command
|
||||||
|
ser = serial.Serial(port, 115200, timeout=1)
|
||||||
|
# (f"Checking port {port}...")
|
||||||
|
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)
|
time.sleep(1)
|
||||||
sys.exit(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:
|
||||||
|
self.serial_interface = serial.Serial(
|
||||||
|
self.serial_port, 115200, timeout=1
|
||||||
|
)
|
||||||
|
|
||||||
self.ser = serial.Serial(self.port, 115200)
|
# Attempt to get name of connected MCU
|
||||||
self.get_logger().info(f"Enabling Relay Mode")
|
self.serial_interface.write(
|
||||||
self.ser.write(b"can_relay_mode,on\n")
|
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}'."
|
||||||
|
)
|
||||||
|
|
||||||
|
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)
|
atexit.register(self.cleanup)
|
||||||
|
|
||||||
|
##################################################
|
||||||
|
# ROS2 Topic Setup
|
||||||
|
|
||||||
# New pub/sub with VicCAN
|
# New pub/sub with VicCAN
|
||||||
self.fromvic_debug_pub_ = self.create_publisher(
|
self.fromvic_debug_pub_ = self.create_publisher(
|
||||||
String, "/anchor/from_vic/debug", 20
|
String, "/anchor/from_vic/debug", 20
|
||||||
@@ -115,22 +203,10 @@ class SerialRelay(Node):
|
|||||||
String, "/anchor/relay", self.on_relay_tovic_string, 10
|
String, "/anchor/relay", self.on_relay_tovic_string, 10
|
||||||
)
|
)
|
||||||
|
|
||||||
def run(self):
|
|
||||||
# This thread makes all the update processes run in the background
|
|
||||||
global thread
|
|
||||||
thread = threading.Thread(target=rclpy.spin, args={self}, daemon=True)
|
|
||||||
thread.start()
|
|
||||||
|
|
||||||
try:
|
|
||||||
while rclpy.ok():
|
|
||||||
self.read_MCU() # Check the MCU for updates
|
|
||||||
except KeyboardInterrupt:
|
|
||||||
sys.exit(0)
|
|
||||||
|
|
||||||
def read_MCU(self):
|
def read_MCU(self):
|
||||||
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
||||||
try:
|
try:
|
||||||
output = str(self.ser.readline(), "utf8")
|
output = str(self.serial_interface.readline(), "utf8")
|
||||||
|
|
||||||
if output:
|
if output:
|
||||||
self.relay_fromvic(output)
|
self.relay_fromvic(output)
|
||||||
@@ -156,14 +232,20 @@ class SerialRelay(Node):
|
|||||||
except serial.SerialException as e:
|
except serial.SerialException as e:
|
||||||
print(f"SerialException: {e}")
|
print(f"SerialException: {e}")
|
||||||
print("Closing serial port.")
|
print("Closing serial port.")
|
||||||
if self.ser.is_open:
|
try:
|
||||||
self.ser.close()
|
if self.serial_interface.is_open:
|
||||||
|
self.serial_interface.close()
|
||||||
|
except:
|
||||||
|
pass
|
||||||
exit(1)
|
exit(1)
|
||||||
except TypeError as e:
|
except TypeError as e:
|
||||||
print(f"TypeError: {e}")
|
print(f"TypeError: {e}")
|
||||||
print("Closing serial port.")
|
print("Closing serial port.")
|
||||||
if self.ser.is_open:
|
try:
|
||||||
self.ser.close()
|
if self.serial_interface.is_open:
|
||||||
|
self.serial_interface.close()
|
||||||
|
except:
|
||||||
|
pass
|
||||||
exit(1)
|
exit(1)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
print(f"Exception: {e}")
|
print(f"Exception: {e}")
|
||||||
@@ -184,7 +266,7 @@ class SerialRelay(Node):
|
|||||||
output += f",{round(num, 7)}" # limit to 7 decimal places
|
output += f",{round(num, 7)}" # limit to 7 decimal places
|
||||||
output += "\n"
|
output += "\n"
|
||||||
# self.get_logger().info(f"VicCAN relay to MCU: {output}")
|
# self.get_logger().info(f"VicCAN relay to MCU: {output}")
|
||||||
self.ser.write(bytes(output, "utf8"))
|
self.serial_interface.write(bytes(output, "utf8"))
|
||||||
|
|
||||||
def relay_fromvic(self, msg: str):
|
def relay_fromvic(self, msg: str):
|
||||||
"""Relay a string message from the MCU to the appropriate VicCAN topic"""
|
"""Relay a string message from the MCU to the appropriate VicCAN topic"""
|
||||||
@@ -246,7 +328,7 @@ class SerialRelay(Node):
|
|||||||
"""Relay a raw string message to the MCU for debugging"""
|
"""Relay a raw string message to the MCU for debugging"""
|
||||||
message = msg.data
|
message = msg.data
|
||||||
# self.get_logger().info(f"Sending command to MCU: {msg}")
|
# self.get_logger().info(f"Sending command to MCU: {msg}")
|
||||||
self.ser.write(bytes(message, "utf8"))
|
self.serial_interface.write(bytes(message, "utf8"))
|
||||||
|
|
||||||
@staticmethod
|
@staticmethod
|
||||||
def list_serial_ports():
|
def list_serial_ports():
|
||||||
@@ -254,28 +336,29 @@ class SerialRelay(Node):
|
|||||||
|
|
||||||
def cleanup(self):
|
def cleanup(self):
|
||||||
print("Cleaning up before terminating...")
|
print("Cleaning up before terminating...")
|
||||||
if self.ser.is_open:
|
if self.serial_interface.is_open:
|
||||||
self.ser.close()
|
self.serial_interface.close()
|
||||||
|
|
||||||
|
|
||||||
def myexcepthook(type, value, tb):
|
|
||||||
print("Uncaught exception:", type, value)
|
|
||||||
if serial_pub:
|
|
||||||
serial_pub.cleanup()
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
rclpy.init(args=args)
|
try:
|
||||||
sys.excepthook = myexcepthook
|
rclpy.init(args=args)
|
||||||
|
anchor_node = Anchor()
|
||||||
|
|
||||||
global serial_pub
|
thread = threading.Thread(target=rclpy.spin, args=(anchor_node,), daemon=True)
|
||||||
|
thread.start()
|
||||||
|
|
||||||
serial_pub = SerialRelay()
|
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
||||||
serial_pub.run()
|
while rclpy.ok():
|
||||||
|
anchor_node.read_MCU() # Check the MCU for updates
|
||||||
|
rate.sleep()
|
||||||
|
except (KeyboardInterrupt, ExternalShutdownException):
|
||||||
|
print("Caught shutdown signal, shutting down...")
|
||||||
|
finally:
|
||||||
|
rclpy.try_shutdown()
|
||||||
|
|
||||||
|
|
||||||
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.signal(
|
||||||
signal.SIGTERM, lambda signum, frame: sys.exit(0)
|
signal.SIGTERM, lambda signum, frame: sys.exit(0)
|
||||||
) # Catch termination signals and exit cleanly
|
) # Catch termination signals and exit cleanly
|
||||||
|
|||||||
@@ -49,7 +49,7 @@ class SerialRelay(Node):
|
|||||||
|
|
||||||
# Create subscribers
|
# Create subscribers
|
||||||
self.man_sub = self.create_subscription(
|
self.man_sub = self.create_subscription(
|
||||||
ArmManual, "/arm/control/manual", self.send_manual, 10
|
ArmManual, "/arm/control/manual", self.send_manual, 2
|
||||||
)
|
)
|
||||||
|
|
||||||
# New messages
|
# New messages
|
||||||
@@ -190,7 +190,7 @@ class SerialRelay(Node):
|
|||||||
|
|
||||||
command += f"can_relay_tovic,digit,39,{msg.effector_yaw},{msg.effector_roll}\n"
|
command += f"can_relay_tovic,digit,39,{msg.effector_yaw},{msg.effector_roll}\n"
|
||||||
|
|
||||||
# command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn
|
command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn
|
||||||
|
|
||||||
command += f"can_relay_tovic,digit,28,{msg.laser}\n"
|
command += f"can_relay_tovic,digit,28,{msg.laser}\n"
|
||||||
|
|
||||||
|
|||||||
Submodule src/astra_descriptions updated: 4ab41e9c82...29a3eea9c5
Submodule src/astra_msgs deleted from 6a57072723
@@ -1,241 +1,203 @@
|
|||||||
import rclpy
|
import signal
|
||||||
from rclpy.node import Node
|
|
||||||
import serial
|
|
||||||
import sys
|
import sys
|
||||||
import threading
|
import threading
|
||||||
import os
|
|
||||||
import glob
|
|
||||||
import time
|
import time
|
||||||
import atexit
|
|
||||||
import signal
|
import rclpy
|
||||||
from std_msgs.msg import String
|
from astra_msgs.action import BioVacuum
|
||||||
from astra_msgs.msg import BioControl
|
from astra_msgs.msg import BioControl, BioDistributor, VicCAN
|
||||||
from astra_msgs.msg import BioFeedback
|
from astra_msgs.srv import BioTestTube
|
||||||
|
from rclpy.action import ActionServer
|
||||||
|
from rclpy.node import Node
|
||||||
|
from std_msgs.msg import Header, String
|
||||||
|
|
||||||
serial_pub = None
|
serial_pub = None
|
||||||
thread = None
|
thread = None
|
||||||
|
|
||||||
|
# used to verify the length of an incoming VicCAN feedback message
|
||||||
|
# key is VicCAN command_id, value is expected length of data list
|
||||||
|
viccan_citadel_msg_len_dict = {
|
||||||
|
# empty because not expecting any VicCAN from citadel atm
|
||||||
|
}
|
||||||
|
viccan_lance_msg_len_dict = {
|
||||||
|
# empty because not sure what VicCAN commands LANCE sends
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
class SerialRelay(Node):
|
class SerialRelay(Node):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
# Initialize node
|
# Initialize node
|
||||||
super().__init__("bio_node")
|
super().__init__("bio_node")
|
||||||
|
|
||||||
# Get launch mode parameter
|
# Anchor Topics
|
||||||
self.declare_parameter("launch_mode", "bio")
|
self.anchor_fromvic_sub_ = self.create_subscription(
|
||||||
self.launch_mode = self.get_parameter("launch_mode").value
|
VicCAN, "/anchor/from_vic/bio", self.relay_fromvic, 20
|
||||||
self.get_logger().info(f"bio launch_mode is: {self.launch_mode}")
|
)
|
||||||
|
self.anchor_tovic_pub_ = self.create_publisher(
|
||||||
# Create publishers
|
VicCAN, "/anchor/to_vic/relay", 20
|
||||||
self.debug_pub = self.create_publisher(String, "/bio/feedback/debug", 10)
|
|
||||||
self.feedback_pub = self.create_publisher(BioFeedback, "/bio/feedback", 10)
|
|
||||||
|
|
||||||
# Create subscribers
|
|
||||||
self.control_sub = self.create_subscription(
|
|
||||||
BioControl, "/bio/control", self.send_control, 10
|
|
||||||
)
|
)
|
||||||
|
|
||||||
# Create a publisher for telemetry
|
self.anchor_sub = self.create_subscription(
|
||||||
self.telemetry_pub_timer = self.create_timer(1.0, self.publish_feedback)
|
String, "/anchor/bio/feedback", self.anchor_feedback, 10
|
||||||
|
)
|
||||||
|
self.anchor_pub = self.create_publisher(String, "/anchor/relay", 10)
|
||||||
|
|
||||||
# Topics used in anchor mode
|
self.distributor_sub = self.create_subscription(
|
||||||
if self.launch_mode == "anchor":
|
BioDistributor,
|
||||||
self.anchor_sub = self.create_subscription(
|
"/bio/control/distributor",
|
||||||
String, "/anchor/bio/feedback", self.anchor_feedback, 10
|
self.distributor_callback,
|
||||||
)
|
10,
|
||||||
self.anchor_pub = self.create_publisher(String, "/anchor/relay", 10)
|
)
|
||||||
|
|
||||||
self.bio_feedback = BioFeedback()
|
# Services
|
||||||
|
self.test_tube_service = self.create_service(
|
||||||
|
BioTestTube, "/bio/control/test_tube", self.test_tube_callback
|
||||||
|
)
|
||||||
|
|
||||||
# Search for ports IF in 'arm' (standalone) and not 'anchor' mode
|
# Actions
|
||||||
if self.launch_mode == "bio":
|
self._action_server = ActionServer(
|
||||||
# Loop through all serial devices on the computer to check for the MCU
|
self, BioVacuum, "/bio/actions/vacuum", self.execute_vacuum
|
||||||
self.port = None
|
)
|
||||||
for i in range(2):
|
|
||||||
try:
|
|
||||||
# connect and send a ping command
|
|
||||||
set_port = (
|
|
||||||
"/dev/ttyACM0" # MCU is controlled through GPIO pins on the PI
|
|
||||||
)
|
|
||||||
ser = serial.Serial(set_port, 115200, timeout=1)
|
|
||||||
# print(f"Checking port {port}...")
|
|
||||||
ser.write(b"ping\n")
|
|
||||||
response = ser.read_until("\n")
|
|
||||||
|
|
||||||
# if pong is in response, then we are talking with the MCU
|
|
||||||
if b"pong" in response:
|
|
||||||
self.port = set_port
|
|
||||||
self.get_logger().info(f"Found MCU at {set_port}!")
|
|
||||||
break
|
|
||||||
except:
|
|
||||||
pass
|
|
||||||
|
|
||||||
if self.port is None:
|
|
||||||
self.get_logger().info(
|
|
||||||
"Unable to find MCU... please make sure it is connected."
|
|
||||||
)
|
|
||||||
time.sleep(1)
|
|
||||||
sys.exit(1)
|
|
||||||
|
|
||||||
self.ser = serial.Serial(self.port, 115200)
|
|
||||||
atexit.register(self.cleanup)
|
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
global thread
|
global thread
|
||||||
thread = threading.Thread(target=rclpy.spin, args=(self,), daemon=True)
|
thread = threading.Thread(target=rclpy.spin, args=(self,), daemon=True)
|
||||||
thread.start()
|
thread.start()
|
||||||
|
|
||||||
# if in arm mode, will need to read from the MCU
|
|
||||||
|
|
||||||
try:
|
try:
|
||||||
while rclpy.ok():
|
while rclpy.ok():
|
||||||
if self.launch_mode == "bio":
|
time.sleep(0.1)
|
||||||
if self.ser.in_waiting:
|
|
||||||
self.read_mcu()
|
|
||||||
else:
|
|
||||||
time.sleep(0.1)
|
|
||||||
except KeyboardInterrupt:
|
except KeyboardInterrupt:
|
||||||
pass
|
pass
|
||||||
finally:
|
|
||||||
self.cleanup()
|
|
||||||
|
|
||||||
# Currently will just spit out all values over the /arm/feedback/debug topic as strings
|
|
||||||
def read_mcu(self):
|
|
||||||
try:
|
|
||||||
output = str(self.ser.readline(), "utf8")
|
|
||||||
if output:
|
|
||||||
self.get_logger().info(f"[MCU] {output}")
|
|
||||||
msg = String()
|
|
||||||
msg.data = output
|
|
||||||
self.debug_pub.publish(msg)
|
|
||||||
except serial.SerialException:
|
|
||||||
self.get_logger().info("SerialException caught... closing serial port.")
|
|
||||||
if self.ser.is_open:
|
|
||||||
self.ser.close()
|
|
||||||
pass
|
|
||||||
except TypeError as e:
|
|
||||||
self.get_logger().info(f"TypeError: {e}")
|
|
||||||
print("Closing serial port.")
|
|
||||||
if self.ser.is_open:
|
|
||||||
self.ser.close()
|
|
||||||
pass
|
|
||||||
except Exception as e:
|
|
||||||
print(f"Exception: {e}")
|
|
||||||
print("Closing serial port.")
|
|
||||||
if self.ser.is_open:
|
|
||||||
self.ser.close()
|
|
||||||
pass
|
|
||||||
|
|
||||||
def send_ik(self, msg):
|
|
||||||
pass
|
|
||||||
|
|
||||||
def send_control(self, msg: BioControl):
|
def send_control(self, msg: BioControl):
|
||||||
# CITADEL Control Commands
|
print("todo")
|
||||||
################
|
|
||||||
|
|
||||||
# Chem Pumps, only send if not zero
|
|
||||||
if msg.pump_id != 0:
|
|
||||||
command = (
|
|
||||||
"can_relay_tovic,citadel,27,"
|
|
||||||
+ str(msg.pump_id)
|
|
||||||
+ ","
|
|
||||||
+ str(msg.pump_amount)
|
|
||||||
+ "\n"
|
|
||||||
)
|
|
||||||
self.send_cmd(command)
|
|
||||||
# Fans, only send if not zero
|
|
||||||
if msg.fan_id != 0:
|
|
||||||
command = (
|
|
||||||
"can_relay_tovic,citadel,40,"
|
|
||||||
+ str(msg.fan_id)
|
|
||||||
+ ","
|
|
||||||
+ str(msg.fan_duration)
|
|
||||||
+ "\n"
|
|
||||||
)
|
|
||||||
self.send_cmd(command)
|
|
||||||
# Servos, only send if not zero
|
|
||||||
if msg.servo_id != 0:
|
|
||||||
command = (
|
|
||||||
"can_relay_tovic,citadel,25,"
|
|
||||||
+ str(msg.servo_id)
|
|
||||||
+ ","
|
|
||||||
+ str(int(msg.servo_state))
|
|
||||||
+ "\n"
|
|
||||||
)
|
|
||||||
self.send_cmd(command)
|
|
||||||
|
|
||||||
# LSS (SCYTHE)
|
|
||||||
command = "can_relay_tovic,citadel,24," + str(msg.bio_arm) + "\n"
|
|
||||||
# self.send_cmd(command)
|
|
||||||
|
|
||||||
# Vibration Motor
|
|
||||||
command += "can_relay_tovic,citadel,26," + str(msg.vibration_motor) + "\n"
|
|
||||||
# self.send_cmd(command)
|
|
||||||
|
|
||||||
# FAERIE Control Commands
|
|
||||||
################
|
|
||||||
|
|
||||||
# To be reviewed before use#
|
|
||||||
|
|
||||||
# Laser
|
|
||||||
command += "can_relay_tovic,digit,28," + str(msg.laser) + "\n"
|
|
||||||
# self.send_cmd(command)
|
|
||||||
|
|
||||||
# Drill (SCABBARD)
|
|
||||||
command += f"can_relay_tovic,digit,19,{msg.drill:.2f}\n"
|
|
||||||
# self.send_cmd(command)
|
|
||||||
|
|
||||||
# Bio linear actuator
|
|
||||||
command += "can_relay_tovic,digit,42," + str(msg.drill_arm) + "\n"
|
|
||||||
self.send_cmd(command)
|
|
||||||
|
|
||||||
def send_cmd(self, msg: str):
|
def send_cmd(self, msg: str):
|
||||||
if (
|
# send to anchor node to relay
|
||||||
self.launch_mode == "anchor"
|
output = String()
|
||||||
): # if in anchor mode, send to anchor node to relay
|
output.data = msg
|
||||||
output = String()
|
self.anchor_pub.publish(output)
|
||||||
output.data = msg
|
|
||||||
self.anchor_pub.publish(output)
|
def relay_fromvic(self, msg: VicCAN):
|
||||||
elif self.launch_mode == "bio": # if in standalone mode, send to MCU directly
|
# self.get_logger().info(msg)
|
||||||
self.get_logger().info(f"[Bio to MCU] {msg}")
|
if msg.mcu_name == "citadel":
|
||||||
self.ser.write(bytes(msg, "utf8"))
|
self.process_fromvic_citadel(msg)
|
||||||
|
|
||||||
|
def process_fromvic_citadel(self, msg: VicCAN):
|
||||||
|
# Check message len to prevent crashing on bad data
|
||||||
|
if msg.command_id in viccan_citadel_msg_len_dict:
|
||||||
|
expected_len = viccan_citadel_msg_len_dict[msg.command_id]
|
||||||
|
if len(msg.data) != expected_len:
|
||||||
|
self.get_logger().warning(
|
||||||
|
f"Ignoring VicCAN message with id {msg.command_id} due to unexpected data length (expected {expected_len}, got {len(msg.data)})"
|
||||||
|
)
|
||||||
|
return
|
||||||
|
|
||||||
def anchor_feedback(self, msg: String):
|
def anchor_feedback(self, msg: String):
|
||||||
output = msg.data
|
output = msg.data
|
||||||
parts = str(output.strip()).split(",")
|
parts = str(output.strip()).split(",")
|
||||||
# self.get_logger().info(f"[Bio Anchor] {msg.data}")
|
self.get_logger().info(f"[Bio Anchor] {msg.data}")
|
||||||
|
# no data planned to be received from citadel, not sure about lance
|
||||||
|
|
||||||
if output.startswith(
|
def distributor_callback(self, msg: BioDistributor):
|
||||||
"can_relay_fromvic,citadel,54"
|
distributor_arr = msg.distributor_id
|
||||||
): # bat, 12, 5, Voltage readings * 100
|
vic_cmd = VicCAN(
|
||||||
self.bio_feedback.bat_voltage = float(parts[3]) / 100.0
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
self.bio_feedback.voltage_12 = float(parts[4]) / 100.0
|
mcu_name="citadel",
|
||||||
self.bio_feedback.voltage_5 = float(parts[5]) / 100.0
|
command_id=40,
|
||||||
elif output.startswith("can_relay_fromvic,digit,57"):
|
data=[
|
||||||
self.bio_feedback.drill_temp = float(parts[3])
|
clamp_short(distributor_arr[0]),
|
||||||
self.bio_feedback.drill_humidity = float(parts[4])
|
clamp_short(distributor_arr[1]),
|
||||||
|
clamp_short(distributor_arr[2]),
|
||||||
|
0,
|
||||||
|
],
|
||||||
|
)
|
||||||
|
self.anchor_tovic_pub_.publish(vic_cmd)
|
||||||
|
|
||||||
def publish_feedback(self):
|
def test_tube_callback(self, request, response):
|
||||||
self.feedback_pub.publish(self.bio_feedback)
|
tubes_cmd = VicCAN(
|
||||||
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
|
mcu_name="citadel",
|
||||||
|
command_id=40,
|
||||||
|
data=[
|
||||||
|
float(int.from_bytes(request.tube_id)),
|
||||||
|
float(request.milliliters),
|
||||||
|
],
|
||||||
|
)
|
||||||
|
self.anchor_tovic_pub_.publish(tubes_cmd)
|
||||||
|
return response
|
||||||
|
|
||||||
@staticmethod
|
def execute_vacuum(self, goal_handle):
|
||||||
def list_serial_ports():
|
valve_id = int.from_bytes(goal_handle.request.valve_id)
|
||||||
return glob.glob("/dev/ttyUSB*") + glob.glob("/dev/ttyACM*")
|
duty = int.from_bytes(goal_handle.request.fan_duty_cycle_percent)
|
||||||
# return glob.glob("/dev/tty[A-Za-z]*")
|
total = goal_handle.request.fan_time_ms
|
||||||
|
|
||||||
def cleanup(self):
|
# open valve
|
||||||
print("Cleaning up...")
|
self.anchor_tovic_pub_.publish(
|
||||||
try:
|
VicCAN(
|
||||||
if self.ser.is_open:
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
self.ser.close()
|
mcu_name="citadel",
|
||||||
except Exception as e:
|
command_id=40,
|
||||||
exit(0)
|
data=[float(valve_id)],
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
# set fan duty cycle
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(
|
||||||
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
|
mcu_name="citadel",
|
||||||
|
command_id=19,
|
||||||
|
data=[float(duty)],
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
feedback = BioVacuum.Feedback()
|
||||||
|
start = time.time()
|
||||||
|
|
||||||
|
while True:
|
||||||
|
elapsed = int((time.time() - start) * 1000)
|
||||||
|
remaining = max(0, total - elapsed)
|
||||||
|
|
||||||
|
feedback.fan_time_remaining_ms = remaining
|
||||||
|
goal_handle.publish_feedback(feedback)
|
||||||
|
|
||||||
|
if remaining == 0:
|
||||||
|
break
|
||||||
|
|
||||||
|
time.sleep(0.1)
|
||||||
|
|
||||||
|
# stop fan
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(
|
||||||
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
|
mcu_name="citadel",
|
||||||
|
command_id=19,
|
||||||
|
data=[0.0],
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
# close valve
|
||||||
|
self.anchor_tovic_pub_.publish(
|
||||||
|
VicCAN(
|
||||||
|
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||||
|
mcu_name="citadel",
|
||||||
|
command_id=40,
|
||||||
|
data=[-1.0],
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
goal_handle.succeed()
|
||||||
|
return BioVacuum.Result()
|
||||||
|
|
||||||
|
|
||||||
|
def clamp_short(x: int) -> int:
|
||||||
|
return max(-32768, min(32767, x))
|
||||||
|
|
||||||
|
|
||||||
def myexcepthook(type, value, tb):
|
def myexcepthook(type, value, tb):
|
||||||
print("Uncaught exception:", type, value)
|
print("Uncaught exception:", type, value)
|
||||||
if serial_pub:
|
|
||||||
serial_pub.cleanup()
|
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
|
|||||||
@@ -31,14 +31,14 @@ CORE_WHEEL_RADIUS = 0.171 # meters
|
|||||||
CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1
|
CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1
|
||||||
|
|
||||||
control_qos = qos.QoSProfile(
|
control_qos = qos.QoSProfile(
|
||||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
# history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||||
depth=2,
|
depth=2,
|
||||||
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
# reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||||
durability=qos.QoSDurabilityPolicy.VOLATILE,
|
# durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||||
deadline=Duration(seconds=1),
|
# deadline=Duration(seconds=1),
|
||||||
lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
# lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||||
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
# liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||||
liveliness_lease_duration=Duration(seconds=5),
|
# liveliness_lease_duration=Duration(seconds=5),
|
||||||
)
|
)
|
||||||
|
|
||||||
# Used to verify the length of an incoming VicCAN feedback message
|
# Used to verify the length of an incoming VicCAN feedback message
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
import rclpy
|
import rclpy
|
||||||
from rclpy.node import Node
|
from rclpy.node import Node
|
||||||
|
from rclpy.executors import ExternalShutdownException
|
||||||
from rclpy import qos
|
from rclpy import qos
|
||||||
from rclpy.duration import Duration
|
from rclpy.duration import Duration
|
||||||
|
|
||||||
@@ -11,6 +12,8 @@ import os
|
|||||||
import sys
|
import sys
|
||||||
import threading
|
import threading
|
||||||
import glob
|
import glob
|
||||||
|
import pwd
|
||||||
|
import grp
|
||||||
from math import copysign
|
from math import copysign
|
||||||
|
|
||||||
from std_msgs.msg import String
|
from std_msgs.msg import String
|
||||||
@@ -32,14 +35,14 @@ ARM_STOP_MSG = ArmManual() # "
|
|||||||
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,
|
||||||
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
# reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||||
durability=qos.QoSDurabilityPolicy.VOLATILE,
|
# durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||||
deadline=Duration(seconds=1),
|
# deadline=Duration(seconds=1),
|
||||||
lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
# lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||||
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
# liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||||
liveliness_lease_duration=Duration(seconds=5),
|
# liveliness_lease_duration=Duration(seconds=5),
|
||||||
)
|
)
|
||||||
|
|
||||||
CORE_MODE = "twist" # "twist" or "duty"
|
CORE_MODE = "twist" # "twist" or "duty"
|
||||||
@@ -71,9 +74,36 @@ class Headless(Node):
|
|||||||
print("No gamepad found. Waiting...")
|
print("No gamepad found. Waiting...")
|
||||||
|
|
||||||
# Initialize the gamepad
|
# Initialize the gamepad
|
||||||
self.gamepad = pygame.joystick.Joystick(0)
|
id = 0
|
||||||
self.gamepad.init()
|
while True:
|
||||||
print(f"Gamepad Found: {self.gamepad.get_name()}")
|
self.num_gamepads = pygame.joystick.get_count()
|
||||||
|
if id >= self.num_gamepads:
|
||||||
|
self.get_logger().fatal("Ran out of controllers to try")
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
try:
|
||||||
|
self.gamepad = pygame.joystick.Joystick(id)
|
||||||
|
self.gamepad.init()
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error("Error when initializing gamepad")
|
||||||
|
self.get_logger().error(e)
|
||||||
|
id += 1
|
||||||
|
continue
|
||||||
|
print(f"Gamepad Found: {self.gamepad.get_name()}")
|
||||||
|
|
||||||
|
if self.gamepad.get_numhats() == 0 or self.gamepad.get_numaxes() < 5:
|
||||||
|
self.get_logger().error("Controller not correctly initialized.")
|
||||||
|
if not is_user_in_group("input"):
|
||||||
|
self.get_logger().warning(
|
||||||
|
"If using NixOS, you may need to add yourself to the 'input' group."
|
||||||
|
)
|
||||||
|
if is_user_in_group("plugdev"):
|
||||||
|
self.get_logger().warning(
|
||||||
|
"If using NixOS, you may need to remove yourself from the 'plugdev' group."
|
||||||
|
)
|
||||||
|
else:
|
||||||
|
break
|
||||||
|
id += 1
|
||||||
|
|
||||||
self.create_timer(0.15, self.send_controls)
|
self.create_timer(0.15, self.send_controls)
|
||||||
|
|
||||||
@@ -115,7 +145,7 @@ class Headless(Node):
|
|||||||
sys.exit(0)
|
sys.exit(0)
|
||||||
|
|
||||||
# Check if controller is still connected
|
# Check if controller is still connected
|
||||||
if pygame.joystick.get_count() == 0:
|
if pygame.joystick.get_count() != self.num_gamepads:
|
||||||
print("Gamepad disconnected. Exiting...")
|
print("Gamepad disconnected. Exiting...")
|
||||||
# Send one last zero control message
|
# Send one last zero control message
|
||||||
self.core_publisher.publish(CORE_STOP_MSG)
|
self.core_publisher.publish(CORE_STOP_MSG)
|
||||||
@@ -296,11 +326,34 @@ def deadzone(value: float, threshold=0.05) -> float:
|
|||||||
return value
|
return value
|
||||||
|
|
||||||
|
|
||||||
|
def is_user_in_group(group_name: str) -> bool:
|
||||||
|
# Copied from https://zetcode.com/python/os-getgrouplist/
|
||||||
|
try:
|
||||||
|
username = os.getlogin()
|
||||||
|
|
||||||
|
# Get group ID from name
|
||||||
|
group_info = grp.getgrnam(group_name)
|
||||||
|
target_gid = group_info.gr_gid
|
||||||
|
|
||||||
|
# Get user's groups
|
||||||
|
user_info = pwd.getpwnam(username)
|
||||||
|
user_groups = os.getgrouplist(username, user_info.pw_gid)
|
||||||
|
|
||||||
|
return target_gid in user_groups
|
||||||
|
except KeyError:
|
||||||
|
return False
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
rclpy.init(args=args)
|
try:
|
||||||
node = Headless()
|
rclpy.init(args=args)
|
||||||
rclpy.spin(node)
|
|
||||||
rclpy.shutdown()
|
node = Headless()
|
||||||
|
rclpy.spin(node)
|
||||||
|
except (KeyboardInterrupt, ExternalShutdownException):
|
||||||
|
print("Caught shutdown signal. Exiting...")
|
||||||
|
finally:
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
|
|||||||
Reference in New Issue
Block a user