mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-04-20 11:51:16 -05:00
Compare commits
6 Commits
fix-oversi
...
ff4a58e6ed
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ff4a58e6ed | ||
|
|
120891c8e5 | ||
|
|
178d5001d6 | ||
|
|
684c2994ec | ||
|
|
bfa50e3a25 | ||
|
|
90fbbac813 |
@@ -1,14 +1,21 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, Shutdown
|
||||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
OpaqueFunction,
|
||||
Shutdown,
|
||||
IncludeLaunchDescription,
|
||||
)
|
||||
from launch.substitutions import (
|
||||
LaunchConfiguration,
|
||||
ThisLaunchFileDir,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.conditions import IfCondition
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
# Prevent making __pycache__ directories
|
||||
@@ -41,7 +48,10 @@ def launch_setup(context, *args, **kwargs):
|
||||
executable="core", # change as needed
|
||||
name="core",
|
||||
output="both",
|
||||
parameters=[{"launch_mode": mode}],
|
||||
parameters=[
|
||||
{"launch_mode": mode},
|
||||
{"use_ros2_control": LaunchConfiguration("use_ros2_control", default=False)},
|
||||
],
|
||||
on_exit=Shutdown(),
|
||||
)
|
||||
)
|
||||
@@ -135,4 +145,46 @@ def generate_launch_description():
|
||||
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),
|
||||
]
|
||||
)
|
||||
|
||||
Submodule src/astra_descriptions updated: c36bd8233d...04c2061443
Submodule src/astra_msgs updated: 2264a2cb67...93dc0e0919
@@ -66,6 +66,10 @@ class SerialRelay(Node):
|
||||
self.launch_mode = self.get_parameter("launch_mode").value
|
||||
self.get_logger().info(f"Core launch_mode is: {self.launch_mode}")
|
||||
|
||||
self.declare_parameter("use_ros2_control", False)
|
||||
self.use_ros2_control = self.get_parameter("use_ros2_control").value
|
||||
self.get_logger().info(f"Use ros2_control: {self.use_ros2_control}")
|
||||
|
||||
##################################################
|
||||
# Topics
|
||||
|
||||
@@ -85,24 +89,28 @@ class SerialRelay(Node):
|
||||
|
||||
# Control
|
||||
|
||||
# autonomy twist -- m/s and rad/s -- for autonomy, in particular Nav2
|
||||
self.cmd_vel_sub_ = self.create_subscription(
|
||||
TwistStamped, "/cmd_vel", self.cmd_vel_callback, 1
|
||||
)
|
||||
# manual twist -- [-1, 1] rather than real units
|
||||
self.twist_man_sub_ = self.create_subscription(
|
||||
Twist, "/core/twist", self.twist_man_callback, qos_profile=control_qos
|
||||
)
|
||||
# manual flags -- brake mode and max duty cycle
|
||||
self.control_state_sub_ = self.create_subscription(
|
||||
CoreCtrlState,
|
||||
"/core/control/state",
|
||||
self.control_state_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
self.twist_max_duty = (
|
||||
0.5 # max duty cycle for twist commands (0.0 - 1.0); walking speed is 0.5
|
||||
)
|
||||
if self.use_ros2_control:
|
||||
# Joint state control for topic-based controller
|
||||
self.joint_command_sub_ = self.create_subscription(
|
||||
JointState, "/core/joint_commands", self.joint_command_callback, 2
|
||||
)
|
||||
else:
|
||||
# autonomy twist -- m/s and rad/s -- for autonomy, in particular Nav2
|
||||
self.cmd_vel_sub_ = self.create_subscription(
|
||||
TwistStamped, "/cmd_vel", self.cmd_vel_callback, 1
|
||||
)
|
||||
# manual twist -- [-1, 1] rather than real units
|
||||
self.twist_man_sub_ = self.create_subscription(
|
||||
Twist, "/core/twist", self.twist_man_callback, qos_profile=control_qos
|
||||
)
|
||||
# manual flags -- brake mode and max duty cycle
|
||||
self.control_state_sub_ = self.create_subscription(
|
||||
CoreCtrlState,
|
||||
"/core/control/state",
|
||||
self.control_state_callback,
|
||||
qos_profile=control_qos,
|
||||
)
|
||||
self.twist_max_duty = 0.5 # max duty cycle for twist commands (0.0 - 1.0); walking speed is 0.5
|
||||
|
||||
# Feedback
|
||||
|
||||
@@ -122,7 +130,7 @@ class SerialRelay(Node):
|
||||
) # TODO: not sure about this
|
||||
# Joint states for topic-based controller
|
||||
self.joint_state_pub_ = self.create_publisher(
|
||||
JointState, "/core/joint_states", qos_profile=qos.qos_profile_sensor_data
|
||||
JointState, "/joint_states", qos_profile=qos.qos_profile_sensor_data
|
||||
)
|
||||
# IMU (embedded BNO-055)
|
||||
self.imu_pub_ = self.create_publisher(
|
||||
@@ -148,10 +156,11 @@ class SerialRelay(Node):
|
||||
|
||||
# Old
|
||||
|
||||
# /core/control
|
||||
self.control_sub = self.create_subscription(
|
||||
CoreControl, "/core/control", self.send_controls, 10
|
||||
) # old control method -- left_stick, right_stick, max_speed, brake, and some other random autonomy stuff
|
||||
if not self.use_ros2_control:
|
||||
# /core/control
|
||||
self.control_sub = self.create_subscription(
|
||||
CoreControl, "/core/control", self.send_controls, 10
|
||||
) # old control method -- left_stick, right_stick, max_speed, brake, and some other random autonomy stuff
|
||||
# /core/feedback
|
||||
self.feedback_pub = self.create_publisher(CoreFeedback, "/core/feedback", 10)
|
||||
self.core_feedback = CoreFeedback()
|
||||
@@ -283,6 +292,40 @@ class SerialRelay(Node):
|
||||
|
||||
# print(f"[Sys] Relaying: {command}")
|
||||
|
||||
def joint_command_callback(self, msg: JointState):
|
||||
# So... topic based control node publishes JointState messages over /joint_commands
|
||||
# with len(msg.name) == 5 and len(msg.velocity) == 4... all 5 non-fixed joints
|
||||
# are included in msg.name, but ig it is implied that msg.velocity only
|
||||
# includes velocities for the commanded joints (ros__parameters.joints).
|
||||
# So, this will be much more hacky and less adaptable than I would like it to be.
|
||||
if len(msg.name) != 5 or len(msg.velocity) != 4 or len(msg.position) != 0:
|
||||
self.get_logger().warning(
|
||||
f"Received joint control message with unexpected number of joints. Ignoring."
|
||||
)
|
||||
return
|
||||
if msg.name != [
|
||||
"left_suspension_joint",
|
||||
"bl_wheel_joint",
|
||||
"br_wheel_joint",
|
||||
"fl_wheel_joint",
|
||||
"fr_wheel_joint",
|
||||
]:
|
||||
self.get_logger().warning(
|
||||
f"Received joint control message with unexpected name[]. Ignoring."
|
||||
)
|
||||
return
|
||||
|
||||
(bl_vel, br_vel, fl_vel, fr_vel) = msg.velocity
|
||||
|
||||
bl_rpm = radps_to_rpm(bl_vel) * CORE_GEAR_RATIO
|
||||
br_rpm = radps_to_rpm(br_vel) * CORE_GEAR_RATIO
|
||||
fl_rpm = radps_to_rpm(fl_vel) * CORE_GEAR_RATIO
|
||||
fr_rpm = radps_to_rpm(fr_vel) * CORE_GEAR_RATIO
|
||||
|
||||
self.send_viccan(
|
||||
20, [fl_rpm, bl_rpm, fr_rpm, br_rpm]
|
||||
) # order expected by embedded
|
||||
|
||||
def cmd_vel_callback(self, msg: TwistStamped):
|
||||
linear = msg.twist.linear.x
|
||||
angular = -msg.twist.angular.z
|
||||
@@ -528,22 +571,27 @@ class SerialRelay(Node):
|
||||
match motorId:
|
||||
case 1:
|
||||
motor = self.feedback_new_state.fl_motor
|
||||
joint_state_msg.name = ["fl_motor_joint"]
|
||||
joint_state_msg.name = ["fl_wheel_joint"]
|
||||
case 2:
|
||||
motor = self.feedback_new_state.bl_motor
|
||||
joint_state_msg.name = ["bl_motor_joint"]
|
||||
joint_state_msg.name = ["bl_wheel_joint"]
|
||||
case 3:
|
||||
motor = self.feedback_new_state.fr_motor
|
||||
joint_state_msg.name = ["fr_motor_joint"]
|
||||
joint_state_msg.name = ["fr_wheel_joint"]
|
||||
case 4:
|
||||
motor = self.feedback_new_state.br_motor
|
||||
joint_state_msg.name = ["br_motor_joint"]
|
||||
joint_state_msg.name = ["br_wheel_joint"]
|
||||
case _:
|
||||
self.get_logger().warning(
|
||||
f"Ignoring REV motor feedback 58 with invalid motorId {motorId}"
|
||||
)
|
||||
return
|
||||
|
||||
# make the fucking shit work
|
||||
joint_state_msg.name.append("left_suspension_joint")
|
||||
joint_state_msg.position.append(0.0)
|
||||
joint_state_msg.velocity.append(0.0)
|
||||
|
||||
joint_state_msg.header.stamp = msg.header.stamp
|
||||
self.joint_state_pub_.publish(joint_state_msg)
|
||||
case _:
|
||||
@@ -581,6 +629,10 @@ def map_range(
|
||||
return (value - in_min) * (out_max - out_min) / (in_max - in_min) + out_min
|
||||
|
||||
|
||||
def radps_to_rpm(radps: float):
|
||||
return radps * 60 / (2 * pi)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
sys.excepthook = myexcepthook
|
||||
|
||||
@@ -138,6 +138,11 @@ class Headless(Node):
|
||||
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.use_bio = self.get_parameter("use_bio").get_parameter_value().bool_value
|
||||
|
||||
@@ -145,7 +150,6 @@ class Headless(Node):
|
||||
self.use_arm_ik = (
|
||||
self.get_parameter("use_arm_ik").get_parameter_value().bool_value
|
||||
)
|
||||
|
||||
# NOTE: only applicable if use_old_topics == True
|
||||
self.declare_parameter("use_new_arm_manual_scheme", True)
|
||||
self.use_new_arm_manual_scheme = (
|
||||
@@ -155,6 +159,13 @@ class Headless(Node):
|
||||
)
|
||||
|
||||
# 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:
|
||||
self.get_logger().fatal("Old topics do not support arm IK control.")
|
||||
sys.exit(1)
|
||||
@@ -184,6 +195,9 @@ class Headless(Node):
|
||||
self.core_twist_pub_ = self.create_publisher(
|
||||
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(
|
||||
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)
|
||||
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):
|
||||
if self.use_old_topics:
|
||||
self.core_publisher.publish(CORE_STOP_MSG)
|
||||
self.arm_publisher.publish(ARM_STOP_MSG)
|
||||
self.bio_publisher.publish(BIO_STOP_MSG)
|
||||
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:
|
||||
self.arm_ik_twist_publisher.publish(self.arm_ik_twist_stop_msg())
|
||||
else:
|
||||
@@ -332,18 +352,28 @@ class Headless(Node):
|
||||
self.core_publisher.publish(input)
|
||||
|
||||
else: # New topics
|
||||
input = Twist()
|
||||
twist = Twist()
|
||||
|
||||
# Forward/back and Turn
|
||||
input.linear.x = -1.0 * left_stick_y
|
||||
input.angular.z = -1.0 * copysign(
|
||||
twist.linear.x = -1.0 * left_stick_y
|
||||
twist.angular.z = -1.0 * copysign(
|
||||
right_stick_x**2, right_stick_x
|
||||
) # 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
|
||||
self.core_twist_pub_.publish(input)
|
||||
self.get_logger().info(
|
||||
f"[Core Ctrl] Linear: {round(input.linear.x, 2)}, Angular: {round(input.angular.z, 2)}"
|
||||
if self.use_cmd_vel:
|
||||
header = Header(stamp=self.get_clock().now().to_msg())
|
||||
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
|
||||
@@ -643,6 +673,11 @@ class Headless(Node):
|
||||
else:
|
||||
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):
|
||||
return JointJog(
|
||||
header=Header(frame_id="base_link", stamp=self.get_clock().now().to_msg()),
|
||||
|
||||
Reference in New Issue
Block a user