mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
29 Commits
67b3c5bc8f
...
main
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
8404999369 | ||
|
|
88574524cf | ||
|
|
30bb32a66b | ||
|
|
010d2da0b6 | ||
|
|
0a257abf43 | ||
|
|
b09b55bee0 | ||
|
|
ec7f272934 | ||
|
|
bc9183d59a | ||
|
|
410d3706ed | ||
|
|
89b3194914 | ||
|
|
4ef226c094 | ||
|
|
327539467c | ||
|
|
e570d371c6 | ||
|
|
f7efa604d2 | ||
|
|
fe46a2ab4d | ||
|
|
941e196316 | ||
|
|
7a3c4af1ce | ||
|
|
5e5a52438d | ||
|
|
c814f34ca6 | ||
|
|
ce39d0aeb9 | ||
|
|
9b96244a1b | ||
|
|
e588ff0a7b | ||
|
|
e83642cfe8 | ||
|
|
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
|
||||||
|
|||||||
23
flake.lock
generated
23
flake.lock
generated
@@ -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",
|
||||||
|
|||||||
11
flake.nix
11
flake.nix
@@ -4,6 +4,11 @@
|
|||||||
inputs = {
|
inputs = {
|
||||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
||||||
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
|
||||||
@@ -28,6 +34,7 @@
|
|||||||
(python313.withPackages (
|
(python313.withPackages (
|
||||||
p: with p; [
|
p: with p; [
|
||||||
pyserial
|
pyserial
|
||||||
|
python-can
|
||||||
pygame
|
pygame
|
||||||
scipy
|
scipy
|
||||||
crccheck
|
crccheck
|
||||||
@@ -83,6 +90,8 @@
|
|||||||
export QT_X11_NO_MITSHM=1
|
export QT_X11_NO_MITSHM=1
|
||||||
'';
|
'';
|
||||||
};
|
};
|
||||||
|
|
||||||
|
formatter = (inputs.treefmt-nix.lib.evalModule pkgs ./treefmt.nix).config.build.wrapper;
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
|
|
||||||
|
|||||||
@@ -1,28 +1,24 @@
|
|||||||
|
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
|
||||||
from std_srvs.srv import Empty
|
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
||||||
|
|
||||||
import signal
|
|
||||||
import time
|
|
||||||
import atexit
|
import atexit
|
||||||
|
|
||||||
import serial
|
from .connector import (
|
||||||
import serial.tools.list_ports
|
Connector,
|
||||||
import os
|
MockConnector,
|
||||||
import sys
|
SerialConnector,
|
||||||
|
CANConnector,
|
||||||
|
NoValidDeviceException,
|
||||||
|
NoWorkingDeviceException,
|
||||||
|
)
|
||||||
|
from .convert import string_to_viccan
|
||||||
import threading
|
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,308 +32,204 @@ 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 ViCAN 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(
|
||||||
|
VicCAN,
|
||||||
|
"/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(
|
||||||
|
String,
|
||||||
|
"/anchor/from_vic/mock_mcu",
|
||||||
|
self.relay_fromvic,
|
||||||
|
20,
|
||||||
|
)
|
||||||
|
self.tovic_string_sub_ = self.create_subscription(
|
||||||
|
String,
|
||||||
|
"/anchor/to_vic/relay_string",
|
||||||
|
self.connector.write_raw,
|
||||||
|
20,
|
||||||
)
|
)
|
||||||
|
|
||||||
# Create publishers
|
# Close devices on exit
|
||||||
self.arm_pub = self.create_publisher(String, "/anchor/arm/feedback", 10)
|
atexit.register(self.cleanup)
|
||||||
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)
|
|
||||||
|
|
||||||
# Create a subscriber
|
|
||||||
self.relay_sub = self.create_subscription(
|
|
||||||
String, "/anchor/relay", self.on_relay_tovic_string, 10
|
|
||||||
)
|
|
||||||
|
|
||||||
def read_MCU(self):
|
|
||||||
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
|
||||||
try:
|
|
||||||
output = str(self.serial_interface.readline(), "utf8")
|
|
||||||
|
|
||||||
if output:
|
|
||||||
self.relay_fromvic(output)
|
|
||||||
# All output over debug temporarily
|
|
||||||
# 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"]:
|
|
||||||
malformed = True
|
|
||||||
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:
|
|
||||||
self.get_logger().warning(
|
|
||||||
f"Ignoring malformed from_vic message: '{msg.strip()}'; reason: {malformed_reason}"
|
|
||||||
)
|
|
||||||
return
|
|
||||||
|
|
||||||
# Have valid VicCAN message
|
|
||||||
|
|
||||||
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):
|
def cleanup(self):
|
||||||
print("Cleaning up before terminating...")
|
self.connector.cleanup()
|
||||||
if self.serial_interface.is_open:
|
|
||||||
self.serial_interface.close()
|
def read_connector(self):
|
||||||
|
"""Check the connector for new data from the MCU, and publish string to appropriate topics"""
|
||||||
|
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(msg)
|
||||||
|
|
||||||
|
@deprecated(
|
||||||
|
"Use /anchor/to_vic/relay or /anchor/to_vic/relay_string instead of /anchor/relay"
|
||||||
|
)
|
||||||
|
def write_connector_legacy(self, msg: String):
|
||||||
|
"""Write to the connector by first attempting to convert String to VicCAN"""
|
||||||
|
# please do not reference this code. ~riley
|
||||||
|
for cmd in msg.data.split("\n"):
|
||||||
|
viccan = string_to_viccan(
|
||||||
|
cmd,
|
||||||
|
"anchor",
|
||||||
|
self.get_logger(),
|
||||||
|
self.get_clock().now().to_msg(),
|
||||||
|
)
|
||||||
|
if viccan:
|
||||||
|
self.write_connector(viccan)
|
||||||
|
|
||||||
|
def relay_fromvic(self, msg: VicCAN):
|
||||||
|
"""Relay a message from the MCU to the appropriate VicCAN topic"""
|
||||||
|
if msg.mcu_name == "core":
|
||||||
|
self.fromvic_core_pub_.publish(msg)
|
||||||
|
elif msg.mcu_name == "arm" or msg.mcu_name == "digit":
|
||||||
|
self.fromvic_arm_pub_.publish(msg)
|
||||||
|
elif msg.mcu_name == "citadel" or msg.mcu_name == "digit":
|
||||||
|
self.fromvic_bio_pub_.publish(msg)
|
||||||
|
|
||||||
|
|
||||||
def main(args=None):
|
def main(args=None):
|
||||||
@@ -350,16 +242,9 @@ def main(args=None):
|
|||||||
|
|
||||||
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
||||||
while rclpy.ok():
|
while rclpy.ok():
|
||||||
anchor_node.read_MCU() # Check the MCU for updates
|
anchor_node.read_connector() # Check the connector for updates
|
||||||
rate.sleep()
|
rate.sleep()
|
||||||
except (KeyboardInterrupt, ExternalShutdownException):
|
except (KeyboardInterrupt, ExternalShutdownException):
|
||||||
print("Caught shutdown signal, shutting down...")
|
print("Caught shutdown signal, shutting down...")
|
||||||
finally:
|
finally:
|
||||||
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()
|
|
||||||
|
|||||||
438
src/anchor_pkg/anchor_pkg/connector.py
Normal file
438
src/anchor_pkg/anchor_pkg/connector.py
Normal file
@@ -0,0 +1,438 @@
|
|||||||
|
from abc import ABC, abstractmethod
|
||||||
|
from astra_msgs.msg import VicCAN
|
||||||
|
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: str):
|
||||||
|
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(viccan_to_string(msg))
|
||||||
|
|
||||||
|
def write_raw(self, msg: str):
|
||||||
|
self.serial_interface.write(bytes(msg, "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: str):
|
||||||
|
self.logger.warn(f"write_raw is not supported for CANConnector. msg: {msg}")
|
||||||
|
|
||||||
|
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: str):
|
||||||
|
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>
|
||||||
|
|
||||||
|
|||||||
@@ -115,8 +115,8 @@ 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.man_jointjog_pub_ = self.create_subscription(
|
self.man_jointjog_sub_ = self.create_subscription(
|
||||||
JointJog,
|
JointJog,
|
||||||
"/arm/manual/joint_jog",
|
"/arm/manual/joint_jog",
|
||||||
self.jointjog_callback,
|
self.jointjog_callback,
|
||||||
|
|||||||
@@ -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."""
|
||||||
|
|||||||
8
treefmt.nix
Normal file
8
treefmt.nix
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
{ pkgs, ... }:
|
||||||
|
{
|
||||||
|
projectRootFile = "flake.nix";
|
||||||
|
programs = {
|
||||||
|
nixfmt.enable = true;
|
||||||
|
black.enable = true;
|
||||||
|
};
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user