diff --git a/.devcontainer/dev/Dockerfile b/.devcontainer/dev/Dockerfile index bbddea36f..ea6fcc382 100644 --- a/.devcontainer/dev/Dockerfile +++ b/.devcontainer/dev/Dockerfile @@ -18,6 +18,7 @@ RUN apt update && apt install -y --no-install-recommends \ # Install MoveIt: RUN apt update && apt install -y --no-install-recommends \ + ros-$ROS_DISTRO-imu-filter-madgwick \ ros-$ROS_DISTRO-moveit \ ros-$ROS_DISTRO-moveit-servo \ ros-$ROS_DISTRO-moveit-visual-tools \ @@ -59,6 +60,7 @@ COPY alliander_joystick/src/ /alliander/ros/src COPY alliander_meta/src/ /alliander/ros/src COPY alliander_moveit/src/ /alliander/ros/src COPY alliander_nav2/src/ /alliander/ros/src +COPY alliander_xsens/src/ /alliander/ros/src # Build repo packages: RUN /alliander/colcon_build.sh diff --git a/.gitignore b/.gitignore index 30e501449..f4c655787 100644 --- a/.gitignore +++ b/.gitignore @@ -22,6 +22,7 @@ clangd/ .venv # for LSP in neovim +.nvim/ **/compile_commands.json # generated compose files diff --git a/alliander_core/src/alliander_description/CMakeLists.txt b/alliander_core/src/alliander_description/CMakeLists.txt index bc5167f99..ccb6a8186 100644 --- a/alliander_core/src/alliander_description/CMakeLists.txt +++ b/alliander_core/src/alliander_description/CMakeLists.txt @@ -11,7 +11,7 @@ find_package(ament_cmake_python REQUIRED) # Shared folders: install( - DIRECTORY franka husarion ouster velodyne realsense zed nmea_gps + DIRECTORY franka husarion nmea_gps ouster velodyne realsense xsens zed DESTINATION share/${PROJECT_NAME} ) diff --git a/alliander_core/src/alliander_description/husarion/urdf/original/gazebo.urdf.xacro b/alliander_core/src/alliander_description/husarion/urdf/original/gazebo.urdf.xacro index e451f3167..546d9f4af 100644 --- a/alliander_core/src/alliander_description/husarion/urdf/original/gazebo.urdf.xacro +++ b/alliander_core/src/alliander_description/husarion/urdf/original/gazebo.urdf.xacro @@ -141,4 +141,4 @@ - \ No newline at end of file + diff --git a/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl b/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl new file mode 100644 index 000000000..df8d2ae91 Binary files /dev/null and b/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl differ diff --git a/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl.license b/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl.license new file mode 100644 index 000000000..14a6ee96d --- /dev/null +++ b/alliander_core/src/alliander_description/xsens/meshes/MTi-6x0R.stl.license @@ -0,0 +1,3 @@ +SPDX-FileCopyrightText: Alliander N. V. + +SPDX-License-Identifier: Apache-2.0 diff --git a/alliander_core/src/alliander_description/xsens/urdf/xsens.urdf.xacro b/alliander_core/src/alliander_description/xsens/urdf/xsens.urdf.xacro new file mode 100644 index 000000000..7afe8b399 --- /dev/null +++ b/alliander_core/src/alliander_description/xsens/urdf/xsens.urdf.xacro @@ -0,0 +1,106 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + 100 + ${namespace}/imu/data + false + false + ${namespace}/imu_link + + + ENU + + + + 0.01.75e-49.7e-60.0 + 0.01.75e-49.7e-60.0 + 0.01.75e-49.7e-60.0 + + + + 0.03.0e-39.8e-50.0 + 0.03.0e-39.8e-50.0 + 0.03.0e-39.8e-50.0 + + + + + + + + + + + + + + diff --git a/alliander_core/src/alliander_utilities/alliander_utilities/config_objects.py b/alliander_core/src/alliander_utilities/alliander_utilities/config_objects.py index 22f4888a7..3caf608c4 100644 --- a/alliander_core/src/alliander_utilities/alliander_utilities/config_objects.py +++ b/alliander_core/src/alliander_utilities/alliander_utilities/config_objects.py @@ -331,6 +331,19 @@ class GPS(Platform): diagnostic_timeouts: tuple[int, int, int] = (3, 5, 10) +@dataclass +class IMU(Platform): + """Configuration for an IMU platform. + + Attributes: + platform_type (str): Type identifier for the platform. + usb_device (str): USB device path, e.g. /dev/imu. + """ + + platform_type: str = "IMU" + usb_device: str = "/dev/imu" + + # Configurations containing lists of platforms: @dataclass class PlatformList(Config): @@ -342,7 +355,7 @@ class PlatformList(Config): platforms: List[ Annotated[ - Union[Platform, Arm, Vehicle, Lidar, Camera, GPS], + Union[Platform, Arm, Vehicle, Camera, GPS, IMU, Lidar], Discriminator(field="platform_type", include_supertypes=True), ] ] = field(default_factory=list) diff --git a/alliander_gazebo/src/alliander_gazebo/launch/gazebo.launch.py b/alliander_gazebo/src/alliander_gazebo/launch/gazebo.launch.py index d90d7bf45..07b0cfbed 100644 --- a/alliander_gazebo/src/alliander_gazebo/launch/gazebo.launch.py +++ b/alliander_gazebo/src/alliander_gazebo/launch/gazebo.launch.py @@ -83,6 +83,10 @@ def get_bridge_topics(platforms: list[T]) -> list[str]: bridge_topics.append( f"/{platform.namespace}/gps/fix@sensor_msgs/msg/NavSatFix@gz.msgs.NavSat" ) + if platform.platform_type == "IMU": + bridge_topics.append( + f"/{platform.namespace}/imu/data@sensor_msgs/msg/Imu@gz.msgs.IMU" + ) return bridge_topics diff --git a/alliander_gps/alliander_gps.Dockerfile b/alliander_gps/alliander_gps.Dockerfile index dfbba64df..ccf2e4558 100644 --- a/alliander_gps/alliander_gps.Dockerfile +++ b/alliander_gps/alliander_gps.Dockerfile @@ -11,7 +11,6 @@ ENV ROS_DISTRO=jazzy RUN apt update && apt install -y --no-install-recommends \ ros-$ROS_DISTRO-husarion-components-description \ ros-$ROS_DISTRO-nmea-navsat-driver \ - ros-$ROS_DISTRO-robot-localization \ && rm -rf /var/lib/apt/lists/* \ && apt autoremove -y \ && apt clean diff --git a/alliander_gps/src/alliander_gps/launch/gps.launch.py b/alliander_gps/src/alliander_gps/launch/gps.launch.py index 552c5a742..495a2306e 100644 --- a/alliander_gps/src/alliander_gps/launch/gps.launch.py +++ b/alliander_gps/src/alliander_gps/launch/gps.launch.py @@ -1,7 +1,6 @@ # SPDX-FileCopyrightText: Alliander N. V. # # SPDX-License-Identifier: Apache-2.0 -from alliander_utilities.adapted_yaml import AdaptedYaml from alliander_utilities.config_objects import GPS from alliander_utilities.launch_argument import LaunchArgument from alliander_utilities.launch_utils import SKIP, state_publisher_node, static_tf_node @@ -9,7 +8,7 @@ from alliander_utilities.ros_utils import get_file_path from launch import LaunchContext, LaunchDescription from launch.actions import OpaqueFunction -from launch_ros.actions import Node, SetParameter +from launch_ros.actions import SetParameter T, F = True, False @@ -50,57 +49,11 @@ def launch_setup(context: LaunchContext) -> list: {"platform_config": gps_config.to_str()}, ) - ekf_global_params = AdaptedYaml( - get_file_path("alliander_gps", ["config"], "ekf_global.yaml"), - { - "odom_frame": f"{gps_config.parent.namespace}/odom", - "base_link_frame": f"{gps_config.parent.namespace}/base_footprint", - "odom0": f"/{gps_config.parent.namespace}/odometry/wheels", - "odom1": f"/{gps_config.namespace}/odometry/gps", - "imu0": f"/{gps_config.parent.namespace}/imu/data", - }, - root_key=gps_config.parent.namespace, - ) - navsat_transform_params = AdaptedYaml( - get_file_path("alliander_gps", ["config"], "navsat_transform.yaml"), - {}, - root_key=gps_config.parent.namespace, - ) - - navsat_transform = Node( - package="robot_localization", - executable="navsat_transform_node", - name="navsat_transform", - namespace=gps_config.namespace, - parameters=[navsat_transform_params.file], - remappings=[ - ("imu", f"/{gps_config.parent.namespace}/imu/data"), - ( - "odometry/filtered", - f"/{gps_config.parent.namespace}/odometry/global", - ), - ], - ) - - # Define EKF node that creates the tf between odom and map: - ekf_global = Node( - package="robot_localization", - executable="ekf_node", - name="ekf_global", - namespace=gps_config.parent.namespace, - parameters=[ekf_global_params.file], - remappings=[ - ("odometry/filtered", f"/{gps_config.parent.namespace}/odometry/global"), - ], - ) - return [ SetParameter(name="use_sim_time", value=gps_config.simulation), Register.on_start(state_publisher, context), Register.on_start(static_tf, context), Register.group(hardware, context) if not gps_config.simulation else SKIP, - Register.on_start(navsat_transform, context) if parent.link else SKIP, - Register.on_start(ekf_global, context) if parent.link else SKIP, ] diff --git a/alliander_nav2/alliander_nav2.Dockerfile b/alliander_nav2/alliander_nav2.Dockerfile index 047275812..60d9777ba 100644 --- a/alliander_nav2/alliander_nav2.Dockerfile +++ b/alliander_nav2/alliander_nav2.Dockerfile @@ -11,6 +11,7 @@ ENV ROS_DISTRO=jazzy RUN apt update && apt install -y --no-install-recommends \ ros-$ROS_DISTRO-navigation2 \ ros-$ROS_DISTRO-nav2-bringup \ + ros-$ROS_DISTRO-robot-localization \ ros-$ROS_DISTRO-slam-toolbox \ && rm -rf /var/lib/apt/lists/* \ && apt autoremove -y \ diff --git a/alliander_nav2/src/alliander_nav2/config/nav2/ekf_global.yaml b/alliander_nav2/src/alliander_nav2/config/nav2/ekf_global.yaml new file mode 100644 index 000000000..4ef9cb6e5 --- /dev/null +++ b/alliander_nav2/src/alliander_nav2/config/nav2/ekf_global.yaml @@ -0,0 +1,101 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + +# Based on: https://github.com/husarion/husarion_ugv_ros/blob/ros2/husarion_ugv_localization/config/enu_localization_with_gps.yaml +ekf_global: + ros__parameters: + frequency: 20.0 + sensor_timeout: 0.05 + two_d_mode: true + + transform_time_offset: 0.0 + transform_timeout: 0.05 + + world_frame: map + map_frame: map + odom_frame: substitute_me + base_link_frame: substitute_me + publish_tf: true + publish_acceleration: false + + odom0: substitute_me + odom0_config: [false, false, false, + false, false, false, + true, true, false, + false, false, true, + false, false, false] + odom0_queue_size: 3 + odom0_nodelay: true + odom0_differential: false + odom0_relative: true + + odom1: substitute_me + odom1_config: [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] + odom1_queue_size: 2 + odom1_differential: false + odom1_relative: false + + imu0: substitute_me + imu0_config: [false, false, false, + false, false, true, + false, false, false, + false, false, true, + false, false, false] + imu0_queue_size: 3 + imu0_nodelay: true + imu0_differential: false + imu0_relative: false + imu0_remove_gravitational_acceleration: false + + use_control: true + stamped_control: true + control_timeout: 0.5 + control_config: [true, true, false, false, false, true] + acceleration_limits: [2.7, 1.5, 0.0, 0.0, 0.0, 5.7] # Values taken from WH01_controller.yaml and WH02_controller.yaml inside husarion_ugv_controller/config + + predict_to_current_time: true + + # Selected values ​​experimentally so as to ensure relatively fast convergence (values ​​should be about 10x higher than the sensor variance values) + dynamic_process_noise_covariance: true + process_noise_covariance: [5e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 5e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 5e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 3e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 3e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 3e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-4, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-4, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2e-4, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5e-5, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5e-5, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5e-5] + + initial_state: [0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0] + + initial_estimate_covariance: [1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 1e5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9] diff --git a/alliander_nav2/src/alliander_nav2/config/nav2/navsat_transform.yaml b/alliander_nav2/src/alliander_nav2/config/nav2/navsat_transform.yaml new file mode 100644 index 000000000..6a0814b15 --- /dev/null +++ b/alliander_nav2/src/alliander_nav2/config/nav2/navsat_transform.yaml @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + +# Based on: https://github.com/husarion/husarion_ugv_ros/blob/ros2/husarion_ugv_localization/config/enu_localization_with_gps.yaml +navsat_transform: + navsat_transform: + ros__parameters: + delay: 3.0 + magnetic_declination_radians: 0.0 + yaw_offset: 0.0 + zero_altitude: true + broadcast_cartesian_transform: false + publish_filtered_gps: true + use_odometry_yaw: true + wait_for_datum: false diff --git a/alliander_nav2/src/alliander_nav2/launch/nav2.launch.py b/alliander_nav2/src/alliander_nav2/launch/nav2.launch.py index fe458d9b4..efd857c26 100644 --- a/alliander_nav2/src/alliander_nav2/launch/nav2.launch.py +++ b/alliander_nav2/src/alliander_nav2/launch/nav2.launch.py @@ -15,7 +15,7 @@ platform_arg = LaunchArgument("platform_config", "") -def launch_setup(context: LaunchContext) -> list: # noqa: PLR0915 +def launch_setup(context: LaunchContext) -> list: # noqa: PLR0912, PLR0915 """The launch setup. Args: @@ -34,11 +34,17 @@ def launch_setup(context: LaunchContext) -> list: # noqa: PLR0915 # Extract lidar and gps namespaces from childs. The first found will be used: namespace_gps = "" namespace_lidar = "" + namespace_imu = "" for child in vehicle_config.childs: if child.platform_type == "Lidar" and not namespace_lidar: namespace_lidar = child.namespace if child.platform_type == "GPS" and not namespace_gps: namespace_gps = child.namespace + if child.platform_type == "IMU" and not namespace_imu: + namespace_imu = child.namespace + # if no external IMU is found, use the vehicle's internal IMU + if not namespace_imu: + namespace_imu = namespace_vehicle # Define configuration: lifecycle_nodes_names = [] @@ -95,6 +101,24 @@ def launch_setup(context: LaunchContext) -> list: # noqa: PLR0915 root_key=namespace_vehicle, ) + ekf_global_params = AdaptedYaml( + get_file_path("alliander_nav2", ["config", "nav2"], "ekf_global.yaml"), + { + "odom_frame": f"{namespace_vehicle}/odom", + "base_link_frame": f"{namespace_vehicle}/base_footprint", + "odom0": f"/{namespace_vehicle}/odometry/wheels", + "odom1": f"/{namespace_gps}/odometry/gps", + "imu0": f"/{namespace_imu}/imu/data", + }, + root_key=namespace_vehicle, + ) + + navsat_transform_params = AdaptedYaml( + get_file_path("alliander_nav2", ["config", "nav2"], "navsat_transform.yaml"), + {}, + root_key=namespace_gps, + ) + local_costmap_params = AdaptedYaml( get_file_path("alliander_nav2", ["config", "nav2"], "local_costmap.yaml"), { @@ -303,6 +327,30 @@ def launch_setup(context: LaunchContext) -> list: # noqa: PLR0915 namespace=namespace_vehicle, ) + # robot-localization nodes + ekf_global = Node( + package="robot_localization", + executable="ekf_node", + name="ekf_global", + namespace=namespace_vehicle, + parameters=[ekf_global_params.file], + remappings=[ + ("odometry/filtered", f"/{namespace_vehicle}/odometry/global"), + ], + ) + + navsat_transform = Node( + package="robot_localization", + executable="navsat_transform_node", + name="navsat_transform", + namespace=namespace_gps, + parameters=[navsat_transform_params.file], + remappings=[ + ("odometry/filtered", f"/{namespace_vehicle}/odometry/global"), + ("imu", f"/{namespace_imu}/imu/data"), + ], + ) + nav2_manager = Node( package="alliander_nav2", executable="nav2_manager.py", @@ -324,6 +372,8 @@ def launch_setup(context: LaunchContext) -> list: # noqa: PLR0915 SetParameter(name="use_sim_time", value=vehicle_config.simulation), SetRemap(src=f"/{namespace_vehicle}/cmd_vel", dst=pub_topic), *[Register.on_start(node, context) for node in register_lifecycle_nodes], + Register.on_start(ekf_global, context) if nav2.gps else SKIP, + Register.on_start(navsat_transform, context) if nav2.gps else SKIP, Register.on_log(lifecycle_manager, "Managed nodes are active", context), Register.on_log(nav2_manager, "Controller is ready.", context) if nav2.navigation diff --git a/alliander_nav2/src/alliander_nav2/test/test_gps_waypoint_follower.py b/alliander_nav2/src/alliander_nav2/test/test_gps_waypoint_follower.py index 0b2ead4e2..f7332cb3e 100755 --- a/alliander_nav2/src/alliander_nav2/test/test_gps_waypoint_follower.py +++ b/alliander_nav2/src/alliander_nav2/test/test_gps_waypoint_follower.py @@ -34,21 +34,29 @@ class Route(Enum): """Enum containing predefined routes for GPS Waypoint Follower. Attributes: - KB_TRUCK_PARKING_SPACE: Route nearby Roboticalab entrance. + IPKW_KB_TRUCK_PARKING_SPACE: Route nearby Roboticalab entrance. + IPKW_KB_RAMP: Route nearby Roboticalab entrance. SIM_TIGHT_ALLEYS: Simulation route in Arnhem, with buildings close together. """ - KB_TRUCK_PARKING_SPACE = auto() + IPKW_KB_TRUCK_PARKING_SPACE = auto() + IPKW_KB_RAMP = auto() SIM_TIGHT_ALLEYS = auto() ROUTES: dict[Route, list[GPSWaypoint]] = { - Route.KB_TRUCK_PARKING_SPACE: [ + Route.IPKW_KB_TRUCK_PARKING_SPACE: [ GPSWaypoint(51.966663, 5.940867), GPSWaypoint(51.966511, 5.940912), GPSWaypoint(51.966512, 5.940945), GPSWaypoint(51.966661, 5.940892, yaw=math.pi / 4), ], + Route.IPKW_KB_RAMP: [ + GPSWaypoint(51.966705, 5.940815, yaw=-math.pi / 4), + GPSWaypoint(51.966705, 5.940869), + GPSWaypoint(51.966694, 5.940869), + GPSWaypoint(51.966694, 5.940815, yaw=math.pi / 4), + ], Route.SIM_TIGHT_ALLEYS: [ GPSWaypoint(51.977291, 5.954022, yaw=-math.pi), GPSWaypoint(51.977251, 5.954025, yaw=-math.pi / 4), @@ -166,9 +174,11 @@ def _yaw_to_quaternion(yaw: float) -> Quaternion: \n\nInput: " ) match route_input: - case "KB_TRUCK_PARKING_SPACE" | "0": - route = Route.KB_TRUCK_PARKING_SPACE - case "SIM_TIGHT_ALLEYS" | "1": + case "IKPW_KB_TRUCK_PARKING_SPACE" | "0": + route = Route.IPKW_KB_TRUCK_PARKING_SPACE + case "IKPW_KB_RAMP" | "1": + route = Route.IPKW_KB_RAMP + case "SIM_TIGHT_ALLEYS" | "2": route = Route.SIM_TIGHT_ALLEYS case _: print("No valid route given. Defaulting to SIM_TIGHT_ALLEYS.") diff --git a/alliander_visualization/src/alliander_visualization/alliander_visualization/tool_manager.py b/alliander_visualization/src/alliander_visualization/alliander_visualization/tool_manager.py index ab3641c92..a7c08a9f7 100644 --- a/alliander_visualization/src/alliander_visualization/alliander_visualization/tool_manager.py +++ b/alliander_visualization/src/alliander_visualization/alliander_visualization/tool_manager.py @@ -51,6 +51,8 @@ def __init__(self, config: VisualizationConfig, platform_list: PlatformList): self.add_depth_camera(Camera.from_str(platform.to_str())) case "GPS": self.add_gps(GPS.from_str(platform.to_str())) + case "IMU": + pass case _: raise NotImplementedError( f"Configuration for platform {type(platform).__name__} is not implemented." diff --git a/alliander_xsens/alliander_xsens.Dockerfile b/alliander_xsens/alliander_xsens.Dockerfile new file mode 100644 index 000000000..795f299db --- /dev/null +++ b/alliander_xsens/alliander_xsens.Dockerfile @@ -0,0 +1,43 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 +ARG BASE_IMAGE=ubuntu:latest +FROM $BASE_IMAGE + +ARG COLCON_BUILD_SEQUENTIAL +ENV ROS_DISTRO=jazzy + +# Install ROS dependencies +RUN apt update && apt install -y --no-install-recommends \ + ros-$ROS_DISTRO-imu-filter-madgwick \ + ros-$ROS_DISTRO-nmea-msgs \ + ros-$ROS_DISTRO-mavros-msgs \ + && rm -rf /var/lib/apt/lists/* \ + && apt autoremove -y \ + && apt clean + +# Install Xsens package: +WORKDIR /$WORKDIR/external +RUN apt update \ + && git clone -b ros2 https://github.com/xsenssupport/Xsens_MTi_ROS_Driver_and_Ntrip_Client.git src/xsens \ + && rosdep update --rosdistro $ROS_DISTRO \ + && rosdep install --from-paths src -y -i +RUN /$WORKDIR/colcon_build.sh + +# Install repo packages: +WORKDIR /$WORKDIR/ros +COPY alliander_core/src/ /$WORKDIR/ros/src +COPY alliander_xsens/src/ /$WORKDIR/ros/src +RUN /$WORKDIR/colcon_build.sh + +# Install python dependencies: +WORKDIR $WORKDIR +COPY pyproject.toml /$WORKDIR/pyproject.toml +RUN uv sync --group alliander-xsens \ + && echo "export PYTHONPATH=\"$(dirname $(dirname $(uv python find)))/lib/python3.12/site-packages:\$PYTHONPATH\"" >> /root/.bashrc \ + && echo "export PATH=\"$(dirname $(dirname $(uv python find)))/bin:\$PATH\"" >> /root/.bashrc + +# Finalize +WORKDIR /$WORKDIR +ENTRYPOINT ["/entrypoint.sh"] +CMD ["sleep", "infinity"] diff --git a/alliander_xsens/docker-compose.yml b/alliander_xsens/docker-compose.yml new file mode 100644 index 000000000..33db70db8 --- /dev/null +++ b/alliander_xsens/docker-compose.yml @@ -0,0 +1,20 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 +services: + alliander_xsens: + image: allianderrobotics/xsens + container_name: alliander_xsens + runtime: nvidia + # USB device is not found by Xsens node first time after boot + restart: on-failure:3 + network_mode: host + privileged: true + mem_limit: 6gb + tty: true + env_file: + - .env + volumes: + - "/tmp/.X11-unix:/tmp/.X11-unix" + - "/dev:/dev" + command: ["/bin/bash", "-c", "ros2 launch alliander_xsens xsens.launch.py"] diff --git a/alliander_xsens/src/alliander_xsens/CMakeLists.txt b/alliander_xsens/src/alliander_xsens/CMakeLists.txt new file mode 100644 index 000000000..5573c3921 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/CMakeLists.txt @@ -0,0 +1,43 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.5) +project(alliander_xsens) + +# CMake dependencies: +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) + +# C++ executables: +include_directories(include) +add_executable(imu_bridge_node + src/main.cpp + src/imu_bridge.cpp +) +ament_target_dependencies(imu_bridge_node + rclcpp + geometry_msgs + sensor_msgs +) +install( + TARGETS imu_bridge_node + DESTINATION lib/${PROJECT_NAME} +) + +# Shared folders: +install( + DIRECTORY config launch + DESTINATION share/${PROJECT_NAME} +) + +# Default test: +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/alliander_xsens/src/alliander_xsens/config/xsens_mti_node.yaml b/alliander_xsens/src/alliander_xsens/config/xsens_mti_node.yaml new file mode 100644 index 000000000..d56583c0b --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/config/xsens_mti_node.yaml @@ -0,0 +1,272 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 +# +# Based on: https://github.com/xsenssupport/Xsens_MTi_ROS_Driver_and_Ntrip_Client/blob/main/src/xsens_ros_mti_driver/param/xsens_mti_node.yaml +/**: + ros__parameters: + # Device Scanning Configuration + # ----------------------------- + # This section allows you to configure how the ROS driver searches for devices. + # You have two options: + # 1. Automatic scanning for devices. + # 2. Manual specification of port and baudrate. + + # Option 1: Automatic Device Scanning + # If set to 'true', the driver will ignore 'port' and 'baudrate' settings. + # It will automatically scan all ports and select the first device found. + scan_for_devices: true + + # Option 2: Manual Device Configuration + # If you prefer to manually specify the device port and baudrate, + # first set 'scan_for_devices' to 'false', then uncomment and update + # the 'port' and 'baudrate' settings below according to your device's specifications. + # + # To find your device's port, you can use the command: ls -l /dev/ttyUSB* + # + # Default baudrate is 115200. You can also use external tools like MT Manager + # or Cutecom for baudrate configuration. For example, + # to set baudrate to 115200, send the command: FA FF 30 00 D1, + # or to set it to 921600, send: FA FF 18 01 80 68. + + # port: '/dev/xsens' # Uncomment and set your device's port. + # baudrate: 115200 # Uncomment and set your device's baudrate. + + # Device Scanning Selection + # ---------------- + # Specify the device ID when operating multiple devices to select a specific one. + # Format: Uppercase hexadecimal string. + # Example: device_id: '00800210C2' + #device_id: '00800210C2' + + # Publisher Configuration + publisher_queue_size: 5 + + # Time Options + # ------------ + # Choose how timestamps are generated for the ROS Node: + # 1) 0: Use UTCTime from MTI, recommended for accurate time synchronization. + # 2) 1: Use UTCTime based on the SampleTimeFine from MTI. + # 3) 2: Use UTCTime from the host device. + # Note: Ensure "UTC Time" or "Sample Time Fine" is selected in MT Manager under Device Settings > Output Configurations, + # or you could also set 'enable_deviceConfig: true' for once to configure output. + time_option: 0 + + # Logging Configuration + # --------------------- + # Enable or disable logging of sensor data into .mtb file. If enabled, logs are stored in /home/[user_name]/Documents/xsens_log. + enable_logging: false + + # Transform Frame ID + # ------------------ + # Default frame_id is "imu_link". Change this if using multiple devices to avoid conflicts. + # frame_id: "imu_link" + + + # Sensor Configuration + # --------------------------- + # If you want to configure your sensor, firstly set this flag to true, then change desired values for the parameters below. + # Note: This configuration is required only once, once it is successful, the configurations are stored in the sensor, then you could set this to false. + enable_deviceConfig: false + + # Sensor Extended Kalman Filter Option Configurations: + # -------------------------- + # ref: https://base.movella.com/s/article/article/MTi-Filter-Profiles-1605869708823 + # If you want to configure the filter option, firstly set the 'enable_filter_config', then: + # For MTi-3/7/8/30/300/G-710/670(G)/680(G): change the 'mti_filter_option' to desired index below for your model. + # For MTi-620(R)/MTi-630(R), and Sirius/Avior VRU/AHRS models: change the 'filter_label_rollpitch' and 'filter_label_yaw' to the exact labels. + enable_filter_config: false + # --------------------------- + # For MTi-670(G): 3 options: 0 = "General", 1 = "GeneralNoBaro", 2 = "GeneralMag" + # For MTi-680(G), 3 options: 0 = "General_RTK", 1 = "GeneralNoBaro_RTK", 2 = "GeneralMag_RTK" + # For MTi-3: 4 options: 0 = "general", 1 = "high_mag_dep", 2 = "dynamic", 3 = "north_reference", 4 = "vru_general" + # For MTi-320: 1 option: 0 = "vru_general" + # For MTi-7: 3 options: 0 = "General", 1 = "GeneralMag", 2 = "GeneralNoBaro" + # For MTi-8: 3 options: 0 = "General_RTK", 1 = "GeneralNoBaro_RTK", 2 = "GeneralMag_RTK" + # For MTi-300: 0 = "general", 1 = "high_mag_dep", 2 = "dynamic", 3 = "lwo_mag_dep", 4 = "vru_general" + # For MTI-G-710: 3 options: 0 = "General", 1 = "GeneralNoBaro", 2 = "GeneralMag", 3 = "Automotive", 4 = "HighPerformanceEDR" + mti_filter_option: 0 + + # For MTi-620(R)/MTi-630(R), and Sirius/Avior VRU/AHRS models: roll pitch options: "Responsive", "General", "Robust" + filter_label_rollpitch: "Robust" + # MTI-620(R) and Sirius/Avior VRU models, yaw has 2 options: "VRU", "VRUAHS" + # MTI-630(R) and Sirius/Avior AHRS models, yaw has 3 options: "FixedMagRef", "NorthReference", "VRU", "VRUAHS" + filter_label_yaw: "NorthReference" + + + # MTi-2/320/200: filter only has VRU, you could enable the AHS options: + # valid for MTI-2/3/320, MTi-20/30, MTI-200/300 when using the VRU filter options. + enable_active_heading_stabilization: false + + + # GNSS Lever Arm Configuration + # ----------------------------------------------- + # Note: Adjust the GNSS lever arm settings only if the antenna's position relative to the sensor has changed. + + # GNSS Lever Arm (meters): [X, Y, Z] + # Applicable to: MTi-8/680(G) + # Default: [0.0, 0.0, 0.0] for unchanged antenna position. + GNSS_LeverArm: [0.0, 0.0, 0.0] + + # u-blox GNSS Platform Settings + # ----------------------------- + # Options: + # 0 = Portable + # 2 = Stationary + # 3 = Pedestrian + # 4 = Automotive + # 5 = AtSea + # 6 = Airborne < 1g + # 7 = Airborne < 2g + # 8 = Airborne < 4g + # 9 = Wrist + # Applicable to: MTi-7/8/670(G)/680(G)/G-710 (GNSS/INS versions). + ublox_platform: 0 + + # u-blox GNSS Receiver Settings + # ----------------------------- + # If set true: Enables Beidou, disables GLONASS + # If set false: Disables Beidou, enables GLONASS + # valid for MTi-7/8/670/680/710 + enable_beidou: false + + + # Message Publishers, Also the output configurations if enable_deviceConfig is set to true + # ------------------ + # Enable or disable publication of various sensor data: + pub_utctime: true + pub_sampletime: true + pub_imu: true + pub_quaternion: true + pub_euler: true + pub_free_acceleration: true + pub_angular_velocity: true + pub_acceleration: true + pub_dq: false + pub_dv: false + pub_mag: true + pub_temperature: true + pub_pressure: true + pub_accelerationhr: false #High Rate Data Acceleration, when this is true, set enable_high_rate to true as well + pub_angular_velocity_hr: false #High Rate Data Angular Velocity, when this is true, set enable_high_rate to true as well + pub_transform: true + pub_status: true + pub_twist: true # For GNSS/INS Version of MTI only + pub_gnss: true # For GNSS/INS Version of MTI only + pub_positionLLA: true # For GNSS/INS Version of MTI only + pub_velocity: true # For GNSS/INS Version of MTI only + pub_nmea: true # For GNSS/INS Version of MTI only + pub_gnsspose: true # For GNSS/INS Version of MTI only + pub_odometry: false # For GNSS/INS Version of MTI only + pub_euler_stddev: false # For Sirius and Avior AHRS/VRU only, this is for setouput config, and value will be published at /imu/data topic. + pub_ship_motion: true # For Sirius and Avior AHRS Only + + + + # Output Data Rate + # ---------------- + # Set the desired output data rate in Hz. The driver will automatically configure the device to match this rate. + # options for MTi-610/620/630/670/680/710/Sirius/Avior quaternion/euler/temperature/dq/dv/rateofturn/acc/free_acc, and for Sirius/Avior EulerStdDev: + #1, 2, 4, 5, 8, 10, 16, 20, 25, 40, 50, 80, 100, 200, 400 + # options for MTi-670/680/710 position/velocity: 1, 2, 4, 5, 8, 10, 16, 20, 25, 40, 50, 80, 100, 200, 400 + # Change 'output_data_rate' if you are using mti-600 or 100 series + output_data_rate: 100 + # options for MTi-1/2/3/7/8: 1, 2, 4, 5, 10, 20, 25, 50, 100 + # options for MTi-600, 710, Sirius, Avior series: mag, baro pressure, max 100Hz:1, 2, 4, 5, 10, 20, 25, 50, 100 + # options for MTi-7/8 series: baro pressure, max 50Hz:1, 2, 5, 10, 25, 50 + # Change 'output_data_rate_lower' if you are using mti-1 series or if you want to change output rate for mag, baro for other product series + # Change 'output_data_rate_lower' if you want to change the output rate for heave position and heave period + output_data_rate_lower: 100 + # Change 'output_data_rate_baro_mtione' if you use mti-7/8 only. + output_data_rate_baro_mtione: 50 + + # High Rate Data for AccelerationHR and RateOfTurn: + # ------------------------------------------------ + # if you want to enable high rate data, firstly change the 'enable_high_rate' to true, then change the data rate according to your sensor model. + enable_high_rate: false + #options for MTi-1 v2: 800, 400, 200, 160 + #options for MTi-1 v3: 1000, 500, 250, 200, 125 + #options for MTi-600/Sirius/Avior: 2000, 1000, 500 + #option for MTi-100/200/300: 1000 + output_data_rate_acchr: 1000 + #options for MTi-1 v2: 800, 400, 200, 160 + #options for MTi-1 v3: 1000, 500, 250, 200, 125 + #options for MTI-600: 1600, 800 + #option for MTi-100/200/300: 1000 + #option for Sirius/Avior: 2000, 1000, 500 + output_date_rate_gyrohr: 1000 + # whether using high rate acceleration data(accelerationHR) to interpolate the orientation and rateofturnHR data. + # when this is set to true, output_data_rate_acchr must >= output_date_rate_gyrohr + interpolate_orientation_high_rate: false + + # Filtering Option Flags + # ------------------------------------- + enable_orientation_smoother: true #valid for MTi-G-710, MTi-670(G), MTi-680(G) + enable_position_velocity_smoother: true #valid for MTi-680(G) only + enable_continuous_zero_rotation_update: true #valid for MTi-680(G) only + + # Other option flags: + # valid for MTi-2/3/7/8/20/30/620/630/670/680/200/300/710/Sirius/Avior + enable_inrun_compass_calibration: false + + + # Set baudrate + # --------------- + #This is necessary if you have hig output rate, and if you see error message of 'data overflow' + enable_setting_baudrate: false + #options: 115200, 230400, 460800, 921600, 2000000 + set_baudrate_value: 2000000 + #options for MTi-600/Sirius/Avior to enable/disable hardware flow control + port_config_hardware_flow_control: true + + + # Manual Gyro Bias Estimation (MGBE) Configuration + # ------------------------------------------------ + + # Enable or disable manual gyro bias estimation. + # If enabled, specify the 'event_interval' and 'duration' in 'manual_gyro_bias_param'. + enable_manual_gyro_bias: false + + # Parameters for manual gyro bias estimation: + # - 'event_interval': Time in seconds between two consecutive invocations. + # - 'duration': Time in seconds for which the MGBE process executes each time. + # The minimum value for 'event_interval' is 10 seconds, for 'duration' is 2 seconds. + manual_gyro_bias_param: [15, 5] # [event_interval, duration] + + # Monitoring MGBE Success: + # To verify if MGBE was successful, use 'rostopic echo /status'. + # If the 'no_rotation_update_status' changes from 3 to 0, MGBE was successful. + + # RotSensor Frame changes + # roll, pitch, yaw values + # if your MTi-630 is installed upside-down(connector to the upside), then use 180deg for the roll. + enable_rotsensor_frame_config: false + rotsensor_rotation_euler: [180.0, 0.0, 0.0] + + + # Sensor Standard Deviation (Optional) + # ------------------------------------ + # Override the covariance matrix in sensor_msgs/Imu and sensor_msgs/MagneticField messages: + linear_acceleration_stddev: [0.0, 0.0, 0.0] # [m/s^2] Standard deviation for linear acceleration + angular_velocity_stddev: [0.0, 0.0, 0.0] # [rad/s] Standard deviation for angular velocity + magnetic_field_stddev: [0.0, 0.0, 0.0] # [Tesla] Standard deviation for magnetic field + # [rad] Standard deviation for orientation, + # for Sirius/Avior, if the pub_euler_stddev is true, will use that value from the sensor and igore this value. + orientation_stddev: [0.0, 0.0, 0.0] + + + + + + + + ##Popular Xbus command + # 1) GoToConfig: FA FF 30 00 D1, GoToMeasurement: FA FF 10 00 F1 + # 2) SetBaudrate: FA FF 18 01 80 68 (921k6) or FA FF 18 01 02 E6 (115k2) + # 3) Set Filter Profile for MTi-680(G) with GeneralMag_RTK: FA FF 64 0E 47 65 6E 65 72 61 6C 4D 61 67 5F 52 54 4B 6C + # 4) RestoreFactoryDef: FA FF 0E 00 F3 + # 5) SetOutputConfiguration + ## 5.1) MTi-670(G)/680(G)/MTi-G-710, 400Hz: FA FF C0 34 10 20 FF FF 10 60 FF FF 10 10 FF FF 20 10 01 90 40 20 01 90 80 20 01 90 C0 20 00 64 08 10 01 90 E0 20 FF FF 50 42 01 90 50 22 01 90 D0 12 01 90 70 10 FF FF 6E + ## 5.2) MTi-7/8/670(G)/680(G)/MTi-G-710, 100Hz: FA FF C0 34 10 20 FF FF 10 60 FF FF 10 10 FF FF 20 10 00 64 40 20 00 64 80 20 00 64 C0 20 00 64 08 10 00 64 E0 20 FF FF 50 42 00 64 50 22 00 64 D0 12 00 64 70 10 FF FF A9 + ## 5.3) MTi-630(R)/MTi-300, 400Hz: FA FF C0 24 10 20 FF FF 10 60 FF FF 10 10 FF FF 20 10 01 90 40 20 01 90 80 20 01 90 C0 20 00 64 08 10 01 90 E0 20 FF FF 95 + ## 5.4) MTi-3/630(R)/MTi-300, 100Hz: FA FF C0 24 10 20 FF FF 10 60 FF FF 10 10 FF FF 20 10 00 64 40 20 00 64 80 20 00 64 C0 20 00 64 08 10 00 64 E0 20 FF FF 49 diff --git a/alliander_xsens/src/alliander_xsens/include/imu_bridge.hpp b/alliander_xsens/src/alliander_xsens/include/imu_bridge.hpp new file mode 100644 index 000000000..59da4e0ab --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/include/imu_bridge.hpp @@ -0,0 +1,45 @@ +// # SPDX-FileCopyrightText: Alliander N. V. +// +// # SPDX-License-Identifier: Apache-2.0 + +#ifndef IMU_BRIDGE_HPP_ +#define IMU_BRIDGE_HPP_ + +#include +#include + +#include "geometry_msgs/msg/vector3_stamped.hpp" +#include "sensor_msgs/msg/imu.hpp" + +/// Class to publish Imu messages from acceleration/angular_velocity messages. +class ImuBridge : public rclcpp::Node { + public: + /** + * @brief constructor for the ImuBridge class. + */ + ImuBridge(); + + private: + // ROS2 communication variables: + /// The ROS2 node + rclcpp::Node::SharedPtr node; + /// Subsciber for the acceleration topic + rclcpp::Subscription::SharedPtr sub_accel; + /// Subscriber for the angular velocity topic + rclcpp::Subscription::SharedPtr + sub_ang_vel; + /// Publisher for the IMU topic + rclcpp::Publisher::SharedPtr pub_imu; + /// Timer for publishing IMU data + rclcpp::TimerBase::SharedPtr timer_imu; + + /// Latest acceleration message + geometry_msgs::msg::Vector3Stamped latest_accel_msg; + /// Latest ang_vel message + geometry_msgs::msg::Vector3Stamped latest_ang_vel_msg; + + /// Publish IMU message + void publish_imu(); +}; + +#endif // IMU_BRIDGE_HPP_ diff --git a/alliander_xsens/src/alliander_xsens/launch/xsens.launch.py b/alliander_xsens/src/alliander_xsens/launch/xsens.launch.py new file mode 100644 index 000000000..4c789a498 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/launch/xsens.launch.py @@ -0,0 +1,111 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + +from alliander_utilities.config_objects import IMU +from alliander_utilities.launch_argument import LaunchArgument +from alliander_utilities.launch_utils import SKIP, state_publisher_node, static_tf_node +from alliander_utilities.register import Register +from alliander_utilities.ros_utils import get_file_path +from launch import LaunchContext, LaunchDescription +from launch.actions import OpaqueFunction +from launch_ros.actions import Node, SetParameter + +platform_arg = LaunchArgument("platform_config", "") + + +def launch_setup(context: LaunchContext) -> list: + """The launch setup. + + Args: + context (LaunchContext): The launch context. + + Returns: + list: The actions to start. + """ + imu_config = IMU.from_str(platform_arg.string_value(context)) + + state_publisher = state_publisher_node( + namespace=imu_config.namespace, + platform="xsens", + xacro="xsens.urdf.xacro", + xacro_arguments={ + "use_sim": str(imu_config.simulation), + "parent": "" if imu_config.parent.link else "world", + }, + ) + + parent = imu_config.parent + static_tf = static_tf_node( + parent_frame=f"{parent.namespace}/{parent.link}" if parent.link else "map", + child_frame=f"{imu_config.namespace}/{parent.connects_to}", + position=imu_config.position, + orientation=imu_config.orientation, + ) + + parameter_file = get_file_path("alliander_xsens", ["config"], "xsens_mti_node.yaml") + hardware = Node( + package="xsens_mti_ros2_driver", + executable="xsens_mti_node", + parameters=[parameter_file], + respawn=True, + remappings=[ + ("/imu/acceleration", "imu/acceleration"), + ("/imu/angular_velocity", "imu/angular_velocity"), + ("/imu/mag", "imu/mag"), + ], + namespace=imu_config.namespace, + ) + + imu_bridge_node = Node( + package="alliander_xsens", + executable="imu_bridge_node", + remappings=[ + ("/topic_in_linear_acceleration", "imu/acceleration"), + ("/topic_in_angular_velocity", "imu/angular_velocity"), + ("/topic_out_imu", "imu/data_raw"), + ], + namespace=imu_config.namespace, + ) + + madgwick_filter_node = Node( + package="imu_filter_madgwick", + executable="imu_filter_madgwick_node", + remappings=[], + namespace=imu_config.namespace, + ) + + return [ + SetParameter(name="use_sim_time", value=imu_config.simulation), + Register.on_start(state_publisher, context), + Register.on_start(static_tf, context), + Register.on_start(imu_bridge_node, context) + if not imu_config.simulation + else SKIP, + Register.on_start( + madgwick_filter_node, + context, + ) + if not imu_config.simulation + else SKIP, + Register.on_start( + hardware, + context, + ) + if not imu_config.simulation + else SKIP, + ] + + +def generate_launch_description() -> LaunchDescription: + """Generate the launch description for the Panther robot. + + Returns: + LaunchDescription: The launch description for the Panther robot. + """ + return LaunchDescription( + [ + platform_arg.declaration, + OpaqueFunction(function=launch_setup), + ] + ) diff --git a/alliander_xsens/src/alliander_xsens/package.xml b/alliander_xsens/src/alliander_xsens/package.xml new file mode 100644 index 000000000..e27c440c8 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/package.xml @@ -0,0 +1,30 @@ + + + + + + + alliander_xsens + 0.1.0 + Contains the Alliander Robotics software for the Xsens IMU. + Alliander Robotics + Apache 2.0 + + ament_cmake + ament_cmake_python + + rclcpp + rclcpp_action + geometry_msgs + sensor_msgs + + ament_lint_auto + + + ament_cmake + + diff --git a/alliander_xsens/src/alliander_xsens/scripts/estimate_magnetometer_bias.py b/alliander_xsens/src/alliander_xsens/scripts/estimate_magnetometer_bias.py new file mode 100755 index 000000000..27f76cfa0 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/scripts/estimate_magnetometer_bias.py @@ -0,0 +1,161 @@ +#!/usr/bin/env python3 + +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 +"""Estimate magnetometer hard-iron bias from live ROS 2 data or a CSV file. + +Usage (live): + uv run estimate_magnetometer_bias.py + +Usage (from CSV): + uv run estimate_magnetometer_bias.py /path/to/data.csv + +Bias is estimated as the midpoint of the measurement range on each axis, +which approximates the hard-iron offset under the assumption that the sensor +was rotated through all orientations during the calibration sweep. +""" + +import sys +import time + +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import MagneticField + +try: + import matplotlib.pyplot as plt + + HAS_MATPLOTLIB = True +except ModuleNotFoundError: + print("matplotlib not found. Data will not be plotted.") + HAS_MATPLOTLIB = False + +MAG_TOPIC = "/xsens/imu/mag" +MAG_TIMEOUT = 2.0 # seconds of silence before bias is estimated + + +class MagneticBiasEstimator(Node): + """ROS 2 node that estimates the hard-iron magnetometer bias. + + Subscribes to magnetometer messages and accumulates samples. Once the + stream has been silent for `MAG_TIMEOUT` seconds the node computes the + midpoint bias and optionally renders a 3-D scatter plot of the collected + measurements. + + """ + + def __init__(self, csv_file: str = "") -> None: + """Initialize the MagneticBiasEstimator. + + Args: + csv_file (str): Optional path to a CSV file with pre-recorded measurements. + When provided the node estimates the bias immediately from the file + rather than waiting for live messages. + """ + super().__init__("magnetic_bias_estimator") + self.sub_mag = self.create_subscription( + MagneticField, MAG_TOPIC, self.mag_callback, 1 + ) + self.timer = self.create_timer(MAG_TIMEOUT, self.on_timer) + self.stamp_mag_received = 0.0 + self.num_mag_received = 0 + + self.mag_x: list[float] = [] + self.mag_y: list[float] = [] + self.mag_z: list[float] = [] + self.magnetic_bias: tuple[float, float, float] = (0.0, 0.0, 0.0) + + if csv_file: + self.parse_csv(csv_file) + + def mag_callback(self, msg: MagneticField) -> None: + """Append an incoming magnetometer sample to the internal buffers. + + Args: + msg (MagneticField): Magnetic field message from IMU. + """ + self.get_logger().info("Received magnetic field message.", once=True) + self.num_mag_received += 1 + self.stamp_mag_received = time.time() + self.mag_x.append(msg.magnetic_field.x) + self.mag_y.append(msg.magnetic_field.y) + self.mag_z.append(msg.magnetic_field.z) + + def on_timer(self) -> None: + """Trigger bias estimation once the magnetometer stream goes silent.""" + if self.num_mag_received == 0: + self.get_logger().info("Waiting for imu/mag messages") + return + if time.time() - self.stamp_mag_received > MAG_TIMEOUT: + self.estimate_bias() + self.plot() + self.num_mag_received = 0 + + def estimate_bias(self) -> None: + """Estimate the hard-iron bias as the midpoint of each axis' range. + + Updates `self.magnetic_bias` with the ``(x, y, z)`` midpoints and + logs the result together with the sample count. + """ + mx = (max(self.mag_x) + min(self.mag_x)) / 2 + my = (max(self.mag_y) + min(self.mag_y)) / 2 + mz = (max(self.mag_z) + min(self.mag_z)) / 2 + self.get_logger().info( + f"Bias estimation with {self.num_mag_received} samples: " + f"mx={mx:.6f}, my={my:.6f}, mz={mz:.6f}" + ) + self.magnetic_bias = (mx, my, mz) + + def plot(self) -> None: + """Show a 3-D scatter plot of all collected samples and the estimated bias. + + Does nothing when matplotlib is not installed. + """ + if not HAS_MATPLOTLIB: + return + + ax = plt.figure().add_subplot(projection="3d") + ax.scatter(self.mag_x, self.mag_y, self.mag_z, label="samples") + ax.scatter(*self.magnetic_bias, color="#ff0000", marker="X", label="bias") + ax.set_xlabel("mag_x") + ax.set_ylabel("mag_y") + ax.set_zlabel("mag_z") + ax.set_title(f"Magnetic field measurements (n={self.num_mag_received})") + ax.legend() + ax.grid(True) + + plt.tight_layout() + plt.show() + + def parse_csv(self, csv_file: str) -> None: + """Load pre-recorded magnetometer data from a CSV file and estimate bias. + + The CSV must contain at least three columns (mag_x, mag_y, mag_z) with + a single header row that is skipped during loading. + + Args: + csv_file (str): Path to the comma-separated data file. + """ + import numpy as np # noqa: PLC0415 + + data = np.loadtxt(csv_file, delimiter=",", skiprows=1) + self.mag_x, self.mag_y, self.mag_z = ( + data[:, 0].tolist(), + data[:, 1].tolist(), + data[:, 2].tolist(), + ) + self.num_mag_received = len(self.mag_x) + + self.estimate_bias() + self.plot() + + +if __name__ == "__main__": + csv_file = sys.argv[1] if len(sys.argv) > 1 else "" + + rclpy.init(args=None) + node = MagneticBiasEstimator(csv_file) + rclpy.spin(node) + + rclpy.shutdown() diff --git a/alliander_xsens/src/alliander_xsens/src/imu_bridge.cpp b/alliander_xsens/src/alliander_xsens/src/imu_bridge.cpp new file mode 100644 index 000000000..fec081a91 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/src/imu_bridge.cpp @@ -0,0 +1,34 @@ +// # SPDX-FileCopyrightText: Alliander N. V. +// +// # SPDX-License-Identifier: Apache-2.0 + +#include "imu_bridge.hpp" + +ImuBridge::ImuBridge() : Node("imu_bridge") { + sub_accel = this->create_subscription( + "/topic_in_linear_acceleration", 1, + [this](const geometry_msgs::msg::Vector3Stamped msg) { + this->latest_accel_msg = msg; + this->publish_imu(); + }); + + sub_ang_vel = this->create_subscription( + "/topic_in_angular_velocity", 1, + [this](const geometry_msgs::msg::Vector3Stamped msg) { + this->latest_ang_vel_msg = msg; + }); + + pub_imu = this->create_publisher("/topic_out_imu", 1); + RCLCPP_INFO(this->get_logger(), "Started IMU bridge topic."); +} + +void ImuBridge::publish_imu() { + sensor_msgs::msg::Imu msg; + msg.header.stamp = this->latest_accel_msg.header.stamp; + msg.header.frame_id = this->latest_accel_msg.header.frame_id; + + msg.linear_acceleration = this->latest_accel_msg.vector; + msg.angular_velocity = this->latest_ang_vel_msg.vector; + + pub_imu->publish(msg); +} diff --git a/alliander_xsens/src/alliander_xsens/src/main.cpp b/alliander_xsens/src/alliander_xsens/src/main.cpp new file mode 100644 index 000000000..985af3ce6 --- /dev/null +++ b/alliander_xsens/src/alliander_xsens/src/main.cpp @@ -0,0 +1,12 @@ +// # SPDX-FileCopyrightText: Alliander N. V. +// +// # SPDX-License-Identifier: Apache-2.0 + +#include "imu_bridge.hpp" + +int main(int argc, char** argv) { + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/components.yml b/components.yml index 22259350a..52e0ebae5 100644 --- a/components.yml +++ b/components.yml @@ -70,6 +70,10 @@ visualization: base_image: allianderrobotics/base repository: allianderrobotics/visualization dockerfile: alliander_visualization/alliander_visualization.Dockerfile +xsens: + base_image: allianderrobotics/base + repository: allianderrobotics/xsens + dockerfile: alliander_xsens/alliander_xsens.Dockerfile # CUDA components: zed: diff --git a/docs/content/platforms.md b/docs/content/platforms.md index 0c17a90c8..ecaada4c4 100644 --- a/docs/content/platforms.md +++ b/docs/content/platforms.md @@ -176,6 +176,17 @@ When using the Velodyne lidar, make sure that the IP-address of the host device | ![Velodyne settings](../img/velodyne/velodyne_settings.png) | ![Teltonika settings](../img/teltonika/teltonika_settings.png) | |-------------------------------------------------------------|----------------------------------------------------------------| +## Xsens IMU +![Xsens](../img/xsens/imu.png) + +### Simulation Xsens + +An Xsens IMU can be launched by creating a configuration with an *IMU* of type *xsens*. + +### Hardware Xsens + +When using the Xsens IMU, make sure that the IMU shows up on your device (use *lsusb* to check) and that the Docker container runs with *privileged: true* (standard in our repo). + ## Teltonika GPS ![Teltonika](../img/teltonika/nmea.png) diff --git a/docs/img/xsens/xsens.png b/docs/img/xsens/xsens.png new file mode 100644 index 000000000..e1a60de77 --- /dev/null +++ b/docs/img/xsens/xsens.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f69c668566e3754af1145f20770e1240f968c6eb79393002c40c7ad166e57c4d +size 160120 diff --git a/docs/img/xsens/xsens.png.license b/docs/img/xsens/xsens.png.license new file mode 100644 index 000000000..14a6ee96d --- /dev/null +++ b/docs/img/xsens/xsens.png.license @@ -0,0 +1,3 @@ +SPDX-FileCopyrightText: Alliander N. V. + +SPDX-License-Identifier: Apache-2.0 diff --git a/predefined_configurations.py b/predefined_configurations.py index 63e8aaa0d..fef6fca3a 100644 --- a/predefined_configurations.py +++ b/predefined_configurations.py @@ -10,6 +10,7 @@ from alliander_core.src.alliander_utilities.alliander_utilities.config_objects import ( GPS, + IMU, Arm, Camera, Lidar, @@ -104,6 +105,10 @@ def config_velodyne(self) -> None: # noqa: D102 def config_realsense(self) -> None: # noqa: D102 self.plat_conf.platforms = [Camera("realsense", (0, 0, 0.5))] + @register_configuration("xsens") + def config_xsens(self) -> None: # noqa: D102 + self.plat_conf.platforms = [IMU("xsens", (0, 0, 0.5))] + @register_configuration("zed") def config_zed(self) -> None: # noqa: D102 self.plat_conf.platforms = [Camera("zed", (0, 0, 0.5), namespace="zed")] @@ -242,12 +247,14 @@ def config_panther_gps_navigation(self) -> None: # noqa: D102 ip_address="10.15.20.5", ) gps = GPS("gps", position=(-0.08, -0.25, 0.2), orientation=(0, 0, -90)) + imu = IMU("xsens", position=(-0.23, -0.08, 0.18), orientation=(0, 0, 180)) camera = Camera("realsense", (0.18, 0, 0.2)) link(vehicle, lidar) link(vehicle, gps) + link(vehicle, imu) link(vehicle, camera) - self.plat_conf.platforms = [vehicle, lidar, gps, camera] + self.plat_conf.platforms = [vehicle, lidar, gps, imu, camera] self.viz_conf.gui = True self.sim_conf.world = "map_5.954036_51.977320" diff --git a/pyproject.toml b/pyproject.toml index 19f64854d..dea492a67 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -61,6 +61,10 @@ alliander-visualization = [ "simplejpeg>=1.9.0", "tornado>=6.5.4", ] +alliander-xsens = [ + "matplotlib>=3.10.9", + "pyserial>=3.5", +] ros = [ "catkin-pkg>=1.1.0", "lark>=1.3.1", diff --git a/run_cppcheck.sh b/run_cppcheck.sh index fdf24cd90..628a6002a 100755 --- a/run_cppcheck.sh +++ b/run_cppcheck.sh @@ -7,5 +7,5 @@ cppcheck \ --suppressions-list=.cppcheck-suppressions \ --enable=warning,performance,portability,style \ --error-exitcode=1 \ - $(find . -name *.cpp) + $(find . -name *.cpp | grep -v '.venv\|.nvim') diff --git a/uv.lock b/uv.lock index 0dd0f22ad..b3665f4e2 100644 --- a/uv.lock +++ b/uv.lock @@ -1,5 +1,5 @@ version = 1 -revision = 2 +revision = 3 requires-python = "==3.12.*" [[package]] @@ -118,6 +118,10 @@ alliander-visualization = [ { name = "simplejpeg" }, { name = "tornado" }, ] +alliander-xsens = [ + { name = "matplotlib" }, + { name = "pyserial" }, +] documentation = [ { name = "myst-parser" }, { name = "sphinx" }, @@ -177,6 +181,10 @@ alliander-visualization = [ { name = "simplejpeg", specifier = ">=1.9.0" }, { name = "tornado", specifier = ">=6.5.4" }, ] +alliander-xsens = [ + { name = "matplotlib", specifier = ">=3.10.9" }, + { name = "pyserial", specifier = ">=3.5" }, +] documentation = [ { name = "myst-parser", specifier = ">=5.0.0" }, { name = "sphinx", specifier = ">=9.1.0" }, @@ -442,6 +450,28 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/09/fe/f61e7129e9e689d9e40bbf8a36fb90f04eceb477f4617c02c6a18463e81f/configparser-7.2.0-py3-none-any.whl", hash = "sha256:fee5e1f3db4156dcd0ed95bc4edfa3580475537711f67a819c966b389d09ce62", size = 17232, upload-time = "2025-03-08T16:04:07.743Z" }, ] +[[package]] +name = "contourpy" +version = "1.3.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/58/01/1253e6698a07380cd31a736d248a3f2a50a7c88779a1813da27503cadc2a/contourpy-1.3.3.tar.gz", hash = "sha256:083e12155b210502d0bca491432bb04d56dc3432f95a979b429f2848c3dbe880", size = 13466174, upload-time = "2025-07-26T12:03:12.549Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/be/45/adfee365d9ea3d853550b2e735f9d66366701c65db7855cd07621732ccfc/contourpy-1.3.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:b08a32ea2f8e42cf1d4be3169a98dd4be32bafe4f22b6c4cb4ba810fa9e5d2cb", size = 293419, upload-time = "2025-07-26T12:01:21.16Z" }, + { url = "https://files.pythonhosted.org/packages/53/3e/405b59cfa13021a56bba395a6b3aca8cec012b45bf177b0eaf7a202cde2c/contourpy-1.3.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:556dba8fb6f5d8742f2923fe9457dbdd51e1049c4a43fd3986a0b14a1d815fc6", size = 273979, upload-time = "2025-07-26T12:01:22.448Z" }, + { url = "https://files.pythonhosted.org/packages/d4/1c/a12359b9b2ca3a845e8f7f9ac08bdf776114eb931392fcad91743e2ea17b/contourpy-1.3.3-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:92d9abc807cf7d0e047b95ca5d957cf4792fcd04e920ca70d48add15c1a90ea7", size = 332653, upload-time = "2025-07-26T12:01:24.155Z" }, + { url = "https://files.pythonhosted.org/packages/63/12/897aeebfb475b7748ea67b61e045accdfcf0d971f8a588b67108ed7f5512/contourpy-1.3.3-cp312-cp312-manylinux_2_26_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:b2e8faa0ed68cb29af51edd8e24798bb661eac3bd9f65420c1887b6ca89987c8", size = 379536, upload-time = "2025-07-26T12:01:25.91Z" }, + { url = "https://files.pythonhosted.org/packages/43/8a/a8c584b82deb248930ce069e71576fc09bd7174bbd35183b7943fb1064fd/contourpy-1.3.3-cp312-cp312-manylinux_2_26_s390x.manylinux_2_28_s390x.whl", hash = "sha256:626d60935cf668e70a5ce6ff184fd713e9683fb458898e4249b63be9e28286ea", size = 384397, upload-time = "2025-07-26T12:01:27.152Z" }, + { url = "https://files.pythonhosted.org/packages/cc/8f/ec6289987824b29529d0dfda0d74a07cec60e54b9c92f3c9da4c0ac732de/contourpy-1.3.3-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4d00e655fcef08aba35ec9610536bfe90267d7ab5ba944f7032549c55a146da1", size = 362601, upload-time = "2025-07-26T12:01:28.808Z" }, + { url = "https://files.pythonhosted.org/packages/05/0a/a3fe3be3ee2dceb3e615ebb4df97ae6f3828aa915d3e10549ce016302bd1/contourpy-1.3.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:451e71b5a7d597379ef572de31eeb909a87246974d960049a9848c3bc6c41bf7", size = 1331288, upload-time = "2025-07-26T12:01:31.198Z" }, + { url = "https://files.pythonhosted.org/packages/33/1d/acad9bd4e97f13f3e2b18a3977fe1b4a37ecf3d38d815333980c6c72e963/contourpy-1.3.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:459c1f020cd59fcfe6650180678a9993932d80d44ccde1fa1868977438f0b411", size = 1403386, upload-time = "2025-07-26T12:01:33.947Z" }, + { url = "https://files.pythonhosted.org/packages/cf/8f/5847f44a7fddf859704217a99a23a4f6417b10e5ab1256a179264561540e/contourpy-1.3.3-cp312-cp312-win32.whl", hash = "sha256:023b44101dfe49d7d53932be418477dba359649246075c996866106da069af69", size = 185018, upload-time = "2025-07-26T12:01:35.64Z" }, + { url = "https://files.pythonhosted.org/packages/19/e8/6026ed58a64563186a9ee3f29f41261fd1828f527dd93d33b60feca63352/contourpy-1.3.3-cp312-cp312-win_amd64.whl", hash = "sha256:8153b8bfc11e1e4d75bcb0bff1db232f9e10b274e0929de9d608027e0d34ff8b", size = 226567, upload-time = "2025-07-26T12:01:36.804Z" }, + { url = "https://files.pythonhosted.org/packages/d1/e2/f05240d2c39a1ed228d8328a78b6f44cd695f7ef47beb3e684cf93604f86/contourpy-1.3.3-cp312-cp312-win_arm64.whl", hash = "sha256:07ce5ed73ecdc4a03ffe3e1b3e3c1166db35ae7584be76f65dbbe28a7791b0cc", size = 193655, upload-time = "2025-07-26T12:01:37.999Z" }, +] + [[package]] name = "cryptography" version = "47.0.0" @@ -481,6 +511,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/60/80/5681af756d0da3a599b7bdb586fac5a1540f1bcefd2717a20e611ddade45/cryptography-47.0.0-cp38-abi3-win_amd64.whl", hash = "sha256:835d2d7f47cdc53b3224e90810fb1d36ca94ea29cc1801fb4c1bc43876735769", size = 3755737, upload-time = "2026-04-24T19:54:35.408Z" }, ] +[[package]] +name = "cycler" +version = "0.12.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a9/95/a3dbbb5028f35eafb79008e7522a75244477d2838f38cbb722248dabc2a8/cycler-0.12.1.tar.gz", hash = "sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c", size = 7615, upload-time = "2023-10-07T05:32:18.335Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e7/05/c19819d5e3d95294a6f5947fb9b9629efb316b96de511b418c53d245aae6/cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30", size = 8321, upload-time = "2023-10-07T05:32:16.783Z" }, +] + [[package]] name = "distlib" version = "0.4.0" @@ -582,6 +621,23 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/85/6a/cdee9ff7f2b7c6ddc219fd95b7c70c0a3d9f0367a506e9793eedfc72e337/flake8_pyproject-1.2.4-py3-none-any.whl", hash = "sha256:ea34c057f9a9329c76d98723bb2bb498cc6ba8ff9872c4d19932d48c91249a77", size = 5694, upload-time = "2025-11-28T21:40:01.309Z" }, ] +[[package]] +name = "fonttools" +version = "4.62.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/9a/08/7012b00a9a5874311b639c3920270c36ee0c445b69d9989a85e5c92ebcb0/fonttools-4.62.1.tar.gz", hash = "sha256:e54c75fd6041f1122476776880f7c3c3295ffa31962dc6ebe2543c00dca58b5d", size = 3580737, upload-time = "2026-03-13T13:54:25.52Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/47/d4/dbacced3953544b9a93088cc10ef2b596d348c983d5c67a404fa41ec51ba/fonttools-4.62.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:90365821debbd7db678809c7491ca4acd1e0779b9624cdc6ddaf1f31992bf974", size = 2870219, upload-time = "2026-03-13T13:52:53.664Z" }, + { url = "https://files.pythonhosted.org/packages/66/9e/a769c8e99b81e5a87ab7e5e7236684de4e96246aae17274e5347d11ebd78/fonttools-4.62.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:12859ff0b47dd20f110804c3e0d0970f7b832f561630cd879969011541a464a9", size = 2414891, upload-time = "2026-03-13T13:52:56.493Z" }, + { url = "https://files.pythonhosted.org/packages/69/64/f19a9e3911968c37e1e620e14dfc5778299e1474f72f4e57c5ec771d9489/fonttools-4.62.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9c125ffa00c3d9003cdaaf7f2c79e6e535628093e14b5de1dccb08859b680936", size = 5033197, upload-time = "2026-03-13T13:52:59.179Z" }, + { url = "https://files.pythonhosted.org/packages/9b/8a/99c8b3c3888c5c474c08dbfd7c8899786de9604b727fcefb055b42c84bba/fonttools-4.62.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:149f7d84afca659d1a97e39a4778794a2f83bf344c5ee5134e09995086cc2392", size = 4988768, upload-time = "2026-03-13T13:53:02.761Z" }, + { url = "https://files.pythonhosted.org/packages/d1/c6/0f904540d3e6ab463c1243a0d803504826a11604c72dd58c2949796a1762/fonttools-4.62.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0aa72c43a601cfa9273bb1ae0518f1acadc01ee181a6fc60cd758d7fdadffc04", size = 4971512, upload-time = "2026-03-13T13:53:05.678Z" }, + { url = "https://files.pythonhosted.org/packages/29/0b/5cbef6588dc9bd6b5c9ad6a4d5a8ca384d0cea089da31711bbeb4f9654a6/fonttools-4.62.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:19177c8d96c7c36359266e571c5173bcee9157b59cfc8cb0153c5673dc5a3a7d", size = 5122723, upload-time = "2026-03-13T13:53:08.662Z" }, + { url = "https://files.pythonhosted.org/packages/4a/47/b3a5342d381595ef439adec67848bed561ab7fdb1019fa522e82101b7d9c/fonttools-4.62.1-cp312-cp312-win32.whl", hash = "sha256:a24decd24d60744ee8b4679d38e88b8303d86772053afc29b19d23bb8207803c", size = 2281278, upload-time = "2026-03-13T13:53:10.998Z" }, + { url = "https://files.pythonhosted.org/packages/28/b1/0c2ab56a16f409c6c8a68816e6af707827ad5d629634691ff60a52879792/fonttools-4.62.1-cp312-cp312-win_amd64.whl", hash = "sha256:9e7863e10b3de72376280b515d35b14f5eeed639d1aa7824f4cf06779ec65e42", size = 2331414, upload-time = "2026-03-13T13:53:13.992Z" }, + { url = "https://files.pythonhosted.org/packages/fd/ba/56147c165442cc5ba7e82ecf301c9a68353cede498185869e6e02b4c264f/fonttools-4.62.1-py3-none-any.whl", hash = "sha256:7487782e2113861f4ddcc07c3436450659e3caa5e470b27dc2177cade2d8e7fd", size = 1152647, upload-time = "2026-03-13T13:54:22.735Z" }, +] + [[package]] name = "frozenlist" version = "1.8.0" @@ -755,6 +811,33 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl", hash = "sha256:85ece4451f492d0c13c5dd7c13a64681a86afae63a5f347908daf103ce6d2f67", size = 134899, upload-time = "2025-03-05T20:05:00.369Z" }, ] +[[package]] +name = "kiwisolver" +version = "1.5.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/d0/67/9c61eccb13f0bdca9307614e782fec49ffdde0f7a2314935d489fa93cd9c/kiwisolver-1.5.0.tar.gz", hash = "sha256:d4193f3d9dc3f6f79aaed0e5637f45d98850ebf01f7ca20e69457f3e8946b66a", size = 103482, upload-time = "2026-03-09T13:15:53.382Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/4d/b2/818b74ebea34dabe6d0c51cb1c572e046730e64844da6ed646d5298c40ce/kiwisolver-1.5.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:4e9750bc21b886308024f8a54ccb9a2cc38ac9fa813bf4348434e3d54f337ff9", size = 123158, upload-time = "2026-03-09T13:13:23.127Z" }, + { url = "https://files.pythonhosted.org/packages/bf/d9/405320f8077e8e1c5c4bd6adc45e1e6edf6d727b6da7f2e2533cf58bff71/kiwisolver-1.5.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:72ec46b7eba5b395e0a7b63025490d3214c11013f4aacb4f5e8d6c3041829588", size = 66388, upload-time = "2026-03-09T13:13:24.765Z" }, + { url = "https://files.pythonhosted.org/packages/99/9f/795fedf35634f746151ca8839d05681ceb6287fbed6cc1c9bf235f7887c2/kiwisolver-1.5.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ed3a984b31da7481b103f68776f7128a89ef26ed40f4dc41a2223cda7fb24819", size = 64068, upload-time = "2026-03-09T13:13:25.878Z" }, + { url = "https://files.pythonhosted.org/packages/c4/13/680c54afe3e65767bed7ec1a15571e1a2f1257128733851ade24abcefbcc/kiwisolver-1.5.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:bb5136fb5352d3f422df33f0c879a1b0c204004324150cc3b5e3c4f310c9049f", size = 1477934, upload-time = "2026-03-09T13:13:27.166Z" }, + { url = "https://files.pythonhosted.org/packages/c8/2f/cebfcdb60fd6a9b0f6b47a9337198bcbad6fbe15e68189b7011fd914911f/kiwisolver-1.5.0-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b2af221f268f5af85e776a73d62b0845fc8baf8ef0abfae79d29c77d0e776aaf", size = 1278537, upload-time = "2026-03-09T13:13:28.707Z" }, + { url = "https://files.pythonhosted.org/packages/f2/0d/9b782923aada3fafb1d6b84e13121954515c669b18af0c26e7d21f579855/kiwisolver-1.5.0-cp312-cp312-manylinux_2_24_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:b0f172dc8ffaccb8522d7c5d899de00133f2f1ca7b0a49b7da98e901de87bf2d", size = 1296685, upload-time = "2026-03-09T13:13:30.528Z" }, + { url = "https://files.pythonhosted.org/packages/27/70/83241b6634b04fe44e892688d5208332bde130f38e610c0418f9ede47ded/kiwisolver-1.5.0-cp312-cp312-manylinux_2_24_s390x.manylinux_2_28_s390x.whl", hash = "sha256:6ab8ba9152203feec73758dad83af9a0bbe05001eb4639e547207c40cfb52083", size = 1346024, upload-time = "2026-03-09T13:13:32.818Z" }, + { url = "https://files.pythonhosted.org/packages/e4/db/30ed226fb271ae1a6431fc0fe0edffb2efe23cadb01e798caeb9f2ceae8f/kiwisolver-1.5.0-cp312-cp312-manylinux_2_39_riscv64.whl", hash = "sha256:cdee07c4d7f6d72008d3f73b9bf027f4e11550224c7c50d8df1ae4a37c1402a6", size = 987241, upload-time = "2026-03-09T13:13:34.435Z" }, + { url = "https://files.pythonhosted.org/packages/ec/bd/c314595208e4c9587652d50959ead9e461995389664e490f4dce7ff0f782/kiwisolver-1.5.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:7c60d3c9b06fb23bd9c6139281ccbdc384297579ae037f08ae90c69f6845c0b1", size = 2227742, upload-time = "2026-03-09T13:13:36.4Z" }, + { url = "https://files.pythonhosted.org/packages/c1/43/0499cec932d935229b5543d073c2b87c9c22846aab48881e9d8d6e742a2d/kiwisolver-1.5.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:e315e5ec90d88e140f57696ff85b484ff68bb311e36f2c414aa4286293e6dee0", size = 2323966, upload-time = "2026-03-09T13:13:38.204Z" }, + { url = "https://files.pythonhosted.org/packages/3d/6f/79b0d760907965acfd9d61826a3d41f8f093c538f55cd2633d3f0db269f6/kiwisolver-1.5.0-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:1465387ac63576c3e125e5337a6892b9e99e0627d52317f3ca79e6930d889d15", size = 1977417, upload-time = "2026-03-09T13:13:39.966Z" }, + { url = "https://files.pythonhosted.org/packages/ab/31/01d0537c41cb75a551a438c3c7a80d0c60d60b81f694dac83dd436aec0d0/kiwisolver-1.5.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:530a3fd64c87cffa844d4b6b9768774763d9caa299e9b75d8eca6a4423b31314", size = 2491238, upload-time = "2026-03-09T13:13:41.698Z" }, + { url = "https://files.pythonhosted.org/packages/e4/34/8aefdd0be9cfd00a44509251ba864f5caf2991e36772e61c408007e7f417/kiwisolver-1.5.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:1d9daea4ea6b9be74fe2f01f7fbade8d6ffab263e781274cffca0dba9be9eec9", size = 2294947, upload-time = "2026-03-09T13:13:43.343Z" }, + { url = "https://files.pythonhosted.org/packages/ad/cf/0348374369ca588f8fe9c338fae49fa4e16eeb10ffb3d012f23a54578a9e/kiwisolver-1.5.0-cp312-cp312-win_amd64.whl", hash = "sha256:f18c2d9782259a6dc132fdc7a63c168cbc74b35284b6d75c673958982a378384", size = 73569, upload-time = "2026-03-09T13:13:45.792Z" }, + { url = "https://files.pythonhosted.org/packages/28/26/192b26196e2316e2bd29deef67e37cdf9870d9af8e085e521afff0fed526/kiwisolver-1.5.0-cp312-cp312-win_arm64.whl", hash = "sha256:f7c7553b13f69c1b29a5bde08ddc6d9d0c8bfb84f9ed01c30db25944aeb852a7", size = 64997, upload-time = "2026-03-09T13:13:46.878Z" }, + { url = "https://files.pythonhosted.org/packages/1c/fa/2910df836372d8761bb6eff7d8bdcb1613b5c2e03f260efe7abe34d388a7/kiwisolver-1.5.0-graalpy312-graalpy250_312_native-macosx_10_13_x86_64.whl", hash = "sha256:5ae8e62c147495b01a0f4765c878e9bfdf843412446a247e28df59936e99e797", size = 130262, upload-time = "2026-03-09T13:15:35.629Z" }, + { url = "https://files.pythonhosted.org/packages/0f/41/c5f71f9f00aabcc71fee8b7475e3f64747282580c2fe748961ba29b18385/kiwisolver-1.5.0-graalpy312-graalpy250_312_native-macosx_11_0_arm64.whl", hash = "sha256:f6764a4ccab3078db14a632420930f6186058750df066b8ea2a7106df91d3203", size = 138036, upload-time = "2026-03-09T13:15:36.894Z" }, + { url = "https://files.pythonhosted.org/packages/fa/06/7399a607f434119c6e1fdc8ec89a8d51ccccadf3341dee4ead6bd14caaf5/kiwisolver-1.5.0-graalpy312-graalpy250_312_native-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c31c13da98624f957b0fb1b5bae5383b2333c2c3f6793d9825dd5ce79b525cb7", size = 194295, upload-time = "2026-03-09T13:15:38.22Z" }, + { url = "https://files.pythonhosted.org/packages/b5/91/53255615acd2a1eaca307ede3c90eb550bae9c94581f8c00081b6b1c8f44/kiwisolver-1.5.0-graalpy312-graalpy250_312_native-win_amd64.whl", hash = "sha256:1f1489f769582498610e015a8ef2d36f28f505ab3096d0e16b4858a9ec214f57", size = 75987, upload-time = "2026-03-09T13:15:39.65Z" }, +] + [[package]] name = "lark" version = "1.3.1" @@ -854,6 +937,32 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/96/5a/4fed77781061647d3be98e2f235ef1869289dd839ca0451a8d50a30fcd5c/mashumaro-3.20-py3-none-any.whl", hash = "sha256:648bc326f64c55447988eab67d6bfe3b7958c0961c83590709b1f950f88f4a3c", size = 94942, upload-time = "2026-02-09T21:53:53.343Z" }, ] +[[package]] +name = "matplotlib" +version = "3.10.9" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "contourpy" }, + { name = "cycler" }, + { name = "fonttools" }, + { name = "kiwisolver" }, + { name = "numpy" }, + { name = "packaging" }, + { name = "pillow" }, + { name = "pyparsing" }, + { name = "python-dateutil" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/63/1b/4be5be87d43d327a0cf4de1a56e86f7f84c89312452406cf122efe2839e6/matplotlib-3.10.9.tar.gz", hash = "sha256:fd66508e8c6877d98e586654b608a0456db8d7e8a546eb1e2600efd957302358", size = 34811233, upload-time = "2026-04-24T00:14:13.539Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/35/c6/5581e26c72233ebb2a2a6fed2d24fb7c66b4700120b813f51b0555acf0b6/matplotlib-3.10.9-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:f0c3c28d9fbcc1fe7a03be236d73430cf6409c41fb2383a7ac52fe932b072cb1", size = 8319908, upload-time = "2026-04-24T00:12:21.323Z" }, + { url = "https://files.pythonhosted.org/packages/b7/18/4880dd762e40cd360c1bf06e890c5a97b997e91cb324602b1a19950ad5ce/matplotlib-3.10.9-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:41cb28c2bd769aa3e98322c6ab09854cbcc52ab69d2759d681bba3e327b2b320", size = 8216016, upload-time = "2026-04-24T00:12:23.4Z" }, + { url = "https://files.pythonhosted.org/packages/32/91/d024616abdba99e83120e07a20658976f6a343646710760c4a51df126029/matplotlib-3.10.9-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:ae20801130378b82d647ff5047c07316295b68dc054ca6b3c13519d0ea624285", size = 8789336, upload-time = "2026-04-24T00:12:26.096Z" }, + { url = "https://files.pythonhosted.org/packages/5c/04/030a2f61ef2158f5e4c259487a92ac877732499fb33d871585d89e03c42d/matplotlib-3.10.9-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6c63ebcd8b4b169eb2f5c200552ae6b8be8999a005b6b507ed76fb8d7d674fe2", size = 9604602, upload-time = "2026-04-24T00:12:29.052Z" }, + { url = "https://files.pythonhosted.org/packages/fc/c2/541e4d09d87bb6b5830fc28b4c887a9a8cf4e1c6cee698a8c05552ae2003/matplotlib-3.10.9-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:d75d11c949914165976c621b2324f9ef162af7ebf4b057ddf95dd1dba7e5edcf", size = 9670966, upload-time = "2026-04-24T00:12:32.131Z" }, + { url = "https://files.pythonhosted.org/packages/04/a1/4571fc46e7702de8d0c2dc54ad1b2f8e29328dea3ee90831181f7353d93c/matplotlib-3.10.9-cp312-cp312-win_amd64.whl", hash = "sha256:d091f9d758b34aaaaa6331d13574bf01891d903b3dec59bfff458ef7551de5d6", size = 8217462, upload-time = "2026-04-24T00:12:35.226Z" }, + { url = "https://files.pythonhosted.org/packages/4b/d0/2269edb12aa30c13c8bcc9382892e39943ce1d28aab4ec296e0381798e81/matplotlib-3.10.9-cp312-cp312-win_arm64.whl", hash = "sha256:10cc5ce06d10231c36f40e875f3c7e8050362a4ee8f0ee5d29a6b3277d57bb42", size = 8136688, upload-time = "2026-04-24T00:12:37.442Z" }, +] + [[package]] name = "mccabe" version = "0.7.0" @@ -1066,6 +1175,25 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/f1/d9/7fb5aa316bc299258e68c73ba3bddbc499654a07f151cba08f6153988714/pathspec-1.1.1-py3-none-any.whl", hash = "sha256:a00ce642f577bf7f473932318056212bc4f8bfdf53128c78bbd5af0b9b20b189", size = 57328, upload-time = "2026-04-27T01:46:07.06Z" }, ] +[[package]] +name = "pillow" +version = "12.2.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/8c/21/c2bcdd5906101a30244eaffc1b6e6ce71a31bd0742a01eb89e660ebfac2d/pillow-12.2.0.tar.gz", hash = "sha256:a830b1a40919539d07806aa58e1b114df53ddd43213d9c8b75847eee6c0182b5", size = 46987819, upload-time = "2026-04-01T14:46:17.687Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/58/be/7482c8a5ebebbc6470b3eb791812fff7d5e0216c2be3827b30b8bb6603ed/pillow-12.2.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:2d192a155bbcec180f8564f693e6fd9bccff5a7af9b32e2e4bf8c9c69dbad6b5", size = 5308279, upload-time = "2026-04-01T14:43:13.246Z" }, + { url = "https://files.pythonhosted.org/packages/d8/95/0a351b9289c2b5cbde0bacd4a83ebc44023e835490a727b2a3bd60ddc0f4/pillow-12.2.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f3f40b3c5a968281fd507d519e444c35f0ff171237f4fdde090dd60699458421", size = 4695490, upload-time = "2026-04-01T14:43:15.584Z" }, + { url = "https://files.pythonhosted.org/packages/de/af/4e8e6869cbed569d43c416fad3dc4ecb944cb5d9492defaed89ddd6fe871/pillow-12.2.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:03e7e372d5240cc23e9f07deca4d775c0817bffc641b01e9c3af208dbd300987", size = 6284462, upload-time = "2026-04-01T14:43:18.268Z" }, + { url = "https://files.pythonhosted.org/packages/e9/9e/c05e19657fd57841e476be1ab46c4d501bffbadbafdc31a6d665f8b737b6/pillow-12.2.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b86024e52a1b269467a802258c25521e6d742349d760728092e1bc2d135b4d76", size = 8094744, upload-time = "2026-04-01T14:43:20.716Z" }, + { url = "https://files.pythonhosted.org/packages/2b/54/1789c455ed10176066b6e7e6da1b01e50e36f94ba584dc68d9eebfe9156d/pillow-12.2.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7371b48c4fa448d20d2714c9a1f775a81155050d383333e0a6c15b1123dda005", size = 6398371, upload-time = "2026-04-01T14:43:23.443Z" }, + { url = "https://files.pythonhosted.org/packages/43/e3/fdc657359e919462369869f1c9f0e973f353f9a9ee295a39b1fea8ee1a77/pillow-12.2.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:62f5409336adb0663b7caa0da5c7d9e7bdbaae9ce761d34669420c2a801b2780", size = 7087215, upload-time = "2026-04-01T14:43:26.758Z" }, + { url = "https://files.pythonhosted.org/packages/8b/f8/2f6825e441d5b1959d2ca5adec984210f1ec086435b0ed5f52c19b3b8a6e/pillow-12.2.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:01afa7cf67f74f09523699b4e88c73fb55c13346d212a59a2db1f86b0a63e8c5", size = 6509783, upload-time = "2026-04-01T14:43:29.56Z" }, + { url = "https://files.pythonhosted.org/packages/67/f9/029a27095ad20f854f9dba026b3ea6428548316e057e6fc3545409e86651/pillow-12.2.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fc3d34d4a8fbec3e88a79b92e5465e0f9b842b628675850d860b8bd300b159f5", size = 7212112, upload-time = "2026-04-01T14:43:32.091Z" }, + { url = "https://files.pythonhosted.org/packages/be/42/025cfe05d1be22dbfdb4f264fe9de1ccda83f66e4fc3aac94748e784af04/pillow-12.2.0-cp312-cp312-win32.whl", hash = "sha256:58f62cc0f00fd29e64b29f4fd923ffdb3859c9f9e6105bfc37ba1d08994e8940", size = 6378489, upload-time = "2026-04-01T14:43:34.601Z" }, + { url = "https://files.pythonhosted.org/packages/5d/7b/25a221d2c761c6a8ae21bfa3874988ff2583e19cf8a27bf2fee358df7942/pillow-12.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:7f84204dee22a783350679a0333981df803dac21a0190d706a50475e361c93f5", size = 7084129, upload-time = "2026-04-01T14:43:37.213Z" }, + { url = "https://files.pythonhosted.org/packages/10/e1/542a474affab20fd4a0f1836cb234e8493519da6b76899e30bcc5d990b8b/pillow-12.2.0-cp312-cp312-win_arm64.whl", hash = "sha256:af73337013e0b3b46f175e79492d96845b16126ddf79c438d7ea7ff27783a414", size = 2463612, upload-time = "2026-04-01T14:43:39.421Z" }, +] + [[package]] name = "platformdirs" version = "4.9.6" @@ -1305,6 +1433,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/5d/68/915cc32c02a91e76d02c8f55d5a138d6ef9e47a0d96d259df98f4842e558/pyproj-3.7.2-cp312-cp312-win_arm64.whl", hash = "sha256:509a146d1398bafe4f53273398c3bb0b4732535065fa995270e52a9d3676bca3", size = 6233452, upload-time = "2025-08-14T12:04:27.287Z" }, ] +[[package]] +name = "pyserial" +version = "3.5" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/1e/7d/ae3f0a63f41e4d2f6cb66a5b57197850f919f59e558159a4dd3a818f5082/pyserial-3.5.tar.gz", hash = "sha256:3c77e014170dfffbd816e6ffc205e9842efb10be9f58ec16d3e8675b4925cddb", size = 159125, upload-time = "2020-11-23T03:59:15.045Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585, upload-time = "2020-11-23T03:59:13.41Z" }, +] + [[package]] name = "pytest" version = "9.0.3"