Skip to content

Commit

Permalink
Updated to match main
Browse files Browse the repository at this point in the history
  • Loading branch information
ShannonGriswold committed Jan 18, 2025
2 parents 5812c07 + 2af41a0 commit 8bfd5eb
Show file tree
Hide file tree
Showing 15 changed files with 64 additions and 52 deletions.
2 changes: 2 additions & 0 deletions .github/workflows/industrial_ci_action.yml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@ jobs:
CCACHE_DIR: "${{ github.workspace }}/.ccache" # directory for ccache (and how we enable ccache in industrial_ci)
steps:
- uses: actions/checkout@v4 # clone target repository
with:
submodules: recursive
- uses: actions/cache@v4 # fetch/store the directory used by ccache before/after the ci run
with:
path: ${{ env.CCACHE_DIR }}
Expand Down
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
[submodule "src/surface/ros2_video_streamer"]
path = src/surface/ros2_video_streamer
url = git@github.com:CWRUbotix/ros2_video_streamer.git
[submodule "src/pi/mavros"]
path = src/pi/mavros
url = https://github.com/mavlink/mavros.git
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
repos:
- repo: https://github.com/astral-sh/ruff-pre-commit
# Ruff version.
rev: v0.7.1
rev: v0.9.1
hooks:
# Run the linter.
- id: ruff
Expand All @@ -11,7 +11,7 @@ repos:
# Run the formatter.
- id: ruff-format
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v19.1.2
rev: v19.1.6
hooks:
- id: clang-format
types_or: [c++, c]
Expand All @@ -21,6 +21,6 @@ repos:
hooks:
- id: trailing-whitespace
- repo: https://github.com/google/yamlfmt
rev: v0.13.0
rev: v0.15.0
hooks:
- id: yamlfmt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
FREQ = 50

gpio_handle = lgpio.gpiochip_open(0)
lgpio.gpio_claim_output(gpio_handle, SERVO_PIN)


def test_gpio(width: int, freq: int = 50) -> None:
Expand Down
5 changes: 4 additions & 1 deletion src/pi/manipulators/manipulators/valve_manipulator_node.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
from typing import Final

import lgpio
import rclpy
from rclpy.node import Node
Expand All @@ -6,7 +8,7 @@
from rov_msgs.msg import ValveManip

# Configuration
SERVO_PIN = 12 # pin used to drive Valve Manip
SERVO_PIN: Final = 12 # pin used to drive Valve Manip


class ValveManipulator(Node):
Expand All @@ -17,6 +19,7 @@ def __init__(self) -> None:
)

self.gpio_handle = lgpio.gpiochip_open(0)
lgpio.gpio_claim_output(self.gpio_handle, SERVO_PIN)
self.curr_active = False

def servo(self, width: int, freq: int = 50) -> None:
Expand Down
1 change: 1 addition & 0 deletions src/pi/mavros
Submodule mavros added at eac7b2
File renamed without changes.
2 changes: 1 addition & 1 deletion src/pi/pi_main/pi_main/run_on_boot.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ def main() -> None:
pi_main_share = get_package_share_directory('pi_main')

file_location = Path(__file__).parent.resolve()
udev_script = str(file_location / 'copy.py')
udev_script = str(file_location / 'copy_udev.py')

cmd = ['/usr/bin/sudo', '/usr/bin/python3', udev_script, pi_main_share]

Expand Down
4 changes: 2 additions & 2 deletions src/pi/pixhawk_communication/launch/mavros_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,12 @@ def generate_launch_description() -> LaunchDescription:
# receive a signal from a GCS.
{'system_id': 255},
# plugin_allowlist allows which mavros nodes get launched. The default is all of them.
{'plugin_allowlist': ['sys_status', 'rc_io', 'command']},
{'plugin_allowlist': ['sys_status', 'rc_io', 'command', 'manual_control']},
{'fcu_url': '/dev/ttyPixhawk'},
],
remappings=[
('/pi/mavros/state', '/tether/mavros/state'),
('/pi/mavros/rc/override', '/tether/mavros/rc/override'),
('/pi/mavros/manual_control/send', '/tether/mavros/manual_control/send'),
('/pi/mavros/cmd/arming', '/tether/mavros/cmd/arming'),
('/pi/mavros/cmd/command', '/tether/mavros/cmd/command'),
],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ class ControllerMode(IntEnum):

@dataclass
class ControllerProfile:
manip_left: int = X_BUTTON
manip_right: int = O_BUTTON
manip_left: int = O_BUTTON
manip_right: int = X_BUTTON
valve_clockwise: int = TRI_BUTTON
valve_counterclockwise: int = SQUARE_BUTTON
roll_left: int = L1 # positive roll
Expand Down Expand Up @@ -168,16 +168,14 @@ def joystick_to_pixhawk(self, msg: Joy) -> None:

def manip_callback(self, msg: Joy) -> None:
buttons: MutableSequence[int] = msg.buttons

for button_id, manip_button in self.manip_buttons.items():
just_pressed = buttons[button_id] == PRESSED

if manip_button.last_button_state is False and just_pressed:
new_manip_state = not manip_button.is_active
manip_button.is_active = new_manip_state

manip_msg = Manip(manip_id=manip_button.claw, activated=manip_button.is_active)
self.manip_publisher.publish(manip_msg)

manip_button.last_button_state = just_pressed

def valve_manip_callback(self, msg: Joy) -> None:
Expand Down
48 changes: 29 additions & 19 deletions src/surface/flight_control/flight_control/multiplexer.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
from collections.abc import Callable
from typing import Final

import rclpy
from mavros_msgs.msg import OverrideRCIn
from mavros_msgs.msg import ManualControl
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
from rclpy.qos import QoSPresetProfiles
Expand All @@ -17,9 +18,14 @@

# Range of values Pixhawk takes
# In microseconds
ZERO_SPEED = 1500
MAX_RANGE_SPEED = 400
RANGE_SPEED = MAX_RANGE_SPEED * SPEED_THROTTLE
ZERO_SPEED: Final = 0
Z_ZERO_SPEED: Final = 500
MAX_RANGE_SPEED: Final = 2000
Z_MAX_RANGE_SPEED: Final = 1000
RANGE_SPEED: Final = MAX_RANGE_SPEED * SPEED_THROTTLE
Z_RANGE_SPEED: Final = Z_MAX_RANGE_SPEED * SPEED_THROTTLE

EXTENSIONS_CODE: Final = 0b00000011

# Channels for RC command
MAX_CHANNEL = 8
Expand Down Expand Up @@ -57,36 +63,39 @@ def __init__(self) -> None:
QoSPresetProfiles.DEFAULT.value,
)

self.rc_pub = self.create_publisher(
OverrideRCIn, 'mavros/rc/override', QoSPresetProfiles.DEFAULT.value
self.mc_pub = self.create_publisher(
ManualControl, 'mavros/manual_control/send', QoSPresetProfiles.DEFAULT.value
)

@staticmethod
def apply(msg: PixhawkInstruction, function_to_apply: Callable[[float], float]) -> None:
"""Apply a function to each dimension of this PixhawkInstruction."""
msg.forward = function_to_apply(msg.forward)
msg.vertical = function_to_apply(msg.vertical)
msg.vertical = msg.vertical
msg.lateral = function_to_apply(msg.lateral)
msg.pitch = function_to_apply(msg.pitch)
msg.yaw = function_to_apply(msg.yaw)
msg.roll = function_to_apply(msg.roll)

@staticmethod
def to_override_rc_in(msg: PixhawkInstruction) -> OverrideRCIn:
def to_manual_control(msg: PixhawkInstruction) -> ManualControl:
"""Convert this PixhawkInstruction to an rc_msg with the appropriate channels array."""
rc_msg = OverrideRCIn()
mc_msg = ManualControl()

# Maps to PWM
MultiplexerNode.apply(msg, lambda value: int(RANGE_SPEED * value) + ZERO_SPEED)
MultiplexerNode.apply(msg, lambda value: (RANGE_SPEED * value) + ZERO_SPEED)

rc_msg.channels[FORWARD_CHANNEL] = msg.forward
rc_msg.channels[THROTTLE_CHANNEL] = msg.vertical
rc_msg.channels[LATERAL_CHANNEL] = msg.lateral
rc_msg.channels[PITCH_CHANNEL] = msg.pitch
rc_msg.channels[YAW_CHANNEL] = msg.yaw
rc_msg.channels[ROLL_CHANNEL] = msg.roll
mc_msg.x = msg.forward
mc_msg.z = (
Z_RANGE_SPEED * msg.vertical
) + Z_ZERO_SPEED # To account for different z limits
mc_msg.y = msg.lateral
mc_msg.r = msg.yaw
mc_msg.enabled_extensions = EXTENSIONS_CODE
mc_msg.s = msg.pitch
mc_msg.t = msg.roll

return rc_msg
return mc_msg

def state_control(
self, req: AutonomousFlight.Request, res: AutonomousFlight.Response
Expand All @@ -106,14 +115,15 @@ def control_callback(self, msg: PixhawkInstruction) -> None:
elif (
msg.author == PixhawkInstruction.KEYBOARD_CONTROL
and self.state == AutonomousFlight.Request.STOP
or msg.author == PixhawkInstruction.AUTONOMOUS_CONTROL
) or (
msg.author == PixhawkInstruction.AUTONOMOUS_CONTROL
and self.state == AutonomousFlight.Request.START
):
pass
else:
return

self.rc_pub.publish(msg=self.to_override_rc_in(msg))
self.mc_pub.publish(self.to_manual_control(msg))


def main() -> None:
Expand Down
2 changes: 1 addition & 1 deletion src/surface/flight_control/launch/flight_control_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ def generate_launch_description() -> LaunchDescription:
multiplexer_node = Node(
package='flight_control',
executable='multiplexer_node',
remappings=[('/surface/mavros/rc/override', '/tether/mavros/rc/override')],
remappings=[('/surface/mavros/manual_control/send', '/tether/mavros/manual_control/send')],
emulate_tty=True,
output='screen',
)
Expand Down
22 changes: 9 additions & 13 deletions src/surface/flight_control/test/test_manual_control.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,9 @@
import rclpy
from flight_control.manual_control_node import ManualControlNode
from flight_control.multiplexer import (
FORWARD_CHANNEL,
LATERAL_CHANNEL,
PITCH_CHANNEL,
RANGE_SPEED,
ROLL_CHANNEL,
THROTTLE_CHANNEL,
YAW_CHANNEL,
Z_RANGE_SPEED,
Z_ZERO_SPEED,
ZERO_SPEED,
MultiplexerNode,
)
Expand Down Expand Up @@ -35,14 +31,14 @@ def test_joystick_profiles() -> None:
roll=0.92,
)

msg = MultiplexerNode.to_override_rc_in(instruction)
msg = MultiplexerNode.to_manual_control(instruction)

assert msg.channels[FORWARD_CHANNEL] == ZERO_SPEED
assert msg.channels[THROTTLE_CHANNEL] == (ZERO_SPEED + RANGE_SPEED)
assert msg.channels[LATERAL_CHANNEL] == (ZERO_SPEED - RANGE_SPEED)
assert msg.x == ZERO_SPEED
assert msg.z == (Z_ZERO_SPEED + Z_RANGE_SPEED)
assert msg.y == (ZERO_SPEED - RANGE_SPEED)

# 1539 1378

assert msg.channels[PITCH_CHANNEL] == ZERO_SPEED + int(RANGE_SPEED * 0.34)
assert msg.channels[YAW_CHANNEL] == ZERO_SPEED + int(RANGE_SPEED * -0.6)
assert msg.channels[ROLL_CHANNEL] == ZERO_SPEED + int(RANGE_SPEED * 0.92)
assert msg.s == ZERO_SPEED + int(RANGE_SPEED * 0.34)
assert msg.r == ZERO_SPEED + int(RANGE_SPEED * -0.6)
assert msg.t == ZERO_SPEED + int(RANGE_SPEED * 0.92)
7 changes: 3 additions & 4 deletions src/surface/gui/gui/widgets/float_comm.py
Original file line number Diff line number Diff line change
Expand Up @@ -136,10 +136,9 @@ def handle_data(self, msg: FloatData) -> None:
time_data = list(msg.time_data)
depth_data = list(msg.depth_data)

if (
msg.profile_number == 0
and self.completed_profile_one
or msg.profile_number not in (0, 1)
if (msg.profile_number == 0 and self.completed_profile_one) or msg.profile_number not in (
0,
1,
):
return

Expand Down
5 changes: 2 additions & 3 deletions src/surface/transceiver/transceiver/serial_reader.py
Original file line number Diff line number Diff line change
Expand Up @@ -130,16 +130,15 @@ def message_parser(self, packet: str) -> FloatData:

if len(packet_sections) != PACKET_SECTIONS:
raise ValueError(
f'Packet expected {PACKET_SECTIONS} sections, '
f'found {len(packet_sections)} sections'
f'Packet expected {PACKET_SECTIONS} sections, found {len(packet_sections)} sections'
)

header = packet_sections[1].split(COMMA_SEPARATOR)
data = packet_sections[2]

if len(header) != HEADER_LENGTH:
raise ValueError(
f'Packet header length of {HEADER_LENGTH} expected ' f'found {len(header)} instead'
f'Packet header length of {HEADER_LENGTH} expected found {len(header)} instead'
)

msg.team_number = int(header[0])
Expand Down

0 comments on commit 8bfd5eb

Please sign in to comment.