mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
41 Commits
ea36ce6ef4
...
core-ros2-
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
90a9519b55 | ||
|
|
ab4f998ac1 | ||
|
|
b3f996113c | ||
|
|
191c9d613d | ||
|
|
5e0946e8d7 | ||
|
|
3dd80bbd29 | ||
|
|
e53c1f32c9 | ||
|
|
d0f6ecf702 | ||
|
|
8404999369 | ||
|
|
88574524cf | ||
|
|
30bb32a66b | ||
|
|
010d2da0b6 | ||
|
|
0a257abf43 | ||
|
|
b09b55bee0 | ||
|
|
ec7f272934 | ||
|
|
bc9183d59a | ||
|
|
410d3706ed | ||
|
|
89b3194914 | ||
|
|
4ef226c094 | ||
|
|
327539467c | ||
|
|
e570d371c6 | ||
|
|
2213896494 | ||
|
|
c42cd39fda | ||
|
|
f1c84c3cc5 | ||
|
|
cf699da0c6 | ||
|
|
7669ded344 | ||
|
|
ec12a083f1 | ||
|
|
f7efa604d2 | ||
|
|
fe46a2ab4d | ||
|
|
941e196316 | ||
|
|
7a3c4af1ce | ||
|
|
5e5a52438d | ||
|
|
c814f34ca6 | ||
|
|
ce39d0aeb9 | ||
|
|
9b96244a1b | ||
|
|
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.
|
||||
```
|
||||
|
||||
### 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
|
||||
|
||||
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
|
||||
```
|
||||
|
||||
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
|
||||
$ 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
|
||||
|
||||
23
flake.lock
generated
23
flake.lock
generated
@@ -60,7 +60,8 @@
|
||||
"nixpkgs": [
|
||||
"nix-ros-overlay",
|
||||
"nixpkgs"
|
||||
]
|
||||
],
|
||||
"treefmt-nix": "treefmt-nix"
|
||||
}
|
||||
},
|
||||
"systems": {
|
||||
@@ -77,6 +78,26 @@
|
||||
"repo": "default",
|
||||
"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",
|
||||
|
||||
15
flake.nix
15
flake.nix
@@ -4,6 +4,11 @@
|
||||
inputs = {
|
||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
||||
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
||||
|
||||
treefmt-nix = {
|
||||
url = "github:numtide/treefmt-nix";
|
||||
inputs.nixpkgs.follows = "nixpkgs";
|
||||
};
|
||||
};
|
||||
|
||||
outputs =
|
||||
@@ -11,7 +16,8 @@
|
||||
self,
|
||||
nix-ros-overlay,
|
||||
nixpkgs,
|
||||
}:
|
||||
...
|
||||
}@inputs:
|
||||
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
|
||||
system:
|
||||
let
|
||||
@@ -28,6 +34,7 @@
|
||||
(python313.withPackages (
|
||||
p: with p; [
|
||||
pyserial
|
||||
python-can
|
||||
pygame
|
||||
scipy
|
||||
crccheck
|
||||
@@ -61,7 +68,7 @@
|
||||
moveit-msgs
|
||||
moveit-ros-planning
|
||||
moveit-ros-planning-interface
|
||||
moveit-ros-visualization
|
||||
moveit-ros-visualization
|
||||
moveit-configs-utils
|
||||
moveit-ros-move-group
|
||||
moveit-servo
|
||||
@@ -72,7 +79,7 @@
|
||||
ompl
|
||||
joy
|
||||
ros2-controllers
|
||||
chomp-motion-planner
|
||||
chomp-motion-planner
|
||||
];
|
||||
}
|
||||
)
|
||||
@@ -83,6 +90,8 @@
|
||||
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
|
||||
from rclpy.node import Node
|
||||
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 serial
|
||||
import serial.tools.list_ports
|
||||
import os
|
||||
import sys
|
||||
from .connector import (
|
||||
Connector,
|
||||
MockConnector,
|
||||
SerialConnector,
|
||||
CANConnector,
|
||||
NoValidDeviceException,
|
||||
NoWorkingDeviceException,
|
||||
)
|
||||
from .convert import string_to_viccan
|
||||
import threading
|
||||
import glob
|
||||
|
||||
from std_msgs.msg import String, Header
|
||||
from astra_msgs.msg import VicCAN
|
||||
|
||||
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
|
||||
]
|
||||
from std_msgs.msg import String
|
||||
|
||||
|
||||
class Anchor(Node):
|
||||
@@ -36,308 +32,204 @@ class Anchor(Node):
|
||||
- VicCAN messages for Arm node
|
||||
* /anchor/from_vic/bio
|
||||
- VicCAN messages for Bio node
|
||||
* /anchor/to_vic/debug
|
||||
- A string copy of the messages published to ./relay are published here
|
||||
|
||||
Subscribers:
|
||||
* /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
|
||||
- Core, Arm, and Bio publish VicCAN messages to this topic to send to the MCU
|
||||
* /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):
|
||||
# Initalize node with name
|
||||
super().__init__("anchor_node") # previously 'serial_publisher'
|
||||
super().__init__("anchor_node")
|
||||
|
||||
self.serial_port: str | None = None # e.g., "/dev/ttyUSB0"
|
||||
logger = self.get_logger()
|
||||
|
||||
# Serial port override
|
||||
if port_override := os.getenv("PORT_OVERRIDE"):
|
||||
self.serial_port = port_override
|
||||
# ROS2 Parameter Setup
|
||||
|
||||
##################################################
|
||||
# Serial MCU Discovery
|
||||
self.declare_parameter(
|
||||
"connector",
|
||||
"auto",
|
||||
ParameterDescriptor(
|
||||
name="connector",
|
||||
description="Declares which MCU connector should be used. Defaults to 'auto'.",
|
||||
type=ParameterType.PARAMETER_STRING,
|
||||
additional_constraints="Must be 'serial', 'can', 'mock', or 'auto'.",
|
||||
),
|
||||
)
|
||||
|
||||
# If there was not a port override, look for a MCU over USB for Serial.
|
||||
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,
|
||||
self.declare_parameter(
|
||||
"can_override",
|
||||
"",
|
||||
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.declare_parameter(
|
||||
"serial_override",
|
||||
"",
|
||||
ParameterDescriptor(
|
||||
name="serial_override",
|
||||
description="Overrides which serial port will be used. Defaults to ''.",
|
||||
type=ParameterType.PARAMETER_STRING,
|
||||
additional_constraints="Must be a valid path to a serial device file that shows up in `ls /dev/tty*`.",
|
||||
),
|
||||
)
|
||||
|
||||
# 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
|
||||
)
|
||||
)
|
||||
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}."
|
||||
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:
|
||||
logger.info("trying CAN connector")
|
||||
self.connector = CANConnector(
|
||||
logger, self.get_clock(), can_override
|
||||
)
|
||||
except (NoValidDeviceException, NoWorkingDeviceException, TypeError):
|
||||
logger.info("CAN connector failed, trying serial connector")
|
||||
self.connector = SerialConnector(
|
||||
logger, self.get_clock(), serial_override
|
||||
)
|
||||
case _:
|
||||
logger.fatal(
|
||||
f"invalid value for connector parameter: {connector_select}"
|
||||
)
|
||||
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()
|
||||
exit(1)
|
||||
|
||||
# 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)
|
||||
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
|
||||
)
|
||||
|
||||
# Attempt to get name of connected MCU
|
||||
self.serial_interface.write(
|
||||
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)
|
||||
|
||||
##################################################
|
||||
# ROS2 Topic Setup
|
||||
|
||||
# New pub/sub with VicCAN
|
||||
self.fromvic_debug_pub_ = self.create_publisher(
|
||||
String, "/anchor/from_vic/debug", 20
|
||||
# Publishers
|
||||
self.fromvic_debug_pub_ = self.create_publisher( # only used by serial
|
||||
String,
|
||||
"/anchor/from_vic/debug",
|
||||
20,
|
||||
)
|
||||
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(
|
||||
VicCAN, "/anchor/from_vic/arm", 20
|
||||
VicCAN,
|
||||
"/anchor/from_vic/arm",
|
||||
20,
|
||||
)
|
||||
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(
|
||||
String, "/anchor/from_vic/mock_mcu", self.on_mock_fromvic, 20
|
||||
)
|
||||
# Subscribers
|
||||
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(
|
||||
String, "/anchor/to_vic/relay_string", self.on_relay_tovic_string, 20
|
||||
self.tovic_sub_legacy_ = self.create_subscription(
|
||||
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
|
||||
self.arm_pub = self.create_publisher(String, "/anchor/arm/feedback", 10)
|
||||
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*")
|
||||
# Close devices on exit
|
||||
atexit.register(self.cleanup)
|
||||
|
||||
def cleanup(self):
|
||||
print("Cleaning up before terminating...")
|
||||
if self.serial_interface.is_open:
|
||||
self.serial_interface.close()
|
||||
self.connector.cleanup()
|
||||
|
||||
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):
|
||||
@@ -350,16 +242,9 @@ def main(args=None):
|
||||
|
||||
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
||||
while rclpy.ok():
|
||||
anchor_node.read_MCU() # Check the MCU for updates
|
||||
anchor_node.read_connector() # Check the connector for updates
|
||||
rate.sleep()
|
||||
except (KeyboardInterrupt, ExternalShutdownException):
|
||||
print("Caught shutdown signal, shutting down...")
|
||||
finally:
|
||||
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,190 +1,174 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
OpaqueFunction,
|
||||
Shutdown,
|
||||
IncludeLaunchDescription,
|
||||
)
|
||||
from launch.substitutions import (
|
||||
LaunchConfiguration,
|
||||
ThisLaunchFileDir,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.actions import DeclareLaunchArgument, Shutdown, IncludeLaunchDescription
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
# Prevent making __pycache__ directories
|
||||
from sys import dont_write_bytecode
|
||||
|
||||
dont_write_bytecode = True
|
||||
|
||||
|
||||
def launch_setup(context, *args, **kwargs):
|
||||
# Retrieve the resolved value of the launch argument 'mode'
|
||||
mode = LaunchConfiguration("mode").perform(context)
|
||||
nodes = []
|
||||
|
||||
if mode == "anchor":
|
||||
# Launch every node and pass "anchor" as the parameter
|
||||
|
||||
nodes.append(
|
||||
Node(
|
||||
package="arm_pkg",
|
||||
executable="arm", # change as needed
|
||||
name="arm",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
nodes.append(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core", # change as needed
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[
|
||||
{"launch_mode": mode},
|
||||
{"use_ros2_control": LaunchConfiguration("use_ros2_control", default=False)},
|
||||
],
|
||||
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(
|
||||
package="arm_pkg",
|
||||
executable="arm",
|
||||
name="arm",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "core":
|
||||
nodes.append(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core",
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "bio":
|
||||
nodes.append(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
executable="bio",
|
||||
name="bio",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
elif mode == "ptz":
|
||||
nodes.append(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="ptz",
|
||||
name="ptz",
|
||||
output="both",
|
||||
on_exit=Shutdown(), # on fail, shutdown if this was the only node to be launched
|
||||
)
|
||||
)
|
||||
else:
|
||||
# If an invalid mode is provided, print an error.
|
||||
print("Invalid mode provided. Choose one of: arm, core, bio, anchor, ptz.")
|
||||
|
||||
return nodes
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
declare_arg = DeclareLaunchArgument(
|
||||
"mode",
|
||||
default_value="anchor",
|
||||
description="Launch mode: arm, core, bio, anchor, or ptz",
|
||||
connector = LaunchConfiguration("connector")
|
||||
serial_override = LaunchConfiguration("serial_override")
|
||||
can_override = LaunchConfiguration("can_override")
|
||||
use_ptz = LaunchConfiguration("use_ptz")
|
||||
|
||||
ld = LaunchDescription()
|
||||
|
||||
# arguments
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"connector",
|
||||
default_value="auto",
|
||||
description="Connector parameter for anchor node (default: 'auto')",
|
||||
)
|
||||
)
|
||||
|
||||
ros2_control_arg = DeclareLaunchArgument(
|
||||
"use_ros2_control",
|
||||
default_value="false",
|
||||
description="Whether to use DiffDriveController for driving instead of direct Twist",
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"serial_override",
|
||||
default_value="",
|
||||
description="Serial port override parameter for anchor node (default: '')",
|
||||
)
|
||||
)
|
||||
|
||||
rsp = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"robot_state_publisher.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"can_override",
|
||||
default_value="",
|
||||
description="CAN network override parameter for anchor node (default: '')",
|
||||
)
|
||||
)
|
||||
|
||||
controllers = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"spawn_controllers.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"use_ptz",
|
||||
default_value="true", # must be string for launch system
|
||||
description="Whether to launch PTZ node (default: true)",
|
||||
)
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
declare_arg,
|
||||
ros2_control_arg,
|
||||
rsp,
|
||||
controllers,
|
||||
OpaqueFunction(function=launch_setup),
|
||||
]
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"use_ros2_control",
|
||||
default_value="false",
|
||||
description="Whether to use DiffDriveController for driving instead of direct Twist",
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"rover_platform_override",
|
||||
default_value="",
|
||||
description="Override the rover platform (either clucky or testbed). If unset, hostname is used; defaults to clucky without hostname.",
|
||||
choices=["clucky", "testbed", ""],
|
||||
)
|
||||
)
|
||||
|
||||
# nodes
|
||||
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(),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="arm_pkg",
|
||||
executable="arm",
|
||||
name="arm",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
executable="bio",
|
||||
name="bio",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core",
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[
|
||||
{"launch_mode": "anchor"},
|
||||
{
|
||||
"use_ros2_control": LaunchConfiguration(
|
||||
"use_ros2_control", default=False
|
||||
)
|
||||
},
|
||||
{
|
||||
"rover_platform_override": LaunchConfiguration(
|
||||
"rover_platform_override", default="auto"
|
||||
)
|
||||
},
|
||||
],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="ptz",
|
||||
name="ptz",
|
||||
output="both",
|
||||
condition=IfCondition(use_ptz),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"robot_state_publisher.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"spawn_controllers.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
)
|
||||
)
|
||||
|
||||
return ld
|
||||
|
||||
@@ -2,15 +2,16 @@
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>anchor_pkg</name>
|
||||
<version>1.0.0</version>
|
||||
<version>0.0.0</version>
|
||||
<description>ASTRA VicCAN driver package, using python-can and pyserial.</description>
|
||||
<maintainer email="tristanmcginnis26@gmail.com">tristan</maintainer>
|
||||
<maintainer email="rjm0037@uah.edu">Riley</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
|
||||
<exec_depend>common_interfaces</exec_depend>
|
||||
<exec_depend>python3-serial</exec_depend>
|
||||
<exec_depend>python3-can</exec_depend>
|
||||
|
||||
<exec_depend>core_pkg</exec_depend>
|
||||
<exec_depend>arm_pkg</exec_depend>
|
||||
|
||||
@@ -12,7 +12,7 @@ from std_msgs.msg import String, Header
|
||||
from sensor_msgs.msg import JointState
|
||||
from control_msgs.msg import JointJog
|
||||
from astra_msgs.msg import SocketFeedback, DigitFeedback, ArmManual # TODO: Old topics
|
||||
from astra_msgs.msg import ArmFeedback, VicCAN, RevMotorState
|
||||
from astra_msgs.msg import ArmFeedback, ArmCtrlState, VicCAN, RevMotorState
|
||||
|
||||
control_qos = qos.QoSProfile(
|
||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
@@ -112,10 +112,10 @@ class ArmNode(Node):
|
||||
|
||||
# Control
|
||||
|
||||
# Manual: /arm/manual/joint_jog is published by Basestation or Headless
|
||||
# Manual: /arm/control/joint_jog is published by Basestation or Headless
|
||||
self.man_jointjog_sub_ = self.create_subscription(
|
||||
JointJog,
|
||||
"/arm/manual/joint_jog",
|
||||
"/arm/control/joint_jog",
|
||||
self.jointjog_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
@@ -126,6 +126,13 @@ class ArmNode(Node):
|
||||
self.joint_command_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
# State: /arm/control/state is published by Basestation or Headless
|
||||
self.man_state_sub_ = self.create_subscription(
|
||||
ArmCtrlState,
|
||||
"/arm/control/state",
|
||||
self.man_state_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
|
||||
# Feedback
|
||||
|
||||
@@ -145,9 +152,14 @@ class ArmNode(Node):
|
||||
|
||||
# Combined Socket and Digit feedback
|
||||
self.arm_feedback_new = ArmFeedback()
|
||||
self.arm_feedback_new.axis0_motor.id = 1
|
||||
self.arm_feedback_new.axis1_motor.id = 2
|
||||
self.arm_feedback_new.axis2_motor.id = 3
|
||||
self.arm_feedback_new.axis3_motor.id = 4
|
||||
|
||||
# IK Arm pose
|
||||
self.saved_joint_state = JointState()
|
||||
self.saved_joint_state.header.frame_id = "base_link"
|
||||
self.saved_joint_state.name = self.all_joint_names
|
||||
# ... initialize with zeros
|
||||
self.saved_joint_state.position = [0.0] * len(self.saved_joint_state.name)
|
||||
@@ -170,10 +182,54 @@ class ArmNode(Node):
|
||||
# Deadzone
|
||||
velocities = [vel if abs(vel) > 0.05 else 0.0 for vel in velocities]
|
||||
|
||||
self.send_velocities(velocities, msg.header)
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(
|
||||
mcu_name="arm",
|
||||
command_id=39,
|
||||
data=velocities[0:4],
|
||||
header=msg.header,
|
||||
)
|
||||
)
|
||||
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(
|
||||
mcu_name="digit",
|
||||
command_id=39,
|
||||
data=velocities[4:6],
|
||||
header=msg.header,
|
||||
)
|
||||
)
|
||||
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(
|
||||
mcu_name="digit",
|
||||
command_id=26,
|
||||
data=[velocities[6]],
|
||||
header=msg.header,
|
||||
)
|
||||
)
|
||||
|
||||
# TODO: use msg.duration
|
||||
|
||||
def man_state_callback(self, msg: ArmCtrlState):
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(
|
||||
mcu_name="arm",
|
||||
command_id=18,
|
||||
data=[1.0 if msg.brake_mode else 0.0],
|
||||
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||
)
|
||||
)
|
||||
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(
|
||||
mcu_name="arm",
|
||||
command_id=34,
|
||||
data=[1.0 if msg.laser else 0.0],
|
||||
header=Header(stamp=self.get_clock().now().to_msg()),
|
||||
)
|
||||
)
|
||||
|
||||
def joint_command_callback(self, msg: JointState):
|
||||
if len(msg.position) < 7 and len(msg.velocity) < 7:
|
||||
self.get_logger().debug("Ignoring malformed /joint_command message.")
|
||||
@@ -199,12 +255,12 @@ class ArmNode(Node):
|
||||
|
||||
# Send Axis 0-3
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(mcu_name="arm", command_id=43, data=velocities[0:3], header=header)
|
||||
VicCAN(mcu_name="arm", command_id=43, data=velocities[0:4], header=header)
|
||||
)
|
||||
# Send Wrist yaw and roll
|
||||
# TODO: Verify embedded
|
||||
self.anchor_tovic_pub_.publish(
|
||||
VicCAN(mcu_name="digit", command_id=43, data=velocities[4:5], header=header)
|
||||
VicCAN(mcu_name="digit", command_id=43, data=velocities[4:6], header=header)
|
||||
)
|
||||
# Send End Effector Gripper
|
||||
# TODO: Verify m/s received correctly by embedded
|
||||
@@ -287,6 +343,8 @@ class ArmNode(Node):
|
||||
)
|
||||
return
|
||||
|
||||
self.arm_feedback_new.header.stamp = msg.header.stamp
|
||||
|
||||
match msg.command_id:
|
||||
case 53: # REV SPARK MAX feedback
|
||||
motorId = round(msg.data[0])
|
||||
@@ -373,11 +431,14 @@ class ArmNode(Node):
|
||||
)
|
||||
return
|
||||
|
||||
self.arm_feedback_new.header.stamp = msg.header.stamp
|
||||
|
||||
match msg.command_id:
|
||||
case 54: # Board voltages
|
||||
self.arm_feedback_new.digit_voltage.vbatt = float(msg.data[0]) / 100.0
|
||||
self.arm_feedback_new.digit_voltage.v12 = float(msg.data[1]) / 100.0
|
||||
self.arm_feedback_new.digit_voltage.v5 = float(msg.data[2]) / 100.0
|
||||
self.arm_feedback_new.digit_voltage.header.stamp = msg.header.stamp
|
||||
case 55: # Arm joint positions
|
||||
self.saved_joint_state.position[4] = math.radians(
|
||||
msg.data[0]
|
||||
|
||||
Submodule src/astra_descriptions updated: 04c2061443...e9dd878727
Submodule src/astra_msgs updated: 93dc0e0919...5a20f3f569
@@ -1,8 +1,11 @@
|
||||
import sys
|
||||
import signal
|
||||
from typing import Literal, cast
|
||||
from scipy.spatial.transform import Rotation
|
||||
from math import copysign, pi
|
||||
from warnings import deprecated
|
||||
from os import getenv
|
||||
from socket import gethostname
|
||||
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
@@ -19,7 +22,12 @@ from astra_msgs.msg import VicCAN, NewCoreFeedback, Barometer, CoreCtrlState
|
||||
|
||||
CORE_WHEELBASE = 0.836 # meters
|
||||
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
|
||||
|
||||
# TODO: update core_description or add testbed_description
|
||||
TESTBED_WHEELBASE = 0.368 # meters
|
||||
TESTBED_WHEEL_RADIUS = 0.108 # meters
|
||||
TESTBED_GEAR_RATIO = 64 # Testbed: 64:1
|
||||
|
||||
control_qos = qos.QoSProfile(
|
||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
@@ -49,6 +57,7 @@ class CoreNode(Node):
|
||||
56: 4, # really 3, but viccan
|
||||
58: 4, # ditto
|
||||
}
|
||||
rover_platform: Literal["clucky", "testbed"]
|
||||
|
||||
def __init__(self):
|
||||
super().__init__("core_node")
|
||||
@@ -63,6 +72,40 @@ class CoreNode(Node):
|
||||
self.get_parameter("use_ros2_control").get_parameter_value().bool_value
|
||||
)
|
||||
|
||||
self.declare_parameter("rover_platform_override", "")
|
||||
rover_platform = (
|
||||
self.get_parameter("rover_platform_override")
|
||||
.get_parameter_value()
|
||||
.string_value
|
||||
)
|
||||
# Verify rover_platform_override value is valid
|
||||
if rover_platform not in ("clucky", "testbed", ""):
|
||||
# Keeping this here, because I want a value error only if the user manually
|
||||
# overrides using a bad value. If we can't determine it automatically
|
||||
# from hostname, then default to clucky.
|
||||
self.get_logger().fatal(
|
||||
"Invalid rover_platform_override parameter value. If set, must be 'clucky' or 'testbed'."
|
||||
)
|
||||
# Attempt to determine platform from hostname, default to clucky on failure
|
||||
rover_platform = rover_platform or gethostname().lower()
|
||||
if rover_platform not in ("clucky", "testbed"):
|
||||
self.get_logger().info(
|
||||
"rover_platform defaulting to clucky, not overridden and could not determine from hostname."
|
||||
)
|
||||
rover_platform = "clucky"
|
||||
self.rover_platform = cast(Literal["clucky", "testbed"], rover_platform)
|
||||
|
||||
if self.rover_platform == "testbed":
|
||||
global TESTBED_WHEELBASE, TESTBED_WHEEL_RADIUS, TESTBED_GEAR_RATIO
|
||||
self.wheelbase = TESTBED_WHEELBASE
|
||||
self.wheel_radius = TESTBED_WHEEL_RADIUS
|
||||
self.gear_ratio = TESTBED_GEAR_RATIO
|
||||
else: # default in case of unset or invalid environment variable
|
||||
global CORE_WHEELBASE, CORE_WHEEL_RADIUS, CORE_GEAR_RATIO
|
||||
self.wheelbase = CORE_WHEELBASE
|
||||
self.wheel_radius = CORE_WHEEL_RADIUS
|
||||
self.gear_ratio = CORE_GEAR_RATIO
|
||||
|
||||
##################################################
|
||||
# Old Topics
|
||||
|
||||
@@ -80,9 +123,7 @@ class CoreNode(Node):
|
||||
self.feedback_pub = self.create_publisher(CoreFeedback, "/core/feedback", 10)
|
||||
self.core_feedback = CoreFeedback()
|
||||
|
||||
self.telemetry_pub_timer = self.create_timer(
|
||||
1.0, self.publish_feedback
|
||||
)
|
||||
self.telemetry_pub_timer = self.create_timer(1.0, self.publish_feedback)
|
||||
|
||||
##################################################
|
||||
# New Topics
|
||||
@@ -104,10 +145,6 @@ class CoreNode(Node):
|
||||
JointState, "/core/joint_commands", self.joint_command_callback, 2
|
||||
)
|
||||
else:
|
||||
# autonomy twist -- m/s and rad/s -- for autonomy, in particular Nav2
|
||||
self.cmd_vel_sub_ = self.create_subscription(
|
||||
TwistStamped, "/cmd_vel", self.cmd_vel_callback, 1
|
||||
)
|
||||
# manual twist -- [-1, 1] rather than real units
|
||||
# TODO: change topic to '/core/control/twist'
|
||||
self.twist_man_sub_ = self.create_subscription(
|
||||
@@ -152,9 +189,19 @@ class CoreNode(Node):
|
||||
Barometer, "/core/feedback/baro", qos_profile=qos.qos_profile_sensor_data
|
||||
)
|
||||
|
||||
###################################################
|
||||
# Timers
|
||||
|
||||
if self.use_ros2_control:
|
||||
self.vel_cmd_timer_ = self.create_timer(0.1, self.vel_cmd_timer_callback)
|
||||
|
||||
###################################################
|
||||
# Saved state
|
||||
|
||||
# Controls
|
||||
self._last_joint_command_time = self.get_clock().now()
|
||||
self._last_joint_command_msg = JointState()
|
||||
|
||||
# Main Core feedback
|
||||
self.feedback_new_state = NewCoreFeedback()
|
||||
self.feedback_new_state.fl_motor.id = 1
|
||||
@@ -226,13 +273,16 @@ class CoreNode(Node):
|
||||
# are included in msg.name, but ig it is implied that msg.velocity only
|
||||
# includes velocities for the commanded joints (ros__parameters.joints).
|
||||
# So, this will be much more hacky and less adaptable than I would like it to be.
|
||||
if len(msg.name) != 5 or len(msg.velocity) != 4 or len(msg.position) != 0:
|
||||
if (
|
||||
len(msg.name) != (4 if self.rover_platform == "testbed" else 5)
|
||||
or len(msg.velocity) != 4
|
||||
or len(msg.position) != 0
|
||||
):
|
||||
self.get_logger().warning(
|
||||
f"Received joint control message with unexpected number of joints. Ignoring."
|
||||
)
|
||||
return
|
||||
if msg.name != [
|
||||
"left_suspension_joint",
|
||||
if msg.name[-4:] != [ # type: ignore
|
||||
"bl_wheel_joint",
|
||||
"br_wheel_joint",
|
||||
"fl_wheel_joint",
|
||||
@@ -243,28 +293,31 @@ class CoreNode(Node):
|
||||
)
|
||||
return
|
||||
|
||||
(bl_vel, br_vel, fl_vel, fr_vel) = msg.velocity
|
||||
# A 10 Hz timer callback actually sends these commands to Core for rate limiting
|
||||
# These come from ros2_control at 50 Hz
|
||||
self._last_joint_command_time = self.get_clock().now()
|
||||
self._last_joint_command_msg = msg
|
||||
|
||||
bl_rpm = radps_to_rpm(bl_vel) * CORE_GEAR_RATIO
|
||||
br_rpm = radps_to_rpm(br_vel) * CORE_GEAR_RATIO
|
||||
fl_rpm = radps_to_rpm(fl_vel) * CORE_GEAR_RATIO
|
||||
fr_rpm = radps_to_rpm(fr_vel) * CORE_GEAR_RATIO
|
||||
def vel_cmd_timer_callback(self):
|
||||
# Safety timeout for diff_drive_controller commands via topic_based_ros2_control.
|
||||
# It is safe to send stop command here because if self.use_ros2_control,
|
||||
# then this is the only callback that is controlling Core's motors.
|
||||
if self.get_clock().now() - self._last_joint_command_time > Duration(
|
||||
nanoseconds=int(1e8) # 100ms
|
||||
):
|
||||
self.send_viccan(20, [0.0, 0.0, 0.0, 0.0])
|
||||
return
|
||||
|
||||
self.send_viccan(
|
||||
20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]
|
||||
) # order expected by embedded
|
||||
# This order is verified by the subscription callback
|
||||
(bl_vel, br_vel, fl_vel, fr_vel) = self._last_joint_command_msg.velocity
|
||||
|
||||
def cmd_vel_callback(self, msg: TwistStamped):
|
||||
linear = msg.twist.linear.x
|
||||
angular = -msg.twist.angular.z
|
||||
# Convert wheel rad/s to motor RPM
|
||||
bl_rpm = radps_to_rpm(bl_vel) * self.gear_ratio
|
||||
br_rpm = radps_to_rpm(br_vel) * self.gear_ratio
|
||||
fl_rpm = radps_to_rpm(fl_vel) * self.gear_ratio
|
||||
fr_rpm = radps_to_rpm(fr_vel) * self.gear_ratio
|
||||
|
||||
vel_left_rads = (linear - (angular * CORE_WHEELBASE / 2)) / CORE_WHEEL_RADIUS
|
||||
vel_right_rads = (linear + (angular * CORE_WHEELBASE / 2)) / CORE_WHEEL_RADIUS
|
||||
|
||||
vel_left_rpm = round((vel_left_rads * 60) / (2 * 3.14159)) * CORE_GEAR_RATIO
|
||||
vel_right_rpm = round((vel_right_rads * 60) / (2 * 3.14159)) * CORE_GEAR_RATIO
|
||||
|
||||
self.send_viccan(20, [vel_left_rpm, vel_right_rpm])
|
||||
self.send_viccan(20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]) # REV Velocity
|
||||
|
||||
def twist_man_callback(self, msg: Twist):
|
||||
linear = msg.linear.x # [-1 1] for forward/back from left stick y
|
||||
@@ -483,14 +536,12 @@ class CoreNode(Node):
|
||||
motorId = round(float(msg.data[0]))
|
||||
position = float(msg.data[1])
|
||||
velocity = float(msg.data[2])
|
||||
joint_state_msg = (
|
||||
JointState()
|
||||
)
|
||||
joint_state_msg = JointState()
|
||||
joint_state_msg.position = [
|
||||
position * (2 * pi) / CORE_GEAR_RATIO
|
||||
position * (2 * pi) / self.gear_ratio
|
||||
] # revolutions to radians
|
||||
joint_state_msg.velocity = [
|
||||
velocity * (2 * pi / 60.0) / CORE_GEAR_RATIO
|
||||
velocity * (2 * pi / 60.0) / self.gear_ratio
|
||||
] # RPM to rad/s
|
||||
|
||||
motor: RevMotorState | None = None
|
||||
@@ -513,15 +564,16 @@ class CoreNode(Node):
|
||||
f"Ignoring REV motor feedback 58 with invalid motorId {motorId}"
|
||||
)
|
||||
return
|
||||
|
||||
|
||||
if motor:
|
||||
motor.position = position
|
||||
motor.velocity = velocity
|
||||
|
||||
# make the fucking shit work
|
||||
joint_state_msg.name.append("left_suspension_joint")
|
||||
joint_state_msg.position.append(0.0)
|
||||
joint_state_msg.velocity.append(0.0)
|
||||
if self.rover_platform == "clucky":
|
||||
joint_state_msg.name.append("left_suspension_joint")
|
||||
joint_state_msg.position.append(0.0)
|
||||
joint_state_msg.velocity.append(0.0)
|
||||
|
||||
joint_state_msg.header.stamp = msg.header.stamp
|
||||
self.joint_state_pub_.publish(joint_state_msg)
|
||||
|
||||
@@ -262,7 +262,7 @@ class PtzNode(Node):
|
||||
f"[{self.get_clock().now().nanoseconds / 1e9:.2f}] PTZ Node: {message_text}"
|
||||
)
|
||||
self.debug_pub.publish(msg)
|
||||
self.get_logger().info(message_text)
|
||||
self.get_logger().debug(message_text)
|
||||
|
||||
def run_async_func(self, coro):
|
||||
"""Run an async function in the event loop."""
|
||||
|
||||
@@ -18,7 +18,7 @@ from std_msgs.msg import Header
|
||||
from geometry_msgs.msg import Twist, TwistStamped
|
||||
from control_msgs.msg import JointJog
|
||||
from astra_msgs.msg import CoreControl, ArmManual, BioControl
|
||||
from astra_msgs.msg import CoreCtrlState
|
||||
from astra_msgs.msg import CoreCtrlState, ArmCtrlState
|
||||
|
||||
import warnings
|
||||
|
||||
@@ -177,6 +177,8 @@ class Headless(Node):
|
||||
self.ctrl_mode = "core" # Start in core mode
|
||||
self.core_brake_mode = False
|
||||
self.core_max_duty = 0.5 # Default max duty cycle (walking speed)
|
||||
self.arm_brake_mode = False
|
||||
self.arm_laser = False
|
||||
|
||||
##################################################
|
||||
# Old Topics
|
||||
@@ -203,7 +205,10 @@ class Headless(Node):
|
||||
)
|
||||
|
||||
self.arm_manual_pub_ = self.create_publisher(
|
||||
JointJog, "/arm/manual_new", qos_profile=control_qos
|
||||
JointJog, "/arm/control/joint_jog", qos_profile=control_qos
|
||||
)
|
||||
self.arm_state_pub_ = self.create_publisher(
|
||||
ArmCtrlState, "/arm/control/state", qos_profile=control_qos
|
||||
)
|
||||
|
||||
self.arm_ik_twist_publisher = self.create_publisher(
|
||||
@@ -361,10 +366,14 @@ class Headless(Node):
|
||||
) # Exponent for finer control (curve)
|
||||
|
||||
# This kinda looks dumb being seperate from the following block, but this
|
||||
# maintains the separation between modifying the control message and sending it
|
||||
# maintains the separation between modifying the control message and sending it.
|
||||
if self.use_cmd_vel:
|
||||
twist.linear.x *= 1.5
|
||||
twist.angular.z *= 0.5
|
||||
# These scaling factors convert raw stick inputs to absolute m/s and rad/s
|
||||
# values that DiffDriveController will convert to motor RPM, rather than
|
||||
# the plain Twist, which just sends the stick values as duty cycle and
|
||||
# sends that scaled to the motors.
|
||||
twist.linear.x *= 1.0
|
||||
twist.angular.z *= 1.5
|
||||
|
||||
# Publish
|
||||
if self.use_cmd_vel:
|
||||
@@ -582,13 +591,26 @@ class Headless(Node):
|
||||
)
|
||||
|
||||
# A: brake
|
||||
# TODO: Brake mode
|
||||
new_brake_mode = button_a
|
||||
|
||||
# Y: linear actuator
|
||||
# TODO: linear actuator
|
||||
# X: laser
|
||||
new_laser = button_x
|
||||
|
||||
self.arm_manual_pub_.publish(arm_input)
|
||||
|
||||
# Only publish state if needed
|
||||
if new_brake_mode != self.arm_brake_mode or new_laser != self.arm_laser:
|
||||
self.arm_brake_mode = new_brake_mode
|
||||
self.arm_laser = new_laser
|
||||
state_msg = ArmCtrlState()
|
||||
state_msg.brake_mode = bool(self.arm_brake_mode)
|
||||
state_msg.laser = bool(self.arm_laser)
|
||||
|
||||
self.arm_state_pub_.publish(state_msg)
|
||||
self.get_logger().info(
|
||||
f"[Arm State] Brake: {self.arm_brake_mode}, Laser: {self.arm_laser}"
|
||||
)
|
||||
|
||||
# IK (ONLY NEW)
|
||||
# =============
|
||||
|
||||
|
||||
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