3 Commits

Author SHA1 Message Date
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
3 changed files with 40 additions and 10 deletions

View File

@@ -79,8 +79,9 @@ class CoreNode(Node):
self.get_logger().info( self.get_logger().info(
"rover_platform parameter is unset, falling back to environment variable" "rover_platform parameter is unset, falling back to environment variable"
) )
rover_platform = getenv("ROVER_PLATFORM", "clucky") rover_platform = getenv("ROVER_PLATFORM", "clucky").lower()
if rover_platform not in ("clucky", "testbed"): # make sure we have a valid value # Verify rover_platform value is valid
if rover_platform not in ("clucky", "testbed"):
raise ValueError("rover platform must be either 'clucky' or 'testbed'.") raise ValueError("rover platform must be either 'clucky' or 'testbed'.")
else: else:
self.rover_platform = cast(Literal["clucky", "testbed"], rover_platform) self.rover_platform = cast(Literal["clucky", "testbed"], rover_platform)
@@ -179,9 +180,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 +284,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: