mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-02-11 17:30:36 +00:00
Compare commits
21 Commits
gazebo-doc
...
core-ros2-
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
fd12e6c44a | ||
|
|
1e8925e135 | ||
|
|
61f5f1fc3e | ||
|
|
65aab7f179 | ||
|
|
697efa7b9d | ||
|
|
b70a0d27c3 | ||
|
|
2d48361b8f | ||
|
|
d9355f16e9 | ||
|
|
9fc120b09e | ||
|
|
4a98c3d435 | ||
|
|
b5be93e5f6 | ||
|
|
0e775c65c6 | ||
|
|
14141651bf | ||
|
|
c10a2a5cca | ||
|
|
df78575206 | ||
|
|
40fa0d0ab8 | ||
|
|
3bb3771dce | ||
|
|
5e7776631d | ||
|
|
b84ca6757d | ||
|
|
96f5eda005 | ||
|
|
4c1416851e |
@@ -15,7 +15,11 @@ echo "[INFO] Network interface is up!"
|
||||
echo "[INFO] Starting ROS node..."
|
||||
|
||||
# Source ROS 2 Humble setup script
|
||||
if command -v nixos-rebuild; then
|
||||
echo "[INFO] running on NixOS"
|
||||
else
|
||||
source /opt/ros/humble/setup.bash
|
||||
fi
|
||||
|
||||
# Source your workspace setup script
|
||||
source $SCRIPT_DIR/../install/setup.bash
|
||||
|
||||
@@ -15,7 +15,11 @@ echo "[INFO] Network interface is up!"
|
||||
echo "[INFO] Starting ROS node..."
|
||||
|
||||
# Source ROS 2 Humble setup script
|
||||
if command -v nixos-rebuild; then
|
||||
echo "[INFO] running on NixOS"
|
||||
else
|
||||
source /opt/ros/humble/setup.bash
|
||||
fi
|
||||
|
||||
# Source your workspace setup script
|
||||
source $SCRIPT_DIR/../install/setup.bash
|
||||
|
||||
@@ -17,7 +17,11 @@ done
|
||||
echo "[INFO] Network interface is up!"
|
||||
|
||||
|
||||
if command -v nixos-rebuild; then
|
||||
echo "[INFO] running on NixOS"
|
||||
else
|
||||
source /opt/ros/humble/setup.bash
|
||||
fi
|
||||
source $ANCHOR_WS/install/setup.bash
|
||||
[[ -f $AUTONOMY_WS/install/setup.bash ]] && source $AUTONOMY_WS/install/setup.bash
|
||||
|
||||
|
||||
16
flake.lock
generated
16
flake.lock
generated
@@ -24,27 +24,27 @@
|
||||
"nixpkgs": "nixpkgs"
|
||||
},
|
||||
"locked": {
|
||||
"lastModified": 1761810010,
|
||||
"narHash": "sha256-o0wJKW603SiOO373BTgeZaF6nDxegMA/cRrzSC2Cscg=",
|
||||
"lastModified": 1770108954,
|
||||
"narHash": "sha256-VBj6bd4LPPSfsZJPa/UPPA92dOs6tmQo0XZKqfz/3W4=",
|
||||
"owner": "lopsided98",
|
||||
"repo": "nix-ros-overlay",
|
||||
"rev": "e277df39e3bc6b372a5138c0bcf10198857c55ab",
|
||||
"rev": "3d05d46451b376e128a1553e78b8870c75d7753a",
|
||||
"type": "github"
|
||||
},
|
||||
"original": {
|
||||
"owner": "lopsided98",
|
||||
"ref": "master",
|
||||
"ref": "develop",
|
||||
"repo": "nix-ros-overlay",
|
||||
"type": "github"
|
||||
}
|
||||
},
|
||||
"nixpkgs": {
|
||||
"locked": {
|
||||
"lastModified": 1744849697,
|
||||
"narHash": "sha256-S9hqvanPSeRu6R4cw0OhvH1rJ+4/s9xIban9C4ocM/0=",
|
||||
"owner": "lopsided98",
|
||||
"lastModified": 1759381078,
|
||||
"narHash": "sha256-gTrEEp5gEspIcCOx9PD8kMaF1iEmfBcTbO0Jag2QhQs=",
|
||||
"owner": "NixOS",
|
||||
"repo": "nixpkgs",
|
||||
"rev": "6318f538166fef9f5118d8d78b9b43a04bb049e4",
|
||||
"rev": "7df7ff7d8e00218376575f0acdcc5d66741351ee",
|
||||
"type": "github"
|
||||
},
|
||||
"original": {
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
description = "Development environment for ASTRA Anchor";
|
||||
|
||||
inputs = {
|
||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/master";
|
||||
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/develop";
|
||||
nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!!
|
||||
};
|
||||
|
||||
@@ -56,10 +56,12 @@
|
||||
control-msgs
|
||||
control-toolbox
|
||||
moveit-core
|
||||
moveit-planners
|
||||
moveit-common
|
||||
moveit-msgs
|
||||
moveit-ros-planning
|
||||
moveit-ros-planning-interface
|
||||
moveit-ros-visualization
|
||||
moveit-configs-utils
|
||||
moveit-ros-move-group
|
||||
moveit-servo
|
||||
@@ -68,9 +70,9 @@
|
||||
pilz-industrial-motion-planner
|
||||
pick-ik
|
||||
ompl
|
||||
chomp-motion-planner
|
||||
joy
|
||||
# ros2-controllers nixpkg does not build :(
|
||||
ros2-controllers
|
||||
chomp-motion-planner
|
||||
];
|
||||
}
|
||||
)
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.executors import ExternalShutdownException
|
||||
from std_srvs.srv import Empty
|
||||
|
||||
import signal
|
||||
@@ -7,6 +8,7 @@ import time
|
||||
import atexit
|
||||
|
||||
import serial
|
||||
import serial.tools.list_ports
|
||||
import os
|
||||
import sys
|
||||
import threading
|
||||
@@ -15,10 +17,15 @@ import glob
|
||||
from std_msgs.msg import String, Header
|
||||
from astra_msgs.msg import VicCAN
|
||||
|
||||
serial_pub = None
|
||||
thread = None
|
||||
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):
|
||||
"""
|
||||
Publishers:
|
||||
* /anchor/from_vic/debug
|
||||
@@ -39,19 +46,62 @@ Subscribers:
|
||||
- Publish raw strings to this topic to send directly to the MCU for debugging
|
||||
"""
|
||||
|
||||
|
||||
class SerialRelay(Node):
|
||||
def __init__(self):
|
||||
# Initalize node with name
|
||||
super().__init__("anchor_node") # previously 'serial_publisher'
|
||||
|
||||
# Loop through all serial devices on the computer to check for the MCU
|
||||
self.port = None
|
||||
self.serial_port: str | None = None # e.g., "/dev/ttyUSB0"
|
||||
|
||||
# Serial port override
|
||||
if port_override := os.getenv("PORT_OVERRIDE"):
|
||||
self.port = port_override
|
||||
ports = SerialRelay.list_serial_ports()
|
||||
for i in range(4):
|
||||
if self.port is not None:
|
||||
self.serial_port = port_override
|
||||
|
||||
##################################################
|
||||
# Serial MCU Discovery
|
||||
|
||||
# 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,
|
||||
)
|
||||
)
|
||||
recog_ports = list(filter(lambda p: (p.vid, p.pid) in KNOWN_USBS, comports))
|
||||
|
||||
if len(recog_ports) == 1: # Found singular recognized MCU
|
||||
found_port = recog_ports[0]
|
||||
self.get_logger().info(
|
||||
f"Selecting MCU '{found_port.description}' at {found_port.device}."
|
||||
)
|
||||
self.serial_port = found_port.device # String, location of device file; e.g., '/dev/ttyACM0'
|
||||
elif len(recog_ports) > 1: # Found multiple recognized MCUs
|
||||
# Kinda jank log message
|
||||
self.get_logger().error(
|
||||
f"Found multiple recognized MCUs: {[p.device for p in recog_ports].__str__()}"
|
||||
)
|
||||
# Don't set self.serial_port; later if-statement will exit()
|
||||
elif (
|
||||
len(recog_ports) == 0 and len(real_ports) > 0
|
||||
): # Found real ports but none recognized; i.e. maybe found an IMU or camera but not a MCU
|
||||
self.get_logger().error(
|
||||
f"No recognized MCUs found; instead found {[p.device for p in real_ports].__str__()}."
|
||||
)
|
||||
# Don't set self.serial_port; later if-statement will exit()
|
||||
else: # Found jack shit
|
||||
self.get_logger().error("No valid Serial ports specified or found.")
|
||||
# Don't set self.serial_port; later if-statement will exit()
|
||||
|
||||
# We still don't have a serial port; fall back to legacy discovery (Areeb's code)
|
||||
# Loop through all serial devices on the computer to check for the MCU
|
||||
if self.serial_port is None:
|
||||
self.get_logger().warning("Falling back to legacy MCU discovery...")
|
||||
ports = Anchor.list_serial_ports()
|
||||
for _ in range(4):
|
||||
if self.serial_port is not None:
|
||||
break
|
||||
for port in ports:
|
||||
try:
|
||||
@@ -63,22 +113,60 @@ class SerialRelay(Node):
|
||||
|
||||
# if pong is in response, then we are talking with the MCU
|
||||
if b"pong" in response:
|
||||
self.port = port
|
||||
self.get_logger().info(f"Found MCU at {self.port}!")
|
||||
self.serial_port = port
|
||||
self.get_logger().info(f"Found MCU at {self.serial_port}!")
|
||||
break
|
||||
except:
|
||||
pass
|
||||
|
||||
if self.port is None:
|
||||
self.get_logger().info("Unable to find MCU...")
|
||||
# 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)
|
||||
|
||||
self.ser = serial.Serial(self.port, 115200)
|
||||
self.get_logger().info(f"Enabling Relay Mode")
|
||||
self.ser.write(b"can_relay_mode,on\n")
|
||||
# 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
|
||||
@@ -115,22 +203,10 @@ class SerialRelay(Node):
|
||||
String, "/anchor/relay", self.on_relay_tovic_string, 10
|
||||
)
|
||||
|
||||
def run(self):
|
||||
# This thread makes all the update processes run in the background
|
||||
global thread
|
||||
thread = threading.Thread(target=rclpy.spin, args={self}, daemon=True)
|
||||
thread.start()
|
||||
|
||||
try:
|
||||
while rclpy.ok():
|
||||
self.read_MCU() # Check the MCU for updates
|
||||
except KeyboardInterrupt:
|
||||
sys.exit(0)
|
||||
|
||||
def read_MCU(self):
|
||||
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
||||
try:
|
||||
output = str(self.ser.readline(), "utf8")
|
||||
output = str(self.serial_interface.readline(), "utf8")
|
||||
|
||||
if output:
|
||||
self.relay_fromvic(output)
|
||||
@@ -156,14 +232,20 @@ class SerialRelay(Node):
|
||||
except serial.SerialException as e:
|
||||
print(f"SerialException: {e}")
|
||||
print("Closing serial port.")
|
||||
if self.ser.is_open:
|
||||
self.ser.close()
|
||||
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.")
|
||||
if self.ser.is_open:
|
||||
self.ser.close()
|
||||
try:
|
||||
if self.serial_interface.is_open:
|
||||
self.serial_interface.close()
|
||||
except:
|
||||
pass
|
||||
exit(1)
|
||||
except Exception as e:
|
||||
print(f"Exception: {e}")
|
||||
@@ -184,7 +266,7 @@ class SerialRelay(Node):
|
||||
output += f",{round(num, 7)}" # limit to 7 decimal places
|
||||
output += "\n"
|
||||
# self.get_logger().info(f"VicCAN relay to MCU: {output}")
|
||||
self.ser.write(bytes(output, "utf8"))
|
||||
self.serial_interface.write(bytes(output, "utf8"))
|
||||
|
||||
def relay_fromvic(self, msg: str):
|
||||
"""Relay a string message from the MCU to the appropriate VicCAN topic"""
|
||||
@@ -246,7 +328,7 @@ class SerialRelay(Node):
|
||||
"""Relay a raw string message to the MCU for debugging"""
|
||||
message = msg.data
|
||||
# self.get_logger().info(f"Sending command to MCU: {msg}")
|
||||
self.ser.write(bytes(message, "utf8"))
|
||||
self.serial_interface.write(bytes(message, "utf8"))
|
||||
|
||||
@staticmethod
|
||||
def list_serial_ports():
|
||||
@@ -254,28 +336,29 @@ class SerialRelay(Node):
|
||||
|
||||
def cleanup(self):
|
||||
print("Cleaning up before terminating...")
|
||||
if self.ser.is_open:
|
||||
self.ser.close()
|
||||
|
||||
|
||||
def myexcepthook(type, value, tb):
|
||||
print("Uncaught exception:", type, value)
|
||||
if serial_pub:
|
||||
serial_pub.cleanup()
|
||||
if self.serial_interface.is_open:
|
||||
self.serial_interface.close()
|
||||
|
||||
|
||||
def main(args=None):
|
||||
try:
|
||||
rclpy.init(args=args)
|
||||
sys.excepthook = myexcepthook
|
||||
anchor_node = Anchor()
|
||||
|
||||
global serial_pub
|
||||
thread = threading.Thread(target=rclpy.spin, args=(anchor_node,), daemon=True)
|
||||
thread.start()
|
||||
|
||||
serial_pub = SerialRelay()
|
||||
serial_pub.run()
|
||||
rate = anchor_node.create_rate(100) # 100 Hz -- arbitrary rate
|
||||
while rclpy.ok():
|
||||
anchor_node.read_MCU() # Check the MCU for updates
|
||||
rate.sleep()
|
||||
except (KeyboardInterrupt, ExternalShutdownException):
|
||||
print("Caught shutdown signal, shutting down...")
|
||||
finally:
|
||||
rclpy.try_shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
# signal.signal(signal.SIGTSTP, lambda signum, frame: sys.exit(0)) # Catch Ctrl+Z and exit cleanly
|
||||
signal.signal(
|
||||
signal.SIGTERM, lambda signum, frame: sys.exit(0)
|
||||
) # Catch termination signals and exit cleanly
|
||||
|
||||
@@ -1,13 +1,21 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, Shutdown
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
OpaqueFunction,
|
||||
Shutdown,
|
||||
IncludeLaunchDescription,
|
||||
)
|
||||
from launch.substitutions import (
|
||||
LaunchConfiguration,
|
||||
ThisLaunchFileDir,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.conditions import IfCondition
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
# Prevent making __pycache__ directories
|
||||
@@ -40,7 +48,10 @@ def launch_setup(context, *args, **kwargs):
|
||||
executable="core", # change as needed
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
parameters=[
|
||||
{"launch_mode": mode},
|
||||
{"use_ros2_control": LaunchConfiguration("use_ros2_control", default=False)},
|
||||
],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
@@ -133,4 +144,46 @@ def generate_launch_description():
|
||||
description="Launch mode: arm, core, bio, anchor, or ptz",
|
||||
)
|
||||
|
||||
return LaunchDescription([declare_arg, OpaqueFunction(function=launch_setup)])
|
||||
ros2_control_arg = DeclareLaunchArgument(
|
||||
"use_ros2_control",
|
||||
default_value="false",
|
||||
description="Whether to use DiffDriveController for driving instead of direct Twist",
|
||||
)
|
||||
|
||||
rsp = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"robot_state_publisher.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
)
|
||||
|
||||
controllers = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(
|
||||
PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("core_description"),
|
||||
"launch",
|
||||
"spawn_controllers.launch.py",
|
||||
]
|
||||
)
|
||||
),
|
||||
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
|
||||
launch_arguments={("hardware_mode", "physical")},
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
declare_arg,
|
||||
ros2_control_arg,
|
||||
rsp,
|
||||
controllers,
|
||||
OpaqueFunction(function=launch_setup),
|
||||
]
|
||||
)
|
||||
|
||||
@@ -49,7 +49,7 @@ class SerialRelay(Node):
|
||||
|
||||
# Create subscribers
|
||||
self.man_sub = self.create_subscription(
|
||||
ArmManual, "/arm/control/manual", self.send_manual, 10
|
||||
ArmManual, "/arm/control/manual", self.send_manual, 2
|
||||
)
|
||||
|
||||
# New messages
|
||||
@@ -190,7 +190,7 @@ class SerialRelay(Node):
|
||||
|
||||
command += f"can_relay_tovic,digit,39,{msg.effector_yaw},{msg.effector_roll}\n"
|
||||
|
||||
# command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn
|
||||
command += f"can_relay_tovic,digit,26,{msg.gripper}\n" # no hardware rn
|
||||
|
||||
command += f"can_relay_tovic,digit,28,{msg.laser}\n"
|
||||
|
||||
|
||||
Submodule src/astra_descriptions updated: 4ab41e9c82...35bf223ae9
Submodule src/astra_msgs updated: 6a57072723...2840bfef34
@@ -31,14 +31,14 @@ CORE_WHEEL_RADIUS = 0.171 # meters
|
||||
CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1
|
||||
|
||||
control_qos = qos.QoSProfile(
|
||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
# history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
depth=2,
|
||||
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||
durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||
deadline=Duration(seconds=1),
|
||||
lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||
liveliness_lease_duration=Duration(seconds=5),
|
||||
# reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||
# durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||
# deadline=Duration(seconds=1),
|
||||
# lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||
# liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||
# liveliness_lease_duration=Duration(seconds=5),
|
||||
)
|
||||
|
||||
# Used to verify the length of an incoming VicCAN feedback message
|
||||
@@ -66,6 +66,10 @@ class SerialRelay(Node):
|
||||
self.launch_mode = self.get_parameter("launch_mode").value
|
||||
self.get_logger().info(f"Core launch_mode is: {self.launch_mode}")
|
||||
|
||||
self.declare_parameter("use_ros2_control", False)
|
||||
self.use_ros2_control = self.get_parameter("use_ros2_control").value
|
||||
self.get_logger().info(f"Use ros2_control: {self.use_ros2_control}")
|
||||
|
||||
##################################################
|
||||
# Topics
|
||||
|
||||
@@ -85,6 +89,12 @@ class SerialRelay(Node):
|
||||
|
||||
# Control
|
||||
|
||||
if self.use_ros2_control:
|
||||
# Joint state control for topic-based controller
|
||||
self.joint_command_sub_ = self.create_subscription(
|
||||
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
|
||||
@@ -100,9 +110,7 @@ class SerialRelay(Node):
|
||||
self.control_state_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
self.twist_max_duty = (
|
||||
0.5 # max duty cycle for twist commands (0.0 - 1.0); walking speed is 0.5
|
||||
)
|
||||
self.twist_max_duty = 0.5 # max duty cycle for twist commands (0.0 - 1.0); walking speed is 0.5
|
||||
|
||||
# Feedback
|
||||
|
||||
@@ -122,7 +130,7 @@ class SerialRelay(Node):
|
||||
) # TODO: not sure about this
|
||||
# Joint states for topic-based controller
|
||||
self.joint_state_pub_ = self.create_publisher(
|
||||
JointState, "/core/joint_states", qos_profile=qos.qos_profile_sensor_data
|
||||
JointState, "/joint_states", qos_profile=qos.qos_profile_sensor_data
|
||||
)
|
||||
# IMU (embedded BNO-055)
|
||||
self.imu_pub_ = self.create_publisher(
|
||||
@@ -148,6 +156,7 @@ class SerialRelay(Node):
|
||||
|
||||
# Old
|
||||
|
||||
if not self.use_ros2_control:
|
||||
# /core/control
|
||||
self.control_sub = self.create_subscription(
|
||||
CoreControl, "/core/control", self.send_controls, 10
|
||||
@@ -283,6 +292,40 @@ class SerialRelay(Node):
|
||||
|
||||
# print(f"[Sys] Relaying: {command}")
|
||||
|
||||
def joint_command_callback(self, msg: JointState):
|
||||
# So... topic based control node publishes JointState messages over /joint_commands
|
||||
# with len(msg.name) == 5 and len(msg.velocity) == 4... all 5 non-fixed joints
|
||||
# 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:
|
||||
self.get_logger().warning(
|
||||
f"Received joint control message with unexpected number of joints. Ignoring."
|
||||
)
|
||||
return
|
||||
if msg.name != [
|
||||
"left_suspension_joint",
|
||||
"bl_wheel_joint",
|
||||
"br_wheel_joint",
|
||||
"fl_wheel_joint",
|
||||
"fr_wheel_joint",
|
||||
]:
|
||||
self.get_logger().warning(
|
||||
f"Received joint control message with unexpected name[]. Ignoring."
|
||||
)
|
||||
return
|
||||
|
||||
(bl_vel, br_vel, fl_vel, fr_vel) = msg.velocity
|
||||
|
||||
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
|
||||
|
||||
self.send_viccan(
|
||||
20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]
|
||||
) # order expected by embedded
|
||||
|
||||
def cmd_vel_callback(self, msg: TwistStamped):
|
||||
linear = msg.twist.linear.x
|
||||
angular = -msg.twist.angular.z
|
||||
@@ -528,22 +571,27 @@ class SerialRelay(Node):
|
||||
match motorId:
|
||||
case 1:
|
||||
motor = self.feedback_new_state.fl_motor
|
||||
joint_state_msg.name = ["fl_motor_joint"]
|
||||
joint_state_msg.name = ["fl_wheel_joint"]
|
||||
case 2:
|
||||
motor = self.feedback_new_state.bl_motor
|
||||
joint_state_msg.name = ["bl_motor_joint"]
|
||||
joint_state_msg.name = ["bl_wheel_joint"]
|
||||
case 3:
|
||||
motor = self.feedback_new_state.fr_motor
|
||||
joint_state_msg.name = ["fr_motor_joint"]
|
||||
joint_state_msg.name = ["fr_wheel_joint"]
|
||||
case 4:
|
||||
motor = self.feedback_new_state.br_motor
|
||||
joint_state_msg.name = ["br_motor_joint"]
|
||||
joint_state_msg.name = ["br_wheel_joint"]
|
||||
case _:
|
||||
self.get_logger().warning(
|
||||
f"Ignoring REV motor feedback 58 with invalid motorId {motorId}"
|
||||
)
|
||||
return
|
||||
|
||||
# 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)
|
||||
|
||||
joint_state_msg.header.stamp = msg.header.stamp
|
||||
self.joint_state_pub_.publish(joint_state_msg)
|
||||
case _:
|
||||
@@ -581,6 +629,10 @@ def map_range(
|
||||
return (value - in_min) * (out_max - out_min) / (in_max - in_min) + out_min
|
||||
|
||||
|
||||
def radps_to_rpm(radps: float):
|
||||
return radps * 60 / (2 * pi)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
sys.excepthook = myexcepthook
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.executors import ExternalShutdownException
|
||||
from rclpy import qos
|
||||
from rclpy.duration import Duration
|
||||
|
||||
@@ -11,6 +12,8 @@ import os
|
||||
import sys
|
||||
import threading
|
||||
import glob
|
||||
import pwd
|
||||
import grp
|
||||
from math import copysign
|
||||
|
||||
from std_msgs.msg import String
|
||||
@@ -32,14 +35,14 @@ ARM_STOP_MSG = ArmManual() # "
|
||||
BIO_STOP_MSG = BioControl() # "
|
||||
|
||||
control_qos = qos.QoSProfile(
|
||||
history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
# history=qos.QoSHistoryPolicy.KEEP_LAST,
|
||||
depth=2,
|
||||
reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||
durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||
deadline=Duration(seconds=1),
|
||||
lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||
liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||
liveliness_lease_duration=Duration(seconds=5),
|
||||
# reliability=qos.QoSReliabilityPolicy.BEST_EFFORT,
|
||||
# durability=qos.QoSDurabilityPolicy.VOLATILE,
|
||||
# deadline=Duration(seconds=1),
|
||||
# lifespan=Duration(nanoseconds=500_000_000), # 500ms
|
||||
# liveliness=qos.QoSLivelinessPolicy.SYSTEM_DEFAULT,
|
||||
# liveliness_lease_duration=Duration(seconds=5),
|
||||
)
|
||||
|
||||
CORE_MODE = "twist" # "twist" or "duty"
|
||||
@@ -71,10 +74,37 @@ class Headless(Node):
|
||||
print("No gamepad found. Waiting...")
|
||||
|
||||
# Initialize the gamepad
|
||||
self.gamepad = pygame.joystick.Joystick(0)
|
||||
id = 0
|
||||
while True:
|
||||
self.num_gamepads = pygame.joystick.get_count()
|
||||
if id >= self.num_gamepads:
|
||||
self.get_logger().fatal("Ran out of controllers to try")
|
||||
sys.exit(1)
|
||||
|
||||
try:
|
||||
self.gamepad = pygame.joystick.Joystick(id)
|
||||
self.gamepad.init()
|
||||
except Exception as e:
|
||||
self.get_logger().error("Error when initializing gamepad")
|
||||
self.get_logger().error(e)
|
||||
id += 1
|
||||
continue
|
||||
print(f"Gamepad Found: {self.gamepad.get_name()}")
|
||||
|
||||
if self.gamepad.get_numhats() == 0 or self.gamepad.get_numaxes() < 5:
|
||||
self.get_logger().error("Controller not correctly initialized.")
|
||||
if not is_user_in_group("input"):
|
||||
self.get_logger().warning(
|
||||
"If using NixOS, you may need to add yourself to the 'input' group."
|
||||
)
|
||||
if is_user_in_group("plugdev"):
|
||||
self.get_logger().warning(
|
||||
"If using NixOS, you may need to remove yourself from the 'plugdev' group."
|
||||
)
|
||||
else:
|
||||
break
|
||||
id += 1
|
||||
|
||||
self.create_timer(0.15, self.send_controls)
|
||||
|
||||
self.core_publisher = self.create_publisher(CoreControl, "/core/control", 2)
|
||||
@@ -115,7 +145,7 @@ class Headless(Node):
|
||||
sys.exit(0)
|
||||
|
||||
# Check if controller is still connected
|
||||
if pygame.joystick.get_count() == 0:
|
||||
if pygame.joystick.get_count() != self.num_gamepads:
|
||||
print("Gamepad disconnected. Exiting...")
|
||||
# Send one last zero control message
|
||||
self.core_publisher.publish(CORE_STOP_MSG)
|
||||
@@ -296,10 +326,33 @@ def deadzone(value: float, threshold=0.05) -> float:
|
||||
return value
|
||||
|
||||
|
||||
def is_user_in_group(group_name: str) -> bool:
|
||||
# Copied from https://zetcode.com/python/os-getgrouplist/
|
||||
try:
|
||||
username = os.getlogin()
|
||||
|
||||
# Get group ID from name
|
||||
group_info = grp.getgrnam(group_name)
|
||||
target_gid = group_info.gr_gid
|
||||
|
||||
# Get user's groups
|
||||
user_info = pwd.getpwnam(username)
|
||||
user_groups = os.getgrouplist(username, user_info.pw_gid)
|
||||
|
||||
return target_gid in user_groups
|
||||
except KeyError:
|
||||
return False
|
||||
|
||||
|
||||
def main(args=None):
|
||||
try:
|
||||
rclpy.init(args=args)
|
||||
|
||||
node = Headless()
|
||||
rclpy.spin(node)
|
||||
except (KeyboardInterrupt, ExternalShutdownException):
|
||||
print("Caught shutdown signal. Exiting...")
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user