1- from collections .abc import Callable
21from typing import Final
32
43import rclpy
76from rclpy .node import Node
87from rclpy .qos import QoSPresetProfiles
98
9+ from flight_control .pixhawk_instruction_utils import (
10+ apply_function ,
11+ pixhawk_instruction_to_tuple ,
12+ tuple_to_pixhawk_instruction ,
13+ )
1014from rov_msgs .msg import PixhawkInstruction
1115from rov_msgs .srv import AutonomousFlight
1216
1317# Brown out protection
14- SPEED_THROTTLE = 0.85
18+ SPEED_THROTTLE : Final = 0.65
1519
1620# Joystick curve
17- JOYSTICK_EXPONENT = 3
21+ JOYSTICK_EXPONENT : Final = 3
1822
1923# Range of values Pixhawk takes
2024# In microseconds
2731
2832EXTENSIONS_CODE : Final = 0b00000011
2933
30- # Channels for RC command
31- MAX_CHANNEL = 8
32- MIN_CHANNEL = 1
33-
34- FORWARD_CHANNEL = 4 # X
35- THROTTLE_CHANNEL = 2 # Z (vertical)
36- LATERAL_CHANNEL = 5 # Y (left & right)
37- PITCH_CHANNEL = 0 # Pitch
38- YAW_CHANNEL = 3 # Yaw
39- ROLL_CHANNEL = 1 # Roll
34+ NEXT_INSTR_FRAC : Final = 0.05
35+ PREV_INSTR_FRAC : Final = 1 - NEXT_INSTR_FRAC
4036
4137
4238def joystick_map (raw : float ) -> float :
39+ """
40+ Convert the provided joystick position to a
41+ float in [-1.0, 1.0] for use in a PixhawkInstruction.
42+
43+ Parameters
44+ ----------
45+ raw : float
46+ The joystick position to convert
47+
48+ Returns
49+ -------
50+ float
51+ A float in [-1.0, 1.0] to act as a PixhawkInstruction dimension
52+ """
4353 mapped = abs (raw ) ** JOYSTICK_EXPONENT
4454 if raw < 0 :
4555 mapped *= - 1
4656 return mapped
4757
4858
59+ def manual_control_map (value : float ) -> float :
60+ """
61+ Convert the provided float in [-1.0, 1.0] to a ManualControl dimension.
62+
63+ Parameters
64+ ----------
65+ value : float
66+ The float in [-1.0, 1.0] to convert to a ManualControl dimension
67+
68+ Returns
69+ -------
70+ float
71+ The resulting ManualControl dimension
72+ """
73+ return RANGE_SPEED * value + ZERO_SPEED
74+
75+
76+ def smooth_value (prev_value : float , next_value : float ) -> float :
77+ """
78+ Get a value that interpolates prev_value & next_value.
79+
80+ Parameters
81+ ----------
82+ prev_value : float
83+ The previous value, affects the result based on PREV_INSTR_FRAC
84+ next_value : float
85+ The next value, affects the result based on NEXT_INSTR_FRAC
86+
87+ Returns
88+ -------
89+ float
90+ The resulting value between prev_value & next_value
91+ """
92+ return PREV_INSTR_FRAC * prev_value + NEXT_INSTR_FRAC * next_value
93+
94+
95+ def to_manual_control (msg : PixhawkInstruction ) -> ManualControl :
96+ """
97+ Convert the provided PixhawkInstruction to a ManualControl message.
98+
99+ Parameters
100+ ----------
101+ msg : PixhawkInstruction
102+ The PixhawkInstruction to convert
103+
104+ Returns
105+ -------
106+ ManualControl
107+ The resulting ManualControl message
108+ """
109+ mc_msg = ManualControl ()
110+
111+ # Maps to PWM
112+ mapped_msg = apply_function (msg , manual_control_map )
113+
114+ # To account for different z limits
115+ mapped_msg .vertical = Z_RANGE_SPEED * msg .vertical + Z_ZERO_SPEED
116+
117+ mc_msg .x = mapped_msg .forward
118+ mc_msg .z = mapped_msg .vertical
119+ mc_msg .y = mapped_msg .lateral
120+ mc_msg .r = mapped_msg .yaw
121+ mc_msg .enabled_extensions = EXTENSIONS_CODE
122+ mc_msg .s = mapped_msg .pitch
123+ mc_msg .t = mapped_msg .roll
124+
125+ return mc_msg
126+
127+
49128class MultiplexerNode (Node ):
50129 def __init__ (self ) -> None :
51130 super ().__init__ ('multiplexer' , parameter_overrides = [])
@@ -67,35 +146,24 @@ def __init__(self) -> None:
67146 ManualControl , 'mavros/manual_control/send' , QoSPresetProfiles .DEFAULT .value
68147 )
69148
70- @staticmethod
71- def apply (msg : PixhawkInstruction , function_to_apply : Callable [[float ], float ]) -> None :
72- """Apply a function to each dimension of this PixhawkInstruction."""
73- msg .forward = function_to_apply (msg .forward )
74- msg .vertical = msg .vertical
75- msg .lateral = function_to_apply (msg .lateral )
76- msg .pitch = function_to_apply (msg .pitch )
77- msg .yaw = function_to_apply (msg .yaw )
78- msg .roll = function_to_apply (msg .roll )
79-
80- @staticmethod
81- def to_manual_control (msg : PixhawkInstruction ) -> ManualControl :
82- """Convert this PixhawkInstruction to an rc_msg with the appropriate channels array."""
83- mc_msg = ManualControl ()
84-
85- # Maps to PWM
86- MultiplexerNode .apply (msg , lambda value : (RANGE_SPEED * value ) + ZERO_SPEED )
87-
88- mc_msg .x = msg .forward
89- mc_msg .z = (
90- Z_RANGE_SPEED * msg .vertical
91- ) + Z_ZERO_SPEED # To account for different z limits
92- mc_msg .y = msg .lateral
93- mc_msg .r = msg .yaw
94- mc_msg .enabled_extensions = EXTENSIONS_CODE
95- mc_msg .s = msg .pitch
96- mc_msg .t = msg .roll
97-
98- return mc_msg
149+ self .previous_instruction_tuple : tuple [float , ...] = pixhawk_instruction_to_tuple (
150+ PixhawkInstruction ()
151+ )
152+
153+ def smooth_pixhawk_instruction (self , msg : PixhawkInstruction ) -> PixhawkInstruction :
154+ instruction_tuple = pixhawk_instruction_to_tuple (msg )
155+
156+ smoothed_tuple = tuple (
157+ smooth_value (previous_value , value )
158+ for (previous_value , value ) in zip (
159+ self .previous_instruction_tuple , instruction_tuple , strict = True
160+ )
161+ )
162+ smoothed_instruction = tuple_to_pixhawk_instruction (smoothed_tuple , msg .author )
163+
164+ self .previous_instruction_tuple = smoothed_tuple
165+
166+ return smoothed_instruction
99167
100168 def state_control (
101169 self , req : AutonomousFlight .Request , res : AutonomousFlight .Response
@@ -111,7 +179,7 @@ def control_callback(self, msg: PixhawkInstruction) -> None:
111179 ):
112180 # Smooth out adjustments
113181 # TODO: look into maybe doing inheritance on a PixhawkInstruction
114- MultiplexerNode . apply (msg , joystick_map )
182+ msg = apply_function (msg , joystick_map )
115183 elif (
116184 msg .author == PixhawkInstruction .KEYBOARD_CONTROL
117185 and self .state == AutonomousFlight .Request .STOP
@@ -123,7 +191,8 @@ def control_callback(self, msg: PixhawkInstruction) -> None:
123191 else :
124192 return
125193
126- self .mc_pub .publish (self .to_manual_control (msg ))
194+ smoothed_instruction = self .smooth_pixhawk_instruction (msg )
195+ self .mc_pub .publish (to_manual_control (smoothed_instruction ))
127196
128197
129198def main () -> None :
0 commit comments