-
Notifications
You must be signed in to change notification settings - Fork 0
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Enhancement/joystick interface cleanup #110
Merged
alekskl01
merged 6 commits into
development
from
enhancement/joystick_interface_cleanup
Nov 12, 2023
Merged
Changes from 5 commits
Commits
Show all changes
6 commits
Select commit
Hold shift + click to select a range
d084dfb
Cleanup and added docstrings to functions
9b936dc
Fixed deadzone on joy driver
c744344
Fixed bugs in tests
67ac579
Updated Readme
23d808b
updated readme again
f281759
removed comment, and type specifiers paranthesis in docstrings
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,2 +1,2 @@ | ||
In the launch files we need to make it able to find the yaml files without having an explicit path such as this: "src/vortex-asv/mission/joystick_interface/launch/joystick_interface_launch.yaml" | ||
Perhaps change to python launch | ||
## Joystick interface | ||
A joystick interface for manual control of ASV Freya. A ROS2 node that subscribes on inputs from the XBOX controller and publishes the according wrench message to be used in Thruster Allocation. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -6,23 +6,23 @@ | |
from std_msgs.msg import Bool | ||
|
||
|
||
class states: | ||
class States: | ||
XBOX_MODE = 1 | ||
AUTONOMOUS_MODE = 2 | ||
NO_GO = 3 # Do nothing | ||
NO_GO = 3 | ||
|
||
|
||
class JoystickInterface(Node): | ||
|
||
def __init__(self): | ||
super().__init__('joystick_interface_node') | ||
self.get_logger().info("Joystick interface is up and running") | ||
self.get_logger().info("Joystick interface is up and running. \n When the XBOX controller is connected, press the killswitch button once to enter XBOX mode.") | ||
|
||
self.last_button_press_time = 0 | ||
self.debounce_duration = 0.25 | ||
self.state = states.NO_GO | ||
self.last_button_press_time_ = 0 | ||
self.debounce_duration_ = 0.25 | ||
self.state_ = States.NO_GO | ||
|
||
self.joystick_buttons_map = [ | ||
self.joystick_buttons_map_ = [ | ||
"A", | ||
"B", | ||
"X", | ||
|
@@ -36,7 +36,7 @@ def __init__(self): | |
"stick_button_right", | ||
] | ||
|
||
self.joystick_axes_map = [ | ||
self.joystick_axes_map_ = [ | ||
"horizontal_axis_left_stick", #Translation (Left and Right) | ||
"vertical_axis_left_stick", #Translation (Forwards and Backwards) | ||
"LT", #Negative thrust/torque multiplier | ||
|
@@ -47,9 +47,9 @@ def __init__(self): | |
"dpad_vertical", | ||
] | ||
|
||
self.joy_subscriber = self.create_subscription(Joy, "joystick/joy", | ||
self.joy_subscriber_ = self.create_subscription(Joy, "joystick/joy", | ||
self.joystick_cb, 1) | ||
self.wrench_publisher = self.create_publisher(Wrench, | ||
self.wrench_publisher_ = self.create_publisher(Wrench, | ||
"thrust/wrench_input", | ||
1) | ||
|
||
|
@@ -58,73 +58,120 @@ def __init__(self): | |
self.declare_parameter('yaw_scale_factor', 50.0) | ||
|
||
#Gets the scaling factors from the yaml file | ||
self.joystick_surge_scaling = self.get_parameter('surge_scale_factor').value | ||
self.joystick_sway_scaling = self.get_parameter('sway_scale_factor').value | ||
self.joystick_yaw_scaling = self.get_parameter('yaw_scale_factor').value | ||
self.joystick_surge_scaling_ = self.get_parameter('surge_scale_factor').value | ||
self.joystick_sway_scaling_ = self.get_parameter('sway_scale_factor').value | ||
self.joystick_yaw_scaling_ = self.get_parameter('yaw_scale_factor').value | ||
|
||
#Killswitch publisher | ||
self.software_killswitch_signal_publisher = self.create_publisher( | ||
self.software_killswitch_signal_publisher_ = self.create_publisher( | ||
Bool, "softWareKillSwitch", 10) | ||
self.software_killswitch_signal_publisher.publish( | ||
self.software_killswitch_signal_publisher_.publish( | ||
Bool(data=False)) #Killswitch is not active | ||
|
||
#Operational mode publisher | ||
self.operational_mode_signal_publisher = self.create_publisher( | ||
self.operational_mode_signal_publisher_ = self.create_publisher( | ||
Bool, "softWareOperationMode", 10) | ||
|
||
# Signal that we are not in autonomous mode | ||
self.operational_mode_signal_publisher.publish(Bool(data=True)) | ||
self.operational_mode_signal_publisher_.publish(Bool(data=True)) | ||
|
||
#Controller publisher | ||
self.enable_controller_publisher = self.create_publisher( | ||
self.enable_controller_publisher_ = self.create_publisher( | ||
Bool, "controller/lqr/enable", 10) | ||
|
||
def right_trigger_linear_converter(self, rt_input: float) -> float: | ||
""" | ||
Does a linear conversion from the right trigger input range of (1 to -1) to (1 to 2) | ||
|
||
#does a linear conversion from trigger inputs (1 to -1) to (1 to 2) | ||
def right_trigger_linear_converter(self, rt_input): | ||
Args: | ||
rt_input (float): The input value of the right trigger, ranging from -1 to 1. | ||
|
||
Returns: | ||
float: The output value, ranging from 1 to 2. | ||
""" | ||
output_value = (rt_input + 1) * (-0.5) + 2 | ||
return output_value | ||
|
||
#does a linear conversion from trigger input (1 to -1) to (1 to 0.5) | ||
def left_trigger_linear_converter(self, lt_input): | ||
def left_trigger_linear_converter(self, lt_input: float ) -> float: | ||
""" | ||
Does a linear conversion from the left trigger input range of (1 to -1) to (1 to 0.5) | ||
|
||
Args: | ||
lt_input (float): The input value of the left trigger, ranging from -1 to 1. | ||
|
||
Returns: | ||
float: The output value, ranging from 1 to 2. | ||
""" | ||
ouput_value = lt_input * 0.25 + 0.75 | ||
return ouput_value | ||
|
||
def create_2d_wrench_message(self, x, y, yaw): | ||
wrench_msg = Wrench() | ||
wrench_msg.force.x = x | ||
wrench_msg.force.y = y | ||
wrench_msg.torque.z = yaw | ||
return wrench_msg | ||
def create_2d_wrench_message(self, x: float, y: float, yaw: float) -> Wrench: | ||
""" | ||
Creates a 2D wrench message with the given x, y, and yaw values. | ||
|
||
Args: | ||
x (float): The x component of the force vector. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. no need to specify type in parentheses, it is already given by the typehints. |
||
y (float): The y component of the force vector. | ||
yaw (float): The z component of the torque vector. | ||
|
||
Returns: | ||
Wrench: A 2D wrench message with the given values. | ||
""" | ||
wrench_msg = Wrench() | ||
wrench_msg.force.x = x | ||
wrench_msg.force.y = y | ||
wrench_msg.torque.z = yaw | ||
return wrench_msg | ||
|
||
def publish_wrench_message(self, wrench): | ||
self.wrench_publisher.publish(wrench) | ||
def publish_wrench_message(self, wrench: Wrench): | ||
""" | ||
Publishes a Wrench message to the wrench_publisher_ topic. | ||
|
||
Args: | ||
wrench (Wrench): The Wrench message to be published. | ||
""" | ||
self.wrench_publisher_.publish(wrench) | ||
|
||
def transition_to_xbox_mode(self): | ||
# We want to turn off controller when moving to xbox mode | ||
self.enable_controller_publisher.publish(Bool(data=False)) | ||
# signal that we enter xbox mode | ||
self.operational_mode_signal_publisher.publish(Bool(data=True)) | ||
self.state = states.XBOX_MODE | ||
""" | ||
Turns off the controller and signals that the operational mode has switched to Xbox mode. | ||
""" | ||
self.enable_controller_publisher_.publish(Bool(data=False)) | ||
self.operational_mode_signal_publisher_.publish(Bool(data=True)) | ||
self.state_ = States.XBOX_MODE | ||
|
||
def transition_to_autonomous_mode(self): | ||
# We want to publish zero force once when transitioning | ||
""" | ||
Publishes a zero force wrench message and signals that the system is turning on autonomous mode. | ||
""" | ||
wrench_msg = self.create_2d_wrench_message(0.0, 0.0, 0.0) | ||
self.publish_wrench_message(wrench_msg) | ||
# signal that we are turning on autonomous mode | ||
self.operational_mode_signal_publisher.publish(Bool(data=False)) | ||
self.state = states.AUTONOMOUS_MODE | ||
|
||
def joystick_cb(self, msg): | ||
self.operational_mode_signal_publisher_.publish(Bool(data=False)) | ||
self.state_ = States.AUTONOMOUS_MODE | ||
|
||
def joystick_cb(self, msg : Joy): | ||
""" | ||
Callback function that receives joy messages and converts them into | ||
wrench messages to be sent to the thruster allocation node. | ||
Handles software killswitch and control mode buttons, | ||
and transitions between different states of operation. | ||
|
||
Args: | ||
msg: A ROS message containing the joy input data. | ||
|
||
Returns: | ||
A ROS message containing the wrench data that was sent to the thruster allocation node. | ||
""" | ||
current_time = self.get_clock().now().to_msg()._sec | ||
|
||
#Input from controller to joystick_interface | ||
buttons = {} | ||
axes = {} | ||
|
||
for i in range(len(msg.buttons)): | ||
buttons[self.joystick_buttons_map[i]] = msg.buttons[i] | ||
buttons[self.joystick_buttons_map_[i]] = msg.buttons[i] | ||
|
||
for i in range(len(msg.axes)): | ||
axes[self.joystick_axes_map[i]] = msg.axes[i] | ||
axes[self.joystick_axes_map_[i]] = msg.axes[i] | ||
|
||
xbox_control_mode_button = buttons["A"] | ||
software_killswitch_button = buttons["B"] | ||
|
@@ -135,52 +182,52 @@ def joystick_cb(self, msg): | |
left_trigger = self.left_trigger_linear_converter(left_trigger) | ||
|
||
surge = axes[ | ||
"vertical_axis_left_stick"] * self.joystick_surge_scaling * left_trigger * right_trigger | ||
"vertical_axis_left_stick"] * self.joystick_surge_scaling_ * left_trigger * right_trigger | ||
sway = axes[ | ||
"horizontal_axis_left_stick"] * self.joystick_sway_scaling * left_trigger * right_trigger | ||
"horizontal_axis_left_stick"] * self.joystick_sway_scaling_ * left_trigger * right_trigger | ||
yaw = axes[ | ||
"horizontal_axis_right_stick"] * self.joystick_yaw_scaling * left_trigger * right_trigger | ||
"horizontal_axis_right_stick"] * self.joystick_yaw_scaling_ * left_trigger * right_trigger | ||
|
||
# Debounce for the buttons | ||
if current_time - self.last_button_press_time < self.debounce_duration: | ||
if current_time - self.last_button_press_time_ < self.debounce_duration_: | ||
software_control_mode_button = False | ||
xbox_control_mode_button = False | ||
software_killswitch_button = False | ||
|
||
# If any button is pressed, update the last button press time | ||
if software_control_mode_button or xbox_control_mode_button or software_killswitch_button: | ||
self.last_button_press_time = current_time | ||
self.last_button_press_time_ = current_time | ||
|
||
# Toggle ks on and off | ||
if self.state == states.NO_GO and software_killswitch_button: | ||
if self.state_ == States.NO_GO and software_killswitch_button: | ||
# signal that killswitch is not blocking | ||
self.software_killswitch_signal_publisher.publish(Bool(data=True)) | ||
self.software_killswitch_signal_publisher_.publish(Bool(data=True)) | ||
self.transition_to_xbox_mode() | ||
return | ||
|
||
if software_killswitch_button: | ||
self.get_logger().info("SW killswitch", throttle_duration_sec=1) | ||
# signal that killswitch is blocking | ||
self.software_killswitch_signal_publisher.publish(Bool(data=False)) | ||
self.software_killswitch_signal_publisher_.publish(Bool(data=False)) | ||
# Turn off controller in sw killswitch | ||
self.enable_controller_publisher.publish(Bool(data=False)) | ||
self.enable_controller_publisher_.publish(Bool(data=False)) | ||
# Publish a zero wrench message when sw killing | ||
wrench_msg = self.create_2d_wrench_message(0.0, 0.0, 0.0) | ||
self.publish_wrench_message(wrench_msg) | ||
self.state = states.NO_GO | ||
self.state_ = States.NO_GO | ||
return wrench_msg | ||
|
||
#Msg published from joystick_interface to thrust allocation | ||
wrench_msg = self.create_2d_wrench_message(surge, sway, yaw) | ||
|
||
if self.state == states.XBOX_MODE: | ||
if self.state_ == States.XBOX_MODE: | ||
self.get_logger().info("XBOX mode", throttle_duration_sec=1) | ||
self.publish_wrench_message(wrench_msg) | ||
|
||
if software_control_mode_button: | ||
self.transition_to_autonomous_mode() | ||
|
||
if self.state == states.AUTONOMOUS_MODE: | ||
if self.state_ == States.AUTONOMOUS_MODE: | ||
self.get_logger().info("autonomous mode", throttle_duration_sec=1) | ||
|
||
if xbox_control_mode_button: | ||
|
@@ -191,11 +238,8 @@ def joystick_cb(self, msg): | |
|
||
def main(): | ||
rclpy.init() | ||
|
||
joystick_interface = JoystickInterface() | ||
print(joystick_interface.joystick_surge_scaling) | ||
rclpy.spin(joystick_interface) | ||
|
||
joystick_interface.destroy_node() | ||
rclpy.shutdown() | ||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
remove commented out line