Skip to content
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

Smooth thrusters #200

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 30 additions & 1 deletion src/surface/flight_control/flight_control/manual_control_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@

CONTROLLER_MODE_PARAM = "controller_mode"

NEXT_INSTR_FRAC = 0.05
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

more yap less frac

PREV_INSTR_FRAC = 1 - NEXT_INSTR_FRAC


class ControllerMode(IntEnum):
ARM = 0
Expand Down Expand Up @@ -109,6 +112,16 @@ def __init__(self) -> None:
self.seen_right_cam = False
self.valve_manip_state = False

self.previous_pixhawk_instruction = PixhawkInstruction(
forward=float(0),
lateral=float(0),
vertical=float(0),
roll=float(0),
pitch=float(0),
yaw=float(0),
author=PixhawkInstruction.MANUAL_CONTROL
)

def controller_callback(self, msg: Joy) -> None:
self.joystick_to_pixhawk(msg)
self.valve_manip_callback(msg)
Expand All @@ -129,7 +142,23 @@ def joystick_to_pixhawk(self, msg: Joy) -> None:
author=PixhawkInstruction.MANUAL_CONTROL
)

self.rc_pub.publish(instruction)
smoothed_instruction = PixhawkInstruction(
forward=ManualControlNode.smooth(self.previous_pixhawk_instruction.forward, instruction.forward),
lateral=ManualControlNode.smooth(self.previous_pixhawk_instruction.lateral, instruction.lateral),
vertical=ManualControlNode.smooth(self.previous_pixhawk_instruction.vertical, instruction.vertical),
roll=ManualControlNode.smooth(self.previous_pixhawk_instruction.roll, instruction.roll),
pitch=ManualControlNode.smooth(self.previous_pixhawk_instruction.pitch, instruction.pitch),
yaw=ManualControlNode.smooth(self.previous_pixhawk_instruction.yaw, instruction.yaw),
author=PixhawkInstruction.MANUAL_CONTROL
)

self.previous_pixhawk_instruction = smoothed_instruction

self.rc_pub.publish(smoothed_instruction)

@staticmethod
def smooth(prev_value: float, next_value: float) -> float:
return PREV_INSTR_FRAC * prev_value + NEXT_INSTR_FRAC * next_value

def manip_callback(self, msg: Joy) -> None:
buttons: MutableSequence[int] = msg.buttons
Expand Down
2 changes: 1 addition & 1 deletion src/surface/flight_control/flight_control/multiplexer.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
from rov_msgs.srv import AutonomousFlight

# Brown out protection
SPEED_THROTTLE = 0.85
SPEED_THROTTLE = 0.65

# Joystick curve
JOYSTICK_EXPONENT = 3
Expand Down