diff --git a/leo_bringup/config/firmware_diff_drive_params.yaml b/leo_bringup/config/firmware_diff_drive_params.yaml
new file mode 100644
index 0000000..6d17ad3
--- /dev/null
+++ b/leo_bringup/config/firmware_diff_drive_params.yaml
@@ -0,0 +1,18 @@
+wheels:
+ encoder_resolution: 878.4
+ torque_constant: 1.17647
+ pid:
+ p: 0.0
+ i: 0.005
+ d: 0.0
+ pwm_duty_limit: 100.0
+
+mecanum_wheels: false
+
+controller:
+ wheel_radius: 0.0625
+ wheel_separation: 0.358
+ angular_velocity_multiplier: 1.76
+ input_timeout: 500
+
+battery_min_voltage: 10.0
\ No newline at end of file
diff --git a/leo_bringup/config/firmware_mecanum_params.yaml b/leo_bringup/config/firmware_mecanum_params.yaml
new file mode 100644
index 0000000..c856909
--- /dev/null
+++ b/leo_bringup/config/firmware_mecanum_params.yaml
@@ -0,0 +1,19 @@
+wheels:
+ encoder_resolution: 878.4
+ torque_constant: 1.17647
+ pid:
+ p: 0.0
+ i: 0.005
+ d: 0.0
+ pwm_duty_limit: 100.0
+
+mecanum_wheels: true
+
+controller:
+ wheel_radius: 0.0635
+ wheel_separation: 0.37
+ wheel_base: 0.3052
+ angular_velocity_multiplier: 1.0
+ input_timeout: 500
+
+battery_min_voltage: 10.0
\ No newline at end of file
diff --git a/leo_bringup/launch/leo_bringup.launch.xml b/leo_bringup/launch/leo_bringup.launch.xml
index d7384e3..4382680 100644
--- a/leo_bringup/launch/leo_bringup.launch.xml
+++ b/leo_bringup/launch/leo_bringup.launch.xml
@@ -4,13 +4,11 @@
default="true"
description="Whether to start the robot_state_publisher node" />
-
-
@@ -18,10 +16,14 @@
default=""
description="The prefix added to each published TF frame id" />
+
+
-
+
+
+
+
+
+
+
+
+
None:
+ super().__init__("firmware_parameter_bridge")
+ self.executor = executor
+
+ leo_fw_share = get_package_share_directory("leo_fw")
+
+ self.declare_parameter(
+ "default_params_file_path",
+ path.join(leo_fw_share, "data", "default_firmware_params.yaml"),
+ )
+ self.declare_parameter("override_params_file_path", "")
+
+ self.load_default_params()
+ self.load_override_params()
+
+ cb_group = MutuallyExclusiveCallbackGroup()
+ self.firmware_parameter_service_client = self.create_client(
+ SetParameters,
+ "firmware/set_parameters",
+ callback_group=cb_group,
+ )
+
+ self.frimware_boot_service_client = self.create_client(
+ Trigger,
+ "firmware/boot",
+ callback_group=cb_group,
+ )
+
+ self.param_bridge_srv = self.create_service(
+ Trigger,
+ "upload_params",
+ self.upload_params_callback,
+ )
+
+ self.firmware_subscriber = self.create_subscription(
+ Empty,
+ "firmware/param_trigger",
+ self.param_trigger_callback,
+ QoSProfile(
+ history=QoSHistoryPolicy.KEEP_LAST,
+ depth=1,
+ reliability=QoSReliabilityPolicy.BEST_EFFORT,
+ durability=QoSDurabilityPolicy.VOLATILE,
+ ),
+ )
+
+ self.send_params()
+
+ def load_default_params(self) -> None:
+ default_params_file: str = (
+ self.get_parameter("default_params_file_path")
+ .get_parameter_value()
+ .string_value
+ )
+
+ with open(default_params_file, "r", encoding="utf-8") as file:
+ self.default_params: dict = yaml.safe_load(file)
+
+ def load_override_params(self) -> None:
+ override_params_file: str = (
+ self.get_parameter("override_params_file_path")
+ .get_parameter_value()
+ .string_value
+ )
+
+ self.override_params = {}
+
+ if override_params_file != "":
+ try:
+ with open(override_params_file, "r", encoding="utf-8") as file:
+ override_yaml = yaml.safe_load(file)
+ if isinstance(override_yaml, dict):
+ self.override_params = override_yaml
+ except (FileNotFoundError, PermissionError, yaml.YAMLError) as exc:
+ self.get_logger().error("Failed to load parameter overrides!")
+ self.get_logger().error(str(exc))
+ else:
+ self.get_logger().warning("Path to file with override parameters is empty.")
+
+ def parse_firmware_parameters(self) -> list[ParameterMsg]:
+ def parse_parameters_recursive(
+ parameters: list[ParameterMsg],
+ param_name_prefix: str,
+ default_dict: dict,
+ override_dict: dict,
+ ) -> None:
+ for key, value in default_dict.items():
+ if isinstance(value, dict):
+ new_name_prefix = param_name_prefix + key + "/"
+ parse_parameters_recursive(
+ parameters,
+ new_name_prefix,
+ value,
+ override_dict.get(key, {}),
+ )
+ continue
+
+ if key in override_dict:
+ value = override_dict[key]
+
+ new_param = rclpy.Parameter(
+ param_name_prefix + key, self.type_dict[type(value)], value
+ )
+ parameters.append(new_param.to_parameter_msg())
+
+ parameters: list[ParameterMsg] = []
+ parse_parameters_recursive(
+ parameters, "", self.default_params, self.override_params
+ )
+ return parameters
+
+ def param_trigger_callback(self, _msg: Empty) -> None:
+ self.get_logger().info("Request for firmware parameters.")
+ success, _ = self.send_params()
+ if success:
+ self.trigger_boot()
+
+ def upload_params_callback(
+ self, _request: Trigger.Request, response: Trigger.Response
+ ) -> Trigger.Response:
+ self.get_logger().info(
+ "Serving user request for setting firmware parameters..."
+ )
+
+ self.load_override_params()
+
+ result, num = self.send_params()
+ if result:
+ response.message = "Successfully set firmware parameters."
+ if num > 0:
+ response.message += (
+ f" {num} parameter(s) was(were) not set. Check node logs."
+ )
+ response.success = True
+ else:
+ response.message = "Failed to set firmware parameters."
+ response.success = False
+
+ return response
+
+ def send_params(self) -> tuple[bool, int]:
+ self.get_logger().info("Trying to set parameters for firmware node...")
+
+ not_set_params_num = 0
+ if not self.firmware_parameter_service_client.wait_for_service(timeout_sec=1.0):
+ self.get_logger().error("Firmware parameter service not active!")
+ return (False, not_set_params_num)
+
+ param_request = SetParameters.Request()
+ param_request.parameters = self.parse_firmware_parameters()
+ future = self.firmware_parameter_service_client.call_async(param_request)
+
+ self.executor.spin_until_future_complete(future, 5.0)
+
+ if future.result():
+ result: SetParametersResult
+ param: ParameterMsg
+ for result, param in zip(future.result().results, param_request.parameters):
+ if not result.successful:
+ self.get_logger().warning(
+ f"Parameter '{param.name}' not set. Reason: '{result.reason}'"
+ )
+ not_set_params_num += 1
+
+ self.get_logger().info("Successfully set parameters for firmware node.")
+
+ return (True, not_set_params_num)
+
+ self.get_logger().error("Unable to set parameters for firmware node.")
+ return (False, not_set_params_num)
+
+ def trigger_boot(self) -> bool:
+ self.get_logger().info("Trying to trigger firmware boot.")
+
+ if not self.frimware_boot_service_client.wait_for_service(timeout_sec=1.0):
+ self.get_logger().error("Firmware boot service not active!")
+
+ boot_request = Trigger.Request()
+ boot_future = self.frimware_boot_service_client.call_async(boot_request)
+
+ self.executor.spin_until_future_complete(boot_future, 5.0)
+
+ if boot_future.result():
+ self.get_logger().info("Firmware boot triggered successfully.")
+ return True
+
+ self.get_logger().error("Didn't get response from firmware boot service!")
+ return False
diff --git a/leo_fw/scripts/firmware_parameter_bridge b/leo_fw/scripts/firmware_parameter_bridge
new file mode 100755
index 0000000..b35c656
--- /dev/null
+++ b/leo_fw/scripts/firmware_parameter_bridge
@@ -0,0 +1,19 @@
+#!/usr/bin/env python3
+
+from leo_fw.nodes import ParameterBridge
+
+import rclpy
+from rclpy.executors import MultiThreadedExecutor
+
+rclpy.init()
+
+executor = MultiThreadedExecutor(num_threads=4)
+
+param_bridge = ParameterBridge(executor)
+
+executor.add_node(param_bridge)
+executor.spin()
+
+param_bridge.get_logger().info("Finishing node.")
+param_bridge.destroy_node()
+rclpy.shutdown()