diff --git a/.gitignore b/.gitignore
index 19b7394a..97e7e6b6 100644
--- a/.gitignore
+++ b/.gitignore
@@ -2,3 +2,6 @@
.DS_Store
.vscode/
__pycache__/
+**/out/
+.venv/
+venv/
\ No newline at end of file
diff --git a/openarm/package.xml b/openarm/package.xml
index 0457deb8..12957414 100644
--- a/openarm/package.xml
+++ b/openarm/package.xml
@@ -27,6 +27,7 @@
openarm_bringup
openarm_description
openarm_hardware
+ openarm_bimanual_moveit_config
ament_lint_auto
ament_lint_common
diff --git a/openarm_bimanual_moveit_config/config/openarm_bimanual.srdf b/openarm_bimanual_moveit_config/config/openarm_bimanual.srdf
deleted file mode 100644
index 8c2c6e1d..00000000
--- a/openarm_bimanual_moveit_config/config/openarm_bimanual.srdf
+++ /dev/null
@@ -1,252 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/openarm_bimanual_moveit_config/config/joint_limits.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/joint_limits.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/joint_limits.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/joint_limits.yaml
diff --git a/openarm_bimanual_moveit_config/config/kinematics.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/kinematics.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/kinematics.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/kinematics.yaml
diff --git a/openarm_bimanual_moveit_config/config/moveit.rviz b/openarm_bimanual_moveit_config/config/openarm_v1.0/moveit.rviz
similarity index 100%
rename from openarm_bimanual_moveit_config/config/moveit.rviz
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/moveit.rviz
diff --git a/openarm_bimanual_moveit_config/config/moveit_controllers.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/moveit_controllers.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/moveit_controllers.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/moveit_controllers.yaml
diff --git a/openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.srdf b/openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.srdf
new file mode 100644
index 00000000..0cb128be
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.srdf
@@ -0,0 +1,143 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/openarm_bimanual_moveit_config/config/openarm_bimanual.urdf.xacro b/openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.urdf.xacro
similarity index 93%
rename from openarm_bimanual_moveit_config/config/openarm_bimanual.urdf.xacro
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.urdf.xacro
index 6f6f4951..929b0556 100644
--- a/openarm_bimanual_moveit_config/config/openarm_bimanual.urdf.xacro
+++ b/openarm_bimanual_moveit_config/config/openarm_v1.0/openarm_bimanual.urdf.xacro
@@ -17,15 +17,11 @@
-
-
-
-
+
-
-
+
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/pilz_cartesian_limits.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/pilz_cartesian_limits.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/pilz_cartesian_limits.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/pilz_cartesian_limits.yaml
diff --git a/openarm_bimanual_moveit_config/config/ros2_controllers.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/ros2_controllers.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/ros2_controllers.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/ros2_controllers.yaml
diff --git a/openarm_bimanual_moveit_config/config/sensors_3d.yaml b/openarm_bimanual_moveit_config/config/openarm_v1.0/sensors_3d.yaml
similarity index 100%
rename from openarm_bimanual_moveit_config/config/sensors_3d.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v1.0/sensors_3d.yaml
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/joint_limits.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/joint_limits.yaml
new file mode 100644
index 00000000..995f9999
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/joint_limits.yaml
@@ -0,0 +1,104 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
+
+# For beginners, we downscale velocity and acceleration limits.
+# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
+default_velocity_scaling_factor: 0.1
+default_acceleration_scaling_factor: 0.1
+
+# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
+# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
+joint_limits:
+ openarm_left_finger_joint1:
+ has_velocity_limits: true
+ max_velocity: 10.0
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint1:
+ has_velocity_limits: true
+ max_velocity: 16.754666
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint2:
+ has_velocity_limits: true
+ max_velocity: 16.754666
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint3:
+ has_velocity_limits: true
+ max_velocity: 5.445426
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint4:
+ has_velocity_limits: true
+ max_velocity: 5.445426
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint5:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint6:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_left_joint7:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_finger_joint1:
+ has_velocity_limits: true
+ max_velocity: 10.0
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint1:
+ has_velocity_limits: true
+ max_velocity: 16.754666
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint2:
+ has_velocity_limits: true
+ max_velocity: 16.754666
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint3:
+ has_velocity_limits: true
+ max_velocity: 5.445426
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint4:
+ has_velocity_limits: true
+ max_velocity: 5.445426
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint5:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint6:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ openarm_right_joint7:
+ has_velocity_limits: true
+ max_velocity: 20.943946
+ has_acceleration_limits: false
+ max_acceleration: 0.0
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/initial_positions.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/kinematics.yaml
similarity index 53%
rename from openarm_bimanual_moveit_config/config/initial_positions.yaml
rename to openarm_bimanual_moveit_config/config/openarm_v2.0/kinematics.yaml
index 4c87cabf..c1d6d23f 100644
--- a/openarm_bimanual_moveit_config/config/initial_positions.yaml
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/kinematics.yaml
@@ -12,21 +12,13 @@
# See the License for the specific language governing permissions and
# limitations under the License.
-# Default initial positions for openarm's ros2_control fake system
-initial_positions:
- openarm_left_finger_joint1: 0
- openarm_left_joint1: 0
- openarm_left_joint2: 0
- openarm_left_joint3: 0
- openarm_left_joint4: 0
- openarm_left_joint5: 0
- openarm_left_joint6: 0
- openarm_left_joint7: 0
- openarm_right_finger_joint1: 0
- openarm_right_joint1: 0
- openarm_right_joint2: 0
- openarm_right_joint3: 0
- openarm_right_joint4: 0
- openarm_right_joint5: 0
- openarm_right_joint6: 0
- openarm_right_joint7: 0
\ No newline at end of file
+
+left_arm:
+ kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
+ kinematics_solver_search_resolution: 0.0050000000000000001
+ kinematics_solver_timeout: 0.0050000000000000001
+
+right_arm:
+ kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
+ kinematics_solver_search_resolution: 0.0050000000000000001
+ kinematics_solver_timeout: 0.0050000000000000001
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit.rviz b/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit.rviz
new file mode 100644
index 00000000..3f2746d9
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit.rviz
@@ -0,0 +1,447 @@
+Panels:
+ - Class: rviz_common/Displays
+ Help Height: 138
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /MotionPlanning1
+ - /MotionPlanning1/Scene Robot1
+ - /MotionPlanning1/Planning Request1
+ Splitter Ratio: 0.5
+ Tree Height: 254
+ - Class: rviz_common/Help
+ Name: Help
+ - Class: rviz_common/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz_default_plugins/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.029999999329447746
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame:
+ Value: true
+ - Acceleration_Scaling_Factor: 0.1
+ Class: moveit_rviz_plugin/MotionPlanning
+ Enabled: true
+ Move Group Namespace: ""
+ MoveIt_Allow_Approximate_IK: false
+ MoveIt_Allow_External_Program: false
+ MoveIt_Allow_Replanning: false
+ MoveIt_Allow_Sensor_Positioning: false
+ MoveIt_Planning_Attempts: 10
+ MoveIt_Planning_Time: 5
+ MoveIt_Use_Cartesian_Path: false
+ MoveIt_Use_Constraint_Aware_IK: false
+ MoveIt_Workspace:
+ Center:
+ X: 0
+ Y: 0
+ Z: 0
+ Size:
+ X: 2
+ Y: 2
+ Z: 2
+ Name: MotionPlanning
+ Planned Path:
+ Color Enabled: false
+ Interrupt Display: false
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ openarm_body_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_left_left_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_left_right_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_right_left_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_right_right_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ world:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Loop Animation: true
+ Robot Alpha: 0.5
+ Robot Color: 150; 50; 150
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Show Trail: false
+ State Display Time: 0.05 s
+ Trail Step Size: 1
+ Trajectory Topic: display_planned_path
+ Use Sim Time: false
+ Planning Metrics:
+ Payload: 1
+ Show Joint Torques: false
+ Show Manipulability: false
+ Show Manipulability Index: false
+ Show Weight Limit: false
+ TextHeight: 0.07999999821186066
+ Planning Request:
+ Colliding Link Color: 255; 0; 0
+ Goal State Alpha: 1
+ Goal State Color: 20; 93; 250
+ Interactive Marker Size: 0
+ Joint Violation Color: 255; 0; 255
+ Planning Group: upper_body
+ Query Goal State: true
+ Query Start State: false
+ Show Workspace: false
+ Start State Alpha: 1
+ Start State Color: 0; 255; 0
+ Planning Scene Topic: monitored_planning_scene
+ Robot Description: robot_description
+ Scene Geometry:
+ Scene Alpha: 1
+ Scene Color: 50; 230; 50
+ Scene Display Time: 0.009999999776482582
+ Show Scene Geometry: true
+ Voxel Coloring: Z-Axis
+ Voxel Rendering: Occupied Voxels
+ Scene Robot:
+ Attached Body Color: 150; 50; 150
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ openarm_body_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_left_left_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_left_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_left_right_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_hand:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_hand_tcp:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_right_left_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link4:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link5:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link6:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link7:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ openarm_right_link8:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ openarm_right_right_finger:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ world:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Robot Alpha: 0.5
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Value: true
+ Velocity_Scaling_Factor: 0.1
+ Enabled: true
+ Global Options:
+ Background Color: 48; 48; 48
+ Fixed Frame: world
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz_default_plugins/Interact
+ Hide Inactive Objects: true
+ - Class: rviz_default_plugins/MoveCamera
+ - Class: rviz_default_plugins/Select
+ Transformation:
+ Current:
+ Class: rviz_default_plugins/TF
+ Value: true
+ Views:
+ Current:
+ Class: rviz_default_plugins/Orbit
+ Distance: 1.3624029159545898
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Focal Point:
+ X: -0.05883333832025528
+ Y: 0.2625991404056549
+ Z: 0.3334124982357025
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.31999996304512024
+ Target Frame: world
+ Value: Orbit (rviz_default_plugins)
+ Yaw: 0.16200032830238342
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Width: 1280
+ Height: 720
+ Help:
+ collapsed: false
+ Hide Left Dock: false
+ Hide Right Dock: false
+ MotionPlanning:
+ collapsed: false
+ MotionPlanning - Trajectory Slider:
+ collapsed: false
+ QMainWindow State: 000000ff00000000fd00000001000000000000036a000006f0fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000007000fffffffb000000100044006900730070006c0061007900730100000069000001ec0000017800fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000002610000036f0000028e00fffffffb0000000800480065006c0070000000029a0000006e000000cf00fffffffb0000000a0056006900650077007301000005dc0000017d0000012300ffffff0000096a000006f000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Views:
+ collapsed: false
+ X: 0
+ Y: 64
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit_controllers.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit_controllers.yaml
new file mode 100644
index 00000000..251e3230
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/moveit_controllers.yaml
@@ -0,0 +1,65 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+
+# MoveIt uses this configuration for controller management
+
+moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
+
+moveit_simple_controller_manager:
+ controller_names:
+ - left_joint_trajectory_controller
+ - right_joint_trajectory_controller
+ - left_gripper_controller
+ - right_gripper_controller
+
+ left_joint_trajectory_controller:
+ type: FollowJointTrajectory
+ joints:
+ - openarm_left_joint1
+ - openarm_left_joint2
+ - openarm_left_joint3
+ - openarm_left_joint4
+ - openarm_left_joint5
+ - openarm_left_joint6
+ - openarm_left_joint7
+ action_ns: follow_joint_trajectory
+ default: true
+
+ right_joint_trajectory_controller:
+ type: FollowJointTrajectory
+ joints:
+ - openarm_right_joint1
+ - openarm_right_joint2
+ - openarm_right_joint3
+ - openarm_right_joint4
+ - openarm_right_joint5
+ - openarm_right_joint6
+ - openarm_right_joint7
+ action_ns: follow_joint_trajectory
+ default: true
+
+ left_gripper_controller:
+ type: GripperCommand
+ joints:
+ - openarm_left_finger_joint1
+ action_ns: gripper_cmd
+ default: true
+
+ right_gripper_controller:
+ type: GripperCommand
+ joints:
+ - openarm_right_finger_joint1
+ action_ns: gripper_cmd
+ default: true
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.srdf b/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.srdf
new file mode 100644
index 00000000..38bcd6f5
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.srdf
@@ -0,0 +1,110 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.urdf.xacro b/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.urdf.xacro
new file mode 100644
index 00000000..dcd714a9
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/openarm_bimanual.urdf.xacro
@@ -0,0 +1,27 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/pilz_cartesian_limits.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/pilz_cartesian_limits.yaml
new file mode 100644
index 00000000..61b7e410
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/pilz_cartesian_limits.yaml
@@ -0,0 +1,20 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+# Limits for the Pilz planner
+cartesian_limits:
+ max_trans_vel: 1.0
+ max_trans_acc: 2.25
+ max_trans_dec: -5.0
+ max_rot_vel: 1.57
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/ros2_controllers.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/ros2_controllers.yaml
new file mode 100644
index 00000000..67fcb2af
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/ros2_controllers.yaml
@@ -0,0 +1,91 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+# This config file is used by ros2_control
+controller_manager:
+ ros__parameters:
+ update_rate: 100 # Hz
+
+ left_arm_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ right_arm_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ left_gripper_controller:
+ type: position_controllers/GripperActionController
+
+ right_gripper_controller:
+ type: position_controllers/GripperActionController
+
+ # left_gripper_controller:
+ # type: joint_trajectory_controller/JointTrajectoryController
+
+ # right_gripper_controller:
+ # type: joint_trajectory_controller/JointTrajectoryController
+
+ joint_state_broadcaster:
+ type: joint_state_broadcaster/JointStateBroadcaster
+
+left_arm_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_joint1
+ - openarm_left_joint2
+ - openarm_left_joint3
+ - openarm_left_joint4
+ - openarm_left_joint5
+ - openarm_left_joint6
+ - openarm_left_joint7
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+ - velocity
+ - effort
+
+right_arm_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_joint1
+ - openarm_right_joint2
+ - openarm_right_joint3
+ - openarm_right_joint4
+ - openarm_right_joint5
+ - openarm_right_joint6
+ - openarm_right_joint7
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+ - velocity
+ - effort
+
+left_gripper_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_finger_joint1
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+right_gripper_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_finger_joint1
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/config/openarm_v2.0/sensors_3d.yaml b/openarm_bimanual_moveit_config/config/openarm_v2.0/sensors_3d.yaml
new file mode 100644
index 00000000..01b9ef2e
--- /dev/null
+++ b/openarm_bimanual_moveit_config/config/openarm_v2.0/sensors_3d.yaml
@@ -0,0 +1,27 @@
+# This file is used to configure the 3D sensors for the robot.
+# It is a placeholder for now. Configure the sensors to use the correct topics and parameters.
+sensors:
+ - default_sensor
+ - kinect_depthimage
+default_sensor:
+ far_clipping_plane_distance: 5.0
+ filtered_cloud_topic: filtered_cloud
+ image_topic: /head_mount_kinect/depth_registered/image_raw
+ max_update_rate: 1.0
+ near_clipping_plane_distance: 0.3
+ padding_offset: 0.03
+ padding_scale: 4.0
+ queue_size: 5
+ sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
+ shadow_threshold: 0.2
+kinect_depthimage:
+ far_clipping_plane_distance: 5.0
+ filtered_cloud_topic: filtered_cloud
+ image_topic: /head_mount_kinect/depth_registered/image_raw
+ max_update_rate: 1.0
+ near_clipping_plane_distance: 0.3
+ padding_offset: 0.03
+ padding_scale: 4.0
+ queue_size: 5
+ sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
+ shadow_threshold: 0.2
\ No newline at end of file
diff --git a/openarm_bimanual_moveit_config/launch/demo.launch.py b/openarm_bimanual_moveit_config/launch/demo.launch.py
index 5ed6731c..f457de2d 100644
--- a/openarm_bimanual_moveit_config/launch/demo.launch.py
+++ b/openarm_bimanual_moveit_config/launch/demo.launch.py
@@ -1,64 +1,58 @@
-# Copyright 2025 Enactic, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
import os
import xacro
-from ament_index_python.packages import (
- get_package_share_directory,
-)
+from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription, LaunchContext
-from launch.actions import (
- DeclareLaunchArgument,
- TimerAction,
- OpaqueFunction,
-)
-from launch.substitutions import (
- LaunchConfiguration,
- PathJoinSubstitution,
-)
+from launch.actions import DeclareLaunchArgument, TimerAction, OpaqueFunction
+from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from moveit_configs_utils import MoveItConfigsBuilder
+# All accepted arm_type values
+VALID_ARM_TYPES = {
+ "v1.0", "v10", "v1_0", "openarm_v1.0", "openarm_v10", "openarm_v1_0",
+ "v2.0", "v20", "v2_0", "openarm_v2.0", "openarm_v20", "openarm_v2_0",
+}
+
+
+def resolve_arm_config(arm_type_str: str) -> tuple[str, str]:
+ """
+ Resolve folder name and xacro file name from arm_type.
+ Accepts: v1.0, v10, v1_0, openarm_v1.0, openarm_v10, openarm_v1_0 (and v2.0 variants)
+ Raises ValueError if arm_type is not recognized.
+ """
+ if arm_type_str not in VALID_ARM_TYPES:
+ raise ValueError(
+ f"Invalid arm_type: '{arm_type_str}'. "
+ f"Please specify openarm_v1.0 or openarm_v2.0."
+ )
+ if any(x in arm_type_str for x in ("1.0", "10", "1_0")):
+ return "openarm_v1.0", "openarm_v10.urdf.xacro"
+ return "openarm_v2.0", "openarm_v20.urdf.xacro"
+
def generate_robot_description(
context: LaunchContext,
description_package,
- description_file,
arm_type,
use_fake_hardware,
right_can_interface,
left_can_interface,
- arm_prefix,
):
- """Render Xacro and return XML string."""
description_package_str = context.perform_substitution(description_package)
- description_file_str = context.perform_substitution(description_file)
arm_type_str = context.perform_substitution(arm_type)
use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
right_can_interface_str = context.perform_substitution(right_can_interface)
left_can_interface_str = context.perform_substitution(left_can_interface)
- arm_prefix_str = context.perform_substitution(arm_prefix)
+
+ folder_name, file_name = resolve_arm_config(arm_type_str)
xacro_path = os.path.join(
get_package_share_directory(description_package_str),
- "urdf",
- "robot",
- description_file_str,
+ "assets", "robot", folder_name, "urdf", file_name
)
- robot_description = xacro.process_file(
+ return xacro.process_file(
xacro_path,
mappings={
"arm_type": arm_type_str,
@@ -67,17 +61,13 @@ def generate_robot_description(
"ros2_control": "true",
"left_can_interface": left_can_interface_str,
"right_can_interface": right_can_interface_str,
- # arm_prefix unused inside xacro but kept for completeness
},
).toprettyxml(indent=" ")
- return robot_description
-
def robot_nodes_spawner(
context: LaunchContext,
description_package,
- description_file,
arm_type,
use_fake_hardware,
controllers_file,
@@ -88,12 +78,10 @@ def robot_nodes_spawner(
robot_description = generate_robot_description(
context,
description_package,
- description_file,
arm_type,
use_fake_hardware,
right_can_interface,
left_can_interface,
- arm_prefix,
)
controllers_file_str = context.perform_substitution(controllers_file)
@@ -138,38 +126,111 @@ def controller_spawner(context: LaunchContext, robot_controller):
]
+def moveit_nodes_spawner(context: LaunchContext, arm_type, use_fake_hardware):
+ arm_type_str = context.perform_substitution(arm_type)
+ use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
+
+ description_pkg_path = get_package_share_directory("openarm_description")
+ moveit_pkg_path = get_package_share_directory(
+ "openarm_bimanual_moveit_config")
+
+ folder_name, file_name = resolve_arm_config(arm_type_str)
+
+ xacro_path = os.path.join(
+ description_pkg_path, "assets", "robot", folder_name, "urdf", file_name
+ )
+
+ if any(x in arm_type_str for x in ("1.0", "10", "1_0")):
+ config_dir = "openarm_v1.0"
+ else:
+ config_dir = "openarm_v2.0"
+
+ moveit_config = (
+ MoveItConfigsBuilder(
+ "openarm", package_name="openarm_bimanual_moveit_config")
+ .robot_description(
+ file_path=xacro_path,
+ mappings={
+ "arm_type": arm_type_str,
+ "bimanual": "true",
+ "use_fake_hardware": use_fake_hardware_str,
+ "ros2_control": "true",
+ }
+ )
+ .robot_description_semantic(file_path=f"config/{config_dir}/openarm_bimanual.srdf")
+ .robot_description_kinematics(file_path=f"config/{config_dir}/kinematics.yaml")
+ .joint_limits(file_path=f"config/{config_dir}/joint_limits.yaml")
+ .trajectory_execution(file_path=f"config/{config_dir}/moveit_controllers.yaml")
+ .planning_pipelines(
+ pipelines=["ompl"],
+ default_planning_pipeline="ompl"
+ )
+ .to_moveit_configs()
+ )
+
+ moveit_params = moveit_config.to_dict()
+
+ pilz_cartesian_limits_path = os.path.join(
+ moveit_pkg_path, "config", config_dir, "pilz_cartesian_limits.yaml"
+ )
+
+ if os.path.exists(pilz_cartesian_limits_path):
+ import yaml
+ with open(pilz_cartesian_limits_path, 'r') as f:
+ config_data = yaml.safe_load(f)
+ if "cartesian_limits" in config_data:
+ if "robot_description_planning" not in moveit_params:
+ moveit_params["robot_description_planning"] = {}
+ moveit_params["robot_description_planning"].update(config_data)
+
+ rviz_cfg = os.path.join(moveit_pkg_path, "config",
+ config_dir, "moveit.rviz")
+
+ return [
+ Node(
+ package="moveit_ros_move_group",
+ executable="move_group",
+ output="screen",
+ parameters=[moveit_params],
+ ),
+ Node(
+ package="rviz2",
+ executable="rviz2",
+ name="rviz2",
+ output="log",
+ arguments=["-d", rviz_cfg],
+ parameters=[moveit_params],
+ ),
+ ]
+
+
def generate_launch_description():
declared_arguments = [
+ DeclareLaunchArgument("description_package",
+ default_value="openarm_description"),
DeclareLaunchArgument(
- "description_package",
- default_value="openarm_description",
- ),
- DeclareLaunchArgument(
- "description_file",
- default_value="v10.urdf.xacro",
+ "arm_type",
+ default_value="openarm_v2.0",
+ description="Arm type. Accepts: v1.0, v10, openarm_v1.0, v2.0, v20, openarm_v2.0, etc."
),
- DeclareLaunchArgument("arm_type", default_value="v10"),
- DeclareLaunchArgument("use_fake_hardware", default_value="false"),
+ DeclareLaunchArgument("use_fake_hardware", default_value="true"),
DeclareLaunchArgument(
"robot_controller",
default_value="joint_trajectory_controller",
choices=["forward_position_controller",
"joint_trajectory_controller"],
),
- DeclareLaunchArgument(
- "runtime_config_package", default_value="openarm_bringup"
- ),
+ DeclareLaunchArgument("runtime_config_package",
+ default_value="openarm_bringup"),
DeclareLaunchArgument("arm_prefix", default_value=""),
DeclareLaunchArgument("right_can_interface", default_value="can0"),
DeclareLaunchArgument("left_can_interface", default_value="can1"),
DeclareLaunchArgument(
"controllers_file",
- default_value="openarm_v10_bimanual_controllers.yaml",
- ),
+ default_value="openarm_bimanual_moveit_controllers.yaml"),
]
description_package = LaunchConfiguration("description_package")
- description_file = LaunchConfiguration("description_file")
arm_type = LaunchConfiguration("arm_type")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
robot_controller = LaunchConfiguration("robot_controller")
@@ -181,14 +242,13 @@ def generate_launch_description():
controllers_file = PathJoinSubstitution(
[FindPackageShare(runtime_config_package), "config",
- "v10_controllers", controllers_file]
+ "controllers", controllers_file]
)
robot_nodes_spawner_func = OpaqueFunction(
function=robot_nodes_spawner,
args=[
description_package,
- description_file,
arm_type,
use_fake_hardware,
controllers_file,
@@ -198,6 +258,11 @@ def generate_launch_description():
],
)
+ moveit_nodes_func = OpaqueFunction(
+ function=moveit_nodes_spawner,
+ args=[arm_type, use_fake_hardware]
+ )
+
jsb_spawner = Node(
package="controller_manager",
executable="spawner",
@@ -206,7 +271,8 @@ def generate_launch_description():
)
controller_spawner_func = OpaqueFunction(
- function=controller_spawner, args=[robot_controller])
+ function=controller_spawner, args=[robot_controller]
+ )
gripper_spawner = Node(
package="controller_manager",
@@ -215,46 +281,13 @@ def generate_launch_description():
"right_gripper_controller", "-c", "/controller_manager"],
)
- delayed_jsb = TimerAction(period=2.0, actions=[jsb_spawner])
- delayed_arm_ctrl = TimerAction(
- period=1.0, actions=[controller_spawner_func])
- delayed_gripper = TimerAction(period=1.0, actions=[gripper_spawner])
-
- moveit_config = MoveItConfigsBuilder(
- "openarm", package_name="openarm_bimanual_moveit_config"
- ).to_moveit_configs()
-
- moveit_params = moveit_config.to_dict()
-
- run_move_group_node = Node(
- package="moveit_ros_move_group",
- executable="move_group",
- output="screen",
- parameters=[moveit_params],
- )
-
- rviz_cfg = os.path.join(
- get_package_share_directory(
- "openarm_bimanual_moveit_config"), "config", "moveit.rviz"
- )
-
- rviz_node = Node(
- package="rviz2",
- executable="rviz2",
- name="rviz2",
- output="log",
- arguments=["-d", rviz_cfg],
- parameters=[moveit_params],
- )
-
return LaunchDescription(
declared_arguments
+ [
robot_nodes_spawner_func,
- delayed_jsb,
- delayed_arm_ctrl,
- delayed_gripper,
- run_move_group_node,
- rviz_node,
+ moveit_nodes_func,
+ TimerAction(period=2.0, actions=[jsb_spawner]),
+ TimerAction(period=1.0, actions=[controller_spawner_func]),
+ TimerAction(period=1.0, actions=[gripper_spawner]),
]
)
diff --git a/openarm_bimanual_moveit_config/launch/move_group.launch.py b/openarm_bimanual_moveit_config/launch/move_group.launch.py
index ec098d29..36bd77c9 100644
--- a/openarm_bimanual_moveit_config/launch/move_group.launch.py
+++ b/openarm_bimanual_moveit_config/launch/move_group.launch.py
@@ -1,8 +1,40 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch
+from launch import LaunchDescription, LaunchContext
+from launch.actions import DeclareLaunchArgument, OpaqueFunction
+from launch.substitutions import LaunchConfiguration
+
+
+def move_group_spawner(context: LaunchContext, arm_type):
+ arm_type_str = context.perform_substitution(arm_type)
+ moveit_config = (
+ MoveItConfigsBuilder(
+ "openarm", package_name="openarm_bimanual_moveit_config")
+ .robot_description_semantic(file_path=f"config/{arm_type_str}/openarm_bimanual.srdf")
+ .joint_limits(file_path=f"config/{arm_type_str}/joint_limits.yaml")
+ .robot_description_kinematics(file_path=f"config/{arm_type_str}/kinematics.yaml")
+ .to_moveit_configs()
+ )
+ return generate_move_group_launch(moveit_config).entities
def generate_launch_description():
- moveit_config = MoveItConfigsBuilder(
- "openarm", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
- return generate_move_group_launch(moveit_config)
+ return LaunchDescription([
+ DeclareLaunchArgument("arm_type", default_value="v20"),
+ OpaqueFunction(function=move_group_spawner, args=[
+ LaunchConfiguration("arm_type")])
+ ])
diff --git a/openarm_bimanual_moveit_config/launch/moveit_rviz.launch.py b/openarm_bimanual_moveit_config/launch/moveit_rviz.launch.py
index 1bed84f3..f2466d58 100644
--- a/openarm_bimanual_moveit_config/launch/moveit_rviz.launch.py
+++ b/openarm_bimanual_moveit_config/launch/moveit_rviz.launch.py
@@ -1,8 +1,40 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_moveit_rviz_launch
+from launch import LaunchDescription, LaunchContext
+from launch.actions import DeclareLaunchArgument, OpaqueFunction
+from launch.substitutions import LaunchConfiguration
+
+
+def rviz_spawner(context: LaunchContext, arm_type):
+ arm_type_str = context.perform_substitution(arm_type)
+ moveit_config = (
+ MoveItConfigsBuilder(
+ "openarm", package_name="openarm_bimanual_moveit_config")
+ .robot_description_semantic(file_path=f"config/{arm_type_str}/openarm_bimanual.srdf")
+ .joint_limits(file_path=f"config/{arm_type_str}/joint_limits.yaml")
+ .robot_description_kinematics(file_path=f"config/{arm_type_str}/kinematics.yaml")
+ .to_moveit_configs()
+ )
+ return generate_moveit_rviz_launch(moveit_config).entities
def generate_launch_description():
- moveit_config = MoveItConfigsBuilder(
- "openarm", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
- return generate_moveit_rviz_launch(moveit_config)
+ return LaunchDescription([
+ DeclareLaunchArgument("arm_type", default_value="v20"),
+ OpaqueFunction(function=rviz_spawner, args=[
+ LaunchConfiguration("arm_type")])
+ ])
diff --git a/openarm_bimanual_moveit_config/launch/spawn_controllers.launch.py b/openarm_bimanual_moveit_config/launch/spawn_controllers.launch.py
index d5ecc3c4..3b363b61 100644
--- a/openarm_bimanual_moveit_config/launch/spawn_controllers.launch.py
+++ b/openarm_bimanual_moveit_config/launch/spawn_controllers.launch.py
@@ -1,8 +1,40 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_spawn_controllers_launch
+from launch import LaunchDescription, LaunchContext
+from launch.actions import DeclareLaunchArgument, OpaqueFunction
+from launch.substitutions import LaunchConfiguration
+
+
+def spawn_controllers_spawner(context: LaunchContext, arm_type):
+ arm_type_str = context.perform_substitution(arm_type)
+ moveit_config = (
+ MoveItConfigsBuilder(
+ "openarm", package_name="openarm_bimanual_moveit_config")
+ .robot_description_semantic(file_path=f"config/{arm_type_str}/openarm_bimanual.srdf")
+ .joint_limits(file_path=f"config/{arm_type_str}/joint_limits.yaml")
+ .robot_description_kinematics(file_path=f"config/{arm_type_str}/kinematics.yaml")
+ .to_moveit_configs()
+ )
+ return generate_spawn_controllers_launch(moveit_config).entities
def generate_launch_description():
- moveit_config = MoveItConfigsBuilder(
- "openarm", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
- return generate_spawn_controllers_launch(moveit_config)
+ return LaunchDescription([
+ DeclareLaunchArgument("arm_type", default_value="v20"),
+ OpaqueFunction(function=spawn_controllers_spawner,
+ args=[LaunchConfiguration("arm_type")])
+ ])
diff --git a/openarm_bimanual_moveit_config/launch/static_virtual_joint_tfs.launch.py b/openarm_bimanual_moveit_config/launch/static_virtual_joint_tfs.launch.py
index 9b82fdc7..f12e6461 100644
--- a/openarm_bimanual_moveit_config/launch/static_virtual_joint_tfs.launch.py
+++ b/openarm_bimanual_moveit_config/launch/static_virtual_joint_tfs.launch.py
@@ -1,8 +1,40 @@
+# Copyright 2025 Enactic, Inc.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch
+from launch import LaunchDescription, LaunchContext
+from launch.actions import DeclareLaunchArgument, OpaqueFunction
+from launch.substitutions import LaunchConfiguration
+
+
+def static_tfs_spawner(context: LaunchContext, arm_type):
+ arm_type_str = context.perform_substitution(arm_type)
+ moveit_config = (
+ MoveItConfigsBuilder(
+ "openarm", package_name="openarm_bimanual_moveit_config")
+ .robot_description_semantic(file_path=f"config/{arm_type_str}/openarm_bimanual.srdf")
+ .joint_limits(file_path=f"config/{arm_type_str}/joint_limits.yaml")
+ .robot_description_kinematics(file_path=f"config/{arm_type_str}/kinematics.yaml")
+ .to_moveit_configs()
+ )
+ return generate_static_virtual_joint_tfs_launch(moveit_config).entities
def generate_launch_description():
- moveit_config = MoveItConfigsBuilder(
- "openarm", package_name="openarm_bimanual_moveit_config").to_moveit_configs()
- return generate_static_virtual_joint_tfs_launch(moveit_config)
+ return LaunchDescription([
+ DeclareLaunchArgument("arm_type", default_value="v20"),
+ OpaqueFunction(function=static_tfs_spawner, args=[
+ LaunchConfiguration("arm_type")])
+ ])
diff --git a/openarm_bringup/config/controllers/openarm_bimanual_controllers.yaml b/openarm_bringup/config/controllers/openarm_bimanual_controllers.yaml
new file mode 100644
index 00000000..914be84c
--- /dev/null
+++ b/openarm_bringup/config/controllers/openarm_bimanual_controllers.yaml
@@ -0,0 +1,208 @@
+# Copyright 2025 Enactic, Inc.
+# Copyright 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+controller_manager:
+ ros__parameters:
+ update_rate: 750 # Hz
+
+ joint_state_broadcaster:
+ type: joint_state_broadcaster/JointStateBroadcaster
+
+ left_forward_position_controller:
+ type: forward_command_controller/ForwardCommandController
+
+ left_forward_velocity_controller:
+ type: forward_command_controller/ForwardCommandController
+
+ left_joint_trajectory_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ left_gripper_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ right_forward_position_controller:
+ type: forward_command_controller/ForwardCommandController
+
+ right_forward_velocity_controller:
+ type: forward_command_controller/ForwardCommandController
+
+ right_joint_trajectory_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ right_gripper_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+left_forward_position_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_joint1
+ - openarm_left_joint2
+ - openarm_left_joint3
+ - openarm_left_joint4
+ - openarm_left_joint5
+ - openarm_left_joint6
+ - openarm_left_joint7
+ interface_name: position
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+left_forward_velocity_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_joint1
+ - openarm_left_joint2
+ - openarm_left_joint3
+ - openarm_left_joint4
+ - openarm_left_joint5
+ - openarm_left_joint6
+ - openarm_left_joint7
+ interface_name: velocity
+ command_interfaces:
+ - velocity
+ state_interfaces:
+ - velocity
+
+left_joint_trajectory_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_joint1
+ - openarm_left_joint2
+ - openarm_left_joint3
+ - openarm_left_joint4
+ - openarm_left_joint5
+ - openarm_left_joint6
+ - openarm_left_joint7
+ interface_name: position
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+ # to achieve high real-time performance, interpolation is disabled and the controller is expected to receive high-frequency commands --- IGNORE ---
+ interpolation_method: "none"
+ interpolate_from_desired_state: true
+
+ state_publish_rate: 50.0
+ action_monitor_rate: 50.0
+ allow_partial_joints_goal: false
+
+ constraints:
+ stopped_velocity_tolerance: 0.0
+ goal_time: 0.0
+ decelerate_on_cancel: false
+ openarm_left_joint1: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint2: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint3: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint4: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint5: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint6: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint7: { trajectory: 0.0, goal: 0.0 }
+
+left_gripper_controller:
+ ros__parameters:
+ joints:
+ - openarm_left_finger_joint1
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+ interpolation_method: "none"
+ constraints:
+ stopped_velocity_tolerance: 0.0
+ goal_time: 0.0
+
+right_forward_position_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_joint1
+ - openarm_right_joint2
+ - openarm_right_joint3
+ - openarm_right_joint4
+ - openarm_right_joint5
+ - openarm_right_joint6
+ - openarm_right_joint7
+ interface_name: position
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+right_forward_velocity_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_joint1
+ - openarm_right_joint2
+ - openarm_right_joint3
+ - openarm_right_joint4
+ - openarm_right_joint5
+ - openarm_right_joint6
+ - openarm_right_joint7
+ interface_name: velocity
+ command_interfaces:
+ - velocity
+ state_interfaces:
+ - velocity
+
+right_joint_trajectory_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_joint1
+ - openarm_right_joint2
+ - openarm_right_joint3
+ - openarm_right_joint4
+ - openarm_right_joint5
+ - openarm_right_joint6
+ - openarm_right_joint7
+ interface_name: position
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+ interpolation_method: "none"
+ interpolate_from_desired_state: true
+
+ state_publish_rate: 50.0
+ action_monitor_rate: 50.0
+ allow_partial_joints_goal: false
+
+ constraints:
+ stopped_velocity_tolerance: 0.0
+ goal_time: 0.0
+ decelerate_on_cancel: false
+ openarm_right_joint1: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint2: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint3: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint4: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint5: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint6: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint7: { trajectory: 0.0, goal: 0.0 }
+
+right_gripper_controller:
+ ros__parameters:
+ joints:
+ - openarm_right_finger_joint1
+ command_interfaces:
+ - position
+ state_interfaces:
+ - position
+
+ interpolation_method: "none"
+ constraints:
+ stopped_velocity_tolerance: 0.0
+ goal_time: 0.0
\ No newline at end of file
diff --git a/openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers.yaml b/openarm_bringup/config/controllers/openarm_bimanual_moveit_controllers.yaml
similarity index 69%
rename from openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers.yaml
rename to openarm_bringup/config/controllers/openarm_bimanual_moveit_controllers.yaml
index 8a386eec..d5c19bcb 100644
--- a/openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers.yaml
+++ b/openarm_bringup/config/controllers/openarm_bimanual_moveit_controllers.yaml
@@ -15,7 +15,7 @@
controller_manager:
ros__parameters:
- update_rate: 100 # Hz
+ update_rate: 100
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
@@ -30,7 +30,7 @@ controller_manager:
type: joint_trajectory_controller/JointTrajectoryController
left_gripper_controller:
- type: position_controllers/GripperActionController
+ type: joint_trajectory_controller/JointTrajectoryController
right_forward_position_controller:
type: forward_command_controller/ForwardCommandController
@@ -42,8 +42,7 @@ controller_manager:
type: joint_trajectory_controller/JointTrajectoryController
right_gripper_controller:
- type: position_controllers/GripperActionController
-
+ type: joint_trajectory_controller/JointTrajectoryController
left_forward_position_controller:
ros__parameters:
@@ -93,22 +92,37 @@ left_joint_trajectory_controller:
state_interfaces:
- position
- state_publish_rate: 50.0 # Defaults to 50
- action_monitor_rate: 50.0 # Defaults to 20
+ interpolation_method: "splines"
+ interpolate_from_desired_state: false
+
+ state_publish_rate: 50.0
+ action_monitor_rate: 20.0
+ allow_partial_joints_goal: false
- allow_partial_joints_goal: false # Defaults to false
constraints:
- stopped_velocity_tolerance: 0.01 # Defaults to 0.01
- goal_time: 0.0 # Defaults to 0.0 (start immediately)
+ stopped_velocity_tolerance: 0.01
+ goal_time: 0.0
+ openarm_left_joint1: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint2: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint3: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint4: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint5: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint6: { trajectory: 0.0, goal: 0.0 }
+ openarm_left_joint7: { trajectory: 0.0, goal: 0.0 }
left_gripper_controller:
ros__parameters:
- joint: openarm_left_finger_joint1
+ joints:
+ - openarm_left_finger_joint1
command_interfaces:
- position
state_interfaces:
- position
+ interpolation_method: "splines"
+ constraints:
+ stopped_velocity_tolerance: 0.01
+ goal_time: 0.0
right_forward_position_controller:
ros__parameters:
@@ -158,18 +172,34 @@ right_joint_trajectory_controller:
state_interfaces:
- position
- state_publish_rate: 50.0 # Defaults to 50
- action_monitor_rate: 50.0 # Defaults to 20
+ interpolation_method: "splines"
+ interpolate_from_desired_state: false
+
+ state_publish_rate: 50.0
+ action_monitor_rate: 20.0
+ allow_partial_joints_goal: false
- allow_partial_joints_goal: false # Defaults to false
constraints:
- stopped_velocity_tolerance: 0.01 # Defaults to 0.01
- goal_time: 0.0 # Defaults to 0.0 (start immediately)
+ stopped_velocity_tolerance: 0.01
+ goal_time: 0.0
+ openarm_right_joint1: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint2: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint3: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint4: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint5: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint6: { trajectory: 0.0, goal: 0.0 }
+ openarm_right_joint7: { trajectory: 0.0, goal: 0.0 }
right_gripper_controller:
ros__parameters:
- joint: openarm_right_finger_joint1
+ joints:
+ - openarm_right_finger_joint1
command_interfaces:
- position
state_interfaces:
- - position
\ No newline at end of file
+ - position
+
+ interpolation_method: "splines"
+ constraints:
+ stopped_velocity_tolerance: 0.01
+ goal_time: 0.0
\ No newline at end of file
diff --git a/openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers_namespaced.yaml b/openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers_namespaced.yaml
deleted file mode 100644
index ca0b9721..00000000
--- a/openarm_bringup/config/v10_controllers/openarm_v10_bimanual_controllers_namespaced.yaml
+++ /dev/null
@@ -1,138 +0,0 @@
-# Copyright 2025 Enactic, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-/**:
- ros__parameters:
- update_rate: 100 # Hz
-
- joint_state_broadcaster:
- type: joint_state_broadcaster/JointStateBroadcaster
-
- left_joint_trajectory_controller:
- type: joint_trajectory_controller/JointTrajectoryController
-
- right_joint_trajectory_controller:
- type: joint_trajectory_controller/JointTrajectoryController
-
- left_forward_position_controller:
- type: forward_command_controller/ForwardCommandController
-
- right_forward_position_controller:
- type: forward_command_controller/ForwardCommandController
-
- left_gripper_controller:
- type: forward_command_controller/ForwardCommandController
-
- right_gripper_controller:
- type: forward_command_controller/ForwardCommandController
-
-/**/left_joint_trajectory_controller:
- ros__parameters:
- joints:
- - openarm_left_joint1
- - openarm_left_joint2
- - openarm_left_joint3
- - openarm_left_joint4
- - openarm_left_joint5
- - openarm_left_joint6
- - openarm_left_joint7
- interface_name: position
- command_interfaces:
- - position
- state_interfaces:
- - position
- - velocity
- state_publish_rate: 100.0
- action_monitor_rate: 20.0
- allow_partial_joints_goal: false
- open_loop_control: false
- allow_integration_in_goal_trajectories: true
- constraints:
- stopped_velocity_tolerance: 0.01
- goal_time: 0.6
- openarm_left_joint1: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint2: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint3: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint4: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint5: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint6: {trajectory: 0.1, goal: 0.1}
- openarm_left_joint7: {trajectory: 0.1, goal: 0.1}
-
-/**/right_joint_trajectory_controller:
- ros__parameters:
- joints:
- - openarm_right_joint1
- - openarm_right_joint2
- - openarm_right_joint3
- - openarm_right_joint4
- - openarm_right_joint5
- - openarm_right_joint6
- - openarm_right_joint7
- interface_name: position
- command_interfaces:
- - position
- state_interfaces:
- - position
- - velocity
- state_publish_rate: 100.0
- action_monitor_rate: 20.0
- allow_partial_joints_goal: false
- open_loop_control: false
- allow_integration_in_goal_trajectories: true
- constraints:
- stopped_velocity_tolerance: 0.01
- goal_time: 0.6
- openarm_right_joint1: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint2: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint3: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint4: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint5: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint6: {trajectory: 0.1, goal: 0.1}
- openarm_right_joint7: {trajectory: 0.1, goal: 0.1}
-
-/**/left_forward_position_controller:
- ros__parameters:
- joints:
- - openarm_left_joint1
- - openarm_left_joint2
- - openarm_left_joint3
- - openarm_left_joint4
- - openarm_left_joint5
- - openarm_left_joint6
- - openarm_left_joint7
- interface_name: position
-
-/**/right_forward_position_controller:
- ros__parameters:
- joints:
- - openarm_right_joint1
- - openarm_right_joint2
- - openarm_right_joint3
- - openarm_right_joint4
- - openarm_right_joint5
- - openarm_right_joint6
- - openarm_right_joint7
- interface_name: position
-
-/**/left_gripper_controller:
- ros__parameters:
- joints:
- - openarm_left_finger_joint1
- interface_name: position
-
-/**/right_gripper_controller:
- ros__parameters:
- joints:
- - openarm_right_finger_joint1
- interface_name: position
diff --git a/openarm_bringup/config/v10_controllers/openarm_v10_controllers.yaml b/openarm_bringup/config/v10_controllers/openarm_v10_controllers.yaml
deleted file mode 100644
index f2f3a03c..00000000
--- a/openarm_bringup/config/v10_controllers/openarm_v10_controllers.yaml
+++ /dev/null
@@ -1,99 +0,0 @@
-# Copyright 2025 Enactic, Inc.
-# Copyright 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-controller_manager:
- ros__parameters:
- update_rate: 100 # Hz
-
- joint_state_broadcaster:
- type: joint_state_broadcaster/JointStateBroadcaster
-
- forward_position_controller:
- type: forward_command_controller/ForwardCommandController
-
- forward_velocity_controller:
- type: forward_command_controller/ForwardCommandController
-
- joint_trajectory_controller:
- type: joint_trajectory_controller/JointTrajectoryController
-
- gripper_controller:
- type: position_controllers/GripperActionController
-
-forward_position_controller:
- ros__parameters:
- joints:
- - openarm_joint1
- - openarm_joint2
- - openarm_joint3
- - openarm_joint4
- - openarm_joint5
- - openarm_joint6
- - openarm_joint7
- interface_name: position
- command_interfaces:
- - position
- state_interfaces:
- - position
-
-
-forward_velocity_controller:
- ros__parameters:
- joints:
- - openarm_joint1
- - openarm_joint2
- - openarm_joint3
- - openarm_joint4
- - openarm_joint5
- - openarm_joint6
- - openarm_joint7
- interface_name: velocity
- command_interfaces:
- - velocity
- state_interfaces:
- - velocity
-
-joint_trajectory_controller:
- ros__parameters:
- joints:
- - openarm_joint1
- - openarm_joint2
- - openarm_joint3
- - openarm_joint4
- - openarm_joint5
- - openarm_joint6
- - openarm_joint7
-
- command_interfaces:
- - position
- state_interfaces:
- - position
-
- state_publish_rate: 50.0 # Defaults to 50
- action_monitor_rate: 50.0 # Defaults to 20
-
- allow_partial_joints_goal: false # Defaults to false
- constraints:
- stopped_velocity_tolerance: 0.01 # Defaults to 0.01
- goal_time: 0.0 # Defaults to 0.0 (start immediately)
-
-
-gripper_controller:
- ros__parameters:
- joint: openarm_finger_joint1
- command_interfaces:
- - position
- state_interfaces:
- - position
\ No newline at end of file
diff --git a/openarm_bringup/launch/openarm.bimanual.launch.py b/openarm_bringup/launch/openarm.bimanual.launch.py
index feac6cc8..2b5fb46f 100644
--- a/openarm_bringup/launch/openarm.bimanual.launch.py
+++ b/openarm_bringup/launch/openarm.bimanual.launch.py
@@ -19,15 +19,33 @@
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription, LaunchContext
-from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction, OpaqueFunction
-from launch.event_handlers import OnProcessExit
-from launch.substitutions import (
- LaunchConfiguration,
- PathJoinSubstitution,
-)
+from launch.actions import DeclareLaunchArgument, TimerAction, OpaqueFunction
+from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
+# All accepted arm_type values
+VALID_ARM_TYPES = {
+ "v1.0", "v10", "v1_0", "openarm_v1.0", "openarm_v10", "openarm_v1_0",
+ "v2.0", "v20", "v2_0", "openarm_v2.0", "openarm_v20", "openarm_v2_0",
+}
+
+
+def resolve_arm_config(arm_type_str: str) -> tuple[str, str]:
+ """
+ Resolve folder name and xacro file name from arm_type.
+ Accepts: v1.0, v10, v1_0, openarm_v1.0, openarm_v10, openarm_v1_0 (and v2.0 variants)
+ Raises ValueError if arm_type is not recognized.
+ """
+ if arm_type_str not in VALID_ARM_TYPES:
+ raise ValueError(
+ f"Invalid arm_type: '{arm_type_str}'. "
+ f"Please specify openarm_v1.0 or openarm_v2.0."
+ )
+ if any(x in arm_type_str for x in ("1.0", "10", "1_0")):
+ return "openarm_v1.0", "openarm_v10.urdf.xacro"
+ return "openarm_v2.0", "openarm_v20.urdf.xacro"
+
def namespace_from_context(context, arm_prefix):
arm_prefix_str = context.perform_substitution(arm_prefix)
@@ -39,20 +57,19 @@ def namespace_from_context(context, arm_prefix):
def generate_robot_description(context: LaunchContext, description_package, description_file,
arm_type, use_fake_hardware, right_can_interface, left_can_interface):
"""Generate robot description using xacro processing."""
-
description_package_str = context.perform_substitution(description_package)
- description_file_str = context.perform_substitution(description_file)
arm_type_str = context.perform_substitution(arm_type)
use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
right_can_interface_str = context.perform_substitution(right_can_interface)
left_can_interface_str = context.perform_substitution(left_can_interface)
+ folder_name, file_name = resolve_arm_config(arm_type_str)
+
xacro_path = os.path.join(
get_package_share_directory(description_package_str),
- "urdf", "robot", description_file_str
+ "assets", "robot", folder_name, "urdf", file_name
)
- # Process xacro with required arguments
robot_description = xacro.process_file(
xacro_path,
mappings={
@@ -69,12 +86,14 @@ def generate_robot_description(context: LaunchContext, description_package, desc
def robot_nodes_spawner(context: LaunchContext, description_package, description_file,
- arm_type, use_fake_hardware, controllers_file, right_can_interface, left_can_interface, arm_prefix):
+ arm_type, use_fake_hardware, controllers_file,
+ right_can_interface, left_can_interface, arm_prefix):
"""Spawn both robot state publisher and control nodes with shared robot description."""
namespace = namespace_from_context(context, arm_prefix)
robot_description = generate_robot_description(
- context, description_package, description_file, arm_type, use_fake_hardware, right_can_interface, left_can_interface,
+ context, description_package, description_file, arm_type,
+ use_fake_hardware, right_can_interface, left_can_interface,
)
controllers_file_str = context.perform_substitution(controllers_file)
@@ -82,8 +101,10 @@ def robot_nodes_spawner(context: LaunchContext, description_package, description
if namespace:
controllers_file_str = controllers_file_str.replace(
- "openarm_v10_bimanual_controllers.yaml", "openarm_v10_bimanual_controllers_namespaced.yaml"
+ "openarm_bimanual_controllers.yaml",
+ "openarm_bimanual_controllers_namespaced.yaml"
)
+
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
@@ -107,8 +128,9 @@ def robot_nodes_spawner(context: LaunchContext, description_package, description
def controller_spawner(context: LaunchContext, robot_controller, arm_prefix):
"""Spawn controller based on robot_controller argument."""
namespace = namespace_from_context(context, arm_prefix)
-
- controller_manager_ref = f"/{namespace}/controller_manager" if namespace else "/controller_manager"
+ controller_manager_ref = (
+ f"/{namespace}/controller_manager" if namespace else "/controller_manager"
+ )
robot_controller_str = context.perform_substitution(robot_controller)
@@ -121,21 +143,20 @@ def controller_spawner(context: LaunchContext, robot_controller, arm_prefix):
else:
raise ValueError(f"Unknown robot_controller: {robot_controller_str}")
- robot_controller_spawner = Node(
- package="controller_manager",
- executable="spawner",
- namespace=namespace,
- arguments=[robot_controller_left,
- robot_controller_right, "-c", controller_manager_ref],
- )
-
- return [robot_controller_spawner]
+ return [
+ Node(
+ package="controller_manager",
+ executable="spawner",
+ namespace=namespace,
+ arguments=[robot_controller_left, robot_controller_right,
+ "-c", controller_manager_ref],
+ )
+ ]
def generate_launch_description():
"""Generate launch description for OpenArm bimanual configuration."""
- # Declare launch arguments
declared_arguments = [
DeclareLaunchArgument(
"description_package",
@@ -144,17 +165,17 @@ def generate_launch_description():
),
DeclareLaunchArgument(
"description_file",
- default_value="v10.urdf.xacro",
+ default_value="v20.urdf.xacro",
description="URDF/XACRO description file with the robot.",
),
DeclareLaunchArgument(
"arm_type",
- default_value="v10",
- description="Type of arm (e.g., v10).",
+ default_value="openarm_v2.0",
+ description="Arm type. Accepts: v1.0, v10, openarm_v1.0, v2.0, v20, openarm_v2.0, etc.",
),
DeclareLaunchArgument(
"use_fake_hardware",
- default_value="false",
+ default_value="true",
description="Use fake hardware instead of real hardware.",
),
DeclareLaunchArgument(
@@ -186,12 +207,11 @@ def generate_launch_description():
),
DeclareLaunchArgument(
"controllers_file",
- default_value="openarm_v10_bimanual_controllers.yaml",
- description="Controllers file(s) to use. Can be a single file or comma-separated list of files.",
+ default_value="openarm_bimanual_controllers.yaml",
+ description="Controllers file to use.",
),
]
- # Initialize launch configurations
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
arm_type = LaunchConfiguration("arm_type")
@@ -205,18 +225,18 @@ def generate_launch_description():
controllers_file = PathJoinSubstitution(
[FindPackageShare(runtime_config_package), "config",
- "v10_controllers", controllers_file]
+ "controllers", controllers_file]
)
robot_nodes_spawner_func = OpaqueFunction(
function=robot_nodes_spawner,
args=[description_package, description_file, arm_type,
- use_fake_hardware, controllers_file, right_can_interface, left_can_interface, arm_prefix]
+ use_fake_hardware, controllers_file,
+ right_can_interface, left_can_interface, arm_prefix]
)
rviz_config_file = PathJoinSubstitution(
- [FindPackageShare(description_package), "rviz",
- "bimanual.rviz"]
+ [FindPackageShare(description_package), "rviz", "bimanual.rviz"]
)
rviz_node = Node(
@@ -227,19 +247,21 @@ def generate_launch_description():
arguments=["-d", rviz_config_file],
)
- # Joint state broadcaster spawner
joint_state_broadcaster_spawner = OpaqueFunction(
function=lambda context: [Node(
package="controller_manager",
executable="spawner",
namespace=namespace_from_context(context, arm_prefix),
- arguments=["joint_state_broadcaster",
- "--controller-manager",
- f"/{namespace_from_context(context, arm_prefix)}/controller_manager" if namespace_from_context(context, arm_prefix) else "/controller_manager"],
+ arguments=[
+ "joint_state_broadcaster",
+ "--controller-manager",
+ f"/{namespace_from_context(context, arm_prefix)}/controller_manager"
+ if namespace_from_context(context, arm_prefix)
+ else "/controller_manager"
+ ],
)]
)
- # Controller spawners
controller_spawner_func = OpaqueFunction(
function=controller_spawner,
args=[robot_controller, arm_prefix]
@@ -250,36 +272,27 @@ def generate_launch_description():
package="controller_manager",
executable="spawner",
namespace=namespace_from_context(context, arm_prefix),
- arguments=["left_gripper_controller",
- "right_gripper_controller", "-c",
- f"/{namespace_from_context(context, arm_prefix)}/controller_manager" if namespace_from_context(context, arm_prefix) else "/controller_manager"],
+ arguments=[
+ "left_gripper_controller", "right_gripper_controller",
+ "-c",
+ f"/{namespace_from_context(context, arm_prefix)}/controller_manager"
+ if namespace_from_context(context, arm_prefix)
+ else "/controller_manager"
+ ],
)]
)
- # Timing and sequencing
LAUNCH_DELAY_SECONDS = 1.0
- delayed_joint_state_broadcaster = TimerAction(
- period=LAUNCH_DELAY_SECONDS,
- actions=[joint_state_broadcaster_spawner],
- )
-
- delayed_robot_controller = TimerAction(
- period=LAUNCH_DELAY_SECONDS,
- actions=[controller_spawner_func],
- )
- delayed_gripper_controller = TimerAction(
- period=LAUNCH_DELAY_SECONDS,
- actions=[gripper_controller_spawner],
- )
return LaunchDescription(
declared_arguments + [
robot_nodes_spawner_func,
rviz_node,
- ] +
- [
- delayed_joint_state_broadcaster,
- delayed_robot_controller,
- delayed_gripper_controller,
+ TimerAction(period=LAUNCH_DELAY_SECONDS, actions=[
+ joint_state_broadcaster_spawner]),
+ TimerAction(period=LAUNCH_DELAY_SECONDS,
+ actions=[controller_spawner_func]),
+ TimerAction(period=LAUNCH_DELAY_SECONDS, actions=[
+ gripper_controller_spawner]),
]
)
diff --git a/openarm_bringup/launch/openarm.launch.py b/openarm_bringup/launch/openarm.launch.py
deleted file mode 100644
index 847bbd0d..00000000
--- a/openarm_bringup/launch/openarm.launch.py
+++ /dev/null
@@ -1,235 +0,0 @@
-# Copyright 2025 Enactic, Inc.
-# Copyright 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-import xacro
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription, LaunchContext
-from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction, OpaqueFunction
-from launch.event_handlers import OnProcessExit
-from launch.substitutions import (
- LaunchConfiguration,
- PathJoinSubstitution,
-)
-from launch_ros.actions import Node
-from launch_ros.substitutions import FindPackageShare
-
-
-def generate_robot_description(context: LaunchContext, description_package, description_file,
- arm_type, use_fake_hardware, can_interface, arm_prefix):
- """Generate robot description using xacro processing."""
-
- # Substitute launch configuration values
- description_package_str = context.perform_substitution(description_package)
- description_file_str = context.perform_substitution(description_file)
- arm_type_str = context.perform_substitution(arm_type)
- use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
- can_interface_str = context.perform_substitution(can_interface)
- arm_prefix_str = context.perform_substitution(arm_prefix)
-
- # Build xacro file path
- xacro_path = os.path.join(
- get_package_share_directory(description_package_str),
- "urdf", "robot", description_file_str
- )
-
- # Process xacro with required arguments
- robot_description = xacro.process_file(
- xacro_path,
- mappings={
- "arm_type": arm_type_str,
- "bimanual": "false",
- "use_fake_hardware": use_fake_hardware_str,
- "ros2_control": "true",
- "can_interface": can_interface_str,
- "arm_prefix": arm_prefix_str,
- }
- ).toprettyxml(indent=" ")
-
- return robot_description
-
-
-def robot_nodes_spawner(context: LaunchContext, description_package, description_file,
- arm_type, use_fake_hardware, controllers_file, can_interface, arm_prefix):
- """Spawn both robot state publisher and control nodes with shared robot description."""
-
- # Generate robot description once
- robot_description = generate_robot_description(
- context, description_package, description_file, arm_type, use_fake_hardware, can_interface, arm_prefix
- )
-
- # Get controllers file path
- controllers_file_str = context.perform_substitution(controllers_file)
- robot_description_param = {"robot_description": robot_description}
-
- # Robot state publisher node
- robot_state_pub_node = Node(
- package="robot_state_publisher",
- executable="robot_state_publisher",
- name="robot_state_publisher",
- output="screen",
- parameters=[robot_description_param],
- )
-
- # Control node
- control_node = Node(
- package="controller_manager",
- executable="ros2_control_node",
- output="both",
- parameters=[robot_description_param, controllers_file_str],
- )
-
- return [robot_state_pub_node, control_node]
-
-
-def generate_launch_description():
- """Generate launch description for OpenArm unimanual configuration."""
-
- # Declare launch arguments
- declared_arguments = [
- DeclareLaunchArgument(
- "description_package",
- default_value="openarm_description",
- description="Description package with robot URDF/xacro files.",
- ),
- DeclareLaunchArgument(
- "description_file",
- default_value="v10.urdf.xacro",
- description="URDF/XACRO description file with the robot.",
- ),
- DeclareLaunchArgument(
- "arm_type",
- default_value="v10",
- description="Type of arm (e.g., v10).",
- ),
- DeclareLaunchArgument(
- "use_fake_hardware",
- default_value="false",
- description="Use fake hardware instead of real hardware.",
- ),
- DeclareLaunchArgument(
- "robot_controller",
- default_value="joint_trajectory_controller",
- choices=["forward_position_controller",
- "joint_trajectory_controller"],
- description="Robot controller to start.",
- ),
- DeclareLaunchArgument(
- "runtime_config_package",
- default_value="openarm_bringup",
- description="Package with the controller's configuration in config folder.",
- ),
- DeclareLaunchArgument(
- "arm_prefix",
- default_value="",
- description="Prefix for the arm.",
- ),
- DeclareLaunchArgument(
- "can_interface",
- default_value="can0",
- description="CAN interface to use.",
- ),
- DeclareLaunchArgument(
- "controllers_file",
- default_value="openarm_v10_controllers.yaml",
- description="Controllers file(s) to use. Can be a single file or comma-separated list of files.",
- ),
- ]
-
- # Initialize launch configurations
- description_package = LaunchConfiguration("description_package")
- description_file = LaunchConfiguration("description_file")
- arm_type = LaunchConfiguration("arm_type")
- use_fake_hardware = LaunchConfiguration("use_fake_hardware")
- robot_controller = LaunchConfiguration("robot_controller")
- runtime_config_package = LaunchConfiguration("runtime_config_package")
- controllers_file = LaunchConfiguration("controllers_file")
- can_interface = LaunchConfiguration("can_interface")
- arm_prefix = LaunchConfiguration("arm_prefix")
- # Configuration file paths
- controllers_file = PathJoinSubstitution(
- [FindPackageShare(runtime_config_package), "config",
- "v10_controllers", controllers_file]
- )
-
- # Robot nodes spawner (both state publisher and control)
- robot_nodes_spawner_func = OpaqueFunction(
- function=robot_nodes_spawner,
- args=[description_package, description_file, arm_type,
- use_fake_hardware, controllers_file, can_interface, arm_prefix]
- )
- # RViz configuration
- rviz_config_file = PathJoinSubstitution(
- [FindPackageShare(description_package), "rviz",
- "arm_only.rviz"]
- )
-
- rviz_node = Node(
- package="rviz2",
- executable="rviz2",
- name="rviz2",
- output="log",
- arguments=["-d", rviz_config_file],
- )
-
- # Joint state broadcaster spawner
- joint_state_broadcaster_spawner = Node(
- package="controller_manager",
- executable="spawner",
- arguments=["joint_state_broadcaster",
- "--controller-manager", "/controller_manager"],
- )
-
- # Controller spawners
- robot_controller_spawner = Node(
- package="controller_manager",
- executable="spawner",
- arguments=[robot_controller, "-c", "/controller_manager"],
- )
-
- gripper_controller_spawner = Node(
- package="controller_manager",
- executable="spawner",
- arguments=["gripper_controller", "-c", "/controller_manager"],
- )
-
- # Timing and sequencing
- delayed_joint_state_broadcaster = TimerAction(
- period=1.0,
- actions=[joint_state_broadcaster_spawner],
- )
-
- delayed_robot_controller = TimerAction(
- period=1.0,
- actions=[robot_controller_spawner],
- )
- delayed_gripper_controller = TimerAction(
- period=1.0,
- actions=[gripper_controller_spawner],
- )
-
- return LaunchDescription(
- declared_arguments + [
- robot_nodes_spawner_func,
- rviz_node,
- ] +
- [
- delayed_joint_state_broadcaster,
- delayed_robot_controller,
- delayed_gripper_controller,
- ]
- )
diff --git a/openarm_bringup/package.xml b/openarm_bringup/package.xml
index 773de5ad..4f9ec12e 100644
--- a/openarm_bringup/package.xml
+++ b/openarm_bringup/package.xml
@@ -26,6 +26,9 @@
ros2_controllers
controller_manager
+ openarm_bimanual_moveit_config
+ openarm_description
+ rviz2
ament_lint_auto
ament_lint_common
diff --git a/openarm_dora_ros2/LICENSE b/openarm_dora_ros2/LICENSE
new file mode 100644
index 00000000..d6456956
--- /dev/null
+++ b/openarm_dora_ros2/LICENSE
@@ -0,0 +1,202 @@
+
+ Apache License
+ Version 2.0, January 2004
+ http://www.apache.org/licenses/
+
+ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+ 1. Definitions.
+
+ "License" shall mean the terms and conditions for use, reproduction,
+ and distribution as defined by Sections 1 through 9 of this document.
+
+ "Licensor" shall mean the copyright owner or entity authorized by
+ the copyright owner that is granting the License.
+
+ "Legal Entity" shall mean the union of the acting entity and all
+ other entities that control, are controlled by, or are under common
+ control with that entity. For the purposes of this definition,
+ "control" means (i) the power, direct or indirect, to cause the
+ direction or management of such entity, whether by contract or
+ otherwise, or (ii) ownership of fifty percent (50%) or more of the
+ outstanding shares, or (iii) beneficial ownership of such entity.
+
+ "You" (or "Your") shall mean an individual or Legal Entity
+ exercising permissions granted by this License.
+
+ "Source" form shall mean the preferred form for making modifications,
+ including but not limited to software source code, documentation
+ source, and configuration files.
+
+ "Object" form shall mean any form resulting from mechanical
+ transformation or translation of a Source form, including but
+ not limited to compiled object code, generated documentation,
+ and conversions to other media types.
+
+ "Work" shall mean the work of authorship, whether in Source or
+ Object form, made available under the License, as indicated by a
+ copyright notice that is included in or attached to the work
+ (an example is provided in the Appendix below).
+
+ "Derivative Works" shall mean any work, whether in Source or Object
+ form, that is based on (or derived from) the Work and for which the
+ editorial revisions, annotations, elaborations, or other modifications
+ represent, as a whole, an original work of authorship. For the purposes
+ of this License, Derivative Works shall not include works that remain
+ separable from, or merely link (or bind by name) to the interfaces of,
+ the Work and Derivative Works thereof.
+
+ "Contribution" shall mean any work of authorship, including
+ the original version of the Work and any modifications or additions
+ to that Work or Derivative Works thereof, that is intentionally
+ submitted to Licensor for inclusion in the Work by the copyright owner
+ or by an individual or Legal Entity authorized to submit on behalf of
+ the copyright owner. For the purposes of this definition, "submitted"
+ means any form of electronic, verbal, or written communication sent
+ to the Licensor or its representatives, including but not limited to
+ communication on electronic mailing lists, source code control systems,
+ and issue tracking systems that are managed by, or on behalf of, the
+ Licensor for the purpose of discussing and improving the Work, but
+ excluding communication that is conspicuously marked or otherwise
+ designated in writing by the copyright owner as "Not a Contribution."
+
+ "Contributor" shall mean Licensor and any individual or Legal Entity
+ on behalf of whom a Contribution has been received by Licensor and
+ subsequently incorporated within the Work.
+
+ 2. Grant of Copyright License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ copyright license to reproduce, prepare Derivative Works of,
+ publicly display, publicly perform, sublicense, and distribute the
+ Work and such Derivative Works in Source or Object form.
+
+ 3. Grant of Patent License. Subject to the terms and conditions of
+ this License, each Contributor hereby grants to You a perpetual,
+ worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+ (except as stated in this section) patent license to make, have made,
+ use, offer to sell, sell, import, and otherwise transfer the Work,
+ where such license applies only to those patent claims licensable
+ by such Contributor that are necessarily infringed by their
+ Contribution(s) alone or by combination of their Contribution(s)
+ with the Work to which such Contribution(s) was submitted. If You
+ institute patent litigation against any entity (including a
+ cross-claim or counterclaim in a lawsuit) alleging that the Work
+ or a Contribution incorporated within the Work constitutes direct
+ or contributory patent infringement, then any patent licenses
+ granted to You under this License for that Work shall terminate
+ as of the date such litigation is filed.
+
+ 4. Redistribution. You may reproduce and distribute copies of the
+ Work or Derivative Works thereof in any medium, with or without
+ modifications, and in Source or Object form, provided that You
+ meet the following conditions:
+
+ (a) You must give any other recipients of the Work or
+ Derivative Works a copy of this License; and
+
+ (b) You must cause any modified files to carry prominent notices
+ stating that You changed the files; and
+
+ (c) You must retain, in the Source form of any Derivative Works
+ that You distribute, all copyright, patent, trademark, and
+ attribution notices from the Source form of the Work,
+ excluding those notices that do not pertain to any part of
+ the Derivative Works; and
+
+ (d) If the Work includes a "NOTICE" text file as part of its
+ distribution, then any Derivative Works that You distribute must
+ include a readable copy of the attribution notices contained
+ within such NOTICE file, excluding those notices that do not
+ pertain to any part of the Derivative Works, in at least one
+ of the following places: within a NOTICE text file distributed
+ as part of the Derivative Works; within the Source form or
+ documentation, if provided along with the Derivative Works; or,
+ within a display generated by the Derivative Works, if and
+ wherever such third-party notices normally appear. The contents
+ of the NOTICE file are for informational purposes only and
+ do not modify the License. You may add Your own attribution
+ notices within Derivative Works that You distribute, alongside
+ or as an addendum to the NOTICE text from the Work, provided
+ that such additional attribution notices cannot be construed
+ as modifying the License.
+
+ You may add Your own copyright statement to Your modifications and
+ may provide additional or different license terms and conditions
+ for use, reproduction, or distribution of Your modifications, or
+ for any such Derivative Works as a whole, provided Your use,
+ reproduction, and distribution of the Work otherwise complies with
+ the conditions stated in this License.
+
+ 5. Submission of Contributions. Unless You explicitly state otherwise,
+ any Contribution intentionally submitted for inclusion in the Work
+ by You to the Licensor shall be under the terms and conditions of
+ this License, without any additional terms or conditions.
+ Notwithstanding the above, nothing herein shall supersede or modify
+ the terms of any separate license agreement you may have executed
+ with Licensor regarding such Contributions.
+
+ 6. Trademarks. This License does not grant permission to use the trade
+ names, trademarks, service marks, or product names of the Licensor,
+ except as required for reasonable and customary use in describing the
+ origin of the Work and reproducing the content of the NOTICE file.
+
+ 7. Disclaimer of Warranty. Unless required by applicable law or
+ agreed to in writing, Licensor provides the Work (and each
+ Contributor provides its Contributions) on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+ implied, including, without limitation, any warranties or conditions
+ of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+ PARTICULAR PURPOSE. You are solely responsible for determining the
+ appropriateness of using or redistributing the Work and assume any
+ risks associated with Your exercise of permissions under this License.
+
+ 8. Limitation of Liability. In no event and under no legal theory,
+ whether in tort (including negligence), contract, or otherwise,
+ unless required by applicable law (such as deliberate and grossly
+ negligent acts) or agreed to in writing, shall any Contributor be
+ liable to You for damages, including any direct, indirect, special,
+ incidental, or consequential damages of any character arising as a
+ result of this License or out of the use or inability to use the
+ Work (including but not limited to damages for loss of goodwill,
+ work stoppage, computer failure or malfunction, or any and all
+ other commercial damages or losses), even if such Contributor
+ has been advised of the possibility of such damages.
+
+ 9. Accepting Warranty or Additional Liability. While redistributing
+ the Work or Derivative Works thereof, You may choose to offer,
+ and charge a fee for, acceptance of support, warranty, indemnity,
+ or other liability obligations and/or rights consistent with this
+ License. However, in accepting such obligations, You may act only
+ on Your own behalf and on Your sole responsibility, not on behalf
+ of any other Contributor, and only if You agree to indemnify,
+ defend, and hold each Contributor harmless for any liability
+ incurred by, or claims asserted against, such Contributor by reason
+ of your accepting any such warranty or additional liability.
+
+ END OF TERMS AND CONDITIONS
+
+ APPENDIX: How to apply the Apache License to your work.
+
+ To apply the Apache License to your work, attach the following
+ boilerplate notice, with the fields enclosed by brackets "[]"
+ replaced with your own identifying information. (Don't include
+ the brackets!) The text should be enclosed in the appropriate
+ comment syntax for the file format. We also recommend that a
+ file or class name and description of purpose be included on the
+ same "printed page" as the copyright notice for easier
+ identification within third-party archives.
+
+ Copyright [yyyy] [name of copyright owner]
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
diff --git a/openarm_dora_ros2/config/dataflow_demo.yaml b/openarm_dora_ros2/config/dataflow_demo.yaml
new file mode 100644
index 00000000..de7a0475
--- /dev/null
+++ b/openarm_dora_ros2/config/dataflow_demo.yaml
@@ -0,0 +1,38 @@
+nodes:
+ - id: tick # ── 250 Hz tick ───────────────────────────────────────────────
+ build: pip install git+https://github.com/enactic/dora-openarm-quitter
+ path: dora-openarm-quitter
+ inputs:
+ tick: dora/timer/millis/4
+ outputs:
+ - tick
+
+ - id: tick-camera
+ build: pip install git+https://github.com/enactic/dora-openarm-quitter
+ path: dora-openarm-quitter
+ inputs:
+ tick: dora/timer/millis/33
+ outputs:
+ - tick
+
+ - id: dummy-leader
+ path: ../node/dummy-leader.py
+ inputs:
+ tick: tick/tick
+ outputs:
+ - left_position
+ - right_position
+ - status
+
+ - id: dummy-camera
+ path: ../node/dummy-camera.py
+ outputs:
+ - image
+
+ - id: dora-to-ros2
+ build: pip install -e ..
+ path: openarm-dora-ros2
+ inputs:
+ left_position: dummy-leader/left_position
+ right_position: dummy-leader/right_position
+ camera_image: dummy-camera/image
\ No newline at end of file
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/PKG-INFO b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/PKG-INFO
new file mode 100644
index 00000000..70a93748
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/PKG-INFO
@@ -0,0 +1,17 @@
+Metadata-Version: 2.4
+Name: dora-openarm-ros2
+Version: 0.2.0
+Summary: dora ros2 converter for openarm
+Author: Enactic, Inc.
+Maintainer: Enactic, Inc.
+License: Apache-2.0
+Requires-Python: >=3.10
+Description-Content-Type: text/markdown
+License-File: LICENSE
+Requires-Dist: daqp==0.7.2
+Requires-Dist: dora-rs==0.5.0
+Requires-Dist: dora-rs-cli==0.5.0
+Requires-Dist: numpy
+Requires-Dist: opencv-python>=4.13.0.92
+Requires-Dist: pyarrow
+Dynamic: license-file
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/SOURCES.txt b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/SOURCES.txt
new file mode 100644
index 00000000..af2ca945
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/SOURCES.txt
@@ -0,0 +1,13 @@
+LICENSE
+pyproject.toml
+node/dora_openarm_ros2.egg-info/PKG-INFO
+node/dora_openarm_ros2.egg-info/SOURCES.txt
+node/dora_openarm_ros2.egg-info/dependency_links.txt
+node/dora_openarm_ros2.egg-info/entry_points.txt
+node/dora_openarm_ros2.egg-info/requires.txt
+node/dora_openarm_ros2.egg-info/top_level.txt
+node/dora_ros2_bridge/__init__.py
+node/dora_ros2_bridge/main.py
+node/dora_ros2_bridge/main_test.py
+node/ros2_dora_bridge/__init__.py
+node/ros2_dora_bridge/main.py
\ No newline at end of file
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/dependency_links.txt b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/dependency_links.txt
new file mode 100644
index 00000000..8b137891
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/dependency_links.txt
@@ -0,0 +1 @@
+
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/entry_points.txt b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/entry_points.txt
new file mode 100644
index 00000000..9a490f2d
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/entry_points.txt
@@ -0,0 +1,3 @@
+[console_scripts]
+openarm-dora-ros2 = dora_ros2_bridge.main:main
+openarm-ros2-dora = ros2_dora_bridge.main:main
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/requires.txt b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/requires.txt
new file mode 100644
index 00000000..f9f58868
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/requires.txt
@@ -0,0 +1,6 @@
+daqp==0.7.2
+dora-rs==0.5.0
+dora-rs-cli==0.5.0
+numpy
+opencv-python>=4.13.0.92
+pyarrow
diff --git a/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/top_level.txt b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/top_level.txt
new file mode 100644
index 00000000..d9eabe46
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_openarm_ros2.egg-info/top_level.txt
@@ -0,0 +1,2 @@
+dora_ros2_bridge
+ros2_dora_bridge
diff --git a/openarm_dora_ros2/node/dora_ros2_bridge/__init__.py b/openarm_dora_ros2/node/dora_ros2_bridge/__init__.py
new file mode 100644
index 00000000..e69de29b
diff --git a/openarm_dora_ros2/node/dora_ros2_bridge/main.py b/openarm_dora_ros2/node/dora_ros2_bridge/main.py
new file mode 100644
index 00000000..75053698
--- /dev/null
+++ b/openarm_dora_ros2/node/dora_ros2_bridge/main.py
@@ -0,0 +1,127 @@
+
+"""
+Dora-to-ROS2 Bridge Node
+
+This node acts as a state holder and message translator between the Dora dataflow
+and ROS 2 control interfaces. It subscribes to joint position and camera inputs
+from the Dora graph and forwards them to the appropriate ROS 2 controllers.
+
+Current use cases:
+ - Teleoperation: relay joint commands from a leader to the robot controllers
+ - Data collection: forward states for rosbag recording
+
+This bridge will be updated as teleoperation and data collection requirements evolve.
+
+Inputs (Dora):
+ - left_position : float64[8] - left arm joints (7) + gripper (1)
+ - right_position : float64[8] - right arm joints (7) + gripper (1)
+ - camera_image : uint8[] - JPEG-encoded image
+
+Outputs (ROS 2):
+ - /left_joint_trajectory_controller/joint_trajectory
+ - /right_joint_trajectory_controller/joint_trajectory
+ - /left_gripper_controller/joint_trajectory
+ - /right_gripper_controller/joint_trajectory
+ - /camera/image_raw/compressed
+"""
+
+#!/usr/bin/env python
+import dora
+import pyarrow as pa
+import numpy as np
+import sys
+
+
+def main():
+
+ # --- 1. ROS 2 Setup ---
+ context = dora.Ros2Context()
+ options = dora.Ros2NodeOptions(rosout=True)
+ node = context.new_node("dora_to_ros2", "/openarm", options)
+
+ qos_arm = dora.Ros2QosPolicies(reliable=True)
+
+ qos_cam = dora.Ros2QosPolicies(reliable=False)
+
+ # --- 2. Define Publishers ---
+ p_l_arm = node.create_publisher(node.create_topic(
+ "/left_joint_trajectory_controller/joint_trajectory", "trajectory_msgs/JointTrajectory", qos_arm))
+ p_r_arm = node.create_publisher(node.create_topic(
+ "/right_joint_trajectory_controller/joint_trajectory", "trajectory_msgs/JointTrajectory", qos_arm))
+ p_l_grp = node.create_publisher(node.create_topic(
+ "/left_gripper_controller/joint_trajectory", "trajectory_msgs/JointTrajectory", qos_arm))
+ p_r_grp = node.create_publisher(node.create_topic(
+ "/right_gripper_controller/joint_trajectory", "trajectory_msgs/JointTrajectory", qos_arm))
+
+ p_cam = node.create_publisher(node.create_topic(
+ "/camera/image_raw/compressed", "sensor_msgs/CompressedImage", qos_cam))
+
+ # --- 3. Pre-defined Constants & Templates (Object Reuse for Speed) ---
+ EMPTY_F64 = np.array([], dtype=np.float64)
+ SEC_0 = np.int32(0)
+ NSEC_0 = np.uint32(0)
+ NSEC_WAIT = np.uint32(0)
+
+ NAMES_L_ARM = [f"openarm_left_joint{i+1}" for i in range(7)]
+ NAMES_R_ARM = [f"openarm_right_joint{i+1}" for i in range(7)]
+ NAMES_L_GRP = ["openarm_left_finger_joint1"]
+ NAMES_R_GRP = ["openarm_right_finger_joint1"]
+
+ joint_msg = {
+ "header": {"stamp": {"sec": SEC_0, "nanosec": NSEC_0}, "frame_id": ""},
+ "joint_names": None,
+ "points": [{
+ "positions": None,
+ "velocities": EMPTY_F64,
+ "accelerations": EMPTY_F64,
+ "effort": EMPTY_F64,
+ "time_from_start": {"sec": SEC_0, "nanosec": NSEC_WAIT}
+ }]
+ }
+
+ compressed_img_msg = {
+ "header": {"stamp": {"sec": SEC_0, "nanosec": NSEC_0}, "frame_id": "world"},
+ "format": "jpeg",
+ "data": None
+ }
+
+ # --- 4. Dora Loop ---
+ dora_node = dora.Node()
+ print("🚀 ROS 2 Bridge: All systems go (Joints + Compressed Image)", flush=True)
+
+ for event in dora_node:
+ if event["type"] != "INPUT":
+ continue
+
+ eid = event["id"]
+ value = event["value"]
+
+ # --- Case A: Camera Image (JPEG Pass-through) ---
+ if eid == "camera_image":
+ img_data = value.to_numpy().astype(np.uint8)
+ compressed_img_msg["data"] = img_data
+ p_cam.publish(pa.array([compressed_img_msg]))
+ continue
+
+ # --- Case B: Joint Positions ---
+ vals = value.to_numpy().astype(np.float64)
+
+ if eid == "left_position":
+ pub_arm, pub_grp, name_arm, name_grp = p_l_arm, p_l_grp, NAMES_L_ARM, NAMES_L_GRP
+ elif eid == "right_position":
+ pub_arm, pub_grp, name_arm, name_grp = p_r_arm, p_r_grp, NAMES_R_ARM, NAMES_R_GRP
+ else:
+ continue
+
+ joint_msg["joint_names"] = name_arm
+ joint_msg["points"][0]["positions"] = vals[:7].tolist()
+ pub_arm.publish(pa.array([joint_msg]))
+
+ if len(vals) >= 8:
+ joint_msg["joint_names"] = name_grp
+ joint_msg["points"][0]["positions"] = vals[7:8].tolist()
+ pub_grp.publish(pa.array([joint_msg]))
+
+
+if __name__ == '__main__':
+ main()
diff --git a/openarm_dora_ros2/node/dummy-camera.py b/openarm_dora_ros2/node/dummy-camera.py
new file mode 100644
index 00000000..030ff8c0
--- /dev/null
+++ b/openarm_dora_ros2/node/dummy-camera.py
@@ -0,0 +1,41 @@
+import dora
+import cv2
+import numpy as np
+import pyarrow as pa
+import time
+
+
+def main():
+ node = dora.Node()
+ W, H = 960, 600
+
+ # Initialize variables for color and timing
+ current_color = [120, 0, 255] # Initial BGR color
+ last_update_time = time.time()
+
+ while True:
+ now = time.time()
+
+ # Update color every 1.0 second
+ if now - last_update_time >= 1.0:
+ # Generate a new random BGR color
+ current_color = np.random.randint(0, 256, size=3).tolist()
+ last_update_time = now
+
+ # Create the frame with the current color
+ frame = np.full((H, W, 3), current_color, dtype=np.uint8)
+
+ # Encode frame as JPEG
+ success, encoded_img = cv2.imencode(
+ '.jpg', frame, [cv2.IMWRITE_JPEG_QUALITY, 90])
+
+ if success:
+ # Send as a flat uint8 array (ravel() ensures correct flattening)
+ node.send_output("image", pa.array(encoded_img.ravel()))
+
+ # Keep the loop running at roughly 30 FPS
+ time.sleep(1/30.0)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/openarm_dora_ros2/node/dummy-leader.py b/openarm_dora_ros2/node/dummy-leader.py
new file mode 100644
index 00000000..883f0cb1
--- /dev/null
+++ b/openarm_dora_ros2/node/dummy-leader.py
@@ -0,0 +1,30 @@
+#!/usr/bin/env python
+# -*- coding: utf-8 -*-
+import dora
+import pyarrow as pa
+import math
+import time
+
+
+def main():
+ node = dora.Node()
+ start_time = time.time()
+
+ print("🚀 Dummy Leader is running! Sending sine wave (0~90 deg) to joint 4...")
+
+ for event in node:
+ if event["type"] == "INPUT" and event["id"] == "tick":
+ t = time.time() - start_time
+
+ angle_rad = (math.pi / 4) + (math.pi / 4) * math.sin(t*0.5)
+
+ positions = [0.0] * 8
+
+ positions[3] = angle_rad
+
+ node.send_output("left_position", pa.array(positions))
+ node.send_output("right_position", pa.array(positions))
+
+
+if __name__ == '__main__':
+ main()
diff --git a/openarm_dora_ros2/node/ros2_dora_bridge/__init__.py b/openarm_dora_ros2/node/ros2_dora_bridge/__init__.py
new file mode 100644
index 00000000..e69de29b
diff --git a/openarm_dora_ros2/node/ros2_dora_bridge/main.py b/openarm_dora_ros2/node/ros2_dora_bridge/main.py
new file mode 100644
index 00000000..e69de29b
diff --git a/openarm_dora_ros2/pyproject.toml b/openarm_dora_ros2/pyproject.toml
new file mode 100644
index 00000000..90e63f53
--- /dev/null
+++ b/openarm_dora_ros2/pyproject.toml
@@ -0,0 +1,31 @@
+[build-system]
+requires = ["setuptools>=64", "wheel"]
+build-backend = "setuptools.build_meta"
+
+[project]
+name = "dora-openarm-ros2"
+version = "0.2.0"
+authors = [{name = "Enactic, Inc."}]
+description = "dora ros2 converter for openarm"
+license = {text = "Apache-2.0"}
+maintainers = [{name = "Enactic, Inc."}]
+readme = "README.md"
+requires-python = ">=3.10"
+dependencies = [
+ "daqp==0.7.2",
+ "dora-rs==0.5.0",
+ "dora-rs-cli==0.5.0",
+ "numpy",
+ "opencv-python>=4.13.0.92",
+ "pyarrow",
+]
+
+[project.scripts]
+openarm-dora-ros2 = "dora_ros2_bridge.main:main"
+openarm-ros2-dora = "ros2_dora_bridge.main:main"
+
+[tool.setuptools]
+package-dir = {"" = "node"}
+
+[tool.setuptools.packages.find]
+where = ["node"]
diff --git a/openarm_dora_ros2/uv.lock b/openarm_dora_ros2/uv.lock
new file mode 100644
index 00000000..bd28ac1a
--- /dev/null
+++ b/openarm_dora_ros2/uv.lock
@@ -0,0 +1,436 @@
+version = 1
+revision = 3
+requires-python = ">=3.10"
+resolution-markers = [
+ "python_full_version >= '3.11'",
+ "python_full_version < '3.11'",
+]
+
+[[package]]
+name = "daqp"
+version = "0.7.2"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/27/17/9d3409165ad752dab54af5779fdd77757957587fe2a3404f92a4fbd4cea3/daqp-0.7.2.tar.gz", hash = "sha256:195855763331d6fc15d54b2354f91b0888e84cf43e1e9ee62f01cdce11f555e7", size = 178815, upload-time = "2025-08-11T21:51:34.578Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/c0/46/9e9ea0bfeabc01f8d72715acdeb0d3e6c0a8eb52226c408d42c83fa59991/daqp-0.7.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:549df8bbaf9e9d864e47691ebd972a4dfb72183d51a4dba6321bc90bb8592651", size = 114002, upload-time = "2025-08-11T21:52:39.884Z" },
+ { url = "https://files.pythonhosted.org/packages/7c/f6/fa60619fb049efbdbc8627cfbbb760a6b22a1976ae132e7962208344953c/daqp-0.7.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:fa2c56abd9d1a9751f4e4c0e590797bf810684ddfbae4b3a8b371c5f096c37d6", size = 104326, upload-time = "2025-07-29T13:01:01.197Z" },
+ { url = "https://files.pythonhosted.org/packages/1e/48/220f3810506b787aaccd3ddac7c55bde11a65c4eba1244c99403009d9fa8/daqp-0.7.2-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4401b97e61ecc63a049a4dd0b2b3ae11a7be1bb0b853bed1dfc570498f2f8311", size = 595931, upload-time = "2025-08-11T21:51:24.922Z" },
+ { url = "https://files.pythonhosted.org/packages/ae/be/5c24447debda10ecad609621250e4616b2cd2bce6af7b03a547e0ec97ed5/daqp-0.7.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1976b1c10d0243cd578bfed60dfc3745eaccd0ef2fda1d9790ce021d4458b49e", size = 561947, upload-time = "2025-07-29T13:41:38.876Z" },
+ { url = "https://files.pythonhosted.org/packages/c8/77/906056a7cc13c3f9017838c666d4ec7d770ec11beccd9931b6d0693c2bf7/daqp-0.7.2-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:be326f00e4de04a88c8e5f3001f6e7590f240f91da51f75db3e5a63a890fe97d", size = 581926, upload-time = "2025-07-29T13:41:40.11Z" },
+ { url = "https://files.pythonhosted.org/packages/e9/44/f7b35bc89e7bf81fb7b3ada3f4d79a34bdc474f34ccf197c2d4e38cb6922/daqp-0.7.2-cp310-cp310-win32.whl", hash = "sha256:cf18a5112e895fee66ba9f7f2b74a50949009f2c3ff820fcb8f571196dc5a6b8", size = 80431, upload-time = "2025-08-11T21:58:46.049Z" },
+ { url = "https://files.pythonhosted.org/packages/22/8c/fb9c4d9e8bd062145dc21bd9cc0002f15d681e0eb659539311aeb150b266/daqp-0.7.2-cp310-cp310-win_amd64.whl", hash = "sha256:460c9c59553d30d34b47a059e97b1a722441c9844f1b88e8dd22867d94790469", size = 97920, upload-time = "2025-08-11T21:58:47.176Z" },
+ { url = "https://files.pythonhosted.org/packages/47/7a/01b10351904cf239b0e9af70edde2d6e1a71447ef0bfb53cd8500a8964d1/daqp-0.7.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:07f992b422ddd6f076ba47a545f79dc4901bd5eb0946a23cbefa0022e7f1e7e3", size = 114159, upload-time = "2025-08-11T21:52:40.733Z" },
+ { url = "https://files.pythonhosted.org/packages/3c/24/303fda9748fa5c39cc2b8e5a63914796f6e9446707f9c61d2daa8d536e0a/daqp-0.7.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:61fe1d6b6afa4de7c8dc44ab6d12002e534cea0dee289eb32df049678a49180f", size = 104374, upload-time = "2025-07-29T13:01:02.591Z" },
+ { url = "https://files.pythonhosted.org/packages/eb/1e/405c9bd710e46e701254b6fa2f8e6d5e1d669d92316a81761f73768edd3b/daqp-0.7.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:dff177e057ba880be171c1e143676098a5518fc1af6e94aaeb0470a84ca35e2c", size = 624880, upload-time = "2025-08-11T21:51:26.51Z" },
+ { url = "https://files.pythonhosted.org/packages/e3/bc/51a921b15a82155149f12e919023c9792ff70e521feaa6bcb2c8df9478e0/daqp-0.7.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9b4f7dee656444690a0fc8fe8c00626e7ec8b486f91fd352a47767d0f4a6f874", size = 589972, upload-time = "2025-07-29T13:41:41.541Z" },
+ { url = "https://files.pythonhosted.org/packages/ba/83/83678ac9733ad4e28dacdb98a70431b50fbf94e1406f1600efd6c8fdb474/daqp-0.7.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2672ef3bfc6b3ed8e18b6add8236e6a171ff2482b32a01de74c6bc56ebf277b2", size = 611194, upload-time = "2025-07-29T13:41:42.517Z" },
+ { url = "https://files.pythonhosted.org/packages/f6/22/ca730fabc4da8c076627acdd39ccbe10185cbf647abf9c2f98ff9c2b13b5/daqp-0.7.2-cp311-cp311-win32.whl", hash = "sha256:f730ef121693e1f2a044b7ec26ddc9b893d1cf5b586cc8c5e56fa79eb12cc3c1", size = 79990, upload-time = "2025-08-11T21:58:47.959Z" },
+ { url = "https://files.pythonhosted.org/packages/d3/84/cdf6dc6a40733817bd32cb3a259dd1dbb8ff025dbda09cfdd611e130361d/daqp-0.7.2-cp311-cp311-win_amd64.whl", hash = "sha256:1c6b6d820e2d7e6147259e92cce59a2e9607bf4ca0a097778359edaef2176893", size = 97704, upload-time = "2025-08-11T21:58:48.733Z" },
+ { url = "https://files.pythonhosted.org/packages/1a/7a/14d99758ee8dd30a4a9872cd9335a39f132300a89a85ce0babf95abf58e1/daqp-0.7.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:128e069af356d058c3118835f54a17a44ec2c2b9892693ba4328129717649608", size = 113417, upload-time = "2025-08-11T21:52:41.539Z" },
+ { url = "https://files.pythonhosted.org/packages/9e/08/041461120e16bab05ea163afdb88fab452aefa9cbeadb9b91b3ec4f23635/daqp-0.7.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:9da7a69e89b5d26302cbfb049f132981fe1c2f2a59a788e46a7b53df242b4828", size = 102660, upload-time = "2025-07-29T13:01:04.352Z" },
+ { url = "https://files.pythonhosted.org/packages/97/84/f8a89433fd182a850aa8db9c0cfffc9d2ebf7347b34eb5e203c8488459a2/daqp-0.7.2-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7d27e010ef42405f5979a93ca75c2c2f323a2b34247aacb4328fb446c61058d3", size = 630535, upload-time = "2025-08-11T21:51:27.509Z" },
+ { url = "https://files.pythonhosted.org/packages/2f/2a/b0a896f1aa8618fae09acf508f0bb0192022383dbf73bea76143345167c8/daqp-0.7.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5bc97b1f8b9ecd3bc1e5b8c0edc839314e6fd9e13061637a664d003e9b7ef7db", size = 584167, upload-time = "2025-07-29T13:41:43.828Z" },
+ { url = "https://files.pythonhosted.org/packages/c4/e2/1f1d0ea885665adc0447089e2c5d803162e81a90499ab2bdcbaebbefd368/daqp-0.7.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:61cb14d6738d64369a1224820514039550c14f3c40054d78c0cb303012002066", size = 602219, upload-time = "2025-07-29T13:41:45.316Z" },
+ { url = "https://files.pythonhosted.org/packages/10/bc/975c5ea099706d49fcb09e3612bbaca6477fe6d343468ebf0b91d2408fce/daqp-0.7.2-cp312-cp312-win32.whl", hash = "sha256:1f384048ae28884ef9264cce3183c74269ee2cd3cbd7c184fe765358c0fc1ba2", size = 79852, upload-time = "2025-08-11T21:58:49.538Z" },
+ { url = "https://files.pythonhosted.org/packages/ea/72/3bbbb5c5da4b982f420000ee4465b46b35d802bfbc73c1f3b772585c8b86/daqp-0.7.2-cp312-cp312-win_amd64.whl", hash = "sha256:49d66d0c92f309eda5acbbbb3b970f2ff90ec93e0f7450ced75fd2df83c12e3b", size = 97974, upload-time = "2025-08-11T21:58:50.415Z" },
+ { url = "https://files.pythonhosted.org/packages/50/4f/f132cd1c0e81e2bfee0bc6d96d86d12be2e5de3f9f603b5e0561f8fa8ab3/daqp-0.7.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:1ee1df0fd2ae40921e3ee52a737de2410a2d9cd65ff49e206ea431e9b8c2483a", size = 112182, upload-time = "2025-08-11T21:52:42.363Z" },
+ { url = "https://files.pythonhosted.org/packages/ab/8d/f651cb2df6e4e132bbce46a4e48d7a6b3098fd35aae8b54471ea553fd147/daqp-0.7.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:296b4c81a452f2972dc4882743c3c60ae6523dff0a7928960c40356efd33961b", size = 101728, upload-time = "2025-07-29T13:01:05.439Z" },
+ { url = "https://files.pythonhosted.org/packages/58/df/0b06a1df719ba762d64b3f838714ca94785199fee2258e60518937b23d54/daqp-0.7.2-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:25bb856f1d4bbedea7cd3203a567caee59e3d3c1964641c4988bcd0ce547afed", size = 622317, upload-time = "2025-08-11T21:51:28.954Z" },
+ { url = "https://files.pythonhosted.org/packages/89/b4/5883da044d0b8cedb0c578ae30eade3f0bfb3e6b0b6140a94025799404d3/daqp-0.7.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1ed193429633df4c4eba9a553920fa574ad15ad3947848106cb487233d181741", size = 576669, upload-time = "2025-07-29T13:41:46.687Z" },
+ { url = "https://files.pythonhosted.org/packages/9b/56/1c3c718097944546f0de541b477f770bd53bd6525db88ecbdd1fc3e8aa2f/daqp-0.7.2-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:7ada42dac9b5f72d1cc8673ec742197ec7573e7ec4c47f81345b9423388be500", size = 598175, upload-time = "2025-07-29T13:41:49.651Z" },
+ { url = "https://files.pythonhosted.org/packages/68/26/5a40dce966a4803c2b817f090fcfae7266dc0e56826c584b6b7df115ad0d/daqp-0.7.2-cp313-cp313-win32.whl", hash = "sha256:35441fa3df9dfd2d7bab35a686b093c11b92bf7a27297e0a1013a12b18bf8a45", size = 79687, upload-time = "2025-08-11T21:58:51.313Z" },
+ { url = "https://files.pythonhosted.org/packages/fd/b8/84176537fa47765fb92f0f3c6f364bdb5f2fe389b448206daf18050a3963/daqp-0.7.2-cp313-cp313-win_amd64.whl", hash = "sha256:d837854c897435f6a2aa44b76e449d04c96987a621476eccc147361e30c937d5", size = 97779, upload-time = "2025-08-11T21:58:52.094Z" },
+ { url = "https://files.pythonhosted.org/packages/13/04/8f8f7d1bdffa642f81ae8f71c8bb4d1a5420013a6942fe1729f6f1733fa0/daqp-0.7.2-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:7ce7ef7b1155312d4d6f9eaac6ee11229a585b1ce1bcb88e474bc3b64e5060ad", size = 112376, upload-time = "2025-08-11T21:52:43.152Z" },
+ { url = "https://files.pythonhosted.org/packages/ee/b0/816a3a9aa89ecd56baac9e6a2d39badfdd115588bdeb235ecde08dfaff45/daqp-0.7.2-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:14ec3183dcfebdd294e87de88aae135488aa2abf54181a26b1f6ab7017a58c68", size = 121498, upload-time = "2026-03-17T21:39:03.022Z" },
+ { url = "https://files.pythonhosted.org/packages/82/60/a5a20788aab6e58bc4bd6eace552cf5713a33ea6bd77faf3f0f3bff1ef47/daqp-0.7.2-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:c07d80d0fcf808f5af2dd5fbf8dcc1d6aefac0ed7a116f92d9f52351166f4095", size = 102357, upload-time = "2025-08-11T21:51:56.628Z" },
+ { url = "https://files.pythonhosted.org/packages/c6/68/e11eb12a0e1a80891cbd899d85317f0f47ef4b6f4f3d04ea6669392f8048/daqp-0.7.2-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cfb5e97cb29be3734069782b6edc395bc836b6cd4dfac43db40f8a7f0235e83c", size = 615029, upload-time = "2025-08-11T21:51:30.295Z" },
+ { url = "https://files.pythonhosted.org/packages/ef/dd/486a78040e59cdb85bd2de5c05472697e88565abffa317f00464f78fbe0e/daqp-0.7.2-cp314-cp314-win32.whl", hash = "sha256:74aa9bb146a5e212ebdb0f0d11c5271347f95cc4261597da1597f869eb46d216", size = 82354, upload-time = "2025-08-11T21:58:52.902Z" },
+ { url = "https://files.pythonhosted.org/packages/fd/a1/15b7d2b6a6c6c3575c5354829eeffcf831e20ee0f066c9e2a6d133bfeb8f/daqp-0.7.2-cp314-cp314-win_amd64.whl", hash = "sha256:a2b498bc6fd27b26851d80f2bfc96ae5b2cd38f0e2ee1cdc13b99b2ac6ba1757", size = 100216, upload-time = "2025-08-11T21:58:53.674Z" },
+ { url = "https://files.pythonhosted.org/packages/7e/13/4376faa7041bb89978aa7a3a620dab56f44e19f3196a6adf524d4c43d1cf/daqp-0.7.2-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:43d1c1b8c245f7889c6337f2ac720d034bdc75f75b6bc6d17f7b26f4b924e788", size = 118006, upload-time = "2025-08-11T21:52:44.187Z" },
+ { url = "https://files.pythonhosted.org/packages/69/b4/ba87ef5d597fc95b9207911c2732dea98a63141dfc94f2a2b32e373494c5/daqp-0.7.2-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:d15cb9650b53b9041df73be88b6f99601df75abf2b10bd8202e46ac89c5cde5f", size = 127358, upload-time = "2026-03-17T21:39:04.086Z" },
+ { url = "https://files.pythonhosted.org/packages/00/68/ad156f98564237fbedec214dbf9f3967c0456470069f83253ebf86713eab/daqp-0.7.2-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:2b5f40821a7a9604263d4531b7d77412d546b99e06a8934fdc033dbc4864c91d", size = 109361, upload-time = "2025-08-11T21:51:57.45Z" },
+ { url = "https://files.pythonhosted.org/packages/f3/f2/d749678272b41802a72dedf54ea6cced8050bd1e6ac601f95ae02813c496/daqp-0.7.2-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:182a80054c73f92519400e91a1c9c483bc212cd76783f6a0ef3cf4525a20fec0", size = 627476, upload-time = "2025-08-11T21:51:31.355Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/4d/719c9248aafcfc8dd151367e84d99bf12997d9e508c31081a1c55b8b3a48/daqp-0.7.2-cp314-cp314t-win32.whl", hash = "sha256:035aa7b180cc2eabaea356808839b28c8c5da7ebaf9babb3ada1e7c4ce97ac32", size = 92811, upload-time = "2025-08-11T21:58:54.84Z" },
+ { url = "https://files.pythonhosted.org/packages/71/f9/04cf36d8a01af947aece4ce4f8f8f1a285f1d7bdab83dbc9fa2e69ecf126/daqp-0.7.2-cp314-cp314t-win_amd64.whl", hash = "sha256:429457545c9fcc55e07b4943933a94c83737713d91f69d3d60d620a8f798ac35", size = 115405, upload-time = "2025-08-11T21:58:55.692Z" },
+]
+
+[[package]]
+name = "dora-openarm-ros2"
+version = "0.2.0"
+source = { editable = "." }
+dependencies = [
+ { name = "daqp" },
+ { name = "dora-rs" },
+ { name = "dora-rs-cli" },
+ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" },
+ { name = "numpy", version = "2.4.4", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" },
+ { name = "opencv-python" },
+ { name = "pyarrow" },
+]
+
+[package.metadata]
+requires-dist = [
+ { name = "daqp", specifier = "==0.7.2" },
+ { name = "dora-rs", specifier = "==0.5.0" },
+ { name = "dora-rs-cli", specifier = "==0.5.0" },
+ { name = "numpy" },
+ { name = "opencv-python", specifier = ">=4.13.0.92" },
+ { name = "pyarrow" },
+]
+
+[[package]]
+name = "dora-rs"
+version = "0.5.0"
+source = { registry = "https://pypi.org/simple" }
+dependencies = [
+ { name = "pyarrow" },
+ { name = "pyyaml" },
+]
+sdist = { url = "https://files.pythonhosted.org/packages/f6/67/3b65873c34a2f668dcc698e3ed9571cfefe58f33cf1b4a1a06a5581f5ea6/dora_rs-0.5.0.tar.gz", hash = "sha256:3e0e41d31821d5c647c84072efb8ea358d38abfb09ea96de7628859a7754bdcd", size = 427224, upload-time = "2026-03-25T19:26:08.881Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/14/70/705f0f7c13b7cc82665f98a5fd57057c078b0bb52afd4f6cd095c3451e18/dora_rs-0.5.0-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:80603b8a500dbe114bce5a333ef6858989b06064664c8c24ba3cb5d8b4fac2f2", size = 18258324, upload-time = "2026-03-25T19:25:55.26Z" },
+ { url = "https://files.pythonhosted.org/packages/9d/be/91f42e924658b70bac526a6357627b6c37e3715621c357c5893e616e74a7/dora_rs-0.5.0-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:37c89d9266231c664d124a1f182e10421e3bfa36d938865e53c3380cc79aa76c", size = 17406326, upload-time = "2026-03-25T19:25:44.719Z" },
+ { url = "https://files.pythonhosted.org/packages/f3/6f/4eccc13c10c92226be5bf069da7c6ae60fbd88b8af4b25a9826fbf791ab2/dora_rs-0.5.0-cp37-abi3-manylinux_2_28_armv7l.whl", hash = "sha256:a7d080908eb9e6b3f00060652ceea068ca5f944f03e975065fec2291f50fbb57", size = 15835974, upload-time = "2026-03-25T19:25:47.388Z" },
+ { url = "https://files.pythonhosted.org/packages/c6/0b/13a843554e602617fdb7a9fb7861534e843c9d217d3e2313a9d7faa902d6/dora_rs-0.5.0-cp37-abi3-manylinux_2_28_i686.whl", hash = "sha256:1213a2e9a76f2a488cc89abebb08a0de0047f031dea83fed3e969c69c55026b2", size = 19131472, upload-time = "2026-03-25T19:25:50.045Z" },
+ { url = "https://files.pythonhosted.org/packages/38/f4/ada8cb79d7e535aaddc32fbc326557105e00902c75a272bc3ecddda903dd/dora_rs-0.5.0-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:ab368789f72c2cfcd38f9871a0c7cafb8e9fb57d57f810672f71d9d43ffabe17", size = 17796791, upload-time = "2026-03-25T19:25:52.879Z" },
+ { url = "https://files.pythonhosted.org/packages/b5/5b/546a15683d396674ba142e2ac0df19203468bce7082f958181ebe3458e1c/dora_rs-0.5.0-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:08f0617699aaa5d3a75d3f94f87dc2b3906dfec5b70ca24398f3b30d0b1c38eb", size = 21162981, upload-time = "2026-03-25T19:25:57.676Z" },
+ { url = "https://files.pythonhosted.org/packages/b4/e9/511ecd0274996cec4d412a1ac0dbbc7ecd72b46026d6a44f838b9bda3bbd/dora_rs-0.5.0-cp37-abi3-musllinux_1_2_armv7l.whl", hash = "sha256:cb21bad41e4013845edd5910167fd234fabc3420be8a03254781222afdb5235e", size = 19917806, upload-time = "2026-03-25T19:26:00.644Z" },
+ { url = "https://files.pythonhosted.org/packages/77/28/b24148d34c8bb642be83d4a0a17545dc9e9962c42003dd9a96c07f347968/dora_rs-0.5.0-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:bfdcce9e1c5d40836f4300136de004fbdc34981ed9e790b93723801eaa99e9bd", size = 21215205, upload-time = "2026-03-25T19:26:03.455Z" },
+ { url = "https://files.pythonhosted.org/packages/25/e1/1e629306ec502eb302e41ab4da718d11b9a528231ab27cce028591009711/dora_rs-0.5.0-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:85c172e083cb300fcc3b95c14a675680633c533d62c0cae65ee73b0a73cb61a5", size = 20993466, upload-time = "2026-03-25T19:26:06.713Z" },
+ { url = "https://files.pythonhosted.org/packages/b9/56/81d7da08648412f0dd5374d3331ddb69a0e2dd775952317709cabe8de123/dora_rs-0.5.0-cp37-abi3-win_amd64.whl", hash = "sha256:b4353f50d3d1aca100057cd959474f30c3c39d4b3d2771adf6dc452eeec53d34", size = 15366445, upload-time = "2026-03-25T19:26:10.736Z" },
+]
+
+[[package]]
+name = "dora-rs-cli"
+version = "0.5.0"
+source = { registry = "https://pypi.org/simple" }
+dependencies = [
+ { name = "dora-rs" },
+ { name = "uv" },
+]
+sdist = { url = "https://files.pythonhosted.org/packages/d1/33/5d54689d9335b3561edfafa640d0f7dac6fbab2ef06de45b7ad700bba674/dora_rs_cli-0.5.0.tar.gz", hash = "sha256:b87e2ade99dce4d9c2ce29a95425054c3d7ad19e5995622de3d448b4fcf07c08", size = 329786, upload-time = "2026-03-25T19:25:28.512Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/14/99/23f3e81c77b60121f65a5bc65a08673fea1cfd8d4f0bbbc2c5147277ae9d/dora_rs_cli-0.5.0-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:f1ee6b878b24ccadb3e7490a3cd6931298b8e7471c781c21dd01749e52a6dfbc", size = 18823766, upload-time = "2026-03-25T19:25:13.065Z" },
+ { url = "https://files.pythonhosted.org/packages/bf/b0/2c21cbc760ebfaca0951c35e7fb0d78341ca672394cbc65d2c2b9789e834/dora_rs_cli-0.5.0-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:b1feb17b1c1717fdf28e9784f1674768f1108dc2bd209caeb569503f27735a66", size = 17887241, upload-time = "2026-03-25T19:25:00.608Z" },
+ { url = "https://files.pythonhosted.org/packages/83/b9/64354734dd18e939699c06f97858185cbd9bd5d5474fc548062a9b86319f/dora_rs_cli-0.5.0-cp37-abi3-manylinux_2_28_armv7l.whl", hash = "sha256:ba117dc5a2072f9886e9bfb52b8e5612bc5897a9dab75b7604e22ef5ad1043ae", size = 16608353, upload-time = "2026-03-25T19:25:03.732Z" },
+ { url = "https://files.pythonhosted.org/packages/93/be/a11a58d07e50ef572b01a4d6a567ae680be81833b1f00cb1222d35f4b511/dora_rs_cli-0.5.0-cp37-abi3-manylinux_2_28_i686.whl", hash = "sha256:490626294f65fe9a8de5ec5a59c506c478e38a1854bd5004ba24004781bf5cb8", size = 19799319, upload-time = "2026-03-25T19:25:06.68Z" },
+ { url = "https://files.pythonhosted.org/packages/ca/56/8c51c41d800e2c9156b789c36202e17057fec158a73c430c960f6ff4524c/dora_rs_cli-0.5.0-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:4d4f4a67f47243a6d108f8ea03d334e72eb3f24c153dc2cc34cb4d065d1c8f49", size = 18300829, upload-time = "2026-03-25T19:25:09.907Z" },
+ { url = "https://files.pythonhosted.org/packages/f8/f9/272d5e7adf12ed50b8e107b7b52b200e444e9cc0350c1daa47f9f81809ad/dora_rs_cli-0.5.0-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:52e1a93a23dfc9fc17d9b3f9563cc96d1f5ead9d0f0e301d63b806e8a43a95b8", size = 21906681, upload-time = "2026-03-25T19:25:16.61Z" },
+ { url = "https://files.pythonhosted.org/packages/97/e8/b2cc65af6a2f523c9f7f622b0a7731d6ecf8e221115266a09f13df8996db/dora_rs_cli-0.5.0-cp37-abi3-musllinux_1_2_armv7l.whl", hash = "sha256:fa5ca65db8ce1f6ed96c5c15e9a2824866948276db06765d7e25b5ab9a8e071f", size = 20770754, upload-time = "2026-03-25T19:25:19.574Z" },
+ { url = "https://files.pythonhosted.org/packages/c3/7e/227a67e217f39fa6e762fd6ab5a997e00c484785348144870bbd41aa40f5/dora_rs_cli-0.5.0-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:f28cfed94039100c0af0274e01c2b72ac2df41d91ba2b834b6fe005aaf1e9b2e", size = 22113021, upload-time = "2026-03-25T19:25:22.723Z" },
+ { url = "https://files.pythonhosted.org/packages/de/47/c7abfa74c0d0a78df4659d51b1d4782a671151b1268607c5a3374665f208/dora_rs_cli-0.5.0-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:0ffdd6465c651d55e1b84612b135b3665125b6a919a70a2ea24ddc042a88356d", size = 21783132, upload-time = "2026-03-25T19:25:26.202Z" },
+ { url = "https://files.pythonhosted.org/packages/bf/60/ec77c1d1bad861670695dee9a311d3a76969406c318ba3a3bbd0c7044be3/dora_rs_cli-0.5.0-cp37-abi3-win_amd64.whl", hash = "sha256:eaa7bc9380186656bec3e6b6ccc3ad3f63b52b912431d9dba47da55c0aba8ca1", size = 16141869, upload-time = "2026-03-25T19:25:30.326Z" },
+]
+
+[[package]]
+name = "numpy"
+version = "2.2.6"
+source = { registry = "https://pypi.org/simple" }
+resolution-markers = [
+ "python_full_version < '3.11'",
+]
+sdist = { url = "https://files.pythonhosted.org/packages/76/21/7d2a95e4bba9dc13d043ee156a356c0a8f0c6309dff6b21b4d71a073b8a8/numpy-2.2.6.tar.gz", hash = "sha256:e29554e2bef54a90aa5cc07da6ce955accb83f21ab5de01a62c8478897b264fd", size = 20276440, upload-time = "2025-05-17T22:38:04.611Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/9a/3e/ed6db5be21ce87955c0cbd3009f2803f59fa08df21b5df06862e2d8e2bdd/numpy-2.2.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:b412caa66f72040e6d268491a59f2c43bf03eb6c96dd8f0307829feb7fa2b6fb", size = 21165245, upload-time = "2025-05-17T21:27:58.555Z" },
+ { url = "https://files.pythonhosted.org/packages/22/c2/4b9221495b2a132cc9d2eb862e21d42a009f5a60e45fc44b00118c174bff/numpy-2.2.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8e41fd67c52b86603a91c1a505ebaef50b3314de0213461c7a6e99c9a3beff90", size = 14360048, upload-time = "2025-05-17T21:28:21.406Z" },
+ { url = "https://files.pythonhosted.org/packages/fd/77/dc2fcfc66943c6410e2bf598062f5959372735ffda175b39906d54f02349/numpy-2.2.6-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:37e990a01ae6ec7fe7fa1c26c55ecb672dd98b19c3d0e1d1f326fa13cb38d163", size = 5340542, upload-time = "2025-05-17T21:28:30.931Z" },
+ { url = "https://files.pythonhosted.org/packages/7a/4f/1cb5fdc353a5f5cc7feb692db9b8ec2c3d6405453f982435efc52561df58/numpy-2.2.6-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:5a6429d4be8ca66d889b7cf70f536a397dc45ba6faeb5f8c5427935d9592e9cf", size = 6878301, upload-time = "2025-05-17T21:28:41.613Z" },
+ { url = "https://files.pythonhosted.org/packages/eb/17/96a3acd228cec142fcb8723bd3cc39c2a474f7dcf0a5d16731980bcafa95/numpy-2.2.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:efd28d4e9cd7d7a8d39074a4d44c63eda73401580c5c76acda2ce969e0a38e83", size = 14297320, upload-time = "2025-05-17T21:29:02.78Z" },
+ { url = "https://files.pythonhosted.org/packages/b4/63/3de6a34ad7ad6646ac7d2f55ebc6ad439dbbf9c4370017c50cf403fb19b5/numpy-2.2.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fc7b73d02efb0e18c000e9ad8b83480dfcd5dfd11065997ed4c6747470ae8915", size = 16801050, upload-time = "2025-05-17T21:29:27.675Z" },
+ { url = "https://files.pythonhosted.org/packages/07/b6/89d837eddef52b3d0cec5c6ba0456c1bf1b9ef6a6672fc2b7873c3ec4e2e/numpy-2.2.6-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:74d4531beb257d2c3f4b261bfb0fc09e0f9ebb8842d82a7b4209415896adc680", size = 15807034, upload-time = "2025-05-17T21:29:51.102Z" },
+ { url = "https://files.pythonhosted.org/packages/01/c8/dc6ae86e3c61cfec1f178e5c9f7858584049b6093f843bca541f94120920/numpy-2.2.6-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:8fc377d995680230e83241d8a96def29f204b5782f371c532579b4f20607a289", size = 18614185, upload-time = "2025-05-17T21:30:18.703Z" },
+ { url = "https://files.pythonhosted.org/packages/5b/c5/0064b1b7e7c89137b471ccec1fd2282fceaae0ab3a9550f2568782d80357/numpy-2.2.6-cp310-cp310-win32.whl", hash = "sha256:b093dd74e50a8cba3e873868d9e93a85b78e0daf2e98c6797566ad8044e8363d", size = 6527149, upload-time = "2025-05-17T21:30:29.788Z" },
+ { url = "https://files.pythonhosted.org/packages/a3/dd/4b822569d6b96c39d1215dbae0582fd99954dcbcf0c1a13c61783feaca3f/numpy-2.2.6-cp310-cp310-win_amd64.whl", hash = "sha256:f0fd6321b839904e15c46e0d257fdd101dd7f530fe03fd6359c1ea63738703f3", size = 12904620, upload-time = "2025-05-17T21:30:48.994Z" },
+ { url = "https://files.pythonhosted.org/packages/da/a8/4f83e2aa666a9fbf56d6118faaaf5f1974d456b1823fda0a176eff722839/numpy-2.2.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f9f1adb22318e121c5c69a09142811a201ef17ab257a1e66ca3025065b7f53ae", size = 21176963, upload-time = "2025-05-17T21:31:19.36Z" },
+ { url = "https://files.pythonhosted.org/packages/b3/2b/64e1affc7972decb74c9e29e5649fac940514910960ba25cd9af4488b66c/numpy-2.2.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c820a93b0255bc360f53eca31a0e676fd1101f673dda8da93454a12e23fc5f7a", size = 14406743, upload-time = "2025-05-17T21:31:41.087Z" },
+ { url = "https://files.pythonhosted.org/packages/4a/9f/0121e375000b5e50ffdd8b25bf78d8e1a5aa4cca3f185d41265198c7b834/numpy-2.2.6-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:3d70692235e759f260c3d837193090014aebdf026dfd167834bcba43e30c2a42", size = 5352616, upload-time = "2025-05-17T21:31:50.072Z" },
+ { url = "https://files.pythonhosted.org/packages/31/0d/b48c405c91693635fbe2dcd7bc84a33a602add5f63286e024d3b6741411c/numpy-2.2.6-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:481b49095335f8eed42e39e8041327c05b0f6f4780488f61286ed3c01368d491", size = 6889579, upload-time = "2025-05-17T21:32:01.712Z" },
+ { url = "https://files.pythonhosted.org/packages/52/b8/7f0554d49b565d0171eab6e99001846882000883998e7b7d9f0d98b1f934/numpy-2.2.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b64d8d4d17135e00c8e346e0a738deb17e754230d7e0810ac5012750bbd85a5a", size = 14312005, upload-time = "2025-05-17T21:32:23.332Z" },
+ { url = "https://files.pythonhosted.org/packages/b3/dd/2238b898e51bd6d389b7389ffb20d7f4c10066d80351187ec8e303a5a475/numpy-2.2.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ba10f8411898fc418a521833e014a77d3ca01c15b0c6cdcce6a0d2897e6dbbdf", size = 16821570, upload-time = "2025-05-17T21:32:47.991Z" },
+ { url = "https://files.pythonhosted.org/packages/83/6c/44d0325722cf644f191042bf47eedad61c1e6df2432ed65cbe28509d404e/numpy-2.2.6-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:bd48227a919f1bafbdda0583705e547892342c26fb127219d60a5c36882609d1", size = 15818548, upload-time = "2025-05-17T21:33:11.728Z" },
+ { url = "https://files.pythonhosted.org/packages/ae/9d/81e8216030ce66be25279098789b665d49ff19eef08bfa8cb96d4957f422/numpy-2.2.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:9551a499bf125c1d4f9e250377c1ee2eddd02e01eac6644c080162c0c51778ab", size = 18620521, upload-time = "2025-05-17T21:33:39.139Z" },
+ { url = "https://files.pythonhosted.org/packages/6a/fd/e19617b9530b031db51b0926eed5345ce8ddc669bb3bc0044b23e275ebe8/numpy-2.2.6-cp311-cp311-win32.whl", hash = "sha256:0678000bb9ac1475cd454c6b8c799206af8107e310843532b04d49649c717a47", size = 6525866, upload-time = "2025-05-17T21:33:50.273Z" },
+ { url = "https://files.pythonhosted.org/packages/31/0a/f354fb7176b81747d870f7991dc763e157a934c717b67b58456bc63da3df/numpy-2.2.6-cp311-cp311-win_amd64.whl", hash = "sha256:e8213002e427c69c45a52bbd94163084025f533a55a59d6f9c5b820774ef3303", size = 12907455, upload-time = "2025-05-17T21:34:09.135Z" },
+ { url = "https://files.pythonhosted.org/packages/82/5d/c00588b6cf18e1da539b45d3598d3557084990dcc4331960c15ee776ee41/numpy-2.2.6-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:41c5a21f4a04fa86436124d388f6ed60a9343a6f767fced1a8a71c3fbca038ff", size = 20875348, upload-time = "2025-05-17T21:34:39.648Z" },
+ { url = "https://files.pythonhosted.org/packages/66/ee/560deadcdde6c2f90200450d5938f63a34b37e27ebff162810f716f6a230/numpy-2.2.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:de749064336d37e340f640b05f24e9e3dd678c57318c7289d222a8a2f543e90c", size = 14119362, upload-time = "2025-05-17T21:35:01.241Z" },
+ { url = "https://files.pythonhosted.org/packages/3c/65/4baa99f1c53b30adf0acd9a5519078871ddde8d2339dc5a7fde80d9d87da/numpy-2.2.6-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:894b3a42502226a1cac872f840030665f33326fc3dac8e57c607905773cdcde3", size = 5084103, upload-time = "2025-05-17T21:35:10.622Z" },
+ { url = "https://files.pythonhosted.org/packages/cc/89/e5a34c071a0570cc40c9a54eb472d113eea6d002e9ae12bb3a8407fb912e/numpy-2.2.6-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:71594f7c51a18e728451bb50cc60a3ce4e6538822731b2933209a1f3614e9282", size = 6625382, upload-time = "2025-05-17T21:35:21.414Z" },
+ { url = "https://files.pythonhosted.org/packages/f8/35/8c80729f1ff76b3921d5c9487c7ac3de9b2a103b1cd05e905b3090513510/numpy-2.2.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f2618db89be1b4e05f7a1a847a9c1c0abd63e63a1607d892dd54668dd92faf87", size = 14018462, upload-time = "2025-05-17T21:35:42.174Z" },
+ { url = "https://files.pythonhosted.org/packages/8c/3d/1e1db36cfd41f895d266b103df00ca5b3cbe965184df824dec5c08c6b803/numpy-2.2.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd83c01228a688733f1ded5201c678f0c53ecc1006ffbc404db9f7a899ac6249", size = 16527618, upload-time = "2025-05-17T21:36:06.711Z" },
+ { url = "https://files.pythonhosted.org/packages/61/c6/03ed30992602c85aa3cd95b9070a514f8b3c33e31124694438d88809ae36/numpy-2.2.6-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:37c0ca431f82cd5fa716eca9506aefcabc247fb27ba69c5062a6d3ade8cf8f49", size = 15505511, upload-time = "2025-05-17T21:36:29.965Z" },
+ { url = "https://files.pythonhosted.org/packages/b7/25/5761d832a81df431e260719ec45de696414266613c9ee268394dd5ad8236/numpy-2.2.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fe27749d33bb772c80dcd84ae7e8df2adc920ae8297400dabec45f0dedb3f6de", size = 18313783, upload-time = "2025-05-17T21:36:56.883Z" },
+ { url = "https://files.pythonhosted.org/packages/57/0a/72d5a3527c5ebffcd47bde9162c39fae1f90138c961e5296491ce778e682/numpy-2.2.6-cp312-cp312-win32.whl", hash = "sha256:4eeaae00d789f66c7a25ac5f34b71a7035bb474e679f410e5e1a94deb24cf2d4", size = 6246506, upload-time = "2025-05-17T21:37:07.368Z" },
+ { url = "https://files.pythonhosted.org/packages/36/fa/8c9210162ca1b88529ab76b41ba02d433fd54fecaf6feb70ef9f124683f1/numpy-2.2.6-cp312-cp312-win_amd64.whl", hash = "sha256:c1f9540be57940698ed329904db803cf7a402f3fc200bfe599334c9bd84a40b2", size = 12614190, upload-time = "2025-05-17T21:37:26.213Z" },
+ { url = "https://files.pythonhosted.org/packages/f9/5c/6657823f4f594f72b5471f1db1ab12e26e890bb2e41897522d134d2a3e81/numpy-2.2.6-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:0811bb762109d9708cca4d0b13c4f67146e3c3b7cf8d34018c722adb2d957c84", size = 20867828, upload-time = "2025-05-17T21:37:56.699Z" },
+ { url = "https://files.pythonhosted.org/packages/dc/9e/14520dc3dadf3c803473bd07e9b2bd1b69bc583cb2497b47000fed2fa92f/numpy-2.2.6-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:287cc3162b6f01463ccd86be154f284d0893d2b3ed7292439ea97eafa8170e0b", size = 14143006, upload-time = "2025-05-17T21:38:18.291Z" },
+ { url = "https://files.pythonhosted.org/packages/4f/06/7e96c57d90bebdce9918412087fc22ca9851cceaf5567a45c1f404480e9e/numpy-2.2.6-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:f1372f041402e37e5e633e586f62aa53de2eac8d98cbfb822806ce4bbefcb74d", size = 5076765, upload-time = "2025-05-17T21:38:27.319Z" },
+ { url = "https://files.pythonhosted.org/packages/73/ed/63d920c23b4289fdac96ddbdd6132e9427790977d5457cd132f18e76eae0/numpy-2.2.6-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:55a4d33fa519660d69614a9fad433be87e5252f4b03850642f88993f7b2ca566", size = 6617736, upload-time = "2025-05-17T21:38:38.141Z" },
+ { url = "https://files.pythonhosted.org/packages/85/c5/e19c8f99d83fd377ec8c7e0cf627a8049746da54afc24ef0a0cb73d5dfb5/numpy-2.2.6-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f92729c95468a2f4f15e9bb94c432a9229d0d50de67304399627a943201baa2f", size = 14010719, upload-time = "2025-05-17T21:38:58.433Z" },
+ { url = "https://files.pythonhosted.org/packages/19/49/4df9123aafa7b539317bf6d342cb6d227e49f7a35b99c287a6109b13dd93/numpy-2.2.6-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1bc23a79bfabc5d056d106f9befb8d50c31ced2fbc70eedb8155aec74a45798f", size = 16526072, upload-time = "2025-05-17T21:39:22.638Z" },
+ { url = "https://files.pythonhosted.org/packages/b2/6c/04b5f47f4f32f7c2b0e7260442a8cbcf8168b0e1a41ff1495da42f42a14f/numpy-2.2.6-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:e3143e4451880bed956e706a3220b4e5cf6172ef05fcc397f6f36a550b1dd868", size = 15503213, upload-time = "2025-05-17T21:39:45.865Z" },
+ { url = "https://files.pythonhosted.org/packages/17/0a/5cd92e352c1307640d5b6fec1b2ffb06cd0dabe7d7b8227f97933d378422/numpy-2.2.6-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:b4f13750ce79751586ae2eb824ba7e1e8dba64784086c98cdbbcc6a42112ce0d", size = 18316632, upload-time = "2025-05-17T21:40:13.331Z" },
+ { url = "https://files.pythonhosted.org/packages/f0/3b/5cba2b1d88760ef86596ad0f3d484b1cbff7c115ae2429678465057c5155/numpy-2.2.6-cp313-cp313-win32.whl", hash = "sha256:5beb72339d9d4fa36522fc63802f469b13cdbe4fdab4a288f0c441b74272ebfd", size = 6244532, upload-time = "2025-05-17T21:43:46.099Z" },
+ { url = "https://files.pythonhosted.org/packages/cb/3b/d58c12eafcb298d4e6d0d40216866ab15f59e55d148a5658bb3132311fcf/numpy-2.2.6-cp313-cp313-win_amd64.whl", hash = "sha256:b0544343a702fa80c95ad5d3d608ea3599dd54d4632df855e4c8d24eb6ecfa1c", size = 12610885, upload-time = "2025-05-17T21:44:05.145Z" },
+ { url = "https://files.pythonhosted.org/packages/6b/9e/4bf918b818e516322db999ac25d00c75788ddfd2d2ade4fa66f1f38097e1/numpy-2.2.6-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:0bca768cd85ae743b2affdc762d617eddf3bcf8724435498a1e80132d04879e6", size = 20963467, upload-time = "2025-05-17T21:40:44Z" },
+ { url = "https://files.pythonhosted.org/packages/61/66/d2de6b291507517ff2e438e13ff7b1e2cdbdb7cb40b3ed475377aece69f9/numpy-2.2.6-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:fc0c5673685c508a142ca65209b4e79ed6740a4ed6b2267dbba90f34b0b3cfda", size = 14225144, upload-time = "2025-05-17T21:41:05.695Z" },
+ { url = "https://files.pythonhosted.org/packages/e4/25/480387655407ead912e28ba3a820bc69af9adf13bcbe40b299d454ec011f/numpy-2.2.6-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:5bd4fc3ac8926b3819797a7c0e2631eb889b4118a9898c84f585a54d475b7e40", size = 5200217, upload-time = "2025-05-17T21:41:15.903Z" },
+ { url = "https://files.pythonhosted.org/packages/aa/4a/6e313b5108f53dcbf3aca0c0f3e9c92f4c10ce57a0a721851f9785872895/numpy-2.2.6-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:fee4236c876c4e8369388054d02d0e9bb84821feb1a64dd59e137e6511a551f8", size = 6712014, upload-time = "2025-05-17T21:41:27.321Z" },
+ { url = "https://files.pythonhosted.org/packages/b7/30/172c2d5c4be71fdf476e9de553443cf8e25feddbe185e0bd88b096915bcc/numpy-2.2.6-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e1dda9c7e08dc141e0247a5b8f49cf05984955246a327d4c48bda16821947b2f", size = 14077935, upload-time = "2025-05-17T21:41:49.738Z" },
+ { url = "https://files.pythonhosted.org/packages/12/fb/9e743f8d4e4d3c710902cf87af3512082ae3d43b945d5d16563f26ec251d/numpy-2.2.6-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f447e6acb680fd307f40d3da4852208af94afdfab89cf850986c3ca00562f4fa", size = 16600122, upload-time = "2025-05-17T21:42:14.046Z" },
+ { url = "https://files.pythonhosted.org/packages/12/75/ee20da0e58d3a66f204f38916757e01e33a9737d0b22373b3eb5a27358f9/numpy-2.2.6-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:389d771b1623ec92636b0786bc4ae56abafad4a4c513d36a55dce14bd9ce8571", size = 15586143, upload-time = "2025-05-17T21:42:37.464Z" },
+ { url = "https://files.pythonhosted.org/packages/76/95/bef5b37f29fc5e739947e9ce5179ad402875633308504a52d188302319c8/numpy-2.2.6-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:8e9ace4a37db23421249ed236fdcdd457d671e25146786dfc96835cd951aa7c1", size = 18385260, upload-time = "2025-05-17T21:43:05.189Z" },
+ { url = "https://files.pythonhosted.org/packages/09/04/f2f83279d287407cf36a7a8053a5abe7be3622a4363337338f2585e4afda/numpy-2.2.6-cp313-cp313t-win32.whl", hash = "sha256:038613e9fb8c72b0a41f025a7e4c3f0b7a1b5d768ece4796b674c8f3fe13efff", size = 6377225, upload-time = "2025-05-17T21:43:16.254Z" },
+ { url = "https://files.pythonhosted.org/packages/67/0e/35082d13c09c02c011cf21570543d202ad929d961c02a147493cb0c2bdf5/numpy-2.2.6-cp313-cp313t-win_amd64.whl", hash = "sha256:6031dd6dfecc0cf9f668681a37648373bddd6421fff6c66ec1624eed0180ee06", size = 12771374, upload-time = "2025-05-17T21:43:35.479Z" },
+ { url = "https://files.pythonhosted.org/packages/9e/3b/d94a75f4dbf1ef5d321523ecac21ef23a3cd2ac8b78ae2aac40873590229/numpy-2.2.6-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:0b605b275d7bd0c640cad4e5d30fa701a8d59302e127e5f79138ad62762c3e3d", size = 21040391, upload-time = "2025-05-17T21:44:35.948Z" },
+ { url = "https://files.pythonhosted.org/packages/17/f4/09b2fa1b58f0fb4f7c7963a1649c64c4d315752240377ed74d9cd878f7b5/numpy-2.2.6-pp310-pypy310_pp73-macosx_14_0_x86_64.whl", hash = "sha256:7befc596a7dc9da8a337f79802ee8adb30a552a94f792b9c9d18c840055907db", size = 6786754, upload-time = "2025-05-17T21:44:47.446Z" },
+ { url = "https://files.pythonhosted.org/packages/af/30/feba75f143bdc868a1cc3f44ccfa6c4b9ec522b36458e738cd00f67b573f/numpy-2.2.6-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ce47521a4754c8f4593837384bd3424880629f718d87c5d44f8ed763edd63543", size = 16643476, upload-time = "2025-05-17T21:45:11.871Z" },
+ { url = "https://files.pythonhosted.org/packages/37/48/ac2a9584402fb6c0cd5b5d1a91dcf176b15760130dd386bbafdbfe3640bf/numpy-2.2.6-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:d042d24c90c41b54fd506da306759e06e568864df8ec17ccc17e9e884634fd00", size = 12812666, upload-time = "2025-05-17T21:45:31.426Z" },
+]
+
+[[package]]
+name = "numpy"
+version = "2.4.4"
+source = { registry = "https://pypi.org/simple" }
+resolution-markers = [
+ "python_full_version >= '3.11'",
+]
+sdist = { url = "https://files.pythonhosted.org/packages/d7/9f/b8cef5bffa569759033adda9481211426f12f53299629b410340795c2514/numpy-2.4.4.tar.gz", hash = "sha256:2d390634c5182175533585cc89f3608a4682ccb173cc9bb940b2881c8d6f8fa0", size = 20731587, upload-time = "2026-03-29T13:22:01.298Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/ef/c6/4218570d8c8ecc9704b5157a3348e486e84ef4be0ed3e38218ab473c83d2/numpy-2.4.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f983334aea213c99992053ede6168500e5f086ce74fbc4acc3f2b00f5762e9db", size = 16976799, upload-time = "2026-03-29T13:18:15.438Z" },
+ { url = "https://files.pythonhosted.org/packages/dd/92/b4d922c4a5f5dab9ed44e6153908a5c665b71acf183a83b93b690996e39b/numpy-2.4.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:72944b19f2324114e9dc86a159787333b77874143efcf89a5167ef83cfee8af0", size = 14971552, upload-time = "2026-03-29T13:18:18.606Z" },
+ { url = "https://files.pythonhosted.org/packages/8a/dc/df98c095978fa6ee7b9a9387d1d58cbb3d232d0e69ad169a4ce784bde4fd/numpy-2.4.4-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:86b6f55f5a352b48d7fbfd2dbc3d5b780b2d79f4d3c121f33eb6efb22e9a2015", size = 5476566, upload-time = "2026-03-29T13:18:21.532Z" },
+ { url = "https://files.pythonhosted.org/packages/28/34/b3fdcec6e725409223dd27356bdf5a3c2cc2282e428218ecc9cb7acc9763/numpy-2.4.4-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:ba1f4fc670ed79f876f70082eff4f9583c15fb9a4b89d6188412de4d18ae2f40", size = 6806482, upload-time = "2026-03-29T13:18:23.634Z" },
+ { url = "https://files.pythonhosted.org/packages/68/62/63417c13aa35d57bee1337c67446761dc25ea6543130cf868eace6e8157b/numpy-2.4.4-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8a87ec22c87be071b6bdbd27920b129b94f2fc964358ce38f3822635a3e2e03d", size = 15973376, upload-time = "2026-03-29T13:18:26.677Z" },
+ { url = "https://files.pythonhosted.org/packages/cf/c5/9fcb7e0e69cef59cf10c746b84f7d58b08bc66a6b7d459783c5a4f6101a6/numpy-2.4.4-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:df3775294accfdd75f32c74ae39fcba920c9a378a2fc18a12b6820aa8c1fb502", size = 16925137, upload-time = "2026-03-29T13:18:30.14Z" },
+ { url = "https://files.pythonhosted.org/packages/7e/43/80020edacb3f84b9efdd1591120a4296462c23fd8db0dde1666f6ef66f13/numpy-2.4.4-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0d4e437e295f18ec29bc79daf55e8a47a9113df44d66f702f02a293d93a2d6dd", size = 17329414, upload-time = "2026-03-29T13:18:33.733Z" },
+ { url = "https://files.pythonhosted.org/packages/fd/06/af0658593b18a5f73532d377188b964f239eb0894e664a6c12f484472f97/numpy-2.4.4-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6aa3236c78803afbcb255045fbef97a9e25a1f6c9888357d205ddc42f4d6eba5", size = 18658397, upload-time = "2026-03-29T13:18:37.511Z" },
+ { url = "https://files.pythonhosted.org/packages/e6/ce/13a09ed65f5d0ce5c7dd0669250374c6e379910f97af2c08c57b0608eee4/numpy-2.4.4-cp311-cp311-win32.whl", hash = "sha256:30caa73029a225b2d40d9fae193e008e24b2026b7ee1a867b7ee8d96ca1a448e", size = 6239499, upload-time = "2026-03-29T13:18:40.372Z" },
+ { url = "https://files.pythonhosted.org/packages/bd/63/05d193dbb4b5eec1eca73822d80da98b511f8328ad4ae3ca4caf0f4db91d/numpy-2.4.4-cp311-cp311-win_amd64.whl", hash = "sha256:6bbe4eb67390b0a0265a2c25458f6b90a409d5d069f1041e6aff1e27e3d9a79e", size = 12614257, upload-time = "2026-03-29T13:18:42.95Z" },
+ { url = "https://files.pythonhosted.org/packages/87/c5/8168052f080c26fa984c413305012be54741c9d0d74abd7fbeeccae3889f/numpy-2.4.4-cp311-cp311-win_arm64.whl", hash = "sha256:fcfe2045fd2e8f3cb0ce9d4ba6dba6333b8fa05bb8a4939c908cd43322d14c7e", size = 10486775, upload-time = "2026-03-29T13:18:45.835Z" },
+ { url = "https://files.pythonhosted.org/packages/28/05/32396bec30fb2263770ee910142f49c1476d08e8ad41abf8403806b520ce/numpy-2.4.4-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:15716cfef24d3a9762e3acdf87e27f58dc823d1348f765bbea6bef8c639bfa1b", size = 16689272, upload-time = "2026-03-29T13:18:49.223Z" },
+ { url = "https://files.pythonhosted.org/packages/c5/f3/a983d28637bfcd763a9c7aafdb6d5c0ebf3d487d1e1459ffdb57e2f01117/numpy-2.4.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:23cbfd4c17357c81021f21540da84ee282b9c8fba38a03b7b9d09ba6b951421e", size = 14699573, upload-time = "2026-03-29T13:18:52.629Z" },
+ { url = "https://files.pythonhosted.org/packages/9b/fd/e5ecca1e78c05106d98028114f5c00d3eddb41207686b2b7de3e477b0e22/numpy-2.4.4-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:8b3b60bb7cba2c8c81837661c488637eee696f59a877788a396d33150c35d842", size = 5204782, upload-time = "2026-03-29T13:18:55.579Z" },
+ { url = "https://files.pythonhosted.org/packages/de/2f/702a4594413c1a8632092beae8aba00f1d67947389369b3777aed783fdca/numpy-2.4.4-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:e4a010c27ff6f210ff4c6ef34394cd61470d01014439b192ec22552ee867f2a8", size = 6552038, upload-time = "2026-03-29T13:18:57.769Z" },
+ { url = "https://files.pythonhosted.org/packages/7f/37/eed308a8f56cba4d1fdf467a4fc67ef4ff4bf1c888f5fc980481890104b1/numpy-2.4.4-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f9e75681b59ddaa5e659898085ae0eaea229d054f2ac0c7e563a62205a700121", size = 15670666, upload-time = "2026-03-29T13:19:00.341Z" },
+ { url = "https://files.pythonhosted.org/packages/0a/0d/0e3ecece05b7a7e87ab9fb587855548da437a061326fff64a223b6dcb78a/numpy-2.4.4-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:81f4a14bee47aec54f883e0cad2d73986640c1590eb9bfaaba7ad17394481e6e", size = 16645480, upload-time = "2026-03-29T13:19:03.63Z" },
+ { url = "https://files.pythonhosted.org/packages/34/49/f2312c154b82a286758ee2f1743336d50651f8b5195db18cdb63675ff649/numpy-2.4.4-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:62d6b0f03b694173f9fcb1fb317f7222fd0b0b103e784c6549f5e53a27718c44", size = 17020036, upload-time = "2026-03-29T13:19:07.428Z" },
+ { url = "https://files.pythonhosted.org/packages/7b/e9/736d17bd77f1b0ec4f9901aaec129c00d59f5d84d5e79bba540ef12c2330/numpy-2.4.4-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fbc356aae7adf9e6336d336b9c8111d390a05df88f1805573ebb0807bd06fd1d", size = 18368643, upload-time = "2026-03-29T13:19:10.775Z" },
+ { url = "https://files.pythonhosted.org/packages/63/f6/d417977c5f519b17c8a5c3bc9e8304b0908b0e21136fe43bf628a1343914/numpy-2.4.4-cp312-cp312-win32.whl", hash = "sha256:0d35aea54ad1d420c812bfa0385c71cd7cc5bcf7c65fed95fc2cd02fe8c79827", size = 5961117, upload-time = "2026-03-29T13:19:13.464Z" },
+ { url = "https://files.pythonhosted.org/packages/2d/5b/e1deebf88ff431b01b7406ca3583ab2bbb90972bbe1c568732e49c844f7e/numpy-2.4.4-cp312-cp312-win_amd64.whl", hash = "sha256:b5f0362dc928a6ecd9db58868fca5e48485205e3855957bdedea308f8672ea4a", size = 12320584, upload-time = "2026-03-29T13:19:16.155Z" },
+ { url = "https://files.pythonhosted.org/packages/58/89/e4e856ac82a68c3ed64486a544977d0e7bdd18b8da75b78a577ca31c4395/numpy-2.4.4-cp312-cp312-win_arm64.whl", hash = "sha256:846300f379b5b12cc769334464656bc882e0735d27d9726568bc932fdc49d5ec", size = 10221450, upload-time = "2026-03-29T13:19:18.994Z" },
+ { url = "https://files.pythonhosted.org/packages/14/1d/d0a583ce4fefcc3308806a749a536c201ed6b5ad6e1322e227ee4848979d/numpy-2.4.4-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:08f2e31ed5e6f04b118e49821397f12767934cfdd12a1ce86a058f91e004ee50", size = 16684933, upload-time = "2026-03-29T13:19:22.47Z" },
+ { url = "https://files.pythonhosted.org/packages/c1/62/2b7a48fbb745d344742c0277f01286dead15f3f68e4f359fbfcf7b48f70f/numpy-2.4.4-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:e823b8b6edc81e747526f70f71a9c0a07ac4e7ad13020aa736bb7c9d67196115", size = 14694532, upload-time = "2026-03-29T13:19:25.581Z" },
+ { url = "https://files.pythonhosted.org/packages/e5/87/499737bfba066b4a3bebff24a8f1c5b2dee410b209bc6668c9be692580f0/numpy-2.4.4-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:4a19d9dba1a76618dd86b164d608566f393f8ec6ac7c44f0cc879011c45e65af", size = 5199661, upload-time = "2026-03-29T13:19:28.31Z" },
+ { url = "https://files.pythonhosted.org/packages/cd/da/464d551604320d1491bc345efed99b4b7034143a85787aab78d5691d5a0e/numpy-2.4.4-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:d2a8490669bfe99a233298348acc2d824d496dee0e66e31b66a6022c2ad74a5c", size = 6547539, upload-time = "2026-03-29T13:19:30.97Z" },
+ { url = "https://files.pythonhosted.org/packages/7d/90/8d23e3b0dafd024bf31bdec225b3bb5c2dbfa6912f8a53b8659f21216cbf/numpy-2.4.4-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:45dbed2ab436a9e826e302fcdcbe9133f9b0006e5af7168afb8963a6520da103", size = 15668806, upload-time = "2026-03-29T13:19:33.887Z" },
+ { url = "https://files.pythonhosted.org/packages/d1/73/a9d864e42a01896bb5974475438f16086be9ba1f0d19d0bb7a07427c4a8b/numpy-2.4.4-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c901b15172510173f5cb310eae652908340f8dede90fff9e3bf6c0d8dfd92f83", size = 16632682, upload-time = "2026-03-29T13:19:37.336Z" },
+ { url = "https://files.pythonhosted.org/packages/34/fb/14570d65c3bde4e202a031210475ae9cde9b7686a2e7dc97ee67d2833b35/numpy-2.4.4-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:99d838547ace2c4aace6c4f76e879ddfe02bb58a80c1549928477862b7a6d6ed", size = 17019810, upload-time = "2026-03-29T13:19:40.963Z" },
+ { url = "https://files.pythonhosted.org/packages/8a/77/2ba9d87081fd41f6d640c83f26fb7351e536b7ce6dd9061b6af5904e8e46/numpy-2.4.4-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:0aec54fd785890ecca25a6003fd9a5aed47ad607bbac5cd64f836ad8666f4959", size = 18357394, upload-time = "2026-03-29T13:19:44.859Z" },
+ { url = "https://files.pythonhosted.org/packages/a2/23/52666c9a41708b0853fa3b1a12c90da38c507a3074883823126d4e9d5b30/numpy-2.4.4-cp313-cp313-win32.whl", hash = "sha256:07077278157d02f65c43b1b26a3886bce886f95d20aabd11f87932750dfb14ed", size = 5959556, upload-time = "2026-03-29T13:19:47.661Z" },
+ { url = "https://files.pythonhosted.org/packages/57/fb/48649b4971cde70d817cf97a2a2fdc0b4d8308569f1dd2f2611959d2e0cf/numpy-2.4.4-cp313-cp313-win_amd64.whl", hash = "sha256:5c70f1cc1c4efbe316a572e2d8b9b9cc44e89b95f79ca3331553fbb63716e2bf", size = 12317311, upload-time = "2026-03-29T13:19:50.67Z" },
+ { url = "https://files.pythonhosted.org/packages/ba/d8/11490cddd564eb4de97b4579ef6bfe6a736cc07e94c1598590ae25415e01/numpy-2.4.4-cp313-cp313-win_arm64.whl", hash = "sha256:ef4059d6e5152fa1a39f888e344c73fdc926e1b2dd58c771d67b0acfbf2aa67d", size = 10222060, upload-time = "2026-03-29T13:19:54.229Z" },
+ { url = "https://files.pythonhosted.org/packages/99/5d/dab4339177a905aad3e2221c915b35202f1ec30d750dd2e5e9d9a72b804b/numpy-2.4.4-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:4bbc7f303d125971f60ec0aaad5e12c62d0d2c925f0ab1273debd0e4ba37aba5", size = 14822302, upload-time = "2026-03-29T13:19:57.585Z" },
+ { url = "https://files.pythonhosted.org/packages/eb/e4/0564a65e7d3d97562ed6f9b0fd0fb0a6f559ee444092f105938b50043876/numpy-2.4.4-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:4d6d57903571f86180eb98f8f0c839fa9ebbfb031356d87f1361be91e433f5b7", size = 5327407, upload-time = "2026-03-29T13:20:00.601Z" },
+ { url = "https://files.pythonhosted.org/packages/29/8d/35a3a6ce5ad371afa58b4700f1c820f8f279948cca32524e0a695b0ded83/numpy-2.4.4-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:4636de7fd195197b7535f231b5de9e4b36d2c440b6e566d2e4e4746e6af0ca93", size = 6647631, upload-time = "2026-03-29T13:20:02.855Z" },
+ { url = "https://files.pythonhosted.org/packages/f4/da/477731acbd5a58a946c736edfdabb2ac5b34c3d08d1ba1a7b437fa0884df/numpy-2.4.4-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ad2e2ef14e0b04e544ea2fa0a36463f847f113d314aa02e5b402fdf910ef309e", size = 15727691, upload-time = "2026-03-29T13:20:06.004Z" },
+ { url = "https://files.pythonhosted.org/packages/e6/db/338535d9b152beabeb511579598418ba0212ce77cf9718edd70262cc4370/numpy-2.4.4-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5a285b3b96f951841799528cd1f4f01cd70e7e0204b4abebac9463eecfcf2a40", size = 16681241, upload-time = "2026-03-29T13:20:09.417Z" },
+ { url = "https://files.pythonhosted.org/packages/e2/a9/ad248e8f58beb7a0219b413c9c7d8151c5d285f7f946c3e26695bdbbe2df/numpy-2.4.4-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:f8474c4241bc18b750be2abea9d7a9ec84f46ef861dbacf86a4f6e043401f79e", size = 17085767, upload-time = "2026-03-29T13:20:13.126Z" },
+ { url = "https://files.pythonhosted.org/packages/b5/1a/3b88ccd3694681356f70da841630e4725a7264d6a885c8d442a697e1146b/numpy-2.4.4-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:4e874c976154687c1f71715b034739b45c7711bec81db01914770373d125e392", size = 18403169, upload-time = "2026-03-29T13:20:17.096Z" },
+ { url = "https://files.pythonhosted.org/packages/c2/c9/fcfd5d0639222c6eac7f304829b04892ef51c96a75d479214d77e3ce6e33/numpy-2.4.4-cp313-cp313t-win32.whl", hash = "sha256:9c585a1790d5436a5374bac930dad6ed244c046ed91b2b2a3634eb2971d21008", size = 6083477, upload-time = "2026-03-29T13:20:20.195Z" },
+ { url = "https://files.pythonhosted.org/packages/d5/e3/3938a61d1c538aaec8ed6fd6323f57b0c2d2d2219512434c5c878db76553/numpy-2.4.4-cp313-cp313t-win_amd64.whl", hash = "sha256:93e15038125dc1e5345d9b5b68aa7f996ec33b98118d18c6ca0d0b7d6198b7e8", size = 12457487, upload-time = "2026-03-29T13:20:22.946Z" },
+ { url = "https://files.pythonhosted.org/packages/97/6a/7e345032cc60501721ef94e0e30b60f6b0bd601f9174ebd36389a2b86d40/numpy-2.4.4-cp313-cp313t-win_arm64.whl", hash = "sha256:0dfd3f9d3adbe2920b68b5cd3d51444e13a10792ec7154cd0a2f6e74d4ab3233", size = 10292002, upload-time = "2026-03-29T13:20:25.909Z" },
+ { url = "https://files.pythonhosted.org/packages/6e/06/c54062f85f673dd5c04cbe2f14c3acb8c8b95e3384869bb8cc9bff8cb9df/numpy-2.4.4-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:f169b9a863d34f5d11b8698ead99febeaa17a13ca044961aa8e2662a6c7766a0", size = 16684353, upload-time = "2026-03-29T13:20:29.504Z" },
+ { url = "https://files.pythonhosted.org/packages/4c/39/8a320264a84404c74cc7e79715de85d6130fa07a0898f67fb5cd5bd79908/numpy-2.4.4-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:2483e4584a1cb3092da4470b38866634bafb223cbcd551ee047633fd2584599a", size = 14704914, upload-time = "2026-03-29T13:20:33.547Z" },
+ { url = "https://files.pythonhosted.org/packages/91/fb/287076b2614e1d1044235f50f03748f31fa287e3dbe6abeb35cdfa351eca/numpy-2.4.4-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:2d19e6e2095506d1736b7d80595e0f252d76b89f5e715c35e06e937679ea7d7a", size = 5210005, upload-time = "2026-03-29T13:20:36.45Z" },
+ { url = "https://files.pythonhosted.org/packages/63/eb/fcc338595309910de6ecabfcef2419a9ce24399680bfb149421fa2df1280/numpy-2.4.4-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:6a246d5914aa1c820c9443ddcee9c02bec3e203b0c080349533fae17727dfd1b", size = 6544974, upload-time = "2026-03-29T13:20:39.014Z" },
+ { url = "https://files.pythonhosted.org/packages/44/5d/e7e9044032a716cdfaa3fba27a8e874bf1c5f1912a1ddd4ed071bf8a14a6/numpy-2.4.4-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:989824e9faf85f96ec9c7761cd8d29c531ad857bfa1daa930cba85baaecf1a9a", size = 15684591, upload-time = "2026-03-29T13:20:42.146Z" },
+ { url = "https://files.pythonhosted.org/packages/98/7c/21252050676612625449b4807d6b695b9ce8a7c9e1c197ee6216c8a65c7c/numpy-2.4.4-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:27a8d92cd10f1382a67d7cf4db7ce18341b66438bdd9f691d7b0e48d104c2a9d", size = 16637700, upload-time = "2026-03-29T13:20:46.204Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/29/56d2bbef9465db24ef25393383d761a1af4f446a1df9b8cded4fe3a5a5d7/numpy-2.4.4-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:e44319a2953c738205bf3354537979eaa3998ed673395b964c1176083dd46252", size = 17035781, upload-time = "2026-03-29T13:20:50.242Z" },
+ { url = "https://files.pythonhosted.org/packages/e3/2b/a35a6d7589d21f44cea7d0a98de5ddcbb3d421b2622a5c96b1edf18707c3/numpy-2.4.4-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:e892aff75639bbef0d2a2cfd55535510df26ff92f63c92cd84ef8d4ba5a5557f", size = 18362959, upload-time = "2026-03-29T13:20:54.019Z" },
+ { url = "https://files.pythonhosted.org/packages/64/c9/d52ec581f2390e0f5f85cbfd80fb83d965fc15e9f0e1aec2195faa142cde/numpy-2.4.4-cp314-cp314-win32.whl", hash = "sha256:1378871da56ca8943c2ba674530924bb8ca40cd228358a3b5f302ad60cf875fc", size = 6008768, upload-time = "2026-03-29T13:20:56.912Z" },
+ { url = "https://files.pythonhosted.org/packages/fa/22/4cc31a62a6c7b74a8730e31a4274c5dc80e005751e277a2ce38e675e4923/numpy-2.4.4-cp314-cp314-win_amd64.whl", hash = "sha256:715d1c092715954784bc79e1174fc2a90093dc4dc84ea15eb14dad8abdcdeb74", size = 12449181, upload-time = "2026-03-29T13:20:59.548Z" },
+ { url = "https://files.pythonhosted.org/packages/70/2e/14cda6f4d8e396c612d1bf97f22958e92148801d7e4f110cabebdc0eef4b/numpy-2.4.4-cp314-cp314-win_arm64.whl", hash = "sha256:2c194dd721e54ecad9ad387c1d35e63dce5c4450c6dc7dd5611283dda239aabb", size = 10496035, upload-time = "2026-03-29T13:21:02.524Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/e8/8fed8c8d848d7ecea092dc3469643f9d10bc3a134a815a3b033da1d2039b/numpy-2.4.4-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:2aa0613a5177c264ff5921051a5719d20095ea586ca88cc802c5c218d1c67d3e", size = 14824958, upload-time = "2026-03-29T13:21:05.671Z" },
+ { url = "https://files.pythonhosted.org/packages/05/1a/d8007a5138c179c2bf33ef44503e83d70434d2642877ee8fbb230e7c0548/numpy-2.4.4-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:42c16925aa5a02362f986765f9ebabf20de75cdefdca827d14315c568dcab113", size = 5330020, upload-time = "2026-03-29T13:21:08.635Z" },
+ { url = "https://files.pythonhosted.org/packages/99/64/ffb99ac6ae93faf117bcbd5c7ba48a7f45364a33e8e458545d3633615dda/numpy-2.4.4-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:874f200b2a981c647340f841730fc3a2b54c9d940566a3c4149099591e2c4c3d", size = 6650758, upload-time = "2026-03-29T13:21:10.949Z" },
+ { url = "https://files.pythonhosted.org/packages/6e/6e/795cc078b78a384052e73b2f6281ff7a700e9bf53bcce2ee579d4f6dd879/numpy-2.4.4-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c9b39d38a9bd2ae1becd7eac1303d031c5c110ad31f2b319c6e7d98b135c934d", size = 15729948, upload-time = "2026-03-29T13:21:14.047Z" },
+ { url = "https://files.pythonhosted.org/packages/5f/86/2acbda8cc2af5f3d7bfc791192863b9e3e19674da7b5e533fded124d1299/numpy-2.4.4-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b268594bccac7d7cf5844c7732e3f20c50921d94e36d7ec9b79e9857694b1b2f", size = 16679325, upload-time = "2026-03-29T13:21:17.561Z" },
+ { url = "https://files.pythonhosted.org/packages/bc/59/cafd83018f4aa55e0ac6fa92aa066c0a1877b77a615ceff1711c260ffae8/numpy-2.4.4-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:ac6b31e35612a26483e20750126d30d0941f949426974cace8e6b5c58a3657b0", size = 17084883, upload-time = "2026-03-29T13:21:21.106Z" },
+ { url = "https://files.pythonhosted.org/packages/f0/85/a42548db84e65ece46ab2caea3d3f78b416a47af387fcbb47ec28e660dc2/numpy-2.4.4-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:8e3ed142f2728df44263aaf5fb1f5b0b99f4070c553a0d7f033be65338329150", size = 18403474, upload-time = "2026-03-29T13:21:24.828Z" },
+ { url = "https://files.pythonhosted.org/packages/ed/ad/483d9e262f4b831000062e5d8a45e342166ec8aaa1195264982bca267e62/numpy-2.4.4-cp314-cp314t-win32.whl", hash = "sha256:dddbbd259598d7240b18c9d87c56a9d2fb3b02fe266f49a7c101532e78c1d871", size = 6155500, upload-time = "2026-03-29T13:21:28.205Z" },
+ { url = "https://files.pythonhosted.org/packages/c7/03/2fc4e14c7bd4ff2964b74ba90ecb8552540b6315f201df70f137faa5c589/numpy-2.4.4-cp314-cp314t-win_amd64.whl", hash = "sha256:a7164afb23be6e37ad90b2f10426149fd75aee07ca55653d2aa41e66c4ef697e", size = 12637755, upload-time = "2026-03-29T13:21:31.107Z" },
+ { url = "https://files.pythonhosted.org/packages/58/78/548fb8e07b1a341746bfbecb32f2c268470f45fa028aacdbd10d9bc73aab/numpy-2.4.4-cp314-cp314t-win_arm64.whl", hash = "sha256:ba203255017337d39f89bdd58417f03c4426f12beed0440cfd933cb15f8669c7", size = 10566643, upload-time = "2026-03-29T13:21:34.339Z" },
+ { url = "https://files.pythonhosted.org/packages/6b/33/8fae8f964a4f63ed528264ddf25d2b683d0b663e3cba26961eb838a7c1bd/numpy-2.4.4-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:58c8b5929fcb8287cbd6f0a3fae19c6e03a5c48402ae792962ac465224a629a4", size = 16854491, upload-time = "2026-03-29T13:21:38.03Z" },
+ { url = "https://files.pythonhosted.org/packages/bc/d0/1aabee441380b981cf8cdda3ae7a46aa827d1b5a8cce84d14598bc94d6d9/numpy-2.4.4-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:eea7ac5d2dce4189771cedb559c738a71512768210dc4e4753b107a2048b3d0e", size = 14895830, upload-time = "2026-03-29T13:21:41.509Z" },
+ { url = "https://files.pythonhosted.org/packages/a5/b8/aafb0d1065416894fccf4df6b49ef22b8db045187949545bced89c034b8e/numpy-2.4.4-pp311-pypy311_pp73-macosx_14_0_arm64.whl", hash = "sha256:51fc224f7ca4d92656d5a5eb315f12eb5fe2c97a66249aa7b5f562528a3be38c", size = 5400927, upload-time = "2026-03-29T13:21:44.747Z" },
+ { url = "https://files.pythonhosted.org/packages/d6/77/063baa20b08b431038c7f9ff5435540c7b7265c78cf56012a483019ca72d/numpy-2.4.4-pp311-pypy311_pp73-macosx_14_0_x86_64.whl", hash = "sha256:28a650663f7314afc3e6ec620f44f333c386aad9f6fc472030865dc0ebb26ee3", size = 6715557, upload-time = "2026-03-29T13:21:47.406Z" },
+ { url = "https://files.pythonhosted.org/packages/c7/a8/379542d45a14f149444c5c4c4e7714707239ce9cc1de8c2803958889da14/numpy-2.4.4-pp311-pypy311_pp73-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:19710a9ca9992d7174e9c52f643d4272dcd1558c5f7af7f6f8190f633bd651a7", size = 15804253, upload-time = "2026-03-29T13:21:50.753Z" },
+ { url = "https://files.pythonhosted.org/packages/a2/c8/f0a45426d6d21e7ea3310a15cf90c43a14d9232c31a837702dba437f3373/numpy-2.4.4-pp311-pypy311_pp73-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9b2aec6af35c113b05695ebb5749a787acd63cafc83086a05771d1e1cd1e555f", size = 16753552, upload-time = "2026-03-29T13:21:54.344Z" },
+ { url = "https://files.pythonhosted.org/packages/04/74/f4c001f4714c3ad9ce037e18cf2b9c64871a84951eaa0baf683a9ca9301c/numpy-2.4.4-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:f2cf083b324a467e1ab358c105f6cad5ea950f50524668a80c486ff1db24e119", size = 12509075, upload-time = "2026-03-29T13:21:57.644Z" },
+]
+
+[[package]]
+name = "opencv-python"
+version = "4.13.0.92"
+source = { registry = "https://pypi.org/simple" }
+dependencies = [
+ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" },
+ { name = "numpy", version = "2.4.4", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" },
+]
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/fc/6f/5a28fef4c4a382be06afe3938c64cc168223016fa520c5abaf37e8862aa5/opencv_python-4.13.0.92-cp37-abi3-macosx_13_0_arm64.whl", hash = "sha256:caf60c071ec391ba51ed00a4a920f996d0b64e3e46068aac1f646b5de0326a19", size = 46247052, upload-time = "2026-02-05T07:01:25.046Z" },
+ { url = "https://files.pythonhosted.org/packages/08/ac/6c98c44c650b8114a0fb901691351cfb3956d502e8e9b5cd27f4ee7fbf2f/opencv_python-4.13.0.92-cp37-abi3-macosx_14_0_x86_64.whl", hash = "sha256:5868a8c028a0b37561579bfb8ac1875babdc69546d236249fff296a8c010ccf9", size = 32568781, upload-time = "2026-02-05T07:01:41.379Z" },
+ { url = "https://files.pythonhosted.org/packages/3e/51/82fed528b45173bf629fa44effb76dff8bc9f4eeaee759038362dfa60237/opencv_python-4.13.0.92-cp37-abi3-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0bc2596e68f972ca452d80f444bc404e08807d021fbba40df26b61b18e01838a", size = 47685527, upload-time = "2026-02-05T06:59:11.24Z" },
+ { url = "https://files.pythonhosted.org/packages/db/07/90b34a8e2cf9c50fe8ed25cac9011cde0676b4d9d9c973751ac7616223a2/opencv_python-4.13.0.92-cp37-abi3-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:402033cddf9d294693094de5ef532339f14ce821da3ad7df7c9f6e8316da32cf", size = 70460872, upload-time = "2026-02-05T06:59:19.162Z" },
+ { url = "https://files.pythonhosted.org/packages/02/6d/7a9cc719b3eaf4377b9c2e3edeb7ed3a81de41f96421510c0a169ca3cfd4/opencv_python-4.13.0.92-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:bccaabf9eb7f897ca61880ce2869dcd9b25b72129c28478e7f2a5e8dee945616", size = 46708208, upload-time = "2026-02-05T06:59:15.419Z" },
+ { url = "https://files.pythonhosted.org/packages/fd/55/b3b49a1b97aabcfbbd6c7326df9cb0b6fa0c0aefa8e89d500939e04aa229/opencv_python-4.13.0.92-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:620d602b8f7d8b8dab5f4b99c6eb353e78d3fb8b0f53db1bd258bb1aa001c1d5", size = 72927042, upload-time = "2026-02-05T06:59:23.389Z" },
+ { url = "https://files.pythonhosted.org/packages/fb/17/de5458312bcb07ddf434d7bfcb24bb52c59635ad58c6e7c751b48949b009/opencv_python-4.13.0.92-cp37-abi3-win32.whl", hash = "sha256:372fe164a3148ac1ca51e5f3ad0541a4a276452273f503441d718fab9c5e5f59", size = 30932638, upload-time = "2026-02-05T07:02:14.98Z" },
+ { url = "https://files.pythonhosted.org/packages/e9/a5/1be1516390333ff9be3a9cb648c9f33df79d5096e5884b5df71a588af463/opencv_python-4.13.0.92-cp37-abi3-win_amd64.whl", hash = "sha256:423d934c9fafb91aad38edf26efb46da91ffbc05f3f59c4b0c72e699720706f5", size = 40212062, upload-time = "2026-02-05T07:02:12.724Z" },
+]
+
+[[package]]
+name = "pyarrow"
+version = "24.0.0"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/91/13/13e1069b351bdc3881266e11147ffccf687505dbb0ea74036237f5d454a5/pyarrow-24.0.0.tar.gz", hash = "sha256:85fe721a14dd823aca09127acbb06c3ca723efbd436c004f16bca601b04dcc83", size = 1180261, upload-time = "2026-04-21T10:51:25.837Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/a5/bf/a34fee1d624152124fa8355c42f34195ad5fe5233ce5bb87946432047d52/pyarrow-24.0.0-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:7c2b98645d576a0b9616892ead22b64a83a5f043c5e2ca15ebcefcb5b70c80cb", size = 35076681, upload-time = "2026-04-21T08:51:46.845Z" },
+ { url = "https://files.pythonhosted.org/packages/1d/41/64180033d7027afce12dc96d0fe1f504c6fa112190582b458acea2399530/pyarrow-24.0.0-cp310-cp310-macosx_12_0_x86_64.whl", hash = "sha256:644a246325b8c69c595ad1dd4b463eba4b0cdb731370e4a86137d433208d6147", size = 36684260, upload-time = "2026-04-21T08:51:53.642Z" },
+ { url = "https://files.pythonhosted.org/packages/57/02/9b9320e673dd8a99411fac78690f3df92f6dd6f59754c750110bca66d64e/pyarrow-24.0.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:3a577bd840ca83f646f0a625dbc571dba7044c43c2d1503afc378b570954345c", size = 45698566, upload-time = "2026-04-21T10:46:02.133Z" },
+ { url = "https://files.pythonhosted.org/packages/67/33/f75e91b9a64c3f33c787e263c93b871ad91b8a4a68c1d5cebddd9840e835/pyarrow-24.0.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:e3268e43984d0b1a185c89b4cfff282a7ead12fc93f56cfd7088bdbcbe727041", size = 48835562, upload-time = "2026-04-21T10:46:10.278Z" },
+ { url = "https://files.pythonhosted.org/packages/a5/63/097510448e47e4091faa41c43ba92f97cecaab8f4535b56a3d149578f634/pyarrow-24.0.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:2392d954fcb920f42d230284b677605e4e2fbb11f2821e823e642abd67fbb491", size = 49394997, upload-time = "2026-04-21T10:46:18.08Z" },
+ { url = "https://files.pythonhosted.org/packages/60/6b/c047d6222ab279024a062742d1807e2fbaf27bba88a98637299ff47b9236/pyarrow-24.0.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:bec9373df11544592b0ba7ec2af0e35059e5f0e7647c6183a854dedd193298f1", size = 51911424, upload-time = "2026-04-21T10:46:25.347Z" },
+ { url = "https://files.pythonhosted.org/packages/3a/ba/464cc70761c2a525d97ebd84e21c31ebd47f3ef4bdcee117009f51c46f24/pyarrow-24.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:c42ab9439498270139cc63e18847a02afe5c8b3ed9c931266533cfe378bd3591", size = 27251730, upload-time = "2026-04-21T10:46:30.913Z" },
+ { url = "https://files.pythonhosted.org/packages/62/c9/a47ab7ece0d86cbe6678418a0fbd1ac4bb493b9184a3891dfa0e7f287ae0/pyarrow-24.0.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:b0e131f880cda8d04e076cee175a46fc0e8bc8b65c99c6c09dff6669335fde74", size = 35068898, upload-time = "2026-04-21T10:46:36.599Z" },
+ { url = "https://files.pythonhosted.org/packages/d1/bc/8db86617a9a58008acf8913d6fed68ea2a46acb6de928db28d724c891a68/pyarrow-24.0.0-cp311-cp311-macosx_12_0_x86_64.whl", hash = "sha256:1b2fe7f9a5566401a0ef2571f197eb92358925c1f0c8dba305d6e43ea0871bb3", size = 36679915, upload-time = "2026-04-21T10:46:42.602Z" },
+ { url = "https://files.pythonhosted.org/packages/eb/8e/fb178720400ef69db251eb4a9c3ccf4af269bc1feb5055529b8fc87170d1/pyarrow-24.0.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:0b3537c00fb8d384f15ac1e79b6eb6db04a16514c8c1d22e59a9b95c8ba42868", size = 45697931, upload-time = "2026-04-21T10:46:48.403Z" },
+ { url = "https://files.pythonhosted.org/packages/f3/27/99c42abe8e21b44f4917f62631f3aa31404882a2c41d8a4cd5c110e13d52/pyarrow-24.0.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:14e31a3c9e35f1ab6356c6378f6f72830e6d2d5f1791df3774a7b097d18a6a1e", size = 48837449, upload-time = "2026-04-21T10:46:55.329Z" },
+ { url = "https://files.pythonhosted.org/packages/36/b6/333749e2666e9032891125bf9c691146e92901bece62030ac1430e2e7c88/pyarrow-24.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b7d9a514e73bc42711e6a35aaccf3587c520024fe0a25d830a1a8a27c15f4f57", size = 49395949, upload-time = "2026-04-21T10:47:01.869Z" },
+ { url = "https://files.pythonhosted.org/packages/17/25/c5201706a2dd374e8ba6ee3fd7a8c89fb7ffc16eed5217a91fd2bd7f7626/pyarrow-24.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b196eb3f931862af3fa84c2a253514d859c08e0d8fe020e07be12e75a5a9780c", size = 51912986, upload-time = "2026-04-21T10:47:09.872Z" },
+ { url = "https://files.pythonhosted.org/packages/f8/d2/4d1bbba65320b21a49678d6fbdc6ff7c649251359fdcfc03568c4136231d/pyarrow-24.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:35405aecb474e683fb36af650618fd5340ee5471fc65a21b36076a18bbc6c981", size = 27255371, upload-time = "2026-04-21T10:47:15.943Z" },
+ { url = "https://files.pythonhosted.org/packages/b4/a9/9686d9f07837f91f775e8932659192e02c74f9d8920524b480b85212cc68/pyarrow-24.0.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:6233c9ed9ab9d1db47de57d9753256d9dcffbf42db341576099f0fd9f6bf4810", size = 34981559, upload-time = "2026-04-21T10:47:22.17Z" },
+ { url = "https://files.pythonhosted.org/packages/80/b6/0ddf0e9b6ead3474ab087ae598c76b031fc45532bf6a63f3a553440fb258/pyarrow-24.0.0-cp312-cp312-macosx_12_0_x86_64.whl", hash = "sha256:f7616236ec1bc2b15bfdec22a71ab38851c86f8f05ff64f379e1278cf20c634a", size = 36663654, upload-time = "2026-04-21T10:47:28.315Z" },
+ { url = "https://files.pythonhosted.org/packages/7c/3b/926382efe8ce27ba729071d3566ade6dfb86bdf112f366000196b2f5780a/pyarrow-24.0.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:1617043b99bd33e5318ae18eb2919af09c71322ef1ca46566cdafc6e6712fb66", size = 45679394, upload-time = "2026-04-21T10:47:34.821Z" },
+ { url = "https://files.pythonhosted.org/packages/b3/7a/829f7d9dfd37c207206081d6dad474d81dde29952401f07f2ba507814818/pyarrow-24.0.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:6165461f55ef6314f026de6638d661188e3455d3ec49834556a0ebbdbace18bb", size = 48863122, upload-time = "2026-04-21T10:47:42.056Z" },
+ { url = "https://files.pythonhosted.org/packages/5f/e8/f88ce625fe8babaae64e8db2d417c7653adb3019b08aae85c5ed787dc816/pyarrow-24.0.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:3b13dedfe76a0ad2d1d859b0811b53827a4e9d93a0bcb05cf59333ab4980cc7e", size = 49376032, upload-time = "2026-04-21T10:47:48.967Z" },
+ { url = "https://files.pythonhosted.org/packages/36/7a/82c363caa145fff88fb475da50d3bf52bb024f61917be5424c3392eaf878/pyarrow-24.0.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:25ea65d868eb04015cd18e6df2fbe98f07e5bda2abefabcb88fce39a947716f6", size = 51929490, upload-time = "2026-04-21T10:47:55.981Z" },
+ { url = "https://files.pythonhosted.org/packages/66/1c/e3e72c8014ad2743ca64a701652c733cc5cbcee15c0463a32a8c55518d9e/pyarrow-24.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:295f0a7f2e242dabd513737cf076007dc5b2d59237e3eca37b05c0c6446f3826", size = 27355660, upload-time = "2026-04-21T10:48:01.718Z" },
+ { url = "https://files.pythonhosted.org/packages/6f/d3/a1abf004482026ddc17f4503db227787fa3cfe41ec5091ff20e4fea55e57/pyarrow-24.0.0-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:02b001b3ed4723caa44f6cd1af2d5c86aa2cf9971dacc2ffa55b21237713dfba", size = 34976759, upload-time = "2026-04-21T10:48:07.258Z" },
+ { url = "https://files.pythonhosted.org/packages/4f/4a/34f0a36d28a2dd32225301b79daad44e243dc1a2bb77d43b60749be255c4/pyarrow-24.0.0-cp313-cp313-macosx_12_0_x86_64.whl", hash = "sha256:04920d6a71aabd08a0417709efce97d45ea8e6fb733d9ca9ecffb13c67839f68", size = 36658471, upload-time = "2026-04-21T10:48:13.347Z" },
+ { url = "https://files.pythonhosted.org/packages/1f/78/543b94712ae8bb1a6023bcc1acf1a740fbff8286747c289cd9468fced2a5/pyarrow-24.0.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:a964266397740257f16f7bb2e4f08a0c81454004beab8ff59dd531b73610e9f2", size = 45675981, upload-time = "2026-04-21T10:48:20.201Z" },
+ { url = "https://files.pythonhosted.org/packages/84/9f/8fb7c222b100d314137fa40ec050de56cd8c6d957d1cfff685ce72f15b17/pyarrow-24.0.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:6f066b179d68c413374294bc1735f68475457c933258df594443bb9d88ddc2a0", size = 48859172, upload-time = "2026-04-21T10:48:27.541Z" },
+ { url = "https://files.pythonhosted.org/packages/a7/d3/1ea72538e6c8b3b475ed78d1049a2c518e655761ea50fe1171fc855fcab7/pyarrow-24.0.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:1183baeb14c5f587b1ec52831e665718ce632caab84b7cd6b85fd44f96114495", size = 49385733, upload-time = "2026-04-21T10:48:34.7Z" },
+ { url = "https://files.pythonhosted.org/packages/c3/be/c3d8b06a1ba35f2260f8e1f771abbee7d5e345c0937aab90675706b1690a/pyarrow-24.0.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:806f24b4085453c197a5078218d1ee08783ebbba271badd153d1ae22a3ee804f", size = 51934335, upload-time = "2026-04-21T10:48:42.099Z" },
+ { url = "https://files.pythonhosted.org/packages/9c/62/89e07a1e7329d2cde3e3c6994ba0839a24977a2beda8be6005ea3d860b99/pyarrow-24.0.0-cp313-cp313-win_amd64.whl", hash = "sha256:e4505fc6583f7b05ab854934896bcac8253b04ac1171a77dfb73efef92076d91", size = 27271748, upload-time = "2026-04-21T10:49:42.532Z" },
+ { url = "https://files.pythonhosted.org/packages/17/1a/cff3a59f80b5b1658549d46611b67163f65e0664431c076ad728bf9d5af4/pyarrow-24.0.0-cp313-cp313t-macosx_12_0_arm64.whl", hash = "sha256:1a4e45017efbf115032e4475ee876d525e0e36c742214fbe405332480ecd6275", size = 35238554, upload-time = "2026-04-21T10:48:48.526Z" },
+ { url = "https://files.pythonhosted.org/packages/a8/99/cce0f42a327bfef2c420fb6078a3eb834826e5d6697bf3009fe11d2ad051/pyarrow-24.0.0-cp313-cp313t-macosx_12_0_x86_64.whl", hash = "sha256:7986f1fa71cee060ad00758bcc79d3a93bab8559bf978fab9e53472a2e25a17b", size = 36782301, upload-time = "2026-04-21T10:48:55.181Z" },
+ { url = "https://files.pythonhosted.org/packages/2a/66/8e560d5ff6793ca29aca213c53eec0dd482dd46cb93b2819e5aab52e4252/pyarrow-24.0.0-cp313-cp313t-manylinux_2_28_aarch64.whl", hash = "sha256:d3e0b61e8efb24ed38898e5cdc5fffa9124be480008d401a1f8071500494ae42", size = 45721929, upload-time = "2026-04-21T10:49:03.676Z" },
+ { url = "https://files.pythonhosted.org/packages/27/0c/a26e25505d030716e078d9f16eb74973cbf0b33b672884e9f9da1c83b871/pyarrow-24.0.0-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:55a3bc1e3df3b5567b7d27ef551b2283f0c68a5e86f1cd56abc569da4f31335b", size = 48825365, upload-time = "2026-04-21T10:49:11.714Z" },
+ { url = "https://files.pythonhosted.org/packages/5f/eb/771f9ecb0c65e73fe9dccdd1717901b9594f08c4515d000c7c62df573811/pyarrow-24.0.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:641f795b361874ac9da5294f8f443dfdbee355cf2bd9e3b8d97aaac2306b9b37", size = 49451819, upload-time = "2026-04-21T10:49:21.474Z" },
+ { url = "https://files.pythonhosted.org/packages/48/da/61ae89a88732f5a785646f3ec6125dbb640fa98a540eb2b9889caa561403/pyarrow-24.0.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:8adc8e6ce5fccf5dc707046ae4914fd537def529709cc0d285d37a7f9cd442ca", size = 51909252, upload-time = "2026-04-21T10:49:31.164Z" },
+ { url = "https://files.pythonhosted.org/packages/cb/1a/8dd5cafab7b66573fa91c03d06d213356ad4edd71813aa75e08ce2b3a844/pyarrow-24.0.0-cp313-cp313t-win_amd64.whl", hash = "sha256:9b18371ad2f44044b81a8d23bc2d8a9b6a6226dca775e8e16cfee640473d6c5d", size = 27388127, upload-time = "2026-04-21T10:49:37.334Z" },
+ { url = "https://files.pythonhosted.org/packages/ad/80/d022a34ff05d2cbedd8ccf841fc1f532ecfa9eb5ed1711b56d0e0ea71fc9/pyarrow-24.0.0-cp314-cp314-macosx_12_0_arm64.whl", hash = "sha256:1cc9057f0319e26333b357e17f3c2c022f1a83739b48a88b25bfd5fa2dc18838", size = 35007997, upload-time = "2026-04-21T10:49:48.796Z" },
+ { url = "https://files.pythonhosted.org/packages/1a/ff/f01485fda6f4e5d441afb8dd5e7681e4db18826c1e271852f5d3957d6a80/pyarrow-24.0.0-cp314-cp314-macosx_12_0_x86_64.whl", hash = "sha256:e6f1278ee4785b6db21229374a1c9e54ec7c549de5d1efc9630b6207de7e170b", size = 36678720, upload-time = "2026-04-21T10:49:55.858Z" },
+ { url = "https://files.pythonhosted.org/packages/9e/c2/2d2d5fea814237923f71b36495211f20b43a1576f9a4d6da7e751a64ec6f/pyarrow-24.0.0-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:adbbedc55506cbdabb830890444fb856bfb0060c46c6f8026c6c2f2cf86ae795", size = 45741852, upload-time = "2026-04-21T10:50:04.624Z" },
+ { url = "https://files.pythonhosted.org/packages/8e/3a/28ba9c1c1ebdbb5f1b94dfebb46f207e52e6a554b7fe4132540fde29a3a0/pyarrow-24.0.0-cp314-cp314-manylinux_2_28_x86_64.whl", hash = "sha256:ae8a1145af31d903fa9bb166824d7abe9b4681a000b0159c9fb99c11bc11ad26", size = 48889852, upload-time = "2026-04-21T10:50:12.293Z" },
+ { url = "https://files.pythonhosted.org/packages/df/51/4a389acfd31dca009f8fb82d7f510bb4130f2b3a8e18cf00194d0687d8ac/pyarrow-24.0.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:d7027eba1df3b2069e2e8d80f644fa0918b68c46432af3d088ddd390d063ecde", size = 49445207, upload-time = "2026-04-21T10:50:20.677Z" },
+ { url = "https://files.pythonhosted.org/packages/19/4b/0bab2b23d2ae901b1b9a03c0efd4b2d070256f8ce3fc43f6e58c167b2081/pyarrow-24.0.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:e56a1ffe9bf7b727432b89104cc0849c21582949dd7bdcb34f17b2001a351a76", size = 51954117, upload-time = "2026-04-21T10:50:29.14Z" },
+ { url = "https://files.pythonhosted.org/packages/29/88/f4e9145da0417b3d2c12035a8492b35ff4a3dbc653e614fcfb51d9dedb38/pyarrow-24.0.0-cp314-cp314-win_amd64.whl", hash = "sha256:38be1808cdd068605b787e6ca9119b27eb275a0234e50212c3492331680c3b1e", size = 28001155, upload-time = "2026-04-21T10:51:22.337Z" },
+ { url = "https://files.pythonhosted.org/packages/79/4f/46a49a63f43526da895b1a45bbb51d5baf8e4d77159f8528fc3e5490007f/pyarrow-24.0.0-cp314-cp314t-macosx_12_0_arm64.whl", hash = "sha256:418e48ce50a45a6a6c73c454677203a9c75c966cb1e92ca3370959185f197a05", size = 35250387, upload-time = "2026-04-21T10:50:35.552Z" },
+ { url = "https://files.pythonhosted.org/packages/a0/da/d5e0cd5ef00796922404806d5f00325cdadc3441ce2c13fe7115f2df9a64/pyarrow-24.0.0-cp314-cp314t-macosx_12_0_x86_64.whl", hash = "sha256:2f16197705a230a78270cdd4ea8a1d57e86b2fdcbc34a1f6aebc72e65c986f9a", size = 36797102, upload-time = "2026-04-21T10:50:42.417Z" },
+ { url = "https://files.pythonhosted.org/packages/34/c7/5904145b0a593a05236c882933d439b5720f0a145381179063722fbfc123/pyarrow-24.0.0-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:fb24ac194bfc5e86839d7dcd52092ee31e5fe6733fe11f5e3b06ef0812b20072", size = 45745118, upload-time = "2026-04-21T10:50:49.324Z" },
+ { url = "https://files.pythonhosted.org/packages/13/d3/cca42fe166d1c6e4d5b80e530b7949104d10e17508a90ae202dac205ce2a/pyarrow-24.0.0-cp314-cp314t-manylinux_2_28_x86_64.whl", hash = "sha256:9700ebd9a51f5895ce75ff4ac4b3c47a7d4b42bc618be8e713e5d56bacf5f931", size = 48844765, upload-time = "2026-04-21T10:50:55.579Z" },
+ { url = "https://files.pythonhosted.org/packages/b0/49/942c3b79878ba928324d1e17c274ed84581db8c0a749b24bcf4cbdf15bd3/pyarrow-24.0.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:d8ddd2768da81d3ee08cfea9b597f4abb4e8e1dc8ae7e204b608d23a0d3ab699", size = 49471890, upload-time = "2026-04-21T10:51:02.439Z" },
+ { url = "https://files.pythonhosted.org/packages/76/97/ff71431000a75d84135a1ace5ca4ba11726a231a8007bbb320a4c54075d5/pyarrow-24.0.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:61a3d7eaa97a14768b542f3d284dc6400dd2470d9f080708b13cd46b6ae18136", size = 51932250, upload-time = "2026-04-21T10:51:10.576Z" },
+ { url = "https://files.pythonhosted.org/packages/51/be/6f79d55816d5c22557cf27533543d5d70dfe692adfbee4b99f2760674f38/pyarrow-24.0.0-cp314-cp314t-win_amd64.whl", hash = "sha256:c91d00057f23b8d353039520dc3a6c09d8608164c692e9f59a175a42b2ae0c19", size = 28131282, upload-time = "2026-04-21T10:51:16.815Z" },
+]
+
+[[package]]
+name = "pyyaml"
+version = "6.0.3"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/05/8e/961c0007c59b8dd7729d542c61a4d537767a59645b82a0b521206e1e25c2/pyyaml-6.0.3.tar.gz", hash = "sha256:d76623373421df22fb4cf8817020cbb7ef15c725b9d5e45f17e189bfc384190f", size = 130960, upload-time = "2025-09-25T21:33:16.546Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/f4/a0/39350dd17dd6d6c6507025c0e53aef67a9293a6d37d3511f23ea510d5800/pyyaml-6.0.3-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:214ed4befebe12df36bcc8bc2b64b396ca31be9304b8f59e25c11cf94a4c033b", size = 184227, upload-time = "2025-09-25T21:31:46.04Z" },
+ { url = "https://files.pythonhosted.org/packages/05/14/52d505b5c59ce73244f59c7a50ecf47093ce4765f116cdb98286a71eeca2/pyyaml-6.0.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:02ea2dfa234451bbb8772601d7b8e426c2bfa197136796224e50e35a78777956", size = 174019, upload-time = "2025-09-25T21:31:47.706Z" },
+ { url = "https://files.pythonhosted.org/packages/43/f7/0e6a5ae5599c838c696adb4e6330a59f463265bfa1e116cfd1fbb0abaaae/pyyaml-6.0.3-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b30236e45cf30d2b8e7b3e85881719e98507abed1011bf463a8fa23e9c3e98a8", size = 740646, upload-time = "2025-09-25T21:31:49.21Z" },
+ { url = "https://files.pythonhosted.org/packages/2f/3a/61b9db1d28f00f8fd0ae760459a5c4bf1b941baf714e207b6eb0657d2578/pyyaml-6.0.3-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:66291b10affd76d76f54fad28e22e51719ef9ba22b29e1d7d03d6777a9174198", size = 840793, upload-time = "2025-09-25T21:31:50.735Z" },
+ { url = "https://files.pythonhosted.org/packages/7a/1e/7acc4f0e74c4b3d9531e24739e0ab832a5edf40e64fbae1a9c01941cabd7/pyyaml-6.0.3-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9c7708761fccb9397fe64bbc0395abcae8c4bf7b0eac081e12b809bf47700d0b", size = 770293, upload-time = "2025-09-25T21:31:51.828Z" },
+ { url = "https://files.pythonhosted.org/packages/8b/ef/abd085f06853af0cd59fa5f913d61a8eab65d7639ff2a658d18a25d6a89d/pyyaml-6.0.3-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:418cf3f2111bc80e0933b2cd8cd04f286338bb88bdc7bc8e6dd775ebde60b5e0", size = 732872, upload-time = "2025-09-25T21:31:53.282Z" },
+ { url = "https://files.pythonhosted.org/packages/1f/15/2bc9c8faf6450a8b3c9fc5448ed869c599c0a74ba2669772b1f3a0040180/pyyaml-6.0.3-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:5e0b74767e5f8c593e8c9b5912019159ed0533c70051e9cce3e8b6aa699fcd69", size = 758828, upload-time = "2025-09-25T21:31:54.807Z" },
+ { url = "https://files.pythonhosted.org/packages/a3/00/531e92e88c00f4333ce359e50c19b8d1de9fe8d581b1534e35ccfbc5f393/pyyaml-6.0.3-cp310-cp310-win32.whl", hash = "sha256:28c8d926f98f432f88adc23edf2e6d4921ac26fb084b028c733d01868d19007e", size = 142415, upload-time = "2025-09-25T21:31:55.885Z" },
+ { url = "https://files.pythonhosted.org/packages/2a/fa/926c003379b19fca39dd4634818b00dec6c62d87faf628d1394e137354d4/pyyaml-6.0.3-cp310-cp310-win_amd64.whl", hash = "sha256:bdb2c67c6c1390b63c6ff89f210c8fd09d9a1217a465701eac7316313c915e4c", size = 158561, upload-time = "2025-09-25T21:31:57.406Z" },
+ { url = "https://files.pythonhosted.org/packages/6d/16/a95b6757765b7b031c9374925bb718d55e0a9ba8a1b6a12d25962ea44347/pyyaml-6.0.3-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:44edc647873928551a01e7a563d7452ccdebee747728c1080d881d68af7b997e", size = 185826, upload-time = "2025-09-25T21:31:58.655Z" },
+ { url = "https://files.pythonhosted.org/packages/16/19/13de8e4377ed53079ee996e1ab0a9c33ec2faf808a4647b7b4c0d46dd239/pyyaml-6.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:652cb6edd41e718550aad172851962662ff2681490a8a711af6a4d288dd96824", size = 175577, upload-time = "2025-09-25T21:32:00.088Z" },
+ { url = "https://files.pythonhosted.org/packages/0c/62/d2eb46264d4b157dae1275b573017abec435397aa59cbcdab6fc978a8af4/pyyaml-6.0.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:10892704fc220243f5305762e276552a0395f7beb4dbf9b14ec8fd43b57f126c", size = 775556, upload-time = "2025-09-25T21:32:01.31Z" },
+ { url = "https://files.pythonhosted.org/packages/10/cb/16c3f2cf3266edd25aaa00d6c4350381c8b012ed6f5276675b9eba8d9ff4/pyyaml-6.0.3-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:850774a7879607d3a6f50d36d04f00ee69e7fc816450e5f7e58d7f17f1ae5c00", size = 882114, upload-time = "2025-09-25T21:32:03.376Z" },
+ { url = "https://files.pythonhosted.org/packages/71/60/917329f640924b18ff085ab889a11c763e0b573da888e8404ff486657602/pyyaml-6.0.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b8bb0864c5a28024fac8a632c443c87c5aa6f215c0b126c449ae1a150412f31d", size = 806638, upload-time = "2025-09-25T21:32:04.553Z" },
+ { url = "https://files.pythonhosted.org/packages/dd/6f/529b0f316a9fd167281a6c3826b5583e6192dba792dd55e3203d3f8e655a/pyyaml-6.0.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1d37d57ad971609cf3c53ba6a7e365e40660e3be0e5175fa9f2365a379d6095a", size = 767463, upload-time = "2025-09-25T21:32:06.152Z" },
+ { url = "https://files.pythonhosted.org/packages/f2/6a/b627b4e0c1dd03718543519ffb2f1deea4a1e6d42fbab8021936a4d22589/pyyaml-6.0.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:37503bfbfc9d2c40b344d06b2199cf0e96e97957ab1c1b546fd4f87e53e5d3e4", size = 794986, upload-time = "2025-09-25T21:32:07.367Z" },
+ { url = "https://files.pythonhosted.org/packages/45/91/47a6e1c42d9ee337c4839208f30d9f09caa9f720ec7582917b264defc875/pyyaml-6.0.3-cp311-cp311-win32.whl", hash = "sha256:8098f252adfa6c80ab48096053f512f2321f0b998f98150cea9bd23d83e1467b", size = 142543, upload-time = "2025-09-25T21:32:08.95Z" },
+ { url = "https://files.pythonhosted.org/packages/da/e3/ea007450a105ae919a72393cb06f122f288ef60bba2dc64b26e2646fa315/pyyaml-6.0.3-cp311-cp311-win_amd64.whl", hash = "sha256:9f3bfb4965eb874431221a3ff3fdcddc7e74e3b07799e0e84ca4a0f867d449bf", size = 158763, upload-time = "2025-09-25T21:32:09.96Z" },
+ { url = "https://files.pythonhosted.org/packages/d1/33/422b98d2195232ca1826284a76852ad5a86fe23e31b009c9886b2d0fb8b2/pyyaml-6.0.3-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7f047e29dcae44602496db43be01ad42fc6f1cc0d8cd6c83d342306c32270196", size = 182063, upload-time = "2025-09-25T21:32:11.445Z" },
+ { url = "https://files.pythonhosted.org/packages/89/a0/6cf41a19a1f2f3feab0e9c0b74134aa2ce6849093d5517a0c550fe37a648/pyyaml-6.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:fc09d0aa354569bc501d4e787133afc08552722d3ab34836a80547331bb5d4a0", size = 173973, upload-time = "2025-09-25T21:32:12.492Z" },
+ { url = "https://files.pythonhosted.org/packages/ed/23/7a778b6bd0b9a8039df8b1b1d80e2e2ad78aa04171592c8a5c43a56a6af4/pyyaml-6.0.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9149cad251584d5fb4981be1ecde53a1ca46c891a79788c0df828d2f166bda28", size = 775116, upload-time = "2025-09-25T21:32:13.652Z" },
+ { url = "https://files.pythonhosted.org/packages/65/30/d7353c338e12baef4ecc1b09e877c1970bd3382789c159b4f89d6a70dc09/pyyaml-6.0.3-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:5fdec68f91a0c6739b380c83b951e2c72ac0197ace422360e6d5a959d8d97b2c", size = 844011, upload-time = "2025-09-25T21:32:15.21Z" },
+ { url = "https://files.pythonhosted.org/packages/8b/9d/b3589d3877982d4f2329302ef98a8026e7f4443c765c46cfecc8858c6b4b/pyyaml-6.0.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ba1cc08a7ccde2d2ec775841541641e4548226580ab850948cbfda66a1befcdc", size = 807870, upload-time = "2025-09-25T21:32:16.431Z" },
+ { url = "https://files.pythonhosted.org/packages/05/c0/b3be26a015601b822b97d9149ff8cb5ead58c66f981e04fedf4e762f4bd4/pyyaml-6.0.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8dc52c23056b9ddd46818a57b78404882310fb473d63f17b07d5c40421e47f8e", size = 761089, upload-time = "2025-09-25T21:32:17.56Z" },
+ { url = "https://files.pythonhosted.org/packages/be/8e/98435a21d1d4b46590d5459a22d88128103f8da4c2d4cb8f14f2a96504e1/pyyaml-6.0.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:41715c910c881bc081f1e8872880d3c650acf13dfa8214bad49ed4cede7c34ea", size = 790181, upload-time = "2025-09-25T21:32:18.834Z" },
+ { url = "https://files.pythonhosted.org/packages/74/93/7baea19427dcfbe1e5a372d81473250b379f04b1bd3c4c5ff825e2327202/pyyaml-6.0.3-cp312-cp312-win32.whl", hash = "sha256:96b533f0e99f6579b3d4d4995707cf36df9100d67e0c8303a0c55b27b5f99bc5", size = 137658, upload-time = "2025-09-25T21:32:20.209Z" },
+ { url = "https://files.pythonhosted.org/packages/86/bf/899e81e4cce32febab4fb42bb97dcdf66bc135272882d1987881a4b519e9/pyyaml-6.0.3-cp312-cp312-win_amd64.whl", hash = "sha256:5fcd34e47f6e0b794d17de1b4ff496c00986e1c83f7ab2fb8fcfe9616ff7477b", size = 154003, upload-time = "2025-09-25T21:32:21.167Z" },
+ { url = "https://files.pythonhosted.org/packages/1a/08/67bd04656199bbb51dbed1439b7f27601dfb576fb864099c7ef0c3e55531/pyyaml-6.0.3-cp312-cp312-win_arm64.whl", hash = "sha256:64386e5e707d03a7e172c0701abfb7e10f0fb753ee1d773128192742712a98fd", size = 140344, upload-time = "2025-09-25T21:32:22.617Z" },
+ { url = "https://files.pythonhosted.org/packages/d1/11/0fd08f8192109f7169db964b5707a2f1e8b745d4e239b784a5a1dd80d1db/pyyaml-6.0.3-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:8da9669d359f02c0b91ccc01cac4a67f16afec0dac22c2ad09f46bee0697eba8", size = 181669, upload-time = "2025-09-25T21:32:23.673Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/16/95309993f1d3748cd644e02e38b75d50cbc0d9561d21f390a76242ce073f/pyyaml-6.0.3-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:2283a07e2c21a2aa78d9c4442724ec1eb15f5e42a723b99cb3d822d48f5f7ad1", size = 173252, upload-time = "2025-09-25T21:32:25.149Z" },
+ { url = "https://files.pythonhosted.org/packages/50/31/b20f376d3f810b9b2371e72ef5adb33879b25edb7a6d072cb7ca0c486398/pyyaml-6.0.3-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ee2922902c45ae8ccada2c5b501ab86c36525b883eff4255313a253a3160861c", size = 767081, upload-time = "2025-09-25T21:32:26.575Z" },
+ { url = "https://files.pythonhosted.org/packages/49/1e/a55ca81e949270d5d4432fbbd19dfea5321eda7c41a849d443dc92fd1ff7/pyyaml-6.0.3-cp313-cp313-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:a33284e20b78bd4a18c8c2282d549d10bc8408a2a7ff57653c0cf0b9be0afce5", size = 841159, upload-time = "2025-09-25T21:32:27.727Z" },
+ { url = "https://files.pythonhosted.org/packages/74/27/e5b8f34d02d9995b80abcef563ea1f8b56d20134d8f4e5e81733b1feceb2/pyyaml-6.0.3-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0f29edc409a6392443abf94b9cf89ce99889a1dd5376d94316ae5145dfedd5d6", size = 801626, upload-time = "2025-09-25T21:32:28.878Z" },
+ { url = "https://files.pythonhosted.org/packages/f9/11/ba845c23988798f40e52ba45f34849aa8a1f2d4af4b798588010792ebad6/pyyaml-6.0.3-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f7057c9a337546edc7973c0d3ba84ddcdf0daa14533c2065749c9075001090e6", size = 753613, upload-time = "2025-09-25T21:32:30.178Z" },
+ { url = "https://files.pythonhosted.org/packages/3d/e0/7966e1a7bfc0a45bf0a7fb6b98ea03fc9b8d84fa7f2229e9659680b69ee3/pyyaml-6.0.3-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:eda16858a3cab07b80edaf74336ece1f986ba330fdb8ee0d6c0d68fe82bc96be", size = 794115, upload-time = "2025-09-25T21:32:31.353Z" },
+ { url = "https://files.pythonhosted.org/packages/de/94/980b50a6531b3019e45ddeada0626d45fa85cbe22300844a7983285bed3b/pyyaml-6.0.3-cp313-cp313-win32.whl", hash = "sha256:d0eae10f8159e8fdad514efdc92d74fd8d682c933a6dd088030f3834bc8e6b26", size = 137427, upload-time = "2025-09-25T21:32:32.58Z" },
+ { url = "https://files.pythonhosted.org/packages/97/c9/39d5b874e8b28845e4ec2202b5da735d0199dbe5b8fb85f91398814a9a46/pyyaml-6.0.3-cp313-cp313-win_amd64.whl", hash = "sha256:79005a0d97d5ddabfeeea4cf676af11e647e41d81c9a7722a193022accdb6b7c", size = 154090, upload-time = "2025-09-25T21:32:33.659Z" },
+ { url = "https://files.pythonhosted.org/packages/73/e8/2bdf3ca2090f68bb3d75b44da7bbc71843b19c9f2b9cb9b0f4ab7a5a4329/pyyaml-6.0.3-cp313-cp313-win_arm64.whl", hash = "sha256:5498cd1645aa724a7c71c8f378eb29ebe23da2fc0d7a08071d89469bf1d2defb", size = 140246, upload-time = "2025-09-25T21:32:34.663Z" },
+ { url = "https://files.pythonhosted.org/packages/9d/8c/f4bd7f6465179953d3ac9bc44ac1a8a3e6122cf8ada906b4f96c60172d43/pyyaml-6.0.3-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:8d1fab6bb153a416f9aeb4b8763bc0f22a5586065f86f7664fc23339fc1c1fac", size = 181814, upload-time = "2025-09-25T21:32:35.712Z" },
+ { url = "https://files.pythonhosted.org/packages/bd/9c/4d95bb87eb2063d20db7b60faa3840c1b18025517ae857371c4dd55a6b3a/pyyaml-6.0.3-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:34d5fcd24b8445fadc33f9cf348c1047101756fd760b4dacb5c3e99755703310", size = 173809, upload-time = "2025-09-25T21:32:36.789Z" },
+ { url = "https://files.pythonhosted.org/packages/92/b5/47e807c2623074914e29dabd16cbbdd4bf5e9b2db9f8090fa64411fc5382/pyyaml-6.0.3-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:501a031947e3a9025ed4405a168e6ef5ae3126c59f90ce0cd6f2bfc477be31b7", size = 766454, upload-time = "2025-09-25T21:32:37.966Z" },
+ { url = "https://files.pythonhosted.org/packages/02/9e/e5e9b168be58564121efb3de6859c452fccde0ab093d8438905899a3a483/pyyaml-6.0.3-cp314-cp314-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:b3bc83488de33889877a0f2543ade9f70c67d66d9ebb4ac959502e12de895788", size = 836355, upload-time = "2025-09-25T21:32:39.178Z" },
+ { url = "https://files.pythonhosted.org/packages/88/f9/16491d7ed2a919954993e48aa941b200f38040928474c9e85ea9e64222c3/pyyaml-6.0.3-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c458b6d084f9b935061bc36216e8a69a7e293a2f1e68bf956dcd9e6cbcd143f5", size = 794175, upload-time = "2025-09-25T21:32:40.865Z" },
+ { url = "https://files.pythonhosted.org/packages/dd/3f/5989debef34dc6397317802b527dbbafb2b4760878a53d4166579111411e/pyyaml-6.0.3-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:7c6610def4f163542a622a73fb39f534f8c101d690126992300bf3207eab9764", size = 755228, upload-time = "2025-09-25T21:32:42.084Z" },
+ { url = "https://files.pythonhosted.org/packages/d7/ce/af88a49043cd2e265be63d083fc75b27b6ed062f5f9fd6cdc223ad62f03e/pyyaml-6.0.3-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:5190d403f121660ce8d1d2c1bb2ef1bd05b5f68533fc5c2ea899bd15f4399b35", size = 789194, upload-time = "2025-09-25T21:32:43.362Z" },
+ { url = "https://files.pythonhosted.org/packages/23/20/bb6982b26a40bb43951265ba29d4c246ef0ff59c9fdcdf0ed04e0687de4d/pyyaml-6.0.3-cp314-cp314-win_amd64.whl", hash = "sha256:4a2e8cebe2ff6ab7d1050ecd59c25d4c8bd7e6f400f5f82b96557ac0abafd0ac", size = 156429, upload-time = "2025-09-25T21:32:57.844Z" },
+ { url = "https://files.pythonhosted.org/packages/f4/f4/a4541072bb9422c8a883ab55255f918fa378ecf083f5b85e87fc2b4eda1b/pyyaml-6.0.3-cp314-cp314-win_arm64.whl", hash = "sha256:93dda82c9c22deb0a405ea4dc5f2d0cda384168e466364dec6255b293923b2f3", size = 143912, upload-time = "2025-09-25T21:32:59.247Z" },
+ { url = "https://files.pythonhosted.org/packages/7c/f9/07dd09ae774e4616edf6cda684ee78f97777bdd15847253637a6f052a62f/pyyaml-6.0.3-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:02893d100e99e03eda1c8fd5c441d8c60103fd175728e23e431db1b589cf5ab3", size = 189108, upload-time = "2025-09-25T21:32:44.377Z" },
+ { url = "https://files.pythonhosted.org/packages/4e/78/8d08c9fb7ce09ad8c38ad533c1191cf27f7ae1effe5bb9400a46d9437fcf/pyyaml-6.0.3-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:c1ff362665ae507275af2853520967820d9124984e0f7466736aea23d8611fba", size = 183641, upload-time = "2025-09-25T21:32:45.407Z" },
+ { url = "https://files.pythonhosted.org/packages/7b/5b/3babb19104a46945cf816d047db2788bcaf8c94527a805610b0289a01c6b/pyyaml-6.0.3-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6adc77889b628398debc7b65c073bcb99c4a0237b248cacaf3fe8a557563ef6c", size = 831901, upload-time = "2025-09-25T21:32:48.83Z" },
+ { url = "https://files.pythonhosted.org/packages/8b/cc/dff0684d8dc44da4d22a13f35f073d558c268780ce3c6ba1b87055bb0b87/pyyaml-6.0.3-cp314-cp314t-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:a80cb027f6b349846a3bf6d73b5e95e782175e52f22108cfa17876aaeff93702", size = 861132, upload-time = "2025-09-25T21:32:50.149Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/5e/f77dc6b9036943e285ba76b49e118d9ea929885becb0a29ba8a7c75e29fe/pyyaml-6.0.3-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:00c4bdeba853cc34e7dd471f16b4114f4162dc03e6b7afcc2128711f0eca823c", size = 839261, upload-time = "2025-09-25T21:32:51.808Z" },
+ { url = "https://files.pythonhosted.org/packages/ce/88/a9db1376aa2a228197c58b37302f284b5617f56a5d959fd1763fb1675ce6/pyyaml-6.0.3-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:66e1674c3ef6f541c35191caae2d429b967b99e02040f5ba928632d9a7f0f065", size = 805272, upload-time = "2025-09-25T21:32:52.941Z" },
+ { url = "https://files.pythonhosted.org/packages/da/92/1446574745d74df0c92e6aa4a7b0b3130706a4142b2d1a5869f2eaa423c6/pyyaml-6.0.3-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:16249ee61e95f858e83976573de0f5b2893b3677ba71c9dd36b9cf8be9ac6d65", size = 829923, upload-time = "2025-09-25T21:32:54.537Z" },
+ { url = "https://files.pythonhosted.org/packages/f0/7a/1c7270340330e575b92f397352af856a8c06f230aa3e76f86b39d01b416a/pyyaml-6.0.3-cp314-cp314t-win_amd64.whl", hash = "sha256:4ad1906908f2f5ae4e5a8ddfce73c320c2a1429ec52eafd27138b7f1cbe341c9", size = 174062, upload-time = "2025-09-25T21:32:55.767Z" },
+ { url = "https://files.pythonhosted.org/packages/f1/12/de94a39c2ef588c7e6455cfbe7343d3b2dc9d6b6b2f40c4c6565744c873d/pyyaml-6.0.3-cp314-cp314t-win_arm64.whl", hash = "sha256:ebc55a14a21cb14062aa4162f906cd962b28e2e9ea38f9b4391244cd8de4ae0b", size = 149341, upload-time = "2025-09-25T21:32:56.828Z" },
+]
+
+[[package]]
+name = "uv"
+version = "0.11.11"
+source = { registry = "https://pypi.org/simple" }
+sdist = { url = "https://files.pythonhosted.org/packages/ba/02/69a3b06fd8a91f95b79e95e14f5ccdd4df0f124c381aefe9d1e2784d5a65/uv-0.11.11.tar.gz", hash = "sha256:2ba46a912a1775957c579a1a42c8c8b480418502326b72427b1cad972c8f659f", size = 4112827, upload-time = "2026-05-06T20:04:47.982Z" }
+wheels = [
+ { url = "https://files.pythonhosted.org/packages/6c/54/39d3c58de992767834120fe3735b85cc60dd00a69b377c3d947ca6f172a1/uv-0.11.11-py3-none-linux_armv6l.whl", hash = "sha256:4977a1193e5dc9c2934b9f97d6cf787382f80deae17646640ee583cfc61486c0", size = 23537936, upload-time = "2026-05-06T20:04:58.626Z" },
+ { url = "https://files.pythonhosted.org/packages/de/c9/d2d7ca30abf4c2d5ae0d9360a1e154115af176308ef1ecdc8bf7af724cf8/uv-0.11.11-py3-none-macosx_10_12_x86_64.whl", hash = "sha256:92817f276758e41b4160fcb6d457ebd9f228f0473efe3808891164f326fdea38", size = 23068282, upload-time = "2026-05-06T20:05:01.466Z" },
+ { url = "https://files.pythonhosted.org/packages/fa/37/f64decba47d7afaace3f238aa4a416dca947bd0a1a9b534c3a0f179e1016/uv-0.11.11-py3-none-macosx_11_0_arm64.whl", hash = "sha256:6eec6ad051e6e5d922cd547b9f7b09a7f821597ae01900a6f01b0a01317e5fd0", size = 21671522, upload-time = "2026-05-06T20:05:04.382Z" },
+ { url = "https://files.pythonhosted.org/packages/93/a6/c129878d7c2a66ffdaa12dc253d3135c5e10fc5b5e15812791e188c6dbec/uv-0.11.11-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.musllinux_1_1_aarch64.whl", hash = "sha256:1d227bb53b701e533f0aa074dd145a6fa31492dc7d6d57a6e72a700b9a4a1991", size = 23283200, upload-time = "2026-05-06T20:04:39.879Z" },
+ { url = "https://files.pythonhosted.org/packages/8f/c2/cff1f9ab7eda3d863e9866fca0e14df37c0fd734b66ebb77d751258b2fae/uv-0.11.11-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.musllinux_1_1_armv7l.whl", hash = "sha256:05ee9f18701692fcb22db98085c041a3be7a35b88c710dea4487c293f42a4b95", size = 23081561, upload-time = "2026-05-06T20:05:07.149Z" },
+ { url = "https://files.pythonhosted.org/packages/ca/44/ebd02ca8fae5961d1bcbcee11019dd170dd0d42517afad753281335700cc/uv-0.11.11-py3-none-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:0632af539d6a1ee00f58da9e7db32fd99e12187aa67426cb90d871154ab5debb", size = 23105780, upload-time = "2026-05-06T20:04:50.107Z" },
+ { url = "https://files.pythonhosted.org/packages/86/f7/0741abcd70591a65f85fc4e8fecd3fb3fb4bdfe50042cccf016714955fd9/uv-0.11.11-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:cb3f2715551d2fc9ef44b6cf0918fcc556cd99e9bf6caa1d8a870a4657d2b180", size = 24542681, upload-time = "2026-05-06T20:04:53.014Z" },
+ { url = "https://files.pythonhosted.org/packages/b1/42/46e7e35f1f39e39d4bf0f712479768cf8d33eb7f35b67fceaea43e975dfd/uv-0.11.11-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c86bd6460579857d7e359bdbfe6f688076c654481ae933151d1449f9ea672fb6", size = 25459284, upload-time = "2026-05-06T20:04:34.168Z" },
+ { url = "https://files.pythonhosted.org/packages/e8/fc/efdb16e1a6c619b021259ac8d8e4b6afd97efb446054ea28761eb2e1a177/uv-0.11.11-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0f69f4df007c7506db8d7f77ccabd466a886ac21e9b04a479dd0cd22e26d2262", size = 24560769, upload-time = "2026-05-06T20:04:42.648Z" },
+ { url = "https://files.pythonhosted.org/packages/4c/f8/a5d5bac297b1379719050788c6b852c6b3eefcb1e82d8465ed22c10cede7/uv-0.11.11-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d5b9f31dab557b5ee4257d8c6ba2608a63c7278537cb0cd102cf6fc518e3fb5c", size = 24639659, upload-time = "2026-05-06T20:04:31.491Z" },
+ { url = "https://files.pythonhosted.org/packages/ee/d5/f3be167a43192062f1409fd6b857a612665d331174293b4ffc73218872e1/uv-0.11.11-py3-none-manylinux_2_28_aarch64.whl", hash = "sha256:8e8faf2e5b3517155fd18e509b19b21135247d43b7fb9a8d61a44a53118d5ab7", size = 23388445, upload-time = "2026-05-06T20:04:25.199Z" },
+ { url = "https://files.pythonhosted.org/packages/9f/cd/ef1f573ee8edd2beab9fcd2449121483829621b3b57f7ba3f35c56ef373b/uv-0.11.11-py3-none-manylinux_2_31_riscv64.musllinux_1_1_riscv64.whl", hash = "sha256:3f8c9a1bea743a3fe39e956455686f4d0dd25ef58e8d70dc11a45381fd7c50e5", size = 24114301, upload-time = "2026-05-06T20:04:28.586Z" },
+ { url = "https://files.pythonhosted.org/packages/9d/be/9181158465719e875a6995c10af24e00cdefba3fe6c9c8cbb02d34b2ade7/uv-0.11.11-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:f68dc7b62050a26ac6b1491398aebbbf0fa5485627e73b1d626666a097dbab07", size = 24155126, upload-time = "2026-05-06T20:04:55.98Z" },
+ { url = "https://files.pythonhosted.org/packages/71/9c/bb306f9964870847f02a931d1fff896726f8bafcf9ce917122ac1bfef14c/uv-0.11.11-py3-none-musllinux_1_1_i686.whl", hash = "sha256:29ddb0d9b24a30ff4360b94e3cb704e82cd5fda86dc224032251f33ab5ceb79e", size = 23824684, upload-time = "2026-05-06T20:05:10.305Z" },
+ { url = "https://files.pythonhosted.org/packages/56/48/434a1cf4798ca200e0dcb36411ba38013edb6d3e1aeb4cd85e8a2d7db9ca/uv-0.11.11-py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:505a31f2c30fa9e83b1853cab06c5b92e66341c914c6f20f3878903aa09a6f34", size = 24862560, upload-time = "2026-05-06T20:04:37.287Z" },
+ { url = "https://files.pythonhosted.org/packages/63/3a/997cddf82917f084d486e1c268c7e94836190fd928c93aa3fb92caee9a7f/uv-0.11.11-py3-none-win32.whl", hash = "sha256:c1e0e3e18cc94680642eac3c3f19f2635c17dd058edcb41b78cbdc459f574eb4", size = 22573619, upload-time = "2026-05-06T20:04:45.35Z" },
+ { url = "https://files.pythonhosted.org/packages/30/5f/db34b840f8d86833ef810de8150fc9ce01a03c779393e08eadbcc4c010d5/uv-0.11.11-py3-none-win_amd64.whl", hash = "sha256:36412b13f6287304789abdf40122d268cee548fce3573e07d148a29370181421", size = 25170135, upload-time = "2026-05-06T20:05:13.001Z" },
+ { url = "https://files.pythonhosted.org/packages/2d/3e/f3ba2557b437ec5b1fde1e0d5248b723432dc90f09b0050f52695596fd2e/uv-0.11.11-py3-none-win_arm64.whl", hash = "sha256:011f42faf5d267a6681ea77e3f236f275cb4490efeecb9599de74dc7ad7df8f6", size = 23597162, upload-time = "2026-05-06T20:05:16.095Z" },
+]
diff --git a/openarm_hardware/CMakeLists.txt b/openarm_hardware/CMakeLists.txt
index 1ed46920..15a23815 100644
--- a/openarm_hardware/CMakeLists.txt
+++ b/openarm_hardware/CMakeLists.txt
@@ -30,7 +30,7 @@ find_package(rclcpp_lifecycle REQUIRED)
find_package(OpenArmCAN REQUIRED)
add_library(${PROJECT_NAME} SHARED
- src/v10_simple_hardware.cpp
+ src/openarm_simple_hardware.cpp
)
target_include_directories(
diff --git a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp b/openarm_hardware/include/openarm_hardware/openarm_simple_hardware.hpp
similarity index 94%
rename from openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp
rename to openarm_hardware/include/openarm_hardware/openarm_simple_hardware.hpp
index 1130df20..60df58cc 100644
--- a/openarm_hardware/include/openarm_hardware/v10_simple_hardware.hpp
+++ b/openarm_hardware/include/openarm_hardware/openarm_simple_hardware.hpp
@@ -38,9 +38,9 @@ namespace openarm_hardware {
* following the pattern from full_arm.cpp example. Much simpler than
* the original implementation.
*/
-class OpenArm_v10HW : public hardware_interface::SystemInterface {
+class OpenArmHW : public hardware_interface::SystemInterface {
public:
- OpenArm_v10HW();
+ OpenArmHW();
TEMPLATES__ROS2_CONTROL__VISIBILITY_PUBLIC
hardware_interface::CallbackReturn on_init(
@@ -117,6 +117,7 @@ class OpenArm_v10HW : public hardware_interface::SystemInterface {
// Configuration
std::string can_interface_;
std::string arm_prefix_;
+ std::string ee_type_;
bool hand_;
bool can_fd_;
@@ -134,6 +135,16 @@ class OpenArm_v10HW : public hardware_interface::SystemInterface {
std::vector vel_states_;
std::vector tau_states_;
+ static constexpr std::array ZERO_POSITION = {
+ 0.0, // joint1
+ 0.0, // joint2
+ 0.0, // joint3
+ 0.0, // joint4
+ 0.0, // joint5
+ 0.0, // joint6
+ 0.0, // joint7
+ };
+
// Helper methods
void return_to_zero();
bool parse_config(const hardware_interface::HardwareInfo& info);
diff --git a/openarm_hardware/openarm_hardware.xml b/openarm_hardware/openarm_hardware.xml
index fd4fee92..83315567 100644
--- a/openarm_hardware/openarm_hardware.xml
+++ b/openarm_hardware/openarm_hardware.xml
@@ -15,11 +15,11 @@
-->
-
- ros2_control hardware interface for OpenArm V10.
+ ros2_control hardware interface for OpenArm .
diff --git a/openarm_hardware/src/v10_simple_hardware.cpp b/openarm_hardware/src/openarm_simple_hardware.cpp
similarity index 68%
rename from openarm_hardware/src/v10_simple_hardware.cpp
rename to openarm_hardware/src/openarm_simple_hardware.cpp
index 2ddaeacb..9321c4a8 100644
--- a/openarm_hardware/src/v10_simple_hardware.cpp
+++ b/openarm_hardware/src/openarm_simple_hardware.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "openarm_hardware/v10_simple_hardware.hpp"
+#include "openarm_hardware/openarm_simple_hardware.hpp"
#include
#include
@@ -26,9 +26,9 @@
namespace openarm_hardware {
-OpenArm_v10HW::OpenArm_v10HW() = default;
+OpenArmHW::OpenArmHW() = default;
-bool OpenArm_v10HW::parse_config(const hardware_interface::HardwareInfo& info) {
+bool OpenArmHW::parse_config(const hardware_interface::HardwareInfo& info) {
// Parse CAN interface (default: can0)
auto it = info.hardware_parameters.find("can_interface");
can_interface_ = (it != info.hardware_parameters.end()) ? it->second : "can0";
@@ -71,6 +71,10 @@ bool OpenArm_v10HW::parse_config(const hardware_interface::HardwareInfo& info) {
kd_[i - 1] = std::stod(it->second);
}
}
+ // Parse ee_type (default: parallel_link for v10)
+ it = info.hardware_parameters.find("ee_type");
+ ee_type_ =
+ (it != info.hardware_parameters.end()) ? it->second : "parallel_link";
if (hand_) {
it = info.hardware_parameters.find("kp_hand");
if (it != info.hardware_parameters.end()) {
@@ -82,14 +86,14 @@ bool OpenArm_v10HW::parse_config(const hardware_interface::HardwareInfo& info) {
}
}
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"),
"Configuration: CAN=%s, arm_prefix=%s, hand=%s, can_fd=%s",
can_interface_.c_str(), arm_prefix_.c_str(),
hand_ ? "enabled" : "disabled", can_fd_ ? "enabled" : "disabled");
return true;
}
-void OpenArm_v10HW::generate_joint_names() {
+void OpenArmHW::generate_joint_names() {
joint_names_.clear();
// TODO: read from urdf properly and sort in the future.
// Currently, the joint names are hardcoded for order consistency to align
@@ -104,19 +108,19 @@ void OpenArm_v10HW::generate_joint_names() {
if (hand_) {
std::string gripper_joint_name = "openarm_" + arm_prefix_ + "finger_joint1";
joint_names_.push_back(gripper_joint_name);
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "Added gripper joint: %s",
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Added gripper joint: %s",
gripper_joint_name.c_str());
} else {
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"),
"Gripper joint NOT added because hand_=false");
}
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"),
"Generated %zu joint names for arm prefix '%s'",
joint_names_.size(), arm_prefix_.c_str());
}
-hardware_interface::CallbackReturn OpenArm_v10HW::on_init(
+hardware_interface::CallbackReturn OpenArmHW::on_init(
const hardware_interface::HardwareInfo& info) {
if (hardware_interface::SystemInterface::on_init(info) !=
CallbackReturn::SUCCESS) {
@@ -133,14 +137,14 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_init(
// Validate joint count (7 arm joints + optional gripper)
size_t expected_joints = ARM_DOF + (hand_ ? 1 : 0);
if (joint_names_.size() != expected_joints) {
- RCLCPP_ERROR(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_ERROR(rclcpp::get_logger("OpenArmHW"),
"Generated %zu joint names, expected %zu", joint_names_.size(),
expected_joints);
return CallbackReturn::ERROR;
}
// Initialize OpenArm with configurable CAN-FD setting
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"),
"Initializing OpenArm on %s with CAN-FD %s...",
can_interface_.c_str(), can_fd_ ? "enabled" : "disabled");
openarm_ =
@@ -152,7 +156,7 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_init(
// Initialize gripper if enabled
if (hand_) {
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "Initializing gripper...");
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Initializing gripper...");
openarm_->init_gripper_motor(DEFAULT_GRIPPER_MOTOR_TYPE,
DEFAULT_GRIPPER_SEND_CAN_ID,
DEFAULT_GRIPPER_RECV_CAN_ID);
@@ -167,13 +171,13 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_init(
vel_states_.resize(total_joints, 0.0);
tau_states_.resize(total_joints, 0.0);
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"),
"OpenArm V10 Simple HW initialized successfully");
return CallbackReturn::SUCCESS;
}
-hardware_interface::CallbackReturn OpenArm_v10HW::on_configure(
+hardware_interface::CallbackReturn OpenArmHW::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
// Set callback mode to ignore during configuration
openarm_->refresh_all();
@@ -184,7 +188,7 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_configure(
}
std::vector
-OpenArm_v10HW::export_state_interfaces() {
+OpenArmHW::export_state_interfaces() {
std::vector state_interfaces;
for (size_t i = 0; i < joint_names_.size(); ++i) {
state_interfaces.emplace_back(hardware_interface::StateInterface(
@@ -199,7 +203,7 @@ OpenArm_v10HW::export_state_interfaces() {
}
std::vector
-OpenArm_v10HW::export_command_interfaces() {
+OpenArmHW::export_command_interfaces() {
std::vector command_interfaces;
// TODO: consider exposing only needed interfaces to avoid undefined behavior.
for (size_t i = 0; i < joint_names_.size(); ++i) {
@@ -216,9 +220,9 @@ OpenArm_v10HW::export_command_interfaces() {
return command_interfaces;
}
-hardware_interface::CallbackReturn OpenArm_v10HW::on_activate(
+hardware_interface::CallbackReturn OpenArmHW::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "Activating OpenArm V10...");
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Activating OpenArm V10...");
openarm_->set_callback_mode_all(openarm::damiao_motor::CallbackMode::STATE);
openarm_->enable_all();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
@@ -227,25 +231,26 @@ hardware_interface::CallbackReturn OpenArm_v10HW::on_activate(
// Return to zero position
return_to_zero();
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "OpenArm V10 activated");
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "OpenArm V10 activated");
return CallbackReturn::SUCCESS;
}
-hardware_interface::CallbackReturn OpenArm_v10HW::on_deactivate(
+hardware_interface::CallbackReturn OpenArmHW::on_deactivate(
const rclcpp_lifecycle::State& /*previous_state*/) {
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
- "Deactivating OpenArm V10...");
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Deactivating OpenArm V10...");
// Disable all motors (like full_arm.cpp exit)
- openarm_->disable_all();
- std::this_thread::sleep_for(std::chrono::milliseconds(100));
- openarm_->recv_all();
+ for (int i = 0; i < 3; ++i) {
+ openarm_->disable_all();
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ openarm_->recv_all();
+ }
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"), "OpenArm V10 deactivated");
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "OpenArm V10 deactivated");
return CallbackReturn::SUCCESS;
}
-hardware_interface::return_type OpenArm_v10HW::read(
+hardware_interface::return_type OpenArmHW::read(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// Receive all motor states
openarm_->refresh_all();
@@ -277,7 +282,7 @@ hardware_interface::return_type OpenArm_v10HW::read(
return hardware_interface::return_type::OK;
}
-hardware_interface::return_type OpenArm_v10HW::write(
+hardware_interface::return_type OpenArmHW::write(
const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) {
// Control arm motors with MIT control
std::vector arm_params;
@@ -293,14 +298,14 @@ hardware_interface::return_type OpenArm_v10HW::write(
openarm_->get_gripper().mit_control_all(
{{gripper_kp_, gripper_kd_, motor_command, 0.0, 0.0}});
}
- openarm_->recv_all(1000);
+ openarm_->recv_all(100);
return hardware_interface::return_type::OK;
}
-void OpenArm_v10HW::return_to_zero() {
- RCLCPP_INFO(rclcpp::get_logger("OpenArm_v10HW"),
- "Returning to zero position...");
+void OpenArmHW::return_to_zero() {
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Returning to zero position...");
+ openarm_->refresh_all();
// Return arm to zero with MIT control
std::vector arm_params;
for (size_t i = 0; i < ARM_DOF; ++i) {
@@ -315,25 +320,95 @@ void OpenArm_v10HW::return_to_zero() {
}
std::this_thread::sleep_for(std::chrono::microseconds(1000));
openarm_->recv_all();
+ const auto& arm_motors = openarm_->get_arm().get_motors();
+
+ std::vector start_pos(ARM_DOF, 0.0);
+ for (size_t i = 0; i < ARM_DOF && i < arm_motors.size(); ++i) {
+ start_pos[i] = arm_motors[i].get_position();
+ }
+
+ const int steps = 200;
+ const int step_ms = 10;
+
+ for (int step = 0; step <= steps; ++step) {
+ double t = static_cast(step) / steps; // 0.0 → 1.0
+
+ std::vector arm_params;
+ for (size_t i = 0; i < ARM_DOF; ++i) {
+ double target = start_pos[i] + t * (ZERO_POSITION[i] - start_pos[i]);
+ arm_params.push_back({kp_[i], kd_[i], target, 0.0, 0.0});
+ }
+ openarm_->get_arm().mit_control_all(arm_params);
+
+ if (hand_) {
+ openarm_->get_gripper().mit_control_all(
+ {{GRIPPER_KP, GRIPPER_KD, GRIPPER_JOINT_0_POSITION, 0.0, 0.0}});
+ }
+
+ openarm_->recv_all();
+ std::this_thread::sleep_for(std::chrono::milliseconds(step_ms));
+ }
+
+ RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Reached zero position");
}
-// Gripper mapping helper functions
-double OpenArm_v10HW::joint_to_motor_radians(double joint_value) {
- // Joint 0=closed -> motor 0 rad, Joint 0.044=open -> motor -1.0472 rad
- return (joint_value / GRIPPER_JOINT_0_POSITION) *
- GRIPPER_MOTOR_1_RADIANS; // Scale from 0-0.044 to 0 to -1.0472
+// void OpenArmHW::return_to_zero() {
+// RCLCPP_INFO(rclcpp::get_logger("OpenArmHW"), "Returning to zero
+// position...");
+
+// // Return arm to zero with MIT control
+// std::vector arm_params;
+// for (size_t i = 0; i < ARM_DOF; ++i) {
+// arm_params.push_back({kp_[i], kd_[i], 0.0, 0.0, 0.0});
+// }
+// openarm_->get_arm().mit_control_all(arm_params);
+
+// // Return gripper to zero if enabled
+// if (hand_) {
+// openarm_->get_gripper().mit_control_all(
+// {{GRIPPER_KP, GRIPPER_KD, GRIPPER_JOINT_0_POSITION, 0.0, 0.0}});
+// }
+// std::this_thread::sleep_for(std::chrono::microseconds(1000));
+// openarm_->recv_all();
+// }
+
+double OpenArmHW::joint_to_motor_radians(double joint_value) {
+ if (ee_type_ == "pinch_gripper") {
+ // revolute: joint 0-1.5708 rad -> motor 0-1.5708
+ return joint_value;
+ } else {
+ // parallel_link (prismatic): 0-0.044m -> 0 to -1.0472 rad
+ return (joint_value / GRIPPER_JOINT_0_POSITION) * GRIPPER_MOTOR_1_RADIANS;
+ }
}
-double OpenArm_v10HW::motor_radians_to_joint(double motor_radians) {
- // Motor 0 rad=closed -> joint 0, Motor -1.0472 rad=open -> joint 0.044
- return GRIPPER_JOINT_0_POSITION *
- (motor_radians /
- GRIPPER_MOTOR_1_RADIANS); // Scale from 0 to -1.0472 to 0-0.044
+double OpenArmHW::motor_radians_to_joint(double motor_radians) {
+ if (ee_type_ == "pinch_gripper") {
+ // revolute:
+ return motor_radians;
+ } else {
+ // parallel_link (prismatic)
+ return GRIPPER_JOINT_0_POSITION * (motor_radians / GRIPPER_MOTOR_1_RADIANS);
+ }
}
+// // Gripper mapping helper functions
+// double OpenArmHW::joint_to_motor_radians(double joint_value) {
+// // Joint 0=closed -> motor 0 rad, Joint 0.044=open -> motor -1.0472 rad
+// return (joint_value / GRIPPER_JOINT_0_POSITION) *
+// GRIPPER_MOTOR_1_RADIANS; // Scale from 0-0.044 to 0 to -1.0472
+// }
+
+// double OpenArmHW::motor_radians_to_joint(double motor_radians) {
+// // Motor 0 rad=closed -> joint 0, Motor -1.0472 rad=open -> joint 0.044
+// return GRIPPER_JOINT_0_POSITION *
+// (motor_radians /
+// GRIPPER_MOTOR_1_RADIANS); // Scale from 0 to -1.0472 to 0-0.044
+// }
+
} // namespace openarm_hardware
#include "pluginlib/class_list_macros.hpp"
-PLUGINLIB_EXPORT_CLASS(openarm_hardware::OpenArm_v10HW,
+PLUGINLIB_EXPORT_CLASS(openarm_hardware::OpenArmHW,
hardware_interface::SystemInterface)