mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
3 Commits
5e0946e8d7
...
ab4f998ac1
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ab4f998ac1 | ||
|
|
b3f996113c | ||
|
|
191c9d613d |
Submodule src/astra_descriptions updated: 04c2061443...e9dd878727
@@ -79,8 +79,9 @@ class CoreNode(Node):
|
||||
self.get_logger().info(
|
||||
"rover_platform parameter is unset, falling back to environment variable"
|
||||
)
|
||||
rover_platform = getenv("ROVER_PLATFORM", "clucky")
|
||||
if rover_platform not in ("clucky", "testbed"): # make sure we have a valid value
|
||||
rover_platform = getenv("ROVER_PLATFORM", "clucky").lower()
|
||||
# Verify rover_platform value is valid
|
||||
if rover_platform not in ("clucky", "testbed"):
|
||||
raise ValueError("rover platform must be either 'clucky' or 'testbed'.")
|
||||
else:
|
||||
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
|
||||
)
|
||||
|
||||
###################################################
|
||||
# Timers
|
||||
|
||||
if self.use_ros2_control:
|
||||
self.vel_cmd_timer_ = self.create_timer(0.1, self.vel_cmd_timer_callback)
|
||||
|
||||
###################################################
|
||||
# Saved state
|
||||
|
||||
# Controls
|
||||
self._last_joint_command_time = self.get_clock().now()
|
||||
self._last_joint_command_msg = JointState()
|
||||
|
||||
# Main Core feedback
|
||||
self.feedback_new_state = NewCoreFeedback()
|
||||
self.feedback_new_state.fl_motor.id = 1
|
||||
@@ -273,16 +284,31 @@ class CoreNode(Node):
|
||||
)
|
||||
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
|
||||
br_rpm = radps_to_rpm(br_vel) * self.gear_ratio
|
||||
fl_rpm = radps_to_rpm(fl_vel) * self.gear_ratio
|
||||
fr_rpm = radps_to_rpm(fr_vel) * self.gear_ratio
|
||||
|
||||
self.send_viccan(
|
||||
20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]
|
||||
) # order expected by embedded
|
||||
self.send_viccan(20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]) # REV Velocity
|
||||
|
||||
def twist_man_callback(self, msg: Twist):
|
||||
linear = msg.linear.x # [-1 1] for forward/back from left stick y
|
||||
|
||||
@@ -366,10 +366,14 @@ class Headless(Node):
|
||||
) # 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
|
||||
# maintains the separation between modifying the control message and sending it.
|
||||
if self.use_cmd_vel:
|
||||
twist.linear.x *= 1.5
|
||||
twist.angular.z *= 0.5
|
||||
# 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
|
||||
if self.use_cmd_vel:
|
||||
|
||||
Reference in New Issue
Block a user