6 Commits

Author SHA1 Message Date
David
ff4a58e6ed refactor: (headless) finish integrating Core cmd_vel 2026-03-19 20:02:37 -05:00
David
120891c8e5 chore: update astra_msgs to main 2026-03-19 19:49:25 -05:00
David
178d5001d6 Merge remote-tracking branch 'origin/main' into core-ros2-control 2026-03-19 19:45:59 -05:00
David Sharpe
684c2994ec cmd_vel headless 2026-03-18 01:17:00 -05:00
David
bfa50e3a25 feat: (core) make compatible with ros2_control 2026-02-26 17:17:05 -06:00
David
90fbbac813 feat: add ros2 control option to main launch for core 2026-02-26 17:17:02 -06:00
5 changed files with 752 additions and 613 deletions

View File

@@ -1,14 +1,21 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction, Shutdown from launch.actions import (
DeclareLaunchArgument,
OpaqueFunction,
Shutdown,
IncludeLaunchDescription,
)
from launch.substitutions import ( from launch.substitutions import (
LaunchConfiguration, LaunchConfiguration,
ThisLaunchFileDir, ThisLaunchFileDir,
PathJoinSubstitution, PathJoinSubstitution,
) )
from launch_ros.actions import Node from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.conditions import IfCondition from launch.conditions import IfCondition
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
# Prevent making __pycache__ directories # Prevent making __pycache__ directories
@@ -41,7 +48,10 @@ def launch_setup(context, *args, **kwargs):
executable="core", # change as needed executable="core", # change as needed
name="core", name="core",
output="both", output="both",
parameters=[{"launch_mode": mode}], parameters=[
{"launch_mode": mode},
{"use_ros2_control": LaunchConfiguration("use_ros2_control", default=False)},
],
on_exit=Shutdown(), on_exit=Shutdown(),
) )
) )
@@ -135,4 +145,46 @@ def generate_launch_description():
description="Launch mode: arm, core, bio, anchor, or ptz", description="Launch mode: arm, core, bio, anchor, or ptz",
) )
return LaunchDescription([declare_arg, OpaqueFunction(function=launch_setup)]) ros2_control_arg = DeclareLaunchArgument(
"use_ros2_control",
default_value="false",
description="Whether to use DiffDriveController for driving instead of direct Twist",
)
rsp = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[
FindPackageShare("core_description"),
"launch",
"robot_state_publisher.launch.py",
]
)
),
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
launch_arguments={("hardware_mode", "physical")},
)
controllers = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[
FindPackageShare("core_description"),
"launch",
"spawn_controllers.launch.py",
]
)
),
condition=IfCondition(LaunchConfiguration("use_ros2_control")),
launch_arguments={("hardware_mode", "physical")},
)
return LaunchDescription(
[
declare_arg,
ros2_control_arg,
rsp,
controllers,
OpaqueFunction(function=launch_setup),
]
)

File diff suppressed because it is too large Load Diff

View File

@@ -138,6 +138,11 @@ class Headless(Node):
self.get_parameter("use_old_topics").get_parameter_value().bool_value self.get_parameter("use_old_topics").get_parameter_value().bool_value
) )
self.declare_parameter("use_cmd_vel", False)
self.use_cmd_vel = (
self.get_parameter("use_cmd_vel").get_parameter_value().bool_value
)
self.declare_parameter("use_bio", False) self.declare_parameter("use_bio", False)
self.use_bio = self.get_parameter("use_bio").get_parameter_value().bool_value self.use_bio = self.get_parameter("use_bio").get_parameter_value().bool_value
@@ -145,7 +150,6 @@ class Headless(Node):
self.use_arm_ik = ( self.use_arm_ik = (
self.get_parameter("use_arm_ik").get_parameter_value().bool_value self.get_parameter("use_arm_ik").get_parameter_value().bool_value
) )
# NOTE: only applicable if use_old_topics == True # NOTE: only applicable if use_old_topics == True
self.declare_parameter("use_new_arm_manual_scheme", True) self.declare_parameter("use_new_arm_manual_scheme", True)
self.use_new_arm_manual_scheme = ( self.use_new_arm_manual_scheme = (
@@ -155,6 +159,13 @@ class Headless(Node):
) )
# Check parameter validity # Check parameter validity
if self.use_cmd_vel:
self.get_logger().info("Using cmd_vel for core control")
global CORE_MODE
CORE_MODE = "twist"
else:
self.get_logger().info("Using astra_msgs/CoreControl for core control")
if self.use_arm_ik and self.use_old_topics: if self.use_arm_ik and self.use_old_topics:
self.get_logger().fatal("Old topics do not support arm IK control.") self.get_logger().fatal("Old topics do not support arm IK control.")
sys.exit(1) sys.exit(1)
@@ -184,6 +195,9 @@ class Headless(Node):
self.core_twist_pub_ = self.create_publisher( self.core_twist_pub_ = self.create_publisher(
Twist, "/core/twist", qos_profile=control_qos Twist, "/core/twist", qos_profile=control_qos
) )
self.core_cmd_vel_pub_ = self.create_publisher(
TwistStamped, "/diff_controller/cmd_vel", qos_profile=control_qos
)
self.core_state_pub_ = self.create_publisher( self.core_state_pub_ = self.create_publisher(
CoreCtrlState, "/core/control/state", qos_profile=control_qos CoreCtrlState, "/core/control/state", qos_profile=control_qos
) )
@@ -231,13 +245,19 @@ class Headless(Node):
# Rumble when node is ready (returns False if rumble not supported) # Rumble when node is ready (returns False if rumble not supported)
self.gamepad.rumble(0.7, 0.8, 150) self.gamepad.rumble(0.7, 0.8, 150)
# Added so you can tell when it starts running after changing the constant logging to debug from info
self.get_logger().info("Defaulting to Core mode. Ready.")
def stop_all(self): def stop_all(self):
if self.use_old_topics: if self.use_old_topics:
self.core_publisher.publish(CORE_STOP_MSG) self.core_publisher.publish(CORE_STOP_MSG)
self.arm_publisher.publish(ARM_STOP_MSG) self.arm_publisher.publish(ARM_STOP_MSG)
self.bio_publisher.publish(BIO_STOP_MSG) self.bio_publisher.publish(BIO_STOP_MSG)
else: else:
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG) if self.use_cmd_vel:
self.core_cmd_vel_pub_.publish(self.core_cmd_vel_stop_msg())
else:
self.core_twist_pub_.publish(CORE_STOP_TWIST_MSG)
if self.use_arm_ik: if self.use_arm_ik:
self.arm_ik_twist_publisher.publish(self.arm_ik_twist_stop_msg()) self.arm_ik_twist_publisher.publish(self.arm_ik_twist_stop_msg())
else: else:
@@ -332,18 +352,28 @@ class Headless(Node):
self.core_publisher.publish(input) self.core_publisher.publish(input)
else: # New topics else: # New topics
input = Twist() twist = Twist()
# Forward/back and Turn # Forward/back and Turn
input.linear.x = -1.0 * left_stick_y twist.linear.x = -1.0 * left_stick_y
input.angular.z = -1.0 * copysign( twist.angular.z = -1.0 * copysign(
right_stick_x**2, right_stick_x right_stick_x**2, right_stick_x
) # Exponent for finer control (curve) ) # 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
if self.use_cmd_vel:
twist.linear.x *= 1.5
twist.angular.z *= 0.5
# Publish # Publish
self.core_twist_pub_.publish(input) if self.use_cmd_vel:
self.get_logger().info( header = Header(stamp=self.get_clock().now().to_msg())
f"[Core Ctrl] Linear: {round(input.linear.x, 2)}, Angular: {round(input.angular.z, 2)}" self.core_cmd_vel_pub_.publish(TwistStamped(header=header, twist=twist))
else:
self.core_twist_pub_.publish(twist)
self.get_logger().debug(
f"[Core Ctrl] Linear: {round(twist.linear.x, 2)}, Angular: {round(twist.angular.z, 2)}"
) )
# Brake mode # Brake mode
@@ -643,6 +673,11 @@ class Headless(Node):
else: else:
pass # TODO: implement new bio control topics pass # TODO: implement new bio control topics
def core_cmd_vel_stop_msg(self):
return TwistStamped(
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg())
)
def arm_manual_stop_msg(self): def arm_manual_stop_msg(self):
return JointJog( return JointJog(
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()), header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()),