mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
41 Commits
7a3c4af1ce
...
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 | ||
|
|
ea36ce6ef4 | ||
|
|
3f795bf8ed | ||
|
|
b257dc7556 | ||
|
|
45825189a5 | ||
|
|
f7efa604d2 | ||
|
|
fe46a2ab4d | ||
|
|
941e196316 | ||
|
|
a17060ceda | ||
|
|
ff4a58e6ed | ||
|
|
120891c8e5 | ||
|
|
178d5001d6 | ||
|
|
684c2994ec | ||
|
|
bfa50e3a25 | ||
|
|
90fbbac813 |
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
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
from warnings import deprecated
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.executors import ExternalShutdownException
|
||||
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
|
||||
|
||||
import signal
|
||||
import atexit
|
||||
|
||||
from .connector import (
|
||||
@@ -15,11 +15,10 @@ from .connector import (
|
||||
NoWorkingDeviceException,
|
||||
)
|
||||
from .convert import string_to_viccan
|
||||
import sys
|
||||
import threading
|
||||
|
||||
from std_msgs.msg import String, Header
|
||||
from astra_msgs.msg import VicCAN
|
||||
from std_msgs.msg import String
|
||||
|
||||
|
||||
class Anchor(Node):
|
||||
@@ -33,12 +32,19 @@ 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
|
||||
- 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
|
||||
@@ -48,6 +54,8 @@ class Anchor(Node):
|
||||
|
||||
logger = self.get_logger()
|
||||
|
||||
# ROS2 Parameter Setup
|
||||
|
||||
self.declare_parameter(
|
||||
"connector",
|
||||
"auto",
|
||||
@@ -59,78 +67,163 @@ class Anchor(Node):
|
||||
),
|
||||
)
|
||||
|
||||
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(self.get_logger())
|
||||
self.connector = SerialConnector(
|
||||
logger, self.get_clock(), serial_override
|
||||
)
|
||||
case "can":
|
||||
logger.info("using CAN connector")
|
||||
self.connector = CANConnector(self.get_logger())
|
||||
self.connector = CANConnector(logger, self.get_clock(), can_override)
|
||||
case "mock":
|
||||
logger.info("using mock connector")
|
||||
self.connector = MockConnector(self.get_logger())
|
||||
self.connector = MockConnector(logger, self.get_clock())
|
||||
case "auto":
|
||||
logger.info("automatically determining connector")
|
||||
try:
|
||||
logger.info("trying CAN connector")
|
||||
self.connector = CANConnector(self.get_logger())
|
||||
self.connector = CANConnector(
|
||||
logger, self.get_clock(), can_override
|
||||
)
|
||||
except (NoValidDeviceException, NoWorkingDeviceException, TypeError):
|
||||
logger.info("CAN connector failed, trying serial connector")
|
||||
self.connector = SerialConnector(self.get_logger())
|
||||
self.connector = SerialConnector(
|
||||
logger, self.get_clock(), serial_override
|
||||
)
|
||||
case _:
|
||||
self.get_logger().fatal(
|
||||
logger.fatal(
|
||||
f"invalid value for connector parameter: {connector_select}"
|
||||
)
|
||||
exit(1)
|
||||
|
||||
# Close devices on exit
|
||||
atexit.register(self.cleanup)
|
||||
|
||||
# ROS2 Topic Setup
|
||||
|
||||
# Publishers
|
||||
self.fromvic_debug_pub_ = self.create_publisher(
|
||||
String, "/anchor/from_vic/debug", 20
|
||||
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,
|
||||
)
|
||||
|
||||
# Subscribers
|
||||
self.tovic_sub_ = self.create_subscription(
|
||||
VicCAN, "/anchor/to_vic/relay", self.connector.write, 20
|
||||
VicCAN,
|
||||
"/anchor/to_vic/relay",
|
||||
self.write_connector,
|
||||
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.on_mock_fromvic, 20
|
||||
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,
|
||||
)
|
||||
|
||||
# Close devices on exit
|
||||
atexit.register(self.cleanup)
|
||||
|
||||
def cleanup(self):
|
||||
self.connector.cleanup()
|
||||
|
||||
def read_MCU(self):
|
||||
"""Check the USB serial port for new data from the MCU, and publish string to appropriate topics"""
|
||||
output = self.connector.read()
|
||||
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 not output:
|
||||
return
|
||||
if raw:
|
||||
self.fromvic_debug_pub_.publish(String(data=raw))
|
||||
|
||||
self.relay_fromvic(output)
|
||||
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 string message from the MCU to the appropriate VicCAN topic"""
|
||||
msg.header = Header(stamp=self.get_clock().now().to_msg(), frame_id="from_vic")
|
||||
|
||||
"""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":
|
||||
@@ -138,15 +231,6 @@ class Anchor(Node):
|
||||
elif msg.mcu_name == "citadel" or msg.mcu_name == "digit":
|
||||
self.fromvic_bio_pub_.publish(msg)
|
||||
|
||||
def on_mock_fromvic(self, msg: String):
|
||||
viccan = string_to_viccan(
|
||||
msg.data,
|
||||
"mock",
|
||||
self.get_logger(),
|
||||
)
|
||||
if viccan:
|
||||
self.relay_fromvic(viccan)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
try:
|
||||
@@ -158,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()
|
||||
|
||||
@@ -1,7 +1,8 @@
|
||||
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
|
||||
from .convert import string_to_viccan as _string_to_viccan, viccan_to_string
|
||||
|
||||
# CAN
|
||||
import can
|
||||
@@ -20,6 +21,16 @@ KNOWN_USBS = [
|
||||
]
|
||||
BAUD_RATE = 115200
|
||||
|
||||
MCU_IDS = [
|
||||
"broadcast",
|
||||
"core",
|
||||
"arm",
|
||||
"digit",
|
||||
"faerie",
|
||||
"citadel",
|
||||
"libs",
|
||||
]
|
||||
|
||||
|
||||
class NoValidDeviceException(Exception):
|
||||
pass
|
||||
@@ -39,18 +50,36 @@ class DeviceClosedException(Exception):
|
||||
|
||||
class Connector(ABC):
|
||||
logger: RcutilsLogger
|
||||
clock: Clock
|
||||
|
||||
def __init__(self, logger: RcutilsLogger):
|
||||
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) -> VicCAN | None:
|
||||
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
|
||||
|
||||
@@ -59,12 +88,19 @@ class SerialConnector(Connector):
|
||||
port: str
|
||||
mcu_name: str
|
||||
serial_interface: serial.Serial
|
||||
override: bool
|
||||
|
||||
def __init__(self, logger: RcutilsLogger):
|
||||
super().__init__(logger)
|
||||
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")
|
||||
@@ -75,7 +111,8 @@ class SerialConnector(Connector):
|
||||
|
||||
# check each of our ports to make sure one of them is responding
|
||||
port = ports[0]
|
||||
mcu_name = self._get_name(port)
|
||||
# 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"
|
||||
@@ -136,34 +173,36 @@ class SerialConnector(Connector):
|
||||
)
|
||||
|
||||
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) -> VicCAN | None:
|
||||
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||
try:
|
||||
raw = str(self.serial_interface.readline(), "utf8")
|
||||
|
||||
if not raw:
|
||||
return None
|
||||
return (None, None)
|
||||
|
||||
return string_to_viccan(raw, self.mcu_name, self.logger)
|
||||
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 TypeError as e:
|
||||
self.logger.error(f"TypeError: {e}")
|
||||
raise DeviceClosedException(f"serial port {self.port} closed unexpectedly")
|
||||
except Exception:
|
||||
pass # pretty much no other error matters
|
||||
return (None, None) # pretty much no other error matters
|
||||
|
||||
def write(self, msg: VicCAN):
|
||||
# go from [ w, x, y, z ] -> "w,x,y,z" & round to 7 digits max
|
||||
data = ",".join([str(round(x, 7)) for x in msg.data])
|
||||
output = f"can_relay_tovic,{msg.mcu_name},{msg.command_id},{data}\n"
|
||||
self.serial_interface.write(bytes(output, "utf8"))
|
||||
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}")
|
||||
@@ -175,26 +214,36 @@ class SerialConnector(Connector):
|
||||
|
||||
|
||||
class CANConnector(Connector):
|
||||
def __init__(self, logger: RcutilsLogger):
|
||||
super().__init__(logger)
|
||||
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
|
||||
|
||||
if self.can_channel is None:
|
||||
avail = can.interfaces.socketcan.SocketcanBus._detect_available_configs()
|
||||
avail = can.interfaces.socketcan.SocketcanBus._detect_available_configs()
|
||||
|
||||
if len(avail) == 0:
|
||||
raise NoValidDeviceException("no CAN interfaces found")
|
||||
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}]"
|
||||
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,
|
||||
)
|
||||
)
|
||||
|
||||
bus = avail[0]
|
||||
self.can_channel = str(bus.get("channel"))
|
||||
self.logger.info(f"found CAN interface '{self.can_channel}'")
|
||||
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(
|
||||
@@ -208,9 +257,9 @@ class CANConnector(Connector):
|
||||
)
|
||||
|
||||
if self.can_channel and self.can_channel.startswith("v"):
|
||||
self.logger.warn("using virtual CAN interface; this is likely vcan*")
|
||||
self.logger.warn("CAN interface is likely virtual")
|
||||
|
||||
def read(self) -> VicCAN | None:
|
||||
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||
if not self.can_bus:
|
||||
raise DeviceClosedException("CAN bus not initialized")
|
||||
|
||||
@@ -221,7 +270,7 @@ class CANConnector(Connector):
|
||||
raise DeviceClosedException("CAN bus closed unexpectedly")
|
||||
|
||||
if message is None:
|
||||
return None
|
||||
return (None, None)
|
||||
|
||||
arbitration_id = message.arbitration_id & 0x7FF
|
||||
data_bytes = bytes(message.data)
|
||||
@@ -230,21 +279,13 @@ class CANConnector(Connector):
|
||||
data_type_key = (arbitration_id >> 6) & 0b11
|
||||
command = arbitration_id & 0x3F
|
||||
|
||||
key_to_mcu: dict[int, str] = {
|
||||
1: "broadcast",
|
||||
2: "core",
|
||||
3: "arm",
|
||||
4: "digit",
|
||||
5: "faerie",
|
||||
6: "citadel",
|
||||
}
|
||||
|
||||
mcu_name = key_to_mcu.get(mcu_key)
|
||||
if mcu_name is None:
|
||||
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
|
||||
return (None, None)
|
||||
|
||||
data: list[float] = []
|
||||
|
||||
@@ -256,33 +297,33 @@ class CANConnector(Connector):
|
||||
self.logger.warn(
|
||||
f"received double payload with insufficient length {len(data_bytes)}; dropping frame"
|
||||
)
|
||||
return None
|
||||
(value,) = struct.unpack("<d", data_bytes[:8])
|
||||
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
|
||||
v1, v2 = struct.unpack("<ff", data_bytes[:8])
|
||||
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
|
||||
i1, i2, i3, i4 = struct.unpack("<hhhh", data_bytes[:8])
|
||||
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
|
||||
return (None, None)
|
||||
except struct.error as e:
|
||||
self.logger.error(f"error unpacking CAN payload: {e}")
|
||||
return None
|
||||
return (None, None)
|
||||
|
||||
viccan = VicCAN(
|
||||
mcu_name=mcu_name,
|
||||
@@ -295,98 +336,65 @@ class CANConnector(Connector):
|
||||
f"decoded as VicCAN(mcu_name={viccan.mcu_name}, command_id={viccan.command_id}, data={viccan.data})"
|
||||
)
|
||||
|
||||
return viccan
|
||||
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 the VicCAN scheme:
|
||||
# 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.
|
||||
mcu_name = (msg.mcu_name or "").lower()
|
||||
mcu_key_map: dict[str, int] = {
|
||||
"broadcast": 1,
|
||||
"core": 2,
|
||||
"arm": 3,
|
||||
"digit": 4,
|
||||
"faerie": 5,
|
||||
"citadel": 6,
|
||||
}
|
||||
|
||||
if mcu_name not in mcu_key_map:
|
||||
# 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
|
||||
|
||||
mcu_key = mcu_key_map[mcu_name] & 0b111
|
||||
|
||||
# Infer data type key from payload length according to the table:
|
||||
# determine data type from length:
|
||||
# 0: double x1, 1: float32 x2, 2: int16 x4, 3: empty
|
||||
data_len = len(msg.data)
|
||||
if data_len == 0:
|
||||
data_type_key = 3
|
||||
elif data_len == 1:
|
||||
data_type_key = 0
|
||||
elif data_len == 2:
|
||||
data_type_key = 1
|
||||
elif data_len == 4:
|
||||
data_type_key = 2
|
||||
else:
|
||||
# Fallback: treat any other non-zero length as float32 x2
|
||||
self.logger.warn(
|
||||
f"unexpected VicCAN data length {data_len}; encoding as float32 x2 (key=1) and truncating/padding as needed"
|
||||
)
|
||||
data_type_key = 1
|
||||
|
||||
# Command is limited to 6 bits.
|
||||
command = int(msg.command_id)
|
||||
if command < 0:
|
||||
self.logger.error(f"invalid negative command_id for CAN frame: {command}")
|
||||
return
|
||||
if command > 0x3F:
|
||||
self.logger.warn(
|
||||
f"command_id 0x{command:X} exceeds 6-bit range; truncating to lower 6 bits"
|
||||
)
|
||||
command &= 0x3F
|
||||
|
||||
arbitration_id = (
|
||||
((mcu_key & 0b111) << 8) | ((data_type_key & 0b11) << 6) | (command & 0x3F)
|
||||
)
|
||||
|
||||
# Map VicCAN.data (floats) to up to 8 CAN data bytes.
|
||||
raw_bytes: list[int] = []
|
||||
for value in msg.data:
|
||||
try:
|
||||
b = int(round(value))
|
||||
except (TypeError, ValueError):
|
||||
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"non-numeric VicCAN data value: {value}; dropping message"
|
||||
f"unexpected VicCAN data length: {data_len}; dropping message"
|
||||
)
|
||||
return
|
||||
|
||||
if b < 0 or b > 255:
|
||||
self.logger.warn(
|
||||
f"VicCAN data value {value} out of byte range; clamping into [0, 255]"
|
||||
)
|
||||
b = max(0, min(255, b))
|
||||
|
||||
raw_bytes.append(b)
|
||||
|
||||
if len(raw_bytes) > 8:
|
||||
self.logger.warn(
|
||||
f"VicCAN data too long for single CAN frame ({len(raw_bytes)} > 8); truncating"
|
||||
# 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"
|
||||
)
|
||||
raw_bytes = raw_bytes[:8]
|
||||
return
|
||||
|
||||
try:
|
||||
can_message = can.Message(
|
||||
arbitration_id=arbitration_id,
|
||||
data=raw_bytes,
|
||||
arbitration_id=(mcu_id << 8) | (data_type << 6) | command,
|
||||
data=data,
|
||||
is_extended_id=False,
|
||||
)
|
||||
except Exception as e:
|
||||
@@ -403,6 +411,9 @@ class CANConnector(Connector):
|
||||
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:
|
||||
@@ -413,11 +424,15 @@ class CANConnector(Connector):
|
||||
|
||||
|
||||
class MockConnector(Connector):
|
||||
def __init__(self, logger: RcutilsLogger):
|
||||
super().__init__(logger)
|
||||
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) -> VicCAN | None:
|
||||
return None
|
||||
def read(self) -> tuple[VicCAN | None, str | None]:
|
||||
return (None, None)
|
||||
|
||||
def write(self, msg: VicCAN):
|
||||
print(msg)
|
||||
pass
|
||||
|
||||
def write_raw(self, msg: str):
|
||||
pass
|
||||
|
||||
@@ -1,30 +1,22 @@
|
||||
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):
|
||||
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.
|
||||
|
||||
Parameters:
|
||||
* msg: str
|
||||
- The message in serial VicCAN format
|
||||
* mcu_name: str
|
||||
- The name of the MCU (e.g. core, citadel, arm)
|
||||
* logger: RcutilsLogger
|
||||
- A logger retrieved from node.get_logger()
|
||||
|
||||
Returns:
|
||||
* VicCAN | None
|
||||
- The VicCAN message on a success or None on a failure
|
||||
On a failure, it will log at a debug level why it failed and return None.
|
||||
"""
|
||||
|
||||
parts: list[str] = msg.split(",")
|
||||
parts: list[str] = msg.strip().split(",")
|
||||
|
||||
# don't need an extra check because len of .split output is always >= 1
|
||||
if parts[0] != "can_relay_fromvic":
|
||||
if not parts[0].startswith("can_relay_"):
|
||||
logger.debug(f"got non-CAN data from {mcu_name}: {msg}")
|
||||
return None
|
||||
elif len(parts) < 3:
|
||||
@@ -34,8 +26,40 @@ def string_to_viccan(msg: str, mcu_name: str, logger: RcutilsLogger):
|
||||
logger.debug(f"got garbage (too many parts) CAN data from {mcu_name}: {msg}")
|
||||
return None
|
||||
|
||||
return VicCAN(
|
||||
mcu_name=parts[1],
|
||||
command_id=int(parts[2]),
|
||||
data=[float(x) for x in parts[3:]],
|
||||
)
|
||||
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,12 +1,16 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, Shutdown
|
||||
from launch.actions import DeclareLaunchArgument, Shutdown, IncludeLaunchDescription
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
connector = LaunchConfiguration("connector")
|
||||
serial_override = LaunchConfiguration("serial_override")
|
||||
can_override = LaunchConfiguration("can_override")
|
||||
use_ptz = LaunchConfiguration("use_ptz")
|
||||
|
||||
ld = LaunchDescription()
|
||||
@@ -16,7 +20,23 @@ def generate_launch_description():
|
||||
DeclareLaunchArgument(
|
||||
"connector",
|
||||
default_value="auto",
|
||||
description="Connector parameter for anchor node (default: auto)",
|
||||
description="Connector parameter for anchor node (default: 'auto')",
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"serial_override",
|
||||
default_value="",
|
||||
description="Serial port override parameter for anchor node (default: '')",
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
DeclareLaunchArgument(
|
||||
"can_override",
|
||||
default_value="",
|
||||
description="CAN network override parameter for anchor node (default: '')",
|
||||
)
|
||||
)
|
||||
|
||||
@@ -28,7 +48,42 @@ def generate_launch_description():
|
||||
)
|
||||
)
|
||||
|
||||
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",
|
||||
@@ -40,27 +95,6 @@ def generate_launch_description():
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="core",
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": "anchor"}],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="core_pkg",
|
||||
executable="ptz",
|
||||
name="ptz",
|
||||
output="both",
|
||||
condition=IfCondition(use_ptz),
|
||||
)
|
||||
)
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="bio_pkg",
|
||||
@@ -74,18 +108,67 @@ def generate_launch_description():
|
||||
|
||||
ld.add_action(
|
||||
Node(
|
||||
package="anchor_pkg",
|
||||
executable="anchor",
|
||||
name="anchor",
|
||||
package="core_pkg",
|
||||
executable="core",
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[
|
||||
{"launch_mode": "anchor"},
|
||||
{
|
||||
"launch_mode": "anchor",
|
||||
"connector": connector,
|
||||
}
|
||||
"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
|
||||
|
||||
@@ -3,14 +3,20 @@
|
||||
<package format="3">
|
||||
<name>anchor_pkg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>Anchor -- ROS and CAN relay node</description>
|
||||
<description>ASTRA VicCAN driver package, using python-can and pyserial.</description>
|
||||
<maintainer email="rjm0037@uah.edu">Riley</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>common_interfaces</depend>
|
||||
<depend>python3-serial</depend>
|
||||
<depend>python3-can</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>
|
||||
<exec_depend>bio_pkg</exec_depend>
|
||||
<exec_depend>core_description</exec_depend>
|
||||
|
||||
<build_depend>black</build_depend>
|
||||
|
||||
|
||||
@@ -2,3 +2,5 @@
|
||||
script_dir=$base/lib/anchor_pkg
|
||||
[install]
|
||||
install_scripts=$base/lib/anchor_pkg
|
||||
[build_scripts]
|
||||
executable= /usr/bin/env python3
|
||||
|
||||
@@ -6,7 +6,7 @@ package_name = "anchor_pkg"
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version="0.0.0",
|
||||
version="1.0.0",
|
||||
packages=find_packages(exclude=["test"]),
|
||||
data_files=[
|
||||
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
||||
@@ -17,8 +17,8 @@ setup(
|
||||
zip_safe=True,
|
||||
maintainer="tristan",
|
||||
maintainer_email="tristanmcginnis26@gmail.com",
|
||||
description="Anchor node used to run all modules through a single modules MCU/Computer. Commands to all modules will be relayed through CAN",
|
||||
license="All Rights Reserved",
|
||||
description="ASTRA VicCAN driver package, using python-can and pyserial.",
|
||||
license="AGPL-3.0-only",
|
||||
entry_points={
|
||||
"console_scripts": ["anchor = anchor_pkg.anchor_node:main"],
|
||||
},
|
||||
|
||||
@@ -1,5 +1,4 @@
|
||||
import sys
|
||||
import threading
|
||||
import signal
|
||||
import math
|
||||
from warnings import deprecated
|
||||
@@ -13,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,
|
||||
@@ -26,8 +25,6 @@ control_qos = qos.QoSProfile(
|
||||
# liveliness_lease_duration=Duration(seconds=5),
|
||||
)
|
||||
|
||||
thread = None
|
||||
|
||||
|
||||
class ArmNode(Node):
|
||||
"""Relay between Anchor and Basestation/Headless/Moveit2 for Arm related topics."""
|
||||
@@ -115,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,
|
||||
)
|
||||
@@ -129,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
|
||||
|
||||
@@ -148,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)
|
||||
@@ -173,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.")
|
||||
@@ -202,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
|
||||
@@ -290,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])
|
||||
@@ -376,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]
|
||||
|
||||
@@ -3,14 +3,15 @@
|
||||
<package format="3">
|
||||
<name>arm_pkg</name>
|
||||
<version>1.0.0</version>
|
||||
<description>Core arm package which handles ROS2 commnuication.</description>
|
||||
<maintainer email="tristanmcginnis26@gmail.com">tristan</maintainer>
|
||||
<description>Relays topics related to Arm between VicCAN (through Anchor) and basestation.</description>
|
||||
<maintainer email="ds0196@uah.edu">David Sharpe</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>common_interfaces</depend>
|
||||
<depend>python3-numpy</depend>
|
||||
<depend>astra_msgs</depend>
|
||||
|
||||
<exec_depend>common_interfaces</exec_depend>
|
||||
<exec_depend>python3-numpy</exec_depend>
|
||||
<exec_depend>astra_msgs</exec_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
|
||||
@@ -12,9 +12,9 @@ setup(
|
||||
],
|
||||
install_requires=["setuptools"],
|
||||
zip_safe=True,
|
||||
maintainer="David",
|
||||
maintainer="David Sharpe",
|
||||
maintainer_email="ds0196@uah.edu",
|
||||
description="Relays topics related to the arm between VicCAN (through Anchor) and basestation.",
|
||||
description="Relays topics related to Arm between VicCAN (through Anchor) and basestation.",
|
||||
license="AGPL-3.0-only",
|
||||
entry_points={
|
||||
"console_scripts": ["arm = arm_pkg.arm_node:main"],
|
||||
|
||||
Submodule src/astra_descriptions updated: c36bd8233d...e9dd878727
Submodule src/astra_msgs updated: 2264a2cb67...5a20f3f569
@@ -2,14 +2,16 @@
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>bio_pkg</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="tristanmcginnis26@gmail.com">tristan</maintainer>
|
||||
<version>1.0.0</version>
|
||||
<description>Biosensor package to handle command interpretation and embedded interfacing.</description>
|
||||
<maintainer email="ds0196@uah.edu">David Sharpe</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>common_interfaces</depend>
|
||||
<depend>astra_msgs</depend>
|
||||
|
||||
<exec_depend>common_interfaces</exec_depend>
|
||||
|
||||
<exec_depend>astra_msgs</exec_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
|
||||
@@ -2,3 +2,5 @@
|
||||
script_dir=$base/lib/bio_pkg
|
||||
[install]
|
||||
install_scripts=$base/lib/bio_pkg
|
||||
[build_scripts]
|
||||
executable= /usr/bin/env python3
|
||||
|
||||
@@ -14,8 +14,8 @@ setup(
|
||||
zip_safe=True,
|
||||
maintainer="tristan",
|
||||
maintainer_email="tristanmcginnis26@gmail.com",
|
||||
description="TODO: Package description",
|
||||
license="TODO: License declaration",
|
||||
description="Relays topics related to Biosensor between VicCAN (through Anchor) and basestation.",
|
||||
license="AGPL-3.0-only",
|
||||
entry_points={
|
||||
"console_scripts": ["bio = bio_pkg.bio_node:main"],
|
||||
},
|
||||
|
||||
@@ -1,112 +0,0 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
|
||||
import pygame
|
||||
|
||||
import time
|
||||
|
||||
import serial
|
||||
import sys
|
||||
import threading
|
||||
import glob
|
||||
import os
|
||||
|
||||
import importlib
|
||||
from std_msgs.msg import String
|
||||
from astra_msgs.msg import CoreControl
|
||||
|
||||
|
||||
os.environ["SDL_VIDEODRIVER"] = "dummy" # Prevents pygame from trying to open a display
|
||||
os.environ["SDL_AUDIODRIVER"] = (
|
||||
"dummy" # Force pygame to use a dummy audio driver before pygame.init()
|
||||
)
|
||||
|
||||
|
||||
max_speed = 90 # Max speed as a duty cycle percentage (1-100)
|
||||
|
||||
|
||||
class Headless(Node):
|
||||
def __init__(self):
|
||||
# Initialize pygame first
|
||||
pygame.init()
|
||||
pygame.joystick.init()
|
||||
|
||||
# Wait for a gamepad to be connected
|
||||
self.gamepad = None
|
||||
print("Waiting for gamepad connection...")
|
||||
while pygame.joystick.get_count() == 0:
|
||||
# Process any pygame events to keep it responsive
|
||||
for event in pygame.event.get():
|
||||
if event.type == pygame.QUIT:
|
||||
pygame.quit()
|
||||
sys.exit(0)
|
||||
time.sleep(1.0) # Check every second
|
||||
print("No gamepad found. Waiting...")
|
||||
|
||||
# Initialize the gamepad
|
||||
self.gamepad = pygame.joystick.Joystick(0)
|
||||
self.gamepad.init()
|
||||
print(f"Gamepad Found: {self.gamepad.get_name()}")
|
||||
|
||||
# Now initialize the ROS2 node
|
||||
super().__init__("core_headless")
|
||||
self.create_timer(0.15, self.send_controls)
|
||||
self.publisher = self.create_publisher(CoreControl, "/core/control", 10)
|
||||
self.lastMsg = (
|
||||
String()
|
||||
) # Used to ignore sending controls repeatedly when they do not change
|
||||
|
||||
def run(self):
|
||||
# This thread makes all the update processes run in the background
|
||||
thread = threading.Thread(target=rclpy.spin, args={self}, daemon=True)
|
||||
thread.start()
|
||||
|
||||
try:
|
||||
while rclpy.ok():
|
||||
self.send_controls()
|
||||
time.sleep(0.1) # Small delay to avoid CPU hogging
|
||||
except KeyboardInterrupt:
|
||||
sys.exit(0)
|
||||
|
||||
def send_controls(self):
|
||||
for event in pygame.event.get():
|
||||
if event.type == pygame.QUIT:
|
||||
pygame.quit()
|
||||
sys.exit(0)
|
||||
|
||||
# Check if controller is still connected
|
||||
if pygame.joystick.get_count() == 0:
|
||||
print("Gamepad disconnected. Exiting...")
|
||||
# Send one last zero control message
|
||||
input = CoreControl()
|
||||
input.left_stick = 0
|
||||
input.right_stick = 0
|
||||
input.max_speed = 0
|
||||
self.publisher.publish(input)
|
||||
self.get_logger().info("Final stop command sent. Shutting down.")
|
||||
# Clean up
|
||||
pygame.quit()
|
||||
sys.exit(0)
|
||||
|
||||
input = CoreControl()
|
||||
input.max_speed = max_speed
|
||||
input.right_stick = -1 * round(self.gamepad.get_axis(4), 2) # right y-axis
|
||||
if self.gamepad.get_axis(5) > 0:
|
||||
input.left_stick = input.right_stick
|
||||
else:
|
||||
input.left_stick = -1 * round(self.gamepad.get_axis(1), 2) # left y-axis
|
||||
|
||||
output = f"L: {input.left_stick}, R: {input.right_stick}, M: {max_speed}"
|
||||
self.get_logger().info(f"[Ctrl] {output}")
|
||||
self.publisher.publish(input)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
node = Headless()
|
||||
rclpy.spin(node)
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
File diff suppressed because it is too large
Load Diff
@@ -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."""
|
||||
|
||||
@@ -3,15 +3,17 @@
|
||||
<package format="3">
|
||||
<name>core_pkg</name>
|
||||
<version>1.0.0</version>
|
||||
<description>Core rover control package to handle command interpretation and embedded interfacing.</description>
|
||||
<maintainer email="tristanmcginnis26@gmail.com">tristan</maintainer>
|
||||
<description>Relays topics related to Core between VicCAN (through Anchor) and basestation.</description>
|
||||
<maintainer email="ds0196@uah.edu">David Sharpe</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>common_interfaces</depend>
|
||||
<depend>python3-scipy</depend>
|
||||
<depend>python-crccheck-pip</depend>
|
||||
<depend>astra_msgs</depend>
|
||||
|
||||
<exec_depend>common_interfaces</exec_depend>
|
||||
<exec_depend>python3-scipy</exec_depend>
|
||||
<exec_depend>python-crccheck-pip</exec_depend>
|
||||
|
||||
<exec_depend>astra_msgs</exec_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
|
||||
@@ -2,3 +2,5 @@
|
||||
script_dir=$base/lib/core_pkg
|
||||
[install]
|
||||
install_scripts=$base/lib/core_pkg
|
||||
[build_scripts]
|
||||
executable= /usr/bin/env python3
|
||||
|
||||
@@ -4,7 +4,7 @@ package_name = "core_pkg"
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version="0.0.0",
|
||||
version="1.0.0",
|
||||
packages=find_packages(exclude=["test"]),
|
||||
data_files=[
|
||||
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
||||
@@ -12,14 +12,13 @@ setup(
|
||||
],
|
||||
install_requires=["setuptools"],
|
||||
zip_safe=True,
|
||||
maintainer="tristan",
|
||||
maintainer_email="tristanmcginnis26@gmail.com",
|
||||
description="Core rover control package to handle command interpretation and embedded interfacing.",
|
||||
license="All Rights Reserved",
|
||||
maintainer="David Sharpe",
|
||||
maintainer_email="ds0196@uah.edu",
|
||||
description="Relays topics related to Core between VicCAN (through Anchor) and basestation.",
|
||||
license="AGPL-3.0-only",
|
||||
entry_points={
|
||||
"console_scripts": [
|
||||
"core = core_pkg.core_node:main",
|
||||
"headless = core_pkg.core_headless:main",
|
||||
"ptz = core_pkg.core_ptz:main",
|
||||
],
|
||||
},
|
||||
|
||||
@@ -3,14 +3,15 @@
|
||||
<package format="3">
|
||||
<name>headless_pkg</name>
|
||||
<version>1.0.0</version>
|
||||
<description>Headless rover control package to handle command interpretation and embedded interfacing.</description>
|
||||
<description>Provides headless rover control, similar to Basestation.</description>
|
||||
<maintainer email="ds0196@uah.edu">David Sharpe</maintainer>
|
||||
<license>AGPL-3.0-only</license>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>common_interfaces</depend>
|
||||
<depend>python3-pygame</depend>
|
||||
<depend>astra_msgs</depend>
|
||||
|
||||
<exec_depend>common_interfaces</exec_depend>
|
||||
<exec_depend>python3-pygame</exec_depend>
|
||||
<exec_depend>astra_msgs</exec_depend>
|
||||
|
||||
<test_depend>ament_copyright</test_depend>
|
||||
<test_depend>ament_flake8</test_depend>
|
||||
|
||||
@@ -2,3 +2,5 @@
|
||||
script_dir=$base/lib/headless_pkg
|
||||
[install]
|
||||
install_scripts=$base/lib/headless_pkg
|
||||
[build_scripts]
|
||||
executable= /usr/bin/env python3
|
||||
|
||||
@@ -14,11 +14,9 @@ setup(
|
||||
zip_safe=True,
|
||||
maintainer="David Sharpe",
|
||||
maintainer_email="ds0196@uah.edu",
|
||||
description="Headless rover control package to handle command interpretation and embedded interfacing.",
|
||||
license="All Rights Reserved",
|
||||
description="Provides headless rover control, similar to Basestation.",
|
||||
license="AGPL-3.0-only",
|
||||
entry_points={
|
||||
"console_scripts": [
|
||||
"headless_full = src.headless_node:main",
|
||||
],
|
||||
"console_scripts": ["headless_full = src.headless_node:main"],
|
||||
},
|
||||
)
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -138,6 +138,11 @@ class Headless(Node):
|
||||
self.get_parameter("use_old_topics").get_parameter_value().bool_value
|
||||
)
|
||||
|
||||
self.declare_parameter("use_cmd_vel", False)
|
||||
self.use_cmd_vel = (
|
||||
self.get_parameter("use_cmd_vel").get_parameter_value().bool_value
|
||||
)
|
||||
|
||||
self.declare_parameter("use_bio", False)
|
||||
self.use_bio = self.get_parameter("use_bio").get_parameter_value().bool_value
|
||||
|
||||
@@ -145,7 +150,6 @@ class Headless(Node):
|
||||
self.use_arm_ik = (
|
||||
self.get_parameter("use_arm_ik").get_parameter_value().bool_value
|
||||
)
|
||||
|
||||
# NOTE: only applicable if use_old_topics == True
|
||||
self.declare_parameter("use_new_arm_manual_scheme", True)
|
||||
self.use_new_arm_manual_scheme = (
|
||||
@@ -155,6 +159,13 @@ class Headless(Node):
|
||||
)
|
||||
|
||||
# Check parameter validity
|
||||
if self.use_cmd_vel:
|
||||
self.get_logger().info("Using cmd_vel for core control")
|
||||
global CORE_MODE
|
||||
CORE_MODE = "twist"
|
||||
else:
|
||||
self.get_logger().info("Using astra_msgs/CoreControl for core control")
|
||||
|
||||
if self.use_arm_ik and self.use_old_topics:
|
||||
self.get_logger().fatal("Old topics do not support arm IK control.")
|
||||
sys.exit(1)
|
||||
@@ -166,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
|
||||
@@ -184,12 +197,18 @@ class Headless(Node):
|
||||
self.core_twist_pub_ = self.create_publisher(
|
||||
Twist, "/core/twist", qos_profile=control_qos
|
||||
)
|
||||
self.core_cmd_vel_pub_ = self.create_publisher(
|
||||
TwistStamped, "/diff_controller/cmd_vel", qos_profile=control_qos
|
||||
)
|
||||
self.core_state_pub_ = self.create_publisher(
|
||||
CoreCtrlState, "/core/control/state", qos_profile=control_qos
|
||||
)
|
||||
|
||||
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(
|
||||
@@ -231,13 +250,19 @@ class Headless(Node):
|
||||
# Rumble when node is ready (returns False if rumble not supported)
|
||||
self.gamepad.rumble(0.7, 0.8, 150)
|
||||
|
||||
# Added so you can tell when it starts running after changing the constant logging to debug from info
|
||||
self.get_logger().info("Defaulting to Core mode. Ready.")
|
||||
|
||||
def stop_all(self):
|
||||
if self.use_old_topics:
|
||||
self.core_publisher.publish(CORE_STOP_MSG)
|
||||
self.arm_publisher.publish(ARM_STOP_MSG)
|
||||
self.bio_publisher.publish(BIO_STOP_MSG)
|
||||
else:
|
||||
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG)
|
||||
if self.use_cmd_vel:
|
||||
self.core_cmd_vel_pub_.publish(self.core_cmd_vel_stop_msg())
|
||||
else:
|
||||
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG)
|
||||
if self.use_arm_ik:
|
||||
self.arm_ik_twist_publisher.publish(self.arm_ik_twist_stop_msg())
|
||||
else:
|
||||
@@ -332,18 +357,32 @@ class Headless(Node):
|
||||
self.core_publisher.publish(input)
|
||||
|
||||
else: # New topics
|
||||
input = Twist()
|
||||
twist = Twist()
|
||||
|
||||
# Forward/back and Turn
|
||||
input.linear.x = -1.0 * left_stick_y
|
||||
input.angular.z = -1.0 * copysign(
|
||||
twist.linear.x = -1.0 * left_stick_y
|
||||
twist.angular.z = -1.0 * copysign(
|
||||
right_stick_x**2, right_stick_x
|
||||
) # 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.
|
||||
if self.use_cmd_vel:
|
||||
# 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
|
||||
self.core_twist_pub_.publish(input)
|
||||
self.get_logger().info(
|
||||
f"[Core Ctrl] Linear: {round(input.linear.x, 2)}, Angular: {round(input.angular.z, 2)}"
|
||||
if self.use_cmd_vel:
|
||||
header = Header(stamp=self.get_clock().now().to_msg())
|
||||
self.core_cmd_vel_pub_.publish(TwistStamped(header=header, twist=twist))
|
||||
else:
|
||||
self.core_twist_pub_.publish(twist)
|
||||
self.get_logger().debug(
|
||||
f"[Core Ctrl] Linear: {round(twist.linear.x, 2)}, Angular: {round(twist.angular.z, 2)}"
|
||||
)
|
||||
|
||||
# Brake mode
|
||||
@@ -552,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)
|
||||
# =============
|
||||
|
||||
@@ -643,6 +695,11 @@ class Headless(Node):
|
||||
else:
|
||||
pass # TODO: implement new bio control topics
|
||||
|
||||
def core_cmd_vel_stop_msg(self):
|
||||
return TwistStamped(
|
||||
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg())
|
||||
)
|
||||
|
||||
def arm_manual_stop_msg(self):
|
||||
return JointJog(
|
||||
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()),
|
||||
|
||||
Reference in New Issue
Block a user