13 Commits

9 changed files with 338 additions and 243 deletions

3
.gitmodules vendored
View File

@@ -1,6 +1,3 @@
[submodule "src/astra_description"] [submodule "src/astra_description"]
path = src/astra_descriptions path = src/astra_descriptions
url = ../astra_descriptions url = ../astra_descriptions
[submodule "src/astra_msgs"]
path = src/astra_msgs
url = git@github.com:SHC-ASTRA/astra_msgs.git

View File

@@ -14,12 +14,8 @@ echo "[INFO] Network interface is up!"
# Your actual ROS node start command goes here # Your actual ROS node start command goes here
echo "[INFO] Starting ROS node..." echo "[INFO] Starting ROS node..."
# Source ROS 2 Humble setup script # Source ROS 2 Humble setup script (if we aren't using nix)
if command -v nixos-rebuild; then command -v ros2 || source /opt/ros/humble/setup.bash
echo "[INFO] running on NixOS"
else
source /opt/ros/humble/setup.bash
fi
# Source your workspace setup script # Source your workspace setup script
source $SCRIPT_DIR/../install/setup.bash source $SCRIPT_DIR/../install/setup.bash

View File

@@ -15,11 +15,7 @@ echo "[INFO] Network interface is up!"
echo "[INFO] Starting ROS node..." echo "[INFO] Starting ROS node..."
# Source ROS 2 Humble setup script # Source ROS 2 Humble setup script
if command -v nixos-rebuild; then command -v ros2 || source /opt/ros/humble/setup.bash
echo "[INFO] running on NixOS"
else
source /opt/ros/humble/setup.bash
fi
# Source your workspace setup script # Source your workspace setup script
source $SCRIPT_DIR/../install/setup.bash source $SCRIPT_DIR/../install/setup.bash

View File

@@ -17,11 +17,7 @@ done
echo "[INFO] Network interface is up!" echo "[INFO] Network interface is up!"
if command -v nixos-rebuild; then command -v ros2 || source /opt/ros/humble/setup.bash
echo "[INFO] running on NixOS"
else
source /opt/ros/humble/setup.bash
fi
source $ANCHOR_WS/install/setup.bash source $ANCHOR_WS/install/setup.bash
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash [[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash

102
flake.lock generated
View File

@@ -1,5 +1,29 @@
{ {
"nodes": { "nodes": {
"astra-msgs": {
"inputs": {
"nix-ros-overlay": "nix-ros-overlay",
"nixpkgs": [
"astra-msgs",
"nix-ros-overlay",
"nixpkgs"
]
},
"locked": {
"lastModified": 1771845042,
"narHash": "sha256-pGsb93ZlMhP3biy8S2eJc1sW+35vmaxlWHTbuwZDlQI=",
"owner": "SHC-ASTRA",
"repo": "astra_msgs",
"rev": "acabfd117d9711afc420612375b4e02f4ce4982d",
"type": "github"
},
"original": {
"owner": "SHC-ASTRA",
"repo": "astra_msgs",
"rev": "acabfd117d9711afc420612375b4e02f4ce4982d",
"type": "github"
}
},
"flake-utils": { "flake-utils": {
"inputs": { "inputs": {
"systems": "systems" "systems": "systems"
@@ -18,17 +42,55 @@
"type": "github" "type": "github"
} }
}, },
"flake-utils_2": {
"inputs": {
"systems": "systems_2"
},
"locked": {
"lastModified": 1731533236,
"narHash": "sha256-l0KFg5HjrsfsO/JpG+r7fRrqm12kzFHyUHqHCVpMMbI=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "11707dc2f618dd54ca8739b309ec4fc024de578b",
"type": "github"
},
"original": {
"owner": "numtide",
"repo": "flake-utils",
"type": "github"
}
},
"nix-ros-overlay": { "nix-ros-overlay": {
"inputs": { "inputs": {
"flake-utils": "flake-utils", "flake-utils": "flake-utils",
"nixpkgs": "nixpkgs" "nixpkgs": "nixpkgs"
}, },
"locked": { "locked": {
"lastModified": 1770108954, "lastModified": 1770622967,
"narHash": "sha256-VBj6bd4LPPSfsZJPa/UPPA92dOs6tmQo0XZKqfz/3W4=", "narHash": "sha256-1LYjTugPSCa/5NkP6/dcZLH5TQYj3R8mAZ/9dgd7jDM=",
"owner": "lopsided98", "owner": "lopsided98",
"repo": "nix-ros-overlay", "repo": "nix-ros-overlay",
"rev": "3d05d46451b376e128a1553e78b8870c75d7753a", "rev": "d1b9f17eba909116356436d46b5192d299c6b49a",
"type": "github"
},
"original": {
"owner": "lopsided98",
"ref": "develop",
"repo": "nix-ros-overlay",
"type": "github"
}
},
"nix-ros-overlay_2": {
"inputs": {
"flake-utils": "flake-utils_2",
"nixpkgs": "nixpkgs_2"
},
"locked": {
"lastModified": 1771404745,
"narHash": "sha256-UVP3TsQJ4PezyQG3B1SsgsTxz32XBVzplJ/cgq7v/uk=",
"owner": "lopsided98",
"repo": "nix-ros-overlay",
"rev": "7cdf7b44ff186869baedbb3b82e5b409bb3e8dd9",
"type": "github" "type": "github"
}, },
"original": { "original": {
@@ -54,9 +116,26 @@
"type": "github" "type": "github"
} }
}, },
"nixpkgs_2": {
"locked": {
"lastModified": 1759381078,
"narHash": "sha256-gTrEEp5gEspIcCOx9PD8kMaF1iEmfBcTbO0Jag2QhQs=",
"owner": "NixOS",
"repo": "nixpkgs",
"rev": "7df7ff7d8e00218376575f0acdcc5d66741351ee",
"type": "github"
},
"original": {
"owner": "lopsided98",
"ref": "nix-ros",
"repo": "nixpkgs",
"type": "github"
}
},
"root": { "root": {
"inputs": { "inputs": {
"nix-ros-overlay": "nix-ros-overlay", "astra-msgs": "astra-msgs",
"nix-ros-overlay": "nix-ros-overlay_2",
"nixpkgs": [ "nixpkgs": [
"nix-ros-overlay", "nix-ros-overlay",
"nixpkgs" "nixpkgs"
@@ -77,6 +156,21 @@
"repo": "default", "repo": "default",
"type": "github" "type": "github"
} }
},
"systems_2": {
"locked": {
"lastModified": 1681028828,
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
"owner": "nix-systems",
"repo": "default",
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
"type": "github"
},
"original": {
"owner": "nix-systems",
"repo": "default",
"type": "github"
}
} }
}, },
"root": "root", "root": "root",

View File

@@ -3,15 +3,13 @@
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";
astra-msgs.url =
"github:SHC-ASTRA/astra_msgs/acabfd117d9711afc420612375b4e02f4ce4982d";
}; };
outputs = outputs =
{ { self, nix-ros-overlay, nixpkgs, astra-msgs }:
self,
nix-ros-overlay,
nixpkgs,
}:
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem ( nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
system: system:
let let
@@ -19,26 +17,31 @@
inherit system; inherit system;
overlays = [ nix-ros-overlay.overlays.default ]; overlays = [ nix-ros-overlay.overlays.default ];
}; };
astra_msgs_pkgs = astra-msgs.packages.${system};
rosDistro = "humble";
in in
{ {
devShells.default = pkgs.mkShell { devShells.default = pkgs.mkShell {
name = "ASTRA Anchor"; name = "ASTRA Anchor";
packages = with pkgs; [ packages = with pkgs; [
colcon colcon
(python313.withPackages ( astra_msgs_pkgs.astra-msgs
p: with p; [
(pkgs.rosPackages.${rosDistro}.python3.withPackages (p: with p; [
pyserial pyserial
pygame pygame
scipy scipy
crccheck crccheck
black black
] ]))
))
( (with rosPackages.${rosDistro};
with rosPackages.humble;
buildEnv { buildEnv {
paths = [ paths = [
ros-core ros-core
rqt-graph
ros2cli ros2cli
ros2run ros2run
ros2bag ros2bag
@@ -74,11 +77,14 @@
ros2-controllers ros2-controllers
chomp-motion-planner chomp-motion-planner
]; ];
} })
)
]; ];
env = {
ASTRAMSGS = "${astra-msgs.outPath}";
};
shellHook = '' shellHook = ''
# Display stuff
export DISPLAY=''${DISPLAY:-:0} export DISPLAY=''${DISPLAY:-:0}
export QT_X11_NO_MITSHM=1 export QT_X11_NO_MITSHM=1
''; '';
@@ -88,6 +94,7 @@
nixConfig = { nixConfig = {
extra-substituters = [ "https://ros.cachix.org" ]; extra-substituters = [ "https://ros.cachix.org" ];
extra-trusted-public-keys = [ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" ]; extra-trusted-public-keys =
[ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" ];
}; };
} }

Submodule src/astra_msgs deleted from 2840bfef34

View File

@@ -1,241 +1,251 @@
import rclpy import signal
from rclpy.node import Node
import serial
import sys import sys
import threading import threading
import os
import glob
import time import time
import atexit
import signal import rclpy
from std_msgs.msg import String from astra_msgs.action import BioVacuum
from astra_msgs.msg import BioControl from astra_msgs.msg import CitadelControl, FaerieControl, VicCAN
from astra_msgs.msg import BioFeedback from astra_msgs.srv import BioTestTube, LibsSystem
from rclpy.action import ActionServer
from rclpy.node import Node
from std_msgs.msg import Header, String
serial_pub = None serial_pub = None
thread = None thread = None
# used to verify the length of an incoming VicCAN feedback message
# key is VicCAN command_id, value is expected length of data list
viccan_citadel_msg_len_dict = {
# empty because not expecting any VicCAN from citadel atm
}
viccan_lance_msg_len_dict = {
# empty because not sure what VicCAN commands LANCE sends
}
class SerialRelay(Node): class SerialRelay(Node):
def __init__(self): def __init__(self):
# Initialize node # Initialize node
super().__init__("bio_node") super().__init__("bio_node")
# Get launch mode parameter # Anchor Topics
self.declare_parameter("launch_mode", "bio") self.anchor_fromvic_sub_ = self.create_subscription(
self.launch_mode = self.get_parameter("launch_mode").value VicCAN, "/anchor/from_vic/bio", self.relay_fromvic, 20
self.get_logger().info(f"bio launch_mode is: {self.launch_mode}") )
self.anchor_tovic_pub_ = self.create_publisher(
# Create publishers VicCAN, "/anchor/to_vic/relay", 20
self.debug_pub = self.create_publisher(String, "/bio/feedback/debug", 10)
self.feedback_pub = self.create_publisher(BioFeedback, "/bio/feedback", 10)
# Create subscribers
self.control_sub = self.create_subscription(
BioControl, "/bio/control", self.send_control, 10
) )
# Create a publisher for telemetry
self.telemetry_pub_timer = self.create_timer(1.0, self.publish_feedback)
# Topics used in anchor mode
if self.launch_mode == "anchor":
self.anchor_sub = self.create_subscription( self.anchor_sub = self.create_subscription(
String, "/anchor/bio/feedback", self.anchor_feedback, 10 String, "/anchor/bio/feedback", self.anchor_feedback, 10
) )
self.anchor_pub = self.create_publisher(String, "/anchor/relay", 10) self.anchor_pub = self.create_publisher(String, "/anchor/relay", 10)
self.bio_feedback = BioFeedback() # Messages
self.citadel_sub = self.create_subscription(
# Search for ports IF in 'arm' (standalone) and not 'anchor' mode CitadelControl,
if self.launch_mode == "bio": "/bio/control/citadel",
# Loop through all serial devices on the computer to check for the MCU self.citadel_callback,
self.port = None 10,
for i in range(2):
try:
# connect and send a ping command
set_port = (
"/dev/ttyACM0" # MCU is controlled through GPIO pins on the PI
) )
ser = serial.Serial(set_port, 115200, timeout=1)
# print(f"Checking port {port}...")
ser.write(b"ping\n")
response = ser.read_until("\n")
# if pong is in response, then we are talking with the MCU self.faerie_sub = self.create_subscription(
if b"pong" in response: FaerieControl,
self.port = set_port "/bio/control/faerie",
self.get_logger().info(f"Found MCU at {set_port}!") self.faerie_callback,
break 10,
except:
pass
if self.port is None:
self.get_logger().info(
"Unable to find MCU... please make sure it is connected."
) )
time.sleep(1)
sys.exit(1)
self.ser = serial.Serial(self.port, 115200) # Services
atexit.register(self.cleanup) self.test_tube_service = self.create_service(
BioTestTube, "/bio/control/test_tube", self.test_tube_callback
)
self.libs_service = self.create_service(
LibsSystem, "bio/control/libs_system", self.libs_callback
)
# Actions
self._action_server = ActionServer(
self, BioVacuum, "/bio/actions/vacuum", self.execute_vacuum
)
def run(self): def run(self):
global thread global thread
thread = threading.Thread(target=rclpy.spin, args=(self,), daemon=True) thread = threading.Thread(target=rclpy.spin, args=(self,), daemon=True)
thread.start() thread.start()
# if in arm mode, will need to read from the MCU
try: try:
while rclpy.ok(): while rclpy.ok():
if self.launch_mode == "bio":
if self.ser.in_waiting:
self.read_mcu()
else:
time.sleep(0.1) time.sleep(0.1)
except KeyboardInterrupt: except KeyboardInterrupt:
pass pass
finally:
self.cleanup()
# Currently will just spit out all values over the /arm/feedback/debug topic as strings
def read_mcu(self):
try:
output = str(self.ser.readline(), "utf8")
if output:
self.get_logger().info(f"[MCU] {output}")
msg = String()
msg.data = output
self.debug_pub.publish(msg)
except serial.SerialException:
self.get_logger().info("SerialException caught... closing serial port.")
if self.ser.is_open:
self.ser.close()
pass
except TypeError as e:
self.get_logger().info(f"TypeError: {e}")
print("Closing serial port.")
if self.ser.is_open:
self.ser.close()
pass
except Exception as e:
print(f"Exception: {e}")
print("Closing serial port.")
if self.ser.is_open:
self.ser.close()
pass
def send_ik(self, msg):
pass
def send_control(self, msg: BioControl):
# CITADEL Control Commands
################
# Chem Pumps, only send if not zero
if msg.pump_id != 0:
command = (
"can_relay_tovic,citadel,27,"
+ str(msg.pump_id)
+ ","
+ str(msg.pump_amount)
+ "\n"
)
self.send_cmd(command)
# Fans, only send if not zero
if msg.fan_id != 0:
command = (
"can_relay_tovic,citadel,40,"
+ str(msg.fan_id)
+ ","
+ str(msg.fan_duration)
+ "\n"
)
self.send_cmd(command)
# Servos, only send if not zero
if msg.servo_id != 0:
command = (
"can_relay_tovic,citadel,25,"
+ str(msg.servo_id)
+ ","
+ str(int(msg.servo_state))
+ "\n"
)
self.send_cmd(command)
# LSS (SCYTHE)
command = "can_relay_tovic,citadel,24," + str(msg.bio_arm) + "\n"
# self.send_cmd(command)
# Vibration Motor
command += "can_relay_tovic,citadel,26," + str(msg.vibration_motor) + "\n"
# self.send_cmd(command)
# FAERIE Control Commands
################
# To be reviewed before use#
# Laser
command += "can_relay_tovic,digit,28," + str(msg.laser) + "\n"
# self.send_cmd(command)
# Drill (SCABBARD)
command += f"can_relay_tovic,digit,19,{msg.drill:.2f}\n"
# self.send_cmd(command)
# Bio linear actuator
command += "can_relay_tovic,digit,42," + str(msg.drill_arm) + "\n"
self.send_cmd(command)
def send_cmd(self, msg: str): def send_cmd(self, msg: str):
if ( # send to anchor node to relay
self.launch_mode == "anchor"
): # if in anchor mode, send to anchor node to relay
output = String() output = String()
output.data = msg output.data = msg
self.anchor_pub.publish(output) self.anchor_pub.publish(output)
elif self.launch_mode == "bio": # if in standalone mode, send to MCU directly
self.get_logger().info(f"[Bio to MCU] {msg}") def relay_fromvic(self, msg: VicCAN):
self.ser.write(bytes(msg, "utf8")) # self.get_logger().info(msg)
if msg.mcu_name == "citadel":
self.process_fromvic_citadel(msg)
def process_fromvic_citadel(self, msg: VicCAN):
# Check message len to prevent crashing on bad data
if msg.command_id in viccan_citadel_msg_len_dict:
expected_len = viccan_citadel_msg_len_dict[msg.command_id]
if len(msg.data) != expected_len:
self.get_logger().warning(
f"Ignoring VicCAN message with id {msg.command_id} due to unexpected data length (expected {expected_len}, got {len(msg.data)})"
)
return
def anchor_feedback(self, msg: String): def anchor_feedback(self, msg: String):
output = msg.data output = msg.data
parts = str(output.strip()).split(",") parts = str(output.strip()).split(",")
# self.get_logger().info(f"[Bio Anchor] {msg.data}") self.get_logger().info(f"[Bio Anchor] {msg.data}")
# no data planned to be received from citadel, not sure about lance
if output.startswith( def citadel_callback(self, msg: CitadelControl):
"can_relay_fromvic,citadel,54" distributor_arr = msg.distributor_id
): # bat, 12, 5, Voltage readings * 100 # Distributor Control
self.bio_feedback.bat_voltage = float(parts[3]) / 100.0 vic_cmd = VicCAN(
self.bio_feedback.voltage_12 = float(parts[4]) / 100.0 header=Header(stamp=self.get_clock().now().to_msg()),
self.bio_feedback.voltage_5 = float(parts[5]) / 100.0 mcu_name="citadel",
elif output.startswith("can_relay_fromvic,digit,57"): command_id=40,
self.bio_feedback.drill_temp = float(parts[3]) data=[
self.bio_feedback.drill_humidity = float(parts[4]) clamp_short(distributor_arr[0]),
clamp_short(distributor_arr[1]),
clamp_short(distributor_arr[2]),
0,
],
)
self.anchor_tovic_pub_.publish(vic_cmd)
# Move Scythe
vic_cmd = VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="digit",
command_id=42,
data=[float(msg.move_scythe)],
)
self.anchor_tovic_pub_.publish(vic_cmd)
def publish_feedback(self): def faerie_callback(self, msg: FaerieControl):
self.feedback_pub.publish(self.bio_feedback) # Move Faerie
vic_cmd = VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="digit",
command_id=42,
data=[float(msg.move_faerie)],
)
self.anchor_tovic_pub_.publish(vic_cmd)
# Drill Speed
vic_cmd = VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="digit",
command_id=19,
data=[
float(msg.drill_speed * 100)
], # change on embedded so we can go (-1,1)
)
self.anchor_tovic_pub_.publish(vic_cmd)
# Vanity Laser Control
vic_cmd = VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="digit",
command_id=28,
data=[float(msg.vanity_laser)],
)
self.anchor_tovic_pub_.publish(vic_cmd)
@staticmethod def test_tube_callback(self, request, response):
def list_serial_ports(): vic_cmd = VicCAN(
return glob.glob("/dev/ttyUSB*") + glob.glob("/dev/ttyACM*") header=Header(stamp=self.get_clock().now().to_msg()),
# return glob.glob("/dev/tty[A-Za-z]*") mcu_name="citadel",
command_id=40,
data=[
float(int(request.tube_id)),
float(request.milliliters),
],
)
self.anchor_tovic_pub_.publish(vic_cmd)
return response
def cleanup(self): def libs_callback(self, request, response):
print("Cleaning up...") print("todo")
try:
if self.ser.is_open: def execute_vacuum(self, goal_handle):
self.ser.close() valve_id = int(goal_handle.request.valve_id)
except Exception as e: duty = int(goal_handle.request.fan_duty_cycle_percent)
exit(0) total = goal_handle.request.fan_time_ms
# open valve
self.anchor_tovic_pub_.publish(
VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="citadel",
command_id=40,
data=[float(valve_id)],
)
)
# set fan duty cycle
self.anchor_tovic_pub_.publish(
VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="citadel",
command_id=19,
data=[float(duty)],
)
)
feedback = BioVacuum.Feedback()
start = time.time()
while True:
elapsed = int((time.time() - start) * 1000)
remaining = max(0, total - elapsed)
feedback.fan_time_remaining_ms = remaining
goal_handle.publish_feedback(feedback)
if remaining == 0:
break
time.sleep(0.1)
# stop fan
self.anchor_tovic_pub_.publish(
VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="citadel",
command_id=19,
data=[0.0],
)
)
# close valve
self.anchor_tovic_pub_.publish(
VicCAN(
header=Header(stamp=self.get_clock().now().to_msg()),
mcu_name="citadel",
command_id=40,
data=[-1.0],
)
)
goal_handle.succeed()
return BioVacuum.Result()
def clamp_short(x: int) -> int:
return max(-32768, min(32767, x))
def myexcepthook(type, value, tb): def myexcepthook(type, value, tb):
print("Uncaught exception:", type, value) print("Uncaught exception:", type, value)
if serial_pub:
serial_pub.cleanup()
def main(args=None): def main(args=None):