feat(core): change rover_platform parameter to override, default with hostname instead of environment variable

This commit is contained in:
David
2026-04-12 17:37:39 -05:00
parent ab4f998ac1
commit 90a9519b55
2 changed files with 25 additions and 16 deletions

View File

@@ -58,10 +58,10 @@ def generate_launch_description():
ld.add_action( ld.add_action(
DeclareLaunchArgument( DeclareLaunchArgument(
"rover_platform", "rover_platform_override",
default_value="auto", default_value="",
description="Choose the rover platform (either clucky or testbed). If left on auto, will defer to ROVER_PLATFORM environment variable.", description="Override the rover platform (either clucky or testbed). If unset, hostname is used; defaults to clucky without hostname.",
choices=["clucky", "testbed", "auto"], choices=["clucky", "testbed", ""],
) )
) )
@@ -120,8 +120,8 @@ def generate_launch_description():
) )
}, },
{ {
"rover_platform": LaunchConfiguration( "rover_platform_override": LaunchConfiguration(
"rover_platform", default="auto" "rover_platform_override", default="auto"
) )
}, },
], ],

View File

@@ -5,6 +5,7 @@ from scipy.spatial.transform import Rotation
from math import copysign, pi from math import copysign, pi
from warnings import deprecated from warnings import deprecated
from os import getenv from os import getenv
from socket import gethostname
import rclpy import rclpy
from rclpy.node import Node from rclpy.node import Node
@@ -71,20 +72,28 @@ class CoreNode(Node):
self.get_parameter("use_ros2_control").get_parameter_value().bool_value self.get_parameter("use_ros2_control").get_parameter_value().bool_value
) )
self.declare_parameter("rover_platform", "auto") self.declare_parameter("rover_platform_override", "")
rover_platform = ( rover_platform = (
self.get_parameter("rover_platform").get_parameter_value().string_value self.get_parameter("rover_platform_override")
.get_parameter_value()
.string_value
) )
if rover_platform == "auto": # Verify rover_platform_override value is valid
self.get_logger().info( if rover_platform not in ("clucky", "testbed", ""):
"rover_platform parameter is unset, falling back to environment variable" # Keeping this here, because I want a value error only if the user manually
# overrides using a bad value. If we can't determine it automatically
# from hostname, then default to clucky.
self.get_logger().fatal(
"Invalid rover_platform_override parameter value. If set, must be 'clucky' or 'testbed'."
) )
rover_platform = getenv("ROVER_PLATFORM", "clucky").lower() # Attempt to determine platform from hostname, default to clucky on failure
# Verify rover_platform value is valid rover_platform = rover_platform or gethostname().lower()
if rover_platform not in ("clucky", "testbed"): if rover_platform not in ("clucky", "testbed"):
raise ValueError("rover platform must be either 'clucky' or 'testbed'.") self.get_logger().info(
else: "rover_platform defaulting to clucky, not overridden and could not determine from hostname."
self.rover_platform = cast(Literal["clucky", "testbed"], rover_platform) )
rover_platform = "clucky"
self.rover_platform = cast(Literal["clucky", "testbed"], rover_platform)
if self.rover_platform == "testbed": if self.rover_platform == "testbed":
global TESTBED_WHEELBASE, TESTBED_WHEEL_RADIUS, TESTBED_GEAR_RATIO global TESTBED_WHEELBASE, TESTBED_WHEEL_RADIUS, TESTBED_GEAR_RATIO