6 Commits

Author SHA1 Message Date
David
90a9519b55 feat(core): change rover_platform parameter to override, default with hostname instead of environment variable 2026-04-12 17:37:39 -05:00
David
ab4f998ac1 feat(core): rate limit motor commands from diff_drive_controller 2026-04-11 21:07:21 -05:00
David
b3f996113c chore: bump astra_descriptions 2026-04-11 19:33:07 -05:00
David
191c9d613d fix(headless): correctly scale cmd_vel values 2026-04-11 19:12:49 -05:00
David
5e0946e8d7 fix(core): align rover_platform parameter with launch file
Launch file uses clucky, testbed, auto. Node was using core, testbed, auto. Replaced core with clucky in the node.
2026-04-11 00:22:51 -05:00
David
3dd80bbd29 fix(arm): change old anchor topic bacc 2026-04-11 00:21:09 -05:00
5 changed files with 65 additions and 28 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

@@ -78,9 +78,7 @@ class ArmNode(Node):
self.anchor_sub = self.create_subscription( self.anchor_sub = self.create_subscription(
String, "/anchor/arm/feedback", self.anchor_feedback, 10 String, "/anchor/arm/feedback", self.anchor_feedback, 10
) )
self.anchor_pub = self.create_publisher( self.anchor_pub = self.create_publisher(String, "/anchor/relay", 10)
String, "/anchor/to_vic/relay_string", 10
)
# Create publishers # Create publishers
self.socket_pub = self.create_publisher( self.socket_pub = self.create_publisher(

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
@@ -56,7 +57,7 @@ class CoreNode(Node):
56: 4, # really 3, but viccan 56: 4, # really 3, but viccan
58: 4, # ditto 58: 4, # ditto
} }
rover_platform: Literal["core", "testbed"] rover_platform: Literal["clucky", "testbed"]
def __init__(self): def __init__(self):
super().__init__("core_node") super().__init__("core_node")
@@ -71,19 +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", "auto") # Attempt to determine platform from hostname, default to clucky on failure
if rover_platform not in ("core", "testbed"): # make sure we have a valid value rover_platform = rover_platform or gethostname().lower()
raise ValueError("rover platform must be either 'core' or 'testbed'.") if rover_platform not in ("clucky", "testbed"):
else: self.get_logger().info(
self.rover_platform = cast(Literal["core", "testbed"], rover_platform) "rover_platform defaulting to clucky, not overridden and could not determine from hostname."
)
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
@@ -179,9 +189,19 @@ class CoreNode(Node):
Barometer, "/core/feedback/baro", qos_profile=qos.qos_profile_sensor_data Barometer, "/core/feedback/baro", qos_profile=qos.qos_profile_sensor_data
) )
###################################################
# Timers
if self.use_ros2_control:
self.vel_cmd_timer_ = self.create_timer(0.1, self.vel_cmd_timer_callback)
################################################### ###################################################
# Saved state # Saved state
# Controls
self._last_joint_command_time = self.get_clock().now()
self._last_joint_command_msg = JointState()
# Main Core feedback # Main Core feedback
self.feedback_new_state = NewCoreFeedback() self.feedback_new_state = NewCoreFeedback()
self.feedback_new_state.fl_motor.id = 1 self.feedback_new_state.fl_motor.id = 1
@@ -273,16 +293,31 @@ class CoreNode(Node):
) )
return return
(bl_vel, br_vel, fl_vel, fr_vel) = msg.velocity # A 10 Hz timer callback actually sends these commands to Core for rate limiting
# These come from ros2_control at 50 Hz
self._last_joint_command_time = self.get_clock().now()
self._last_joint_command_msg = msg
def vel_cmd_timer_callback(self):
# Safety timeout for diff_drive_controller commands via topic_based_ros2_control.
# It is safe to send stop command here because if self.use_ros2_control,
# then this is the only callback that is controlling Core's motors.
if self.get_clock().now() - self._last_joint_command_time > Duration(
nanoseconds=int(1e8) # 100ms
):
self.send_viccan(20, [0.0, 0.0, 0.0, 0.0])
return
# This order is verified by the subscription callback
(bl_vel, br_vel, fl_vel, fr_vel) = self._last_joint_command_msg.velocity
# Convert wheel rad/s to motor RPM
bl_rpm = radps_to_rpm(bl_vel) * self.gear_ratio bl_rpm = radps_to_rpm(bl_vel) * self.gear_ratio
br_rpm = radps_to_rpm(br_vel) * self.gear_ratio br_rpm = radps_to_rpm(br_vel) * self.gear_ratio
fl_rpm = radps_to_rpm(fl_vel) * self.gear_ratio fl_rpm = radps_to_rpm(fl_vel) * self.gear_ratio
fr_rpm = radps_to_rpm(fr_vel) * self.gear_ratio fr_rpm = radps_to_rpm(fr_vel) * self.gear_ratio
self.send_viccan( self.send_viccan(20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]) # REV Velocity
20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]
) # order expected by embedded
def twist_man_callback(self, msg: Twist): def twist_man_callback(self, msg: Twist):
linear = msg.linear.x # [-1 1] for forward/back from left stick y linear = msg.linear.x # [-1 1] for forward/back from left stick y

View File

@@ -366,10 +366,14 @@ class Headless(Node):
) # Exponent for finer control (curve) ) # Exponent for finer control (curve)
# This kinda looks dumb being seperate from the following block, but this # This kinda looks dumb being seperate from the following block, but this
# maintains the separation between modifying the control message and sending it # maintains the separation between modifying the control message and sending it.
if self.use_cmd_vel: if self.use_cmd_vel:
twist.linear.x *= 1.5 # These scaling factors convert raw stick inputs to absolute m/s and rad/s
twist.angular.z *= 0.5 # 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 # Publish
if self.use_cmd_vel: if self.use_cmd_vel: