finish adding parameters

This commit is contained in:
ryleu
2026-03-23 20:39:50 -05:00
parent fe46a2ab4d
commit f7efa604d2
4 changed files with 91 additions and 8 deletions

View File

@@ -60,6 +60,20 @@ $ ros2 launch anchor_pkg rover.launch.py # Must be run on a computer connected
$ ros2 run headless_pkg headless_full # Optionally run in a separate shell on the same or different computer. $ ros2 run headless_pkg headless_full # Optionally run in a separate shell on the same or different computer.
``` ```
### Using the Mock Connector
Anchor provides a mock connector meant for testing and scripting purposes. You can select the mock connector by running anchor with this command:
```bash
$ ros2 launch anchor_pkg rover.launch.py connector:="mock"
```
You can see all data sent to it in a string format with this command:
```bash
$ ros2 topic echo /anchor/to_vic/debug
```
### Testing Serial ### Testing Serial
You can fake the presence of a Serial device (i.e., MCU) by using the following command: You can fake the presence of a Serial device (i.e., MCU) by using the following command:
@@ -68,10 +82,31 @@ You can fake the presence of a Serial device (i.e., MCU) by using the following
$ socat -dd -v pty,rawer,crnl,link=/tmp/ttyACM9 pty,rawer,crnl,link=/tmp/ttyOUT $ socat -dd -v pty,rawer,crnl,link=/tmp/ttyACM9 pty,rawer,crnl,link=/tmp/ttyOUT
``` ```
When you go to run anchor, use the `PORT_OVERRIDE` environment variable to point it to the fake serial port, like so: When you go to run anchor, use the `serial_override` ROS2 parameter to point it to the fake serial port, like so:
```bash ```bash
$ PORT_OVERRIDE=/tmp/ttyACM9 ros2 launch anchor_pkg rover.launch.py $ ros2 launch anchor_pkg rover.launch.py connector:=serial serial_override:=/tmp/ttyACM9
```
### Testing CAN
You can create a virtual CAN network by using the following commands to create and then enable it:
```bash
sudo ip link add dev vcan0 type vcan
sudo ip link set vcan0 up
```
When you go to run anchor, use the `can_override` ROS2 parameter to point it to the virtual CAN network, like so:
```bash
$ ros2 launch anchor_pkg rover.launch.py connector:=can can_override:=vcan0
```
Once you're done, you should delete the virtual network so that anchor doesn't get confused if you plug in a real CAN adapter:
```bash
$ sudo ip link delete vcan0
``` ```
### Connecting the GuliKit Controller ### Connecting the GuliKit Controller

View File

@@ -51,6 +51,8 @@ class Anchor(Node):
logger = self.get_logger() logger = self.get_logger()
# ROS2 Parameter Setup
self.declare_parameter( self.declare_parameter(
"connector", "connector",
"auto", "auto",
@@ -73,6 +75,17 @@ class Anchor(Node):
), ),
) )
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 # Determine which connector to use. Options are Mock, Serial, and CAN
connector_select = ( connector_select = (
self.get_parameter("connector").get_parameter_value().string_value self.get_parameter("connector").get_parameter_value().string_value
@@ -80,10 +93,15 @@ class Anchor(Node):
can_override = ( can_override = (
self.get_parameter("can_override").get_parameter_value().string_value 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: match connector_select:
case "serial": case "serial":
logger.info("using serial connector") logger.info("using serial connector")
self.connector = SerialConnector(logger, self.get_clock()) self.connector = SerialConnector(
logger, self.get_clock(), serial_override
)
case "can": case "can":
logger.info("using CAN connector") logger.info("using CAN connector")
self.connector = CANConnector(logger, self.get_clock(), can_override) self.connector = CANConnector(logger, self.get_clock(), can_override)
@@ -99,7 +117,9 @@ class Anchor(Node):
) )
except (NoValidDeviceException, NoWorkingDeviceException, TypeError): except (NoValidDeviceException, NoWorkingDeviceException, TypeError):
logger.info("CAN connector failed, trying serial connector") logger.info("CAN connector failed, trying serial connector")
self.connector = SerialConnector(logger, self.get_clock()) self.connector = SerialConnector(
logger, self.get_clock(), serial_override
)
case _: case _:
logger.fatal( logger.fatal(
f"invalid value for connector parameter: {connector_select}" f"invalid value for connector parameter: {connector_select}"

View File

@@ -78,12 +78,19 @@ class SerialConnector(Connector):
port: str port: str
mcu_name: str mcu_name: str
serial_interface: serial.Serial serial_interface: serial.Serial
override: bool
def __init__(self, logger: RcutilsLogger, clock: Clock): def __init__(self, logger: RcutilsLogger, clock: Clock, serial_override: str = ""):
super().__init__(logger, clock) super().__init__(logger, clock)
ports = self._find_ports() 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: if len(ports) <= 0:
raise NoValidDeviceException("no valid serial device found") raise NoValidDeviceException("no valid serial device found")
@@ -94,7 +101,8 @@ class SerialConnector(Connector):
# check each of our ports to make sure one of them is responding # check each of our ports to make sure one of them is responding
port = ports[0] 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: if not mcu_name:
raise NoWorkingDeviceException( raise NoWorkingDeviceException(
f"found {port}, but it did not respond with its name" f"found {port}, but it did not respond with its name"

View File

@@ -7,6 +7,8 @@ from launch_ros.actions import Node
def generate_launch_description(): def generate_launch_description():
connector = LaunchConfiguration("connector") connector = LaunchConfiguration("connector")
serial_override = LaunchConfiguration("serial_override")
can_override = LaunchConfiguration("can_override")
use_ptz = LaunchConfiguration("use_ptz") use_ptz = LaunchConfiguration("use_ptz")
ld = LaunchDescription() ld = LaunchDescription()
@@ -16,7 +18,23 @@ def generate_launch_description():
DeclareLaunchArgument( DeclareLaunchArgument(
"connector", "connector",
default_value="auto", 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="auto",
description="CAN network override parameter for anchor node (default: '')",
) )
) )
@@ -82,6 +100,8 @@ def generate_launch_description():
{ {
"launch_mode": "anchor", "launch_mode": "anchor",
"connector": connector, "connector": connector,
"serial_override": serial_override,
"can_override": can_override,
} }
], ],
on_exit=Shutdown(), on_exit=Shutdown(),