From c2b4ce2a97e588643c07af85b9f0e90daa52ad4a Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Mon, 13 Jan 2025 16:34:27 -0500 Subject: [PATCH 01/42] Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (#228) * Remove Gazebo Classic support * Move the repos * Add to not released repos list as well * Fix the Robotiq params * Fix request adapters in ompl_planning.yaml * Fix the 6DOF too * Actually fix the configs now * Switch fake to mock * Remove one more unnecessary dependency * Add gz_ros2_control to rolling repos * Other renames * Fix .repos files * Skip the gz_ros2_control rosdep key in Humble CI * More fixes to get CI working * Use main branch of ros2_robotiq_gripper and fix gazebo paths * Additional needed modifications * Final Modifications * Formatting Modifications --------- Co-authored-by: Abed Al Rahman Al Mrad --- .github/workflows/humble-binary-build.yml | 1 + README.md | 29 +++--- kortex_bringup/launch/gen3_lite.launch.py | 2 +- .../launch/kortex_sim_control.launch.py | 90 ++++++------------- kortex_bringup/package.xml | 3 +- .../arms/gen3/6dof/urdf/gen3_macro.xacro | 2 - .../gen3/6dof/urdf/kortex.ros2_control.xacro | 8 +- .../arms/gen3/7dof/urdf/gen3_macro.xacro | 6 +- .../gen3/7dof/urdf/kortex.ros2_control.xacro | 10 +-- .../6dof/config/ros2_controllers.yaml | 4 +- .../gen3_lite/6dof/urdf/gen3_lite_macro.xacro | 8 +- .../6dof/urdf/kortex.ros2_control.xacro | 12 +-- .../urdf/gen3_lite_2f.ros2_control.xacro | 18 ++-- .../urdf/gen3_lite_2f_macro.xacro | 14 +-- .../urdf/robotiq_2f_140_macro.xacro | 8 +- .../urdf/robotiq_2f_85_macro.xacro | 8 +- kortex_description/package.xml | 1 + kortex_description/readme.md | 4 +- kortex_description/robots/gen3.xacro | 4 +- .../robots/gen3_lite_gen3_lite_2f.xacro | 2 - kortex_description/robots/kinova.urdf.xacro | 23 ++--- kortex_description/robots/kortex_robot.xacro | 4 +- .../config/ompl_planning.yaml | 41 +++------ .../launch/sim.launch.py | 8 +- .../package.xml | 5 +- .../config/ompl_planning.yaml | 41 +++------ .../launch/sim.launch.py | 8 +- .../package.xml | 5 +- .../launch/sim.launch.py | 8 +- ...os => ros2_kortex-not-released.jazzy.repos | 6 +- ros2_kortex-not-released.rolling.repos | 8 -- ...ex.humble.repos => ros2_kortex.jazzy.repos | 12 ++- ros2_kortex.repos | 2 +- ...ion.humble.repos => simulation.jazzy.repos | 15 +--- simulation.repos | 22 ++--- 35 files changed, 153 insertions(+), 289 deletions(-) rename ros2_kortex-not-released.humble.repos => ros2_kortex-not-released.jazzy.repos (71%) rename ros2_kortex.humble.repos => ros2_kortex.jazzy.repos (67%) rename simulation.humble.repos => simulation.jazzy.repos (52%) diff --git a/.github/workflows/humble-binary-build.yml b/.github/workflows/humble-binary-build.yml index 4e0c2276..a7984242 100644 --- a/.github/workflows/humble-binary-build.yml +++ b/.github/workflows/humble-binary-build.yml @@ -24,6 +24,7 @@ jobs: - {ROS_DISTRO: humble, ROS_REPO: testing} env: UPSTREAM_WORKSPACE: ros2_kortex-not-released.${{ matrix.env.ROS_DISTRO }}.repos + ROSDEP_SKIP_KEYS: gz_ros2_control CCACHE_DIR: ${{ github.workspace }}/.ccache BASEDIR: ${{ github.workspace }}/.work CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }} diff --git a/README.md b/README.md index bda52628..83a0d9b7 100644 --- a/README.md +++ b/README.md @@ -113,9 +113,10 @@ If the bug fix you need isn't in a released version or If you want to build this vcs import src --skip-existing --input src/ros2_kortex/ros2_kortex-not-released.$ROS_DISTRO.repos ``` - If you plan on simulating the robot with ignition or gazebo, make sure to pull the additional simulation packages. If you're on ROS2 Humble, run + If you plan on simulating the robot with Gazebo, make sure to pull the additional simulation packages. + If you're on ROS 2 Humble, run ``` - vcs import src --skip-existing --input src/ros2_kortex/simulation.humble.repos + vcs import src --skip-existing --input src/ros2_kortex/simulation.jazzy.repos ``` otherwise @@ -125,12 +126,10 @@ If the bug fix you need isn't in a released version or If you want to build this If you plan on using MoveIt, you must make sure that you have it already [installed](https://moveit.ros.org/install-moveit2/binary/) either from binaries or by building it from source. - If you plan on simulating the Gen3 7Dof robot mounted on the Husky mobile robot from clearpath, make sure to pull the additional related packages. On ROS2 Humble, run - ``` - vcs import src --skip-existing --input src/ros2_kortex/clearpath.repos - ``` -4. Install dependencies, compile, and source the workspace: +4. Follow the instructions to install [Gazebo Harmonic](https://gazebosim.org/docs/harmonic/getstarted/) + +5. Install dependencies, compile, and source the workspace: ``` rosdep install --ignore-src --from-paths src -y -r colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release @@ -140,7 +139,7 @@ If the bug fix you need isn't in a released version or If you want to build this ``` colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --parallel-workers 3 ``` -5. Source the previously built workspace using the following command: +6. Source the previously built workspace using the following command: ``` echo 'source ~/workspace/ros2_kortex_ws/install/setup.bash' >> ~/.bashrc ``` @@ -215,7 +214,7 @@ You can specify the following arguments if you wish to change your arm configura * `robot_type`: Your robot model. Default value (and only one) is `gen3`. -* `gripper` : Gripper to use. Possible values for the Gen3 are either `robotiq_2f_85`, `robotiq_2f_140` or `""`. Default is `robotiq_2f_85`. An empty string will not initialise any gripper. +* `gripper` : Gripper to use. Possible values for the Gen3 are either `robotiq_2f_85`, `robotiq_2f_140` or `""`. Default is `""`. An empty string will not initialise any gripper. * `gripper_joint_name` : Name of the controlled joint of the gripper attached to the arm. Default value is `robotiq_85_left_knuckle_joint`. @@ -308,11 +307,11 @@ The `kortex_sim_control.launch.py` launch file is designed to simulate all of ou ```bash ros2 launch kortex_bringup kortex_sim_control.launch.py \ use_sim_time:=true \ - launch_rviz:=false + launch_rviz:=false \ + robot_controller:=joint_trajectory_controller ``` -* `sim_ignition` : Use Ignition for simulation. Default value is `true`. -* `sim_gazebo` : Use Gazebo Classic for simulation. Default value is `false`. +* `sim_gazebo` : Use Gazebo for simulation. Default value is `false`. * `robot_type` : Your robot model. Possible values are either `gen3` or `gen3_lite`.Default is `gen3`. * `robot_name` : Name you would like your robot to have. Default value is `gen3`. * `dof` : Degrees of freedom of the arm. Possible values are either `6` or `7`.Default value is `7`. @@ -325,9 +324,9 @@ ros2 launch kortex_bringup kortex_sim_control.launch.py \ * `description_file` : URDF/XACRO description file with the robot. Default value is `kinova.urdf.xacro`. * `prefix` : Prefix of the joint names, useful for multi-robot setup. If changed, then also joint names in the controllers' configuration have to be updated. Default value is `""` (none). * `use_sim_time` : Use simulated clock. Default value is `true`. -* `gripper` : Gripper to use. Possible values for the Gen3 are either `robotiq_2f_85`, `robotiq_2f_140` or `""`. Default is `robotiq_2f_85`. An empty string will not initialise any gripper. +* `gripper` : Gripper to use. Possible values for the Gen3 are: `robotiq_2f_85`, `robotiq_2f_140`, `""` and `gen3_lite_2f`. Default is `robotiq_2f_85`. An empty string will not initialise any gripper. -#### MoveIt2 +#### MoveIt 2 To generate motion plans and execute them with a simulated 7 DoF Kinova Gen3 arm with mock hardware: @@ -345,7 +344,7 @@ ros2 launch kinova_gen3_6dof_robotiq_2f_85_moveit_config robot.launch.py \ use_fake_hardware:=true ``` -To generate motion plans and execute them with an ignition simulated 7 DoF Kinova Gen3 arm (previously launched with the command at the [simulation](#simulation) section): +To generate motion plans and execute them with a Gazebo simulated 7 DoF Kinova Gen3 arm (previously launched with the command at the [simulation](#simulation) section): ```bash ros2 launch kinova_gen3_7dof_robotiq_2f_85_moveit_config sim.launch.py \ diff --git a/kortex_bringup/launch/gen3_lite.launch.py b/kortex_bringup/launch/gen3_lite.launch.py index 5eb1d3d4..844114db 100644 --- a/kortex_bringup/launch/gen3_lite.launch.py +++ b/kortex_bringup/launch/gen3_lite.launch.py @@ -61,7 +61,7 @@ def generate_launch_description(): declared_arguments.append( DeclareLaunchArgument( "robot_controller", - default_value="gen3_lite_joint_trajectory_controller", + default_value="joint_trajectory_controller", description="Robot controller to start.", ) ) diff --git a/kortex_bringup/launch/kortex_sim_control.launch.py b/kortex_bringup/launch/kortex_sim_control.launch.py index e33034f6..5d50503a 100644 --- a/kortex_bringup/launch/kortex_sim_control.launch.py +++ b/kortex_bringup/launch/kortex_sim_control.launch.py @@ -14,10 +14,12 @@ # # Author: Marq Rasmussen +import os +from ament_index_python.packages import get_package_prefix from launch import LaunchDescription from launch.actions import ( + AppendEnvironmentVariable, DeclareLaunchArgument, - ExecuteProcess, IncludeLaunchDescription, OpaqueFunction, RegisterEventHandler, @@ -38,7 +40,6 @@ def launch_setup(context, *args, **kwargs): # Initialize Arguments sim_gazebo = LaunchConfiguration("sim_gazebo") - sim_ignition = LaunchConfiguration("sim_ignition") robot_type = LaunchConfiguration("robot_type") dof = LaunchConfiguration("dof") vision = LaunchConfiguration("vision") @@ -97,9 +98,6 @@ def launch_setup(context, *args, **kwargs): "sim_gazebo:=", sim_gazebo, " ", - "sim_ignition:=", - sim_ignition, - " ", "simulation_controllers:=", robot_controllers, " ", @@ -171,7 +169,7 @@ def launch_setup(context, *args, **kwargs): condition=UnlessCondition(is_gen3_lite), ) - robot_hand_controller_spawner = Node( + robot_hand_lite_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=[robot_lite_hand_controller, "-c", "/controller_manager"], @@ -182,42 +180,16 @@ def launch_setup(context, *args, **kwargs): bridge = Node( package="ros_gz_bridge", executable="parameter_bridge", - arguments=["/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock"], - output="screen", - ) - - # Gazebo nodes - gzserver = ExecuteProcess( - cmd=["gzserver", "-s", "libgazebo_ros_init.so", "-s", "libgazebo_ros_factory.so", ""], + arguments=["/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"], output="screen", - condition=IfCondition(sim_gazebo), ) - # Gazebo client - gzclient = ExecuteProcess( - cmd=["gzclient"], - output="screen", - condition=IfCondition(sim_gazebo), - ) - - # gazebo = IncludeLaunchDescription( - # PythonLaunchDescriptionSource( - # [PathJoinSubstitution([FindPackageShare("gazebo_ros"), "launch", "gazebo.launch.py"])] - # ), - # launch_arguments={"verbose": "false"}.items(), - # ) - - # Spawn robot - gazebo_spawn_robot = Node( - package="gazebo_ros", - executable="spawn_entity.py", - name="spawn_robot", - arguments=["-entity", robot_name, "-topic", "robot_description"], - output="screen", - condition=IfCondition(sim_gazebo), + robotiq_description_prefix = get_package_prefix("robotiq_description") + gz_robotiq_env_var_resource_path = AppendEnvironmentVariable( + "GZ_SIM_RESOURCE_PATH", os.path.join(robotiq_description_prefix, "share") ) - ignition_spawn_entity = Node( + gz_spawn_entity = Node( package="ros_gz_sim", executable="create", output="screen", @@ -241,15 +213,17 @@ def launch_setup(context, *args, **kwargs): "-Y", "0.0", ], - condition=IfCondition(sim_ignition), + condition=IfCondition(sim_gazebo), ) - ignition_launch_description = IncludeLaunchDescription( + gz_launch_description = IncludeLaunchDescription( PythonLaunchDescriptionSource( [FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"] ), - launch_arguments={"ign_args": " -r -v 3 empty.sdf"}.items(), - condition=IfCondition(sim_ignition), + launch_arguments={ + "gz_args": " -r -v 3 empty.sdf --physics-engine gz-physics-bullet-featherstone-plugin" + }.items(), + condition=IfCondition(sim_gazebo), ) # Bridge @@ -258,10 +232,10 @@ def launch_setup(context, *args, **kwargs): executable="parameter_bridge", parameters=[{"use_sim_time": use_sim_time}], arguments=[ - "/wrist_mounted_camera/image@sensor_msgs/msg/Image[ignition.msgs.Image", - "/wrist_mounted_camera/depth_image@sensor_msgs/msg/Image[ignition.msgs.Image", - "/wrist_mounted_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked", - "/wrist_mounted_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", + "/wrist_mounted_camera/image@sensor_msgs/msg/Image[gz.msgs.Image", + "/wrist_mounted_camera/depth_image@sensor_msgs/msg/Image[gz.msgs.Image", + "/wrist_mounted_camera/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked", + "/wrist_mounted_camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo", ], output="screen", ) @@ -274,11 +248,10 @@ def launch_setup(context, *args, **kwargs): robot_traj_controller_spawner, robot_pos_controller_spawner, robot_hand_controller_spawner, - gzserver, - gzclient, - gazebo_spawn_robot, - ignition_launch_description, - ignition_spawn_entity, + robot_hand_lite_controller_spawner, + gz_robotiq_env_var_resource_path, + gz_launch_description, + gz_spawn_entity, gazebo_bridge, ] @@ -288,18 +261,11 @@ def launch_setup(context, *args, **kwargs): def generate_launch_description(): declared_arguments = [] # Simulation specific arguments - declared_arguments.append( - DeclareLaunchArgument( - "sim_ignition", - default_value="true", - description="Use Ignition for simulation", - ) - ) declared_arguments.append( DeclareLaunchArgument( "sim_gazebo", - default_value="false", - description="Use Gazebo Classic for simulation", + default_value="true", + description="Use Gazebo for simulation", ) ) # Robot specific arguments @@ -369,7 +335,7 @@ def generate_launch_description(): declared_arguments.append( DeclareLaunchArgument( "robot_controller", - default_value="gen3_lite_joint_trajectory_controller", + default_value="joint_trajectory_controller", description="Robot controller to start.", ) ) @@ -404,8 +370,8 @@ def generate_launch_description(): declared_arguments.append( DeclareLaunchArgument( "gripper", - default_value="robotiq_2f_85", - choices=["robotiq_2f_85", "robotiq_2f_140", "gen3_lite_2f"], + default_value="", + choices=["robotiq_2f_85", "robotiq_2f_140", "gen3_lite_2f", ""], description="Gripper to use", ) ) diff --git a/kortex_bringup/package.xml b/kortex_bringup/package.xml index 2742ebd1..f8648b02 100644 --- a/kortex_bringup/package.xml +++ b/kortex_bringup/package.xml @@ -22,13 +22,14 @@ rviz2 urdf xacro - gazebo_ros2_control gripper_controllers joint_trajectory_controller joint_state_broadcaster robotiq_description kortex_description kortex_driver + ros_gz_bridge + ros_gz_sim ament_cmake diff --git a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro index d3387924..8a568ff9 100644 --- a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro @@ -26,7 +26,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -41,7 +40,6 @@ use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" sim_gazebo="${sim_gazebo}" - sim_ignition="${sim_ignition}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" diff --git a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro index e2b631f8..24503529 100644 --- a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro @@ -7,7 +7,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -29,10 +28,7 @@ - gazebo_ros2_control/GazeboSystem - - - ign_ros2_control/IgnitionSystem + gz_ros2_control/GazeboSimSystem topic_based_ros2_control/TopicBasedSystem @@ -44,7 +40,7 @@ ${fake_sensor_commands} 0.0 - + kortex_driver/KortexMultiInterfaceHardware ${robot_ip} ${username} diff --git a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro index 90a05f38..c647a04c 100644 --- a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro @@ -26,7 +26,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -41,7 +40,6 @@ use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" sim_gazebo="${sim_gazebo}" - sim_ignition="${sim_ignition}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" @@ -452,7 +450,7 @@ - + @@ -472,7 +470,7 @@ - + diff --git a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro index e85bbdfb..0524907b 100644 --- a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro @@ -7,7 +7,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -29,10 +28,7 @@ - gazebo_ros2_control/GazeboSystem - - - ign_ros2_control/IgnitionSystem + gz_ros2_control/GazeboSimSystem topic_based_ros2_control/TopicBasedSystem @@ -44,7 +40,7 @@ ${fake_sensor_commands} 0.0 - + kortex_driver/KortexMultiInterfaceHardware ${robot_ip} ${username} @@ -137,7 +133,7 @@ - + diff --git a/kortex_description/arms/gen3_lite/6dof/config/ros2_controllers.yaml b/kortex_description/arms/gen3_lite/6dof/config/ros2_controllers.yaml index b1dbf1e6..665c9c3c 100644 --- a/kortex_description/arms/gen3_lite/6dof/config/ros2_controllers.yaml +++ b/kortex_description/arms/gen3_lite/6dof/config/ros2_controllers.yaml @@ -5,7 +5,7 @@ controller_manager: joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster - gen3_lite_joint_trajectory_controller: + joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController twist_controller: @@ -17,7 +17,7 @@ controller_manager: gen3_lite_2f_gripper_controller: type: position_controllers/GripperActionController -gen3_lite_joint_trajectory_controller: +joint_trajectory_controller: ros__parameters: joints: - joint_1 diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro index 998e1bce..47616e3f 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro @@ -25,7 +25,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -35,9 +34,9 @@ - + - + @@ -45,7 +44,7 @@ - + @@ -58,7 +57,6 @@ use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" sim_gazebo="${sim_gazebo}" - sim_ignition="${sim_ignition}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro index f7a3f19b..5b909bb6 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro @@ -7,7 +7,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -30,12 +29,7 @@ - gazebo_ros2_control/GazeboSystem - - - - - ign_ros2_control/IgnitionSystem + gz_ros2_control/GazeboSimSystem @@ -52,7 +46,7 @@ 0.0 - + kortex_driver/KortexMultiInterfaceHardware ${robot_ip} @@ -151,7 +145,7 @@ - + diff --git a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro index d671ce3a..1712fde0 100644 --- a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro +++ b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro @@ -5,7 +5,7 @@ prefix use_fake_hardware:=false fake_sensor_commands:=false - sim_ignition:=false + sim_gazebo:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -30,15 +30,15 @@ ${isaac_joint_states} 0.02 - - ign_ros2_control/IgnitionSystem + + gz_ros2_control/GzSimSystem mock_components/GenericSystem ${fake_sensor_commands} 0.0 - + kortex_driver/KortexMultiInterfaceHardware ${robot_ip} ${username} @@ -56,7 +56,7 @@ - + @@ -67,11 +67,11 @@ - + ${prefix}right_finger_bottom_joint -1 - + @@ -80,7 +80,7 @@ ${prefix}right_finger_bottom_joint -1 - + @@ -89,7 +89,7 @@ ${prefix}right_finger_bottom_joint -1 - + diff --git a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro index 55f03507..3bf45914 100644 --- a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro +++ b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro @@ -7,24 +7,24 @@ com_port use_fake_hardware:=false fake_sensor_commands:=false - sim_ignition:=false + sim_gazebo:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states use_internal_bus_gripper_comm:=true moveit_active:=false"> - + - - + + - + @@ -32,7 +32,7 @@ prefix="${prefix}" use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" - sim_ignition="${sim_ignition}" + sim_gazebo="${sim_gazebo}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" @@ -215,7 +215,7 @@ - + diff --git a/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro b/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro index bb54731b..16d0241d 100644 --- a/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro +++ b/kortex_description/grippers/robotiq_2f_140/urdf/robotiq_2f_140_macro.xacro @@ -5,7 +5,7 @@ prefix use_fake_hardware:=false fake_sensor_commands:=false - sim_ignition:=false + sim_gazebo:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -16,7 +16,7 @@ - + @@ -27,8 +27,8 @@ include_ros2_control="${include_ros2_control}" com_port="${com_port}" use_fake_hardware="${use_fake_hardware}" - fake_sensor_commands="${fake_sensor_commands}" - sim_ignition="${sim_ignition}" + mock_sensor_commands="${fake_sensor_commands}" + sim_gazebo="${sim_gazebo}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}"> diff --git a/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro b/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro index cbf7f42f..9ff28785 100644 --- a/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro +++ b/kortex_description/grippers/robotiq_2f_85/urdf/robotiq_2f_85_macro.xacro @@ -5,7 +5,7 @@ prefix use_fake_hardware:=false fake_sensor_commands:=false - sim_ignition:=false + sim_gazebo:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -16,7 +16,7 @@ - + @@ -27,8 +27,8 @@ include_ros2_control="${include_ros2_control}" com_port="${com_port}" use_fake_hardware="${use_fake_hardware}" - fake_sensor_commands="${fake_sensor_commands}" - sim_ignition="${sim_ignition}" + mock_sensor_commands="${fake_sensor_commands}" + sim_gazebo="${sim_gazebo}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}"> diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 1fbbd82a..0d363214 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -15,6 +15,7 @@ for Kortex arms and supported grippers

ament_cmake + gz_ros2_control joint_state_publisher_gui joint_state_publisher joint_trajectory_controller diff --git a/kortex_description/readme.md b/kortex_description/readme.md index 56e57d78..74241404 100644 --- a/kortex_description/readme.md +++ b/kortex_description/readme.md @@ -55,8 +55,7 @@ Param | Description | Default | `use_internal_bus_gripper_comm` | Boolean value to indicate if your gripper will be communicated with through the internal Kinova communication interface. Set to true if the gripper is directly plugged into the kinova arm. Set to false if running in simulation or if gripper is connected to PC via USB. Setting to false will create a ros2_control instance for the gripper. | false | `use_fake_hardware` | Boolean value to indicate whether or not the hardware components will be mocked. If true the hardware params will be ignored and the hardware components will be mocked. | false | `fake_sensor_commands` | Boolean value. If set to true will create fake command interfaces for faking sensor measurements with an external command. | false | -`sim_gazebo` | Boolean value to indicate whether or not the gazebo_ros2_control/GazeboSystem plugin will be loaded. | false | -`sim_ignition` | Boolean value to indicate whether or not the ign_ros2_control/IgnitionSystem plugin will be loaded. | false | +`sim_gazebo` | Boolean value to indicate whether or not the gz_ros2_control/GazeboSimSystem plugin will be loaded. | false | `sim_isaac` | Boolean value to indicate whether or not the topic_based_ros2_control/TopicBasedSystem plugin will be loaded and the "joint_commands_topic" and "joint_states_topic" parameters will be set to the `isaac_joint_commands` and `isaac_joint_states` values respectively. | false | `isaac_joint_commands` | Name of the joint commands topic to be used by Isaac Sim. | /isaac_joint_commands | `isaac_joint_states` | Name of the joint states topic to be used by Isaac Sim. | /isaac_joint_states | @@ -88,7 +87,6 @@ Param | Description | Default | connection_inactivity_timeout_ms="2000" use_internal_bus_gripper_comm="true" sim_gazebo="false" - sim_ignition="false" sim_isaac="false" prefix="" use_fake_hardware="false" diff --git a/kortex_description/robots/gen3.xacro b/kortex_description/robots/gen3.xacro index 9527825c..8b0b586a 100644 --- a/kortex_description/robots/gen3.xacro +++ b/kortex_description/robots/gen3.xacro @@ -18,7 +18,6 @@ - @@ -27,7 +26,7 @@ - + @@ -53,7 +52,6 @@ use_fake_hardware="$(arg use_fake_hardware)" fake_sensor_commands="$(arg fake_sensor_commands)" sim_gazebo="$(arg sim_gazebo)" - sim_ignition="$(arg sim_ignition)" sim_isaac="$(arg sim_isaac)" use_external_cable="$(arg use_external_cable)" initial_positions="${xacro.load_yaml(initial_positions_file)}" > diff --git a/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro b/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro index 39eaf908..cbbcd839 100644 --- a/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro +++ b/kortex_description/robots/gen3_lite_gen3_lite_2f.xacro @@ -18,7 +18,6 @@ - @@ -51,7 +50,6 @@ use_fake_hardware="$(arg use_fake_hardware)" fake_sensor_commands="$(arg fake_sensor_commands)" sim_gazebo="$(arg sim_gazebo)" - sim_ignition="$(arg sim_ignition)" sim_isaac="$(arg sim_isaac)" use_external_cable="$(arg use_external_cable)" moveit_active = "$(arg moveit_active)" > diff --git a/kortex_description/robots/kinova.urdf.xacro b/kortex_description/robots/kinova.urdf.xacro index eacc4e15..61f52148 100644 --- a/kortex_description/robots/kinova.urdf.xacro +++ b/kortex_description/robots/kinova.urdf.xacro @@ -24,7 +24,6 @@ - @@ -36,7 +35,7 @@ - + @@ -66,7 +65,6 @@ use_fake_hardware="$(arg use_fake_hardware)" fake_sensor_commands="$(arg fake_sensor_commands)" sim_gazebo="$(arg sim_gazebo)" - sim_ignition="$(arg sim_ignition)" sim_isaac="$(arg sim_isaac)" initial_positions="${xacro.load_yaml(initial_positions_file)}" moveit_active="$(arg moveit_active)"> @@ -78,22 +76,11 @@ - - $(arg simulation_controllers) - - -
- - - - - - - + $(arg simulation_controllers) $(arg prefix)controller_manager - + $(arg gazebo_renderer) @@ -127,7 +114,7 @@ 0 + Gazebo will default to different default values --> 554.25469 554.25469 @@ -150,7 +137,7 @@ color_optical_frame - camera_color_frame + camera_color_frame 1 $(arg camera_fps) true diff --git a/kortex_description/robots/kortex_robot.xacro b/kortex_description/robots/kortex_robot.xacro index f89c6f57..b9ac9adf 100644 --- a/kortex_description/robots/kortex_robot.xacro +++ b/kortex_description/robots/kortex_robot.xacro @@ -22,7 +22,6 @@ use_fake_hardware:=false fake_sensor_commands:=false sim_gazebo:=false - sim_ignition:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states @@ -53,7 +52,6 @@ use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" sim_gazebo="${sim_gazebo}" - sim_ignition="${sim_ignition}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" @@ -86,7 +84,7 @@ prefix="${prefix}" use_fake_hardware="${use_fake_hardware}" fake_sensor_commands="${fake_sensor_commands}" - sim_ignition="${sim_ignition}" + sim_gazebo="${sim_gazebo}" sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml index 44372b03..0effe503 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml @@ -1,33 +1,14 @@ -###################################### NOTE ############################################# -# -# This is the Humble version of this file. On other ROS2 distributions (such as Rolling), -# you might encounter errors with MoveIt regarding the syntax of the request_adpters -# section, such as: -# -# what(): parameter 'ompl.request_adapters' has invalid type: expected [string] got [string_array] -# -# This is because on Humble, MoveIt is expecting a simple string for the request adapters, -# while some distributions expect it as an array of strings instead. If it's the case for you, -# You just need to remove the folded style block (>-) and replace it by a list of strings : -# -# request_adapters: -# - default_planner_request_adapters/AddTimeOptimalParameterization -# - default_planner_request_adapters/ResolveConstraintFrames -# - default_planner_request_adapters/FixWorkspaceBounds -# - default_planner_request_adapters/FixStartStateBounds -# - default_planner_request_adapters/FixStartStateCollision -# - default_planner_request_adapters/FixStartStatePathConstraints -# -###################################### NOTE ############################################# - -planning_plugin: ompl_interface/OMPLPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - ompl_interface/OMPLPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planner_configs: SBLkConfigDefault: diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/sim.launch.py b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/sim.launch.py index 8f52efe5..e3109475 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/sim.launch.py +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/sim.launch.py @@ -32,9 +32,9 @@ def generate_launch_description(): # Simulation specific arguments declared_arguments.append( DeclareLaunchArgument( - "sim_ignition", + "sim_gazebo", default_value="true", - description="Use Ignition for simulation", + description="Use Gazebo for simulation", ) ) declared_arguments.append( @@ -51,14 +51,14 @@ def generate_launch_description(): # Initialize Arguments launch_rviz = LaunchConfiguration("launch_rviz") use_sim_time = LaunchConfiguration("use_sim_time") - sim_ignition = LaunchConfiguration("sim_ignition") + sim_gazebo = LaunchConfiguration("sim_gazebo") description_arguments = { "robot_ip": "xxx.yyy.zzz.www", "use_fake_hardware": "false", "gripper": "robotiq_2f_85", "dof": "6", - "sim_ignition": sim_ignition, + "sim_gazebo": sim_gazebo, } moveit_config = ( diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml index 464c5e00..0d722c69 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml @@ -26,10 +26,7 @@ joint_state_publisher_gui tf2_ros xacro - - - + joint_trajectory_controller controller_manager kortex_description moveit_configs_utils diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml index 44372b03..0effe503 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/config/ompl_planning.yaml @@ -1,33 +1,14 @@ -###################################### NOTE ############################################# -# -# This is the Humble version of this file. On other ROS2 distributions (such as Rolling), -# you might encounter errors with MoveIt regarding the syntax of the request_adpters -# section, such as: -# -# what(): parameter 'ompl.request_adapters' has invalid type: expected [string] got [string_array] -# -# This is because on Humble, MoveIt is expecting a simple string for the request adapters, -# while some distributions expect it as an array of strings instead. If it's the case for you, -# You just need to remove the folded style block (>-) and replace it by a list of strings : -# -# request_adapters: -# - default_planner_request_adapters/AddTimeOptimalParameterization -# - default_planner_request_adapters/ResolveConstraintFrames -# - default_planner_request_adapters/FixWorkspaceBounds -# - default_planner_request_adapters/FixStartStateBounds -# - default_planner_request_adapters/FixStartStateCollision -# - default_planner_request_adapters/FixStartStatePathConstraints -# -###################################### NOTE ############################################# - -planning_plugin: ompl_interface/OMPLPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - ompl_interface/OMPLPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planner_configs: SBLkConfigDefault: diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/sim.launch.py b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/sim.launch.py index 8a080130..79d0528a 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/sim.launch.py +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/sim.launch.py @@ -32,9 +32,9 @@ def generate_launch_description(): # Simulation specific arguments declared_arguments.append( DeclareLaunchArgument( - "sim_ignition", + "sim_gazebo", default_value="true", - description="Use Ignition for simulation", + description="Use Gazebo for simulation", ) ) declared_arguments.append( @@ -58,7 +58,7 @@ def generate_launch_description(): # Initialize Arguments launch_rviz = LaunchConfiguration("launch_rviz") use_sim_time = LaunchConfiguration("use_sim_time") - sim_ignition = LaunchConfiguration("sim_ignition") + sim_gazebo = LaunchConfiguration("sim_gazebo") vision = LaunchConfiguration("vision") description_arguments = { @@ -66,7 +66,7 @@ def generate_launch_description(): "use_fake_hardware": "false", "gripper": "robotiq_2f_85", "dof": "7", - "sim_ignition": sim_ignition, + "sim_gazebo": sim_gazebo, "vision": vision, } diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml index f34b3a8c..c3c1ea85 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml @@ -26,10 +26,7 @@ joint_state_publisher_gui tf2_ros xacro - - - + joint_trajectory_controller controller_manager kortex_description moveit_configs_utils diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py index f0db94de..d7ba869c 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py @@ -39,9 +39,9 @@ def generate_launch_description(): ) declared_arguments.append( DeclareLaunchArgument( - "sim_ignition", + "sim_gazebo", default_value="true", - description="Use Ignition for simulation", + description="Use Gazebo for simulation", ) ) declared_arguments.append( @@ -58,7 +58,7 @@ def generate_launch_description(): # Initialize Arguments launch_rviz = LaunchConfiguration("launch_rviz") use_sim_time = LaunchConfiguration("use_sim_time") - sim_ignition = LaunchConfiguration("sim_ignition") + sim_gazebo = LaunchConfiguration("sim_gazebo") moveit_active = LaunchConfiguration("moveit_active") description_arguments = { @@ -66,7 +66,7 @@ def generate_launch_description(): "use_fake_hardware": "false", "gripper": "gen3_lite_2f", "dof": "6", - "sim_ignition": sim_ignition, + "sim_gazebo": sim_gazebo, "moveit_active": moveit_active, } diff --git a/ros2_kortex-not-released.humble.repos b/ros2_kortex-not-released.jazzy.repos similarity index 71% rename from ros2_kortex-not-released.humble.repos rename to ros2_kortex-not-released.jazzy.repos index 6a2cbfaf..eed1f540 100644 --- a/ros2_kortex-not-released.humble.repos +++ b/ros2_kortex-not-released.jazzy.repos @@ -6,8 +6,12 @@ repositories: ros2_robotiq_gripper: type: git url: https://github.com/picknikrobotics/ros2_robotiq_gripper.git - version: b6136bdc866a929bfb096890ca61dde1335ffd30 + version: main serial: type: git url: https://github.com/tylerjw/serial.git version: ros2 + gz_ros2_control: + type: git + url: https://github.com/ros-controls/gz_ros2_control.git + version: jazzy diff --git a/ros2_kortex-not-released.rolling.repos b/ros2_kortex-not-released.rolling.repos index ffbb0db0..76a9cfea 100644 --- a/ros2_kortex-not-released.rolling.repos +++ b/ros2_kortex-not-released.rolling.repos @@ -1,12 +1,4 @@ repositories: - ros2_control: - type: git - url: https://github.com/ros-controls/ros2_control.git - version: master - ros2_controllers: - type: git - url: https://github.com/ros-controls/ros2_controllers.git - version: master picknik_controllers: type: git url: https://github.com/picknikrobotics/picknik_controllers.git diff --git a/ros2_kortex.humble.repos b/ros2_kortex.jazzy.repos similarity index 67% rename from ros2_kortex.humble.repos rename to ros2_kortex.jazzy.repos index da520577..90660188 100644 --- a/ros2_kortex.humble.repos +++ b/ros2_kortex.jazzy.repos @@ -2,16 +2,20 @@ repositories: control_msgs: type: git url: https://github.com/ros-controls/control_msgs.git - version: humble + version: master ros2_control: type: git url: https://github.com/ros-controls/ros2_control.git - version: humble + version: master ros2_controllers: type: git url: https://github.com/ros-controls/ros2_controllers.git - version: humble + version: master ros2_robotiq_gripper: type: git url: https://github.com/picknikrobotics/ros2_robotiq_gripper.git - version: b6136bdc866a929bfb096890ca61dde1335ffd30 + version: main + gz_ros2_control: + type: git + url: https://github.com/ros-controls/gz_ros2_control.git + version: jazzy diff --git a/ros2_kortex.repos b/ros2_kortex.repos index 5da7477e..fd089dd8 100644 --- a/ros2_kortex.repos +++ b/ros2_kortex.repos @@ -14,4 +14,4 @@ repositories: ros2_robotiq_gripper: type: git url: https://github.com/picknikrobotics/ros2_robotiq_gripper.git - version: b6136bdc866a929bfb096890ca61dde1335ffd30 + version: main diff --git a/simulation.humble.repos b/simulation.jazzy.repos similarity index 52% rename from simulation.humble.repos rename to simulation.jazzy.repos index 0f9cc1bc..53e9d85e 100644 --- a/simulation.humble.repos +++ b/simulation.jazzy.repos @@ -1,16 +1,9 @@ repositories: - - gazebo_ros2_control: + ros_gz: type: git - url: https://github.com/ros-simulation/gazebo_ros2_control.git - version: humble - + url: https://github.com/gazebosim/ros_gz.git + version: jazzy gz_ros2_control: type: git url: https://github.com/ros-controls/gz_ros2_control.git - version: humble - - ros_gz: - type: git - url: https://github.com/gazebosim/ros_gz.git - version: humble + version: jazzy diff --git a/simulation.repos b/simulation.repos index 16dc2a35..4c54e918 100644 --- a/simulation.repos +++ b/simulation.repos @@ -1,21 +1,9 @@ repositories: - - gazebo_ros2_control: + ros_gz: type: git - url: https://github.com/ros-simulation/gazebo_ros2_control.git - version: master - - ign_ros2_control: - type: git - url: https://github.com/ignitionrobotics/ign_ros2_control.git - version: master - - ros_ign: - type: git - url: https://github.com/ignitionrobotics/ros_ign.git + url: https://github.com/gazebosim/ros_gz.git version: ros2 - - ros_ign: + gz_ros2_control: type: git - url: https://github.com/ignitionrobotics/ros_ign.git - version: ros2 + url: https://github.com/ros-controls/gz_ros2_control.git + version: rolling From 8ac64df8cb250b5c21707b5b93ec01cb71741a82 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Wed, 15 Jan 2025 12:41:51 -0500 Subject: [PATCH 02/42] README ROS2 Jazzy addition --- README.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 83a0d9b7..f14d60b8 100644 --- a/README.md +++ b/README.md @@ -58,11 +58,13 @@ ROS2 Kortex is the official ROS2 package to interact with Kortex and its related If you're a developer, we recommend using Rolling to get the latest features and fixes. Rolling Release: [Install ROS2 Rolling](https://docs.ros.org/en/rolling/Installation/Ubuntu-Install-Debians.html)
- Latest Release: [Install ROS2 Iron](https://docs.ros.org/en/iron/Installation/Ubuntu-Install-Debians.html)
- Stable LTS Release: [Install ROS2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) + Latest LTS Release: [Install ROS2 Jazzy](https://docs.ros.org/en/jazzy/Installation/Ubuntu-Install-Debs.html)
+ Previous Stable LTS Release: [Install ROS2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) After installing a version of ROS, source the setup.bash, which will set the `$ROS_DISTRO` environment variable. +**NOTE** Please use the `Humble_Gazebo_Classic_Support` branch for ROS2 Humble and the `main` branch for ROS2 Jazzy + 2. Install this package from binary ``` sudo apt install ros-$ROS_DISTRO-kortex-bringup From c11b6e8b2a210be8f5a936fb1e973c2811060363 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Thu, 16 Jan 2025 11:54:59 -0500 Subject: [PATCH 03/42] binary packages versions update --- kortex_bringup/package.xml | 2 +- .../kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml | 2 +- .../kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/kortex_bringup/package.xml b/kortex_bringup/package.xml index f8648b02..c1460ba7 100644 --- a/kortex_bringup/package.xml +++ b/kortex_bringup/package.xml @@ -2,7 +2,7 @@ kortex_bringup - 0.2.2 + 0.2.3 Launch file and run-time configurations, e.g. controllers. Marq Rasmussen diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml index 0d722c69..dfecd8c8 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_6dof_robotiq_2f_85_moveit_config - 0.2.2 + 0.2.3 An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml index c3c1ea85..7550cc68 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_7dof_robotiq_2f_85_moveit_config - 0.2.2 + 0.2.3 An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework From 337471f5e5710a9eeeebf5ad44a6bf443f419964 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Thu, 16 Jan 2025 16:16:39 -0500 Subject: [PATCH 04/42] More Binary packages version modification --- kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml index 124c1805..4a806840 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_lite_moveit_config - 0.3.0 + 0.2.3 An automatically generated package with all the configuration and launch files for using the gen3_lite with the MoveIt Motion Planning Framework From 0a7eb3bd3ed0fcd7c5fff2b0a641a9d1ab4c8083 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Thu, 16 Jan 2025 16:34:04 -0500 Subject: [PATCH 05/42] More packages versions modification --- kortex_api/package.xml | 2 +- kortex_description/package.xml | 2 +- kortex_driver/package.xml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/kortex_api/package.xml b/kortex_api/package.xml index 0ce96ee5..3f6c5b93 100644 --- a/kortex_api/package.xml +++ b/kortex_api/package.xml @@ -1,7 +1,7 @@ kortex_api - 0.2.2 + 0.2.3 kortex_api Marq Rasmussen diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 0d363214..1d5ab4c4 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -2,7 +2,7 @@ kortex_description - 0.2.2 + 0.2.3

URDF and xacro description package for Kortex robots

This package contains configuration data, 3D models and launch files diff --git a/kortex_driver/package.xml b/kortex_driver/package.xml index 04774659..eaf6722a 100644 --- a/kortex_driver/package.xml +++ b/kortex_driver/package.xml @@ -2,7 +2,7 @@ kortex_driver - 0.2.2 + 0.2.3 ROS2 driver package for the Kinova Robot Hardware. Alex Moriarty Felix Maisonneuve From 566c345e7d689612b171940bbe2b446822ffd595 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Fri, 24 Jan 2025 09:44:44 -0500 Subject: [PATCH 06/42] Changing the list of packages maintainers --- kortex_driver/package.xml | 1 - .../kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml | 2 +- .../kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/kortex_driver/package.xml b/kortex_driver/package.xml index eaf6722a..c77fb935 100644 --- a/kortex_driver/package.xml +++ b/kortex_driver/package.xml @@ -5,7 +5,6 @@ 0.2.3 ROS2 driver package for the Kinova Robot Hardware. Alex Moriarty - Felix Maisonneuve Martin Leroux Marq Rasmussen BSD diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml index dfecd8c8..89978b4f 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml @@ -6,7 +6,7 @@ An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework - Anthony Baker +Abed Al Rahman Al Mrad BSD-3-Clause diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml index 7550cc68..630457b1 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml @@ -6,7 +6,7 @@ An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework - Anthony Baker +Abed Al Rahman Al Mrad BSD-3-Clause From 9c07a2666215574848b711486b3614f853378e16 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Tue, 11 Feb 2025 19:09:53 -0500 Subject: [PATCH 07/42] Ubuntu version bump up in the ros-lint action workspace (#269) * Ubuntu version bump up in the ros-lint action workspace * fixed the format --- .github/workflows/ci-ros-lint.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml index c6079968..ea071bb7 100644 --- a/.github/workflows/ci-ros-lint.yml +++ b/.github/workflows/ci-ros-lint.yml @@ -5,7 +5,7 @@ on: jobs: ament_lint: name: ament_${{ matrix.linter }} - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 # Updated to match your Ubuntu version bump strategy: fail-fast: false matrix: @@ -13,6 +13,8 @@ jobs: steps: - uses: actions/checkout@v3 - uses: ros-tooling/setup-ros@v0.6 + - name: Set environment variable for cppcheck 2.7 + run: echo "AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS=1" >> $GITHUB_ENV - uses: ros-tooling/action-ros-lint@v0.1 with: distribution: rolling @@ -41,7 +43,7 @@ jobs: ament_lint_100: name: ament_${{ matrix.linter }} - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 strategy: fail-fast: false matrix: From fb633aacf9c1c85d61a96c1099b5afa3d533e5a3 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Wed, 2 Apr 2025 17:03:42 -0400 Subject: [PATCH 08/42] Replaced file:// with package:// + Added temporary repositories as dependencies (#275) * Replaced file:// with package:// + Added temporary repositories as dependencies * format rectification --- .../arms/gen3/6dof/urdf/gen3_macro.xacro | 32 ++++++++--------- .../arms/gen3/7dof/urdf/gen3_macro.xacro | 36 +++++++++---------- .../gen3_lite/6dof/urdf/gen3_lite_macro.xacro | 24 ++++++------- kortex_description/package.xml | 1 + ros2_kortex.jazzy.repos | 15 ++++++++ 5 files changed, 62 insertions(+), 46 deletions(-) diff --git a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro index 8a568ff9..fdf05bed 100644 --- a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro @@ -71,7 +71,7 @@ - + @@ -80,7 +80,7 @@ - + @@ -93,7 +93,7 @@ - + @@ -102,7 +102,7 @@ - + @@ -158,7 +158,7 @@ xyz="0 0 0" rpy="0 0 0" /> - + @@ -169,7 +169,7 @@ xyz="0 0 0" rpy="0 0 0" /> - + @@ -189,7 +189,7 @@ - + @@ -198,7 +198,7 @@ - + @@ -218,7 +218,7 @@ - + @@ -227,7 +227,7 @@ - + @@ -258,7 +258,7 @@ - + @@ -267,7 +267,7 @@ - + @@ -288,7 +288,7 @@ - + @@ -297,7 +297,7 @@ - + @@ -312,7 +312,7 @@ - + @@ -321,7 +321,7 @@ - + diff --git a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro index c647a04c..a442395d 100644 --- a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro @@ -71,7 +71,7 @@ - + @@ -80,7 +80,7 @@ - + @@ -93,7 +93,7 @@ - + @@ -102,7 +102,7 @@ - + @@ -149,7 +149,7 @@ - + @@ -158,7 +158,7 @@ - + @@ -183,7 +183,7 @@ - + @@ -192,7 +192,7 @@ - + @@ -239,7 +239,7 @@ - + @@ -248,7 +248,7 @@ - + @@ -273,7 +273,7 @@ - + @@ -282,7 +282,7 @@ - + @@ -329,7 +329,7 @@ - + @@ -338,7 +338,7 @@ - + @@ -364,7 +364,7 @@ - + @@ -373,7 +373,7 @@ - + @@ -388,7 +388,7 @@ - + @@ -397,7 +397,7 @@ - + diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro index 47616e3f..8450fd70 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro @@ -90,7 +90,7 @@ - + @@ -99,7 +99,7 @@ - + @@ -115,7 +115,7 @@ - + @@ -124,7 +124,7 @@ - + @@ -147,7 +147,7 @@ - + @@ -156,7 +156,7 @@ - + @@ -179,7 +179,7 @@ - + @@ -188,7 +188,7 @@ - + @@ -211,7 +211,7 @@ - + @@ -220,7 +220,7 @@ - + @@ -243,7 +243,7 @@ - + @@ -252,7 +252,7 @@ - + diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 1d5ab4c4..36fcf612 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -27,5 +27,6 @@ for Kortex arms and supported grippers

ament_cmake +
diff --git a/ros2_kortex.jazzy.repos b/ros2_kortex.jazzy.repos index 90660188..5a83b3f8 100644 --- a/ros2_kortex.jazzy.repos +++ b/ros2_kortex.jazzy.repos @@ -7,6 +7,21 @@ repositories: type: git url: https://github.com/ros-controls/ros2_control.git version: master + # Temporarily added this clone waiting for Jazzy sync that allows rosdep to find it + ros2_control_cmake: + type: git + url: https://github.com/ros-controls/ros2_control_cmake.git + version: master + # Temporarily added this clone waiting for Jazzy sync that allows rosdep to find it + generate_parameter_library: + type: git + url: https://github.com/PickNikRobotics/generate_parameter_library.git + version: main + # Temporarily added this clone waiting for Jazzy sync that allows rosdep to find it + control_toolbox: + type: git + url: https://github.com/ros-controls/control_toolbox.git + version: ros2-master ros2_controllers: type: git url: https://github.com/ros-controls/ros2_controllers.git From 11292a51d4c8b15ed198ba091017c88804e47eb6 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Thu, 17 Apr 2025 11:11:48 -0400 Subject: [PATCH 09/42] Update README.md (#278) Removed the binary packages installation instructions because these binary packages are not released yet --- README.md | 20 +------------------- 1 file changed, 1 insertion(+), 19 deletions(-) diff --git a/README.md b/README.md index f14d60b8..7f913aba 100644 --- a/README.md +++ b/README.md @@ -65,29 +65,11 @@ ROS2 Kortex is the official ROS2 package to interact with Kortex and its related **NOTE** Please use the `Humble_Gazebo_Classic_Support` branch for ROS2 Humble and the `main` branch for ROS2 Jazzy -2. Install this package from binary - ``` - sudo apt install ros-$ROS_DISTRO-kortex-bringup - ``` - -3. Optional: install MoveIt Configuration and Cyclone DDS - - If you have a 7dof arm: - ``` - sudo apt install ros-$ROS_DISTRO-kinova-gen3-7dof-robotiq-2f-85-moveit-config - ``` - If you have a 6dof arm: - ``` - sudo apt install ros-$ROS_DISTRO-kinova-gen3-6dof-robotiq-2f-85-moveit-config - ``` - If you plan to use MoveIt, it is recommended to install and use Cyclone DDS. +2. If you plan to use MoveIt, it is recommended to install and use Cyclone DDS. ``` sudo apt install ros-$ROS_DISTRO-rmw-cyclonedds-cpp export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp ``` - -4. Go to Usage section - ## Contributing to this repository or building from source Note: It is recommended to use a released binary version of this package and apt install it. From b7d58a62d0230693a0e820fbf5a1a59aaaf2c3a9 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Mon, 12 May 2025 14:16:00 -0400 Subject: [PATCH 10/42] Update README.md (#285) --- README.md | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/README.md b/README.md index 7f913aba..2e508407 100644 --- a/README.md +++ b/README.md @@ -72,11 +72,7 @@ ROS2 Kortex is the official ROS2 package to interact with Kortex and its related ``` ## Contributing to this repository or building from source -Note: It is recommended to use a released binary version of this package and apt install it. -If you want the latest version of this repository for testing latest fixes -check out testing with pre-released binaries: https://docs.ros.org/en/rolling/Installation/Testing.html - -If the bug fix you need isn't in a released version or If you want to build this repository from source or contribute back to the repository read on. +To build this repository from source or contribute back to the repository read on. 1. Make sure that `colcon`, its extensions, and `vcs` are installed: ``` From 309f9c9d4a277970e542e5ac1fe260ced0630f65 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Fri, 23 May 2025 13:17:00 -0400 Subject: [PATCH 11/42] Modified the README.md file to add more clarity to the branches structure and organization --- README.md | 31 ++++++++++--------------------- 1 file changed, 10 insertions(+), 21 deletions(-) diff --git a/README.md b/README.md index 2e508407..0325f8d5 100644 --- a/README.md +++ b/README.md @@ -12,58 +12,47 @@ ROS2 Kortex is the official ROS2 package to interact with Kortex and its related ROS 2 Distro Humble - Iron - Rolling + Jazzy Branch - main - main - main + humble + main Build Status - + Humble Binary Build - - Iron Binary Build - - - - + Rolling Binary Build Release Status - coming soon - coming soon - coming soon + Stable (binary available — may lag behind source) + Stable (source only) **Note:** There are several CI jobs checking against future upstream changes see [detailed build status](.github/workflows/README.md) for a full list of CI jobs and for more information. +**Note:** Gazebo classic support was removed from the `main` branch of this repository ## Getting started 1. Install ROS 2. - If you're a developer, we recommend using Rolling to get the latest features and fixes. + For this branch, ROS2 Jazzy has to be installed on Ubuntu 24.04. - Rolling Release: [Install ROS2 Rolling](https://docs.ros.org/en/rolling/Installation/Ubuntu-Install-Debians.html)
Latest LTS Release: [Install ROS2 Jazzy](https://docs.ros.org/en/jazzy/Installation/Ubuntu-Install-Debs.html)
- Previous Stable LTS Release: [Install ROS2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) - - After installing a version of ROS, source the setup.bash, which will set the `$ROS_DISTRO` environment variable. -**NOTE** Please use the `Humble_Gazebo_Classic_Support` branch for ROS2 Humble and the `main` branch for ROS2 Jazzy + After installing ROS2, source the setup.bash, which will set the `$ROS_DISTRO` environment variable. 2. If you plan to use MoveIt, it is recommended to install and use Cyclone DDS. ``` From d6c92b0824f9405edf5dc2f585d6350c66489df4 Mon Sep 17 00:00:00 2001 From: c-oechsner <74612331+c-oechsner@users.noreply.github.com> Date: Mon, 15 Sep 2025 23:41:18 +0200 Subject: [PATCH 12/42] Fixed pi issue #295 (#296) * fixed pi issue #295 * fix pi issue #295 in gen3_2f85.urdf * fix for 2F 140 gripper * added moveit_cpp * Added repos for successful build * Applied the PI modification only * Modified the code format --------- Co-authored-by: Abed Al Rahman Al Mrad --- .../arms/gen3/6dof/urdf/gen3_macro.xacro | 9 +++--- .../gen3/6dof/urdf/kortex.ros2_control.xacro | 12 ++++---- .../arms/gen3/7dof/urdf/gen3_macro.xacro | 29 +++++++++---------- .../gen3/7dof/urdf/kortex.ros2_control.xacro | 16 +++++----- kortex_description/robots/gen3_2f85.urdf | 16 +++++----- kortex_driver/src/hardware_interface.cpp | 2 +- 6 files changed, 41 insertions(+), 43 deletions(-) diff --git a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro index fdf05bed..50b32df9 100644 --- a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro @@ -4,7 +4,6 @@ -
@@ -237,7 +236,7 @@ - +
@@ -332,7 +331,7 @@ - +
diff --git a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro index 24503529..2d890845 100644 --- a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro @@ -58,8 +58,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_1']} @@ -91,8 +91,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_4']} @@ -113,8 +113,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_6']} diff --git a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro index a442395d..e1d8427b 100644 --- a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro @@ -4,7 +4,6 @@ - @@ -208,8 +207,8 @@ @@ -298,8 +297,8 @@ @@ -414,8 +413,8 @@ @@ -453,19 +452,19 @@ - + - + - + @@ -473,19 +472,19 @@ - + - + - + diff --git a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro index 0524907b..6dc5f133 100644 --- a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro @@ -58,8 +58,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_1']} @@ -80,8 +80,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_3']} @@ -102,8 +102,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_5']} @@ -124,8 +124,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} ${initial_positions['joint_7']} diff --git a/kortex_description/robots/gen3_2f85.urdf b/kortex_description/robots/gen3_2f85.urdf index 7f787bdd..f70298ec 100644 --- a/kortex_description/robots/gen3_2f85.urdf +++ b/kortex_description/robots/gen3_2f85.urdf @@ -28,8 +28,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} -3.15 @@ -58,8 +58,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} -3.15 @@ -88,8 +88,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} -3.2 @@ -118,8 +118,8 @@ - {-2*pi} - {2*pi} + ${-2*pi} + ${2*pi} -3.2 diff --git a/kortex_driver/src/hardware_interface.cpp b/kortex_driver/src/hardware_interface.cpp index 60c766e2..f0e856b1 100644 --- a/kortex_driver/src/hardware_interface.cpp +++ b/kortex_driver/src/hardware_interface.cpp @@ -894,7 +894,7 @@ return_type KortexMultiInterfaceHardware::write( { // Keep alive mode - no controller active feedback_ = base_cyclic_.RefreshFeedback(); - RCLCPP_DEBUG(LOGGER, "No controller active in LOW_LEVEL_SERVOING mode !"); + // RCLCPP_DEBUG(LOGGER, "No controller active in LOW_LEVEL_SERVOING mode !"); } } else From b86f223249da004f6ef863c788ed4fce7157be24 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Mon, 29 Sep 2025 12:17:35 -0400 Subject: [PATCH 13/42] modified the kortex trademark name (#305) * modified the kortex trademark name * rectified the formatting --- README.md | 6 +++--- kortex_api/package.xml | 2 +- kortex_description/package.xml | 4 ++-- kortex_description/readme.md | 6 +++--- kortex_driver/README.md | 4 ++-- kortex_moveit_config/readme.md | 6 +++--- 6 files changed, 14 insertions(+), 14 deletions(-) diff --git a/README.md b/README.md index 0325f8d5..90caed9d 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,10 @@ -# ROS 2 Kortex -> Kinova® Kortex™ is the common software platform behind all of the products in the Gen3 family (Gen3 and Gen3 lite). It unifies the inner workings of the various robots and their related external tools, like the API.
+# ROS 2 KINOVA KORTEX™ +> Kinova® KINOVA KORTEX™ is the common software platform behind all of the products in the Gen3 family (Gen3 and Gen3 lite). It unifies the inner workings of the various robots and their related external tools, like the API.
> https://www.kinovarobotics.com/product/gen3-robots
Kinova Gen3 7DoF manipulator with Intel RealSense 3D Vision Module and Robotiq 2F-85 2 Finger 85mm Adaptive Gripper
-ROS2 Kortex is the official ROS2 package to interact with Kortex and its related products. It is built upon the Kortex API, documentation for which can be found in the [GitHub Kortex repository](https://github.com/Kinovarobotics/kortex). +ROS2 Kortex is the official ROS2 package to interact with KINOVA KORTEX™ and its related products. It is built upon the KINOVA KORTEX™ API, documentation for which can be found in the [GitHub Kortex repository](https://github.com/Kinovarobotics/kortex). ## Build status diff --git a/kortex_api/package.xml b/kortex_api/package.xml index 3f6c5b93..bca4bd08 100644 --- a/kortex_api/package.xml +++ b/kortex_api/package.xml @@ -2,7 +2,7 @@ kortex_api 0.2.3 - kortex_api + KINOVA KORTEX™ API Marq Rasmussen diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 36fcf612..932879b1 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -4,9 +4,9 @@ kortex_description 0.2.3 -

URDF and xacro description package for Kortex robots

+

URDF and xacro description package for KINOVA KORTEX™ robots

This package contains configuration data, 3D models and launch files -for Kortex arms and supported grippers

+for KINOVA KORTEX™ arms and supported grippers

Alexandre Vannobel diff --git a/kortex_description/readme.md b/kortex_description/readme.md index 74241404..88eba348 100644 --- a/kortex_description/readme.md +++ b/kortex_description/readme.md @@ -10,8 +10,8 @@ * * --> -# Kortex Description -This package contains the URDF (Unified Robot Description Format), STL and configuration files for the Kortex-compatible robots. +# KINOVA KORTEX™ Description +This package contains the URDF (Unified Robot Description Format), STL and configuration files for the KINOVA KORTEX™-compatible robots. ## Usage @@ -62,7 +62,7 @@ Param | Description | Default | `use_external_cable` | Boolean value that sets joint limits to avoid wrapping of external cables if true. | false | `initial_positions` | Dictionary of initial joint positions. | {joint_1: 0.0, joint_2: 0.0, joint_3: 0.0, joint_4: 0.0, joint_5: 0.0, joint_6: 0.0, joint_7: 0.0} | `gripper_max_velocity` | Desired velocity in percentage (0.0-100.0%) with which the position will be set. | 100.0 | -`gripper_max_force` | Desired force in percentage (0.0-100.0%) with which the position will be set. NOTE: deprecated according to the [Kortex repo](https://github.com/Kinovarobotics/kortex/blob/master/api_cpp/doc/markdown/messages/GripperCyclic/MotorCommand.md). | 100.0 | +`gripper_max_force` | Desired force in percentage (0.0-100.0%) with which the position will be set. NOTE: deprecated according to the [KINOVA KORTEX™ repo](https://github.com/Kinovarobotics/kortex/blob/master/api_cpp/doc/markdown/messages/GripperCyclic/MotorCommand.md). | 100.0 | `gripper_com_port` | Specifies the USB port that the gripper is plugged in on. This will only be used if `use_internal_bus_gripper_comm` is false. | /dev/ttyUSB0 | ### Example Usage diff --git a/kortex_driver/README.md b/kortex_driver/README.md index ae4e4b81..ed4a1760 100644 --- a/kortex_driver/README.md +++ b/kortex_driver/README.md @@ -1,5 +1,5 @@ -# ROS 2 Kortex Driver -The ROS 2 Kortex driver implements the `ros2_control` hardware interface for a `SystemInterface`. +# ROS 2 KINOVA KORTEX™ Driver +The ROS 2 KINOVA KORTEX™ driver implements the `ros2_control` hardware interface for a `SystemInterface`. ### Command interfaces This driver exports commands interfaces for position, velocity, and effort interfaces for each joint defined in the URDF. diff --git a/kortex_moveit_config/readme.md b/kortex_moveit_config/readme.md index 1ee9ae13..12d09311 100644 --- a/kortex_moveit_config/readme.md +++ b/kortex_moveit_config/readme.md @@ -10,12 +10,12 @@ * * --> -# Kortex MoveIt 2 Config +# KINOVA KORTEX™ MoveIt 2 Config ## Naming The packages that don't use a gripper are named `ARM_move_it_config`, where "ARM" is the name of the arm you are using. -See the `kortex_description/arms` folder for a list of supported Kinova Kortex robots. +See the `kortex_description/arms` folder for a list of supported Kinova KINOVA KORTEX™ robots. The packages that use a gripper are named `ARM_GRIPPER_move_it_config`, where "ARM" is the name of the arm you are using and "GRIPPER" is the name of the gripper you are using. -See the `kortex_description/grippers` folder for a list of supported Kinova Kortex grippers. +See the `kortex_description/grippers` folder for a list of supported Kinova KINOVA KORTEX™ grippers. From cafe348144f223cecbbaeee29f6ad38ade011336 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Tue, 4 Nov 2025 18:10:35 -0500 Subject: [PATCH 14/42] Update branches for some dependency repos (#314) * Modifications to account for ROS2 API update & ParallelGripper intergration * Format rectification * Reversed some modifications * rectified format --- ros2_kortex.jazzy.repos | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ros2_kortex.jazzy.repos b/ros2_kortex.jazzy.repos index 5a83b3f8..4e4ab424 100644 --- a/ros2_kortex.jazzy.repos +++ b/ros2_kortex.jazzy.repos @@ -2,11 +2,11 @@ repositories: control_msgs: type: git url: https://github.com/ros-controls/control_msgs.git - version: master + version: jazzy ros2_control: type: git url: https://github.com/ros-controls/ros2_control.git - version: master + version: jazzy # Temporarily added this clone waiting for Jazzy sync that allows rosdep to find it ros2_control_cmake: type: git @@ -21,11 +21,11 @@ repositories: control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git - version: ros2-master + version: jazzy ros2_controllers: type: git url: https://github.com/ros-controls/ros2_controllers.git - version: master + version: jazzy ros2_robotiq_gripper: type: git url: https://github.com/picknikrobotics/ros2_robotiq_gripper.git From cee5f4c40f45d48d45ea890a0afae18640111e30 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Wed, 12 Nov 2025 16:40:54 -0500 Subject: [PATCH 15/42] Modifications to fix moveit issues while controlling Gen3_lite (#316) * Modifications to account for ROS2 API update & ParallelGripper intergration * Format rectification * Reversed some modifications * rectified format * Modifications to fix moveit issues while controlling Gen3_lite * README modification * format rectification --- README.md | 3 +- .../6dof/urdf/kortex.ros2_control.xacro | 4 +- .../urdf/gen3_lite_2f_macro.xacro | 3 ++ .../config/joint_limits.yaml | 41 ++++++++++++------- .../config/moveit_controllers.yaml | 4 +- .../config/ompl_planning.yaml | 41 +++++-------------- .../config/ros2_controllers.yaml | 4 +- .../launch/sim.launch.py | 23 +++++++++-- 8 files changed, 66 insertions(+), 57 deletions(-) diff --git a/README.md b/README.md index 90caed9d..b8b600f8 100644 --- a/README.md +++ b/README.md @@ -276,8 +276,7 @@ The `kortex_sim_control.launch.py` launch file is designed to simulate all of ou ```bash ros2 launch kortex_bringup kortex_sim_control.launch.py \ use_sim_time:=true \ - launch_rviz:=false \ - robot_controller:=joint_trajectory_controller + launch_rviz:=false ``` * `sim_gazebo` : Use Gazebo for simulation. Default value is `false`. diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro index 5b909bb6..be1ecf97 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro @@ -154,13 +154,13 @@
- + - +
diff --git a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro index 3bf45914..f1b5b029 100644 --- a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro +++ b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro @@ -145,6 +145,7 @@ + @@ -179,6 +180,7 @@ + @@ -211,6 +213,7 @@ + diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml index f60acab6..48687a88 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml @@ -11,35 +11,46 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 1.6000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 0.86 joint_2: has_velocity_limits: true max_velocity: 1.6000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 0.43 joint_3: has_velocity_limits: true max_velocity: 1.6000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 0.34 joint_4: has_velocity_limits: true max_velocity: 1.6000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 0.86 joint_5: has_velocity_limits: true max_velocity: 1.6000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 8.6 joint_6: has_velocity_limits: true max_velocity: 3.2000000000000002 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 8.6 + left_finger_bottom_joint: + has_velocity_limits: true + max_velocity: 0.6 + has_acceleration_limits: true + max_acceleration: 1.0 + has_position_limits: true + min_position: -0.96 + max_position: 0.09 right_finger_bottom_joint: has_velocity_limits: true - max_velocity: 0.59999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 0.6 + has_acceleration_limits: true + max_acceleration: 1.0 + has_position_limits: true + min_position: -0.09 + max_position: 0.96 diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/moveit_controllers.yaml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/moveit_controllers.yaml index 1001f9f8..25195297 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/moveit_controllers.yaml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/moveit_controllers.yaml @@ -1,9 +1,9 @@ moveit_simple_controller_manager: controller_names: - - gen3_lite_joint_trajectory_controller + - joint_trajectory_controller - gen3_lite_2f_gripper_controller - gen3_lite_joint_trajectory_controller: + joint_trajectory_controller: type: FollowJointTrajectory joints: - joint_1 diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ompl_planning.yaml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ompl_planning.yaml index 363357e8..22048f11 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ompl_planning.yaml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ompl_planning.yaml @@ -1,33 +1,14 @@ -###################################### NOTE ############################################# -# -# This is the Humble version of this file. On other ROS2 distributions (such as Rolling), -# you might encounter errors with MoveIt regarding the syntax of the request_adpters -# section, such as: -# -# what(): parameter 'ompl.request_adapters' has invalid type: expected [string] got [string_array] -# -# This is because on Humble, MoveIt is expecting a simple string for the request adapters, -# while some distributions expect it as an array of strings instead. If it's the case for you, -# You just need to remove the folded style block (>-) and replace it by a list of strings : -# -# request_adapters: -# - default_planner_request_adapters/AddTimeOptimalParameterization -# - default_planner_request_adapters/ResolveConstraintFrames -# - default_planner_request_adapters/FixWorkspaceBounds -# - default_planner_request_adapters/FixStartStateBounds -# - default_planner_request_adapters/FixStartStateCollision -# - default_planner_request_adapters/FixStartStatePathConstraints -# -###################################### NOTE ############################################# - -planning_plugin: ompl_interface/OMPLPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - ompl_interface/OMPLPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planner_configs: SBLkConfigDefault: diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ros2_controllers.yaml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ros2_controllers.yaml index b1dbf1e6..665c9c3c 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ros2_controllers.yaml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/ros2_controllers.yaml @@ -5,7 +5,7 @@ controller_manager: joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster - gen3_lite_joint_trajectory_controller: + joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController twist_controller: @@ -17,7 +17,7 @@ controller_manager: gen3_lite_2f_gripper_controller: type: position_controllers/GripperActionController -gen3_lite_joint_trajectory_controller: +joint_trajectory_controller: ros__parameters: joints: - joint_1 diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py index d7ba869c..517e1bf1 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/sim.launch.py @@ -77,7 +77,12 @@ def generate_launch_description(): .robot_description(mappings=description_arguments) .trajectory_execution(file_path="config/moveit_controllers.yaml") .planning_scene_monitor( - publish_robot_description=True, publish_robot_description_semantic=True + publish_robot_description=True, + publish_robot_description_semantic=True, + publish_planning_scene=True, + publish_geometry_updates=True, + publish_state_updates=True, + publish_transforms_updates=True, ) .planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"]) .to_moveit_configs() @@ -88,12 +93,22 @@ def generate_launch_description(): package="moveit_ros_move_group", executable="move_group", output="log", - parameters=[moveit_config.to_dict(), {"use_sim_time": use_sim_time}], + parameters=[ + moveit_config.to_dict(), + { + "use_sim_time": use_sim_time, + "publish_robot_description_semantic": True, + "allow_trajectory_execution": True, + "capabilities": "", + "disable_capabilities": "", + "monitor_dynamics": False, + }, + ], arguments=[ "--ros-args", "--log-level", - "fatal", - ], # MoveIt is spamming the log because of unknown '*_mimic' joints + "info", + ], condition=IfCondition(launch_rviz), ) From 679560832ea67f646007ab34868f7d4098e53418 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Thu, 13 Nov 2025 11:45:58 -0500 Subject: [PATCH 16/42] modified README (#317) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index b8b600f8..7c256275 100644 --- a/README.md +++ b/README.md @@ -83,7 +83,7 @@ To build this repository from source or contribute back to the repository read o ``` If you plan on simulating the robot with Gazebo, make sure to pull the additional simulation packages. - If you're on ROS 2 Humble, run + If you're on ROS 2 Jazzy, run ``` vcs import src --skip-existing --input src/ros2_kortex/simulation.jazzy.repos ``` From 57f84ff56b7774674756ca0da8388f4eee757ed6 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Mon, 17 Nov 2025 11:47:56 -0500 Subject: [PATCH 17/42] fixed gen3_lite moveit issues (#318) * fixed gen3_lite moveit issues * rectified format --- README.md | 25 ++++++++----- .../6dof/urdf/kortex.ros2_control.xacro | 10 +++-- .../urdf/gen3_lite_2f_macro.xacro | 12 +++--- .../launch/robot.launch.py | 3 +- .../launch/robot.launch.py | 2 +- .../config/joint_limits.yaml | 11 ------ .../launch/robot.launch.py | 37 ++++++++++--------- 7 files changed, 50 insertions(+), 50 deletions(-) diff --git a/README.md b/README.md index 7c256275..183e9ca7 100644 --- a/README.md +++ b/README.md @@ -221,6 +221,20 @@ You can test the gripper by calling the Action server with the following command ros2 action send_goal /robotiq_gripper_controller/gripper_cmd control_msgs/action/GripperCommand "{command:{position: 0.0, max_effort: 100.0}}" ``` +#### Gen3_lite gripper + +The Gen3_lite gripper will be available on the Action topic: + +```bash +/gen3_lite_2f_gripper_controller/gripper_cmd +``` + +You can test the gripper by calling the Action server with the following command and setting the desired `position` of the gripper (`0.0=open`, `0.8=close`) + +```bash +ros2 action send_goal /gen3_lite_2f_gripper_controller/gripper_cmd control_msgs/action/GripperCommand "{command:{position: 0.0, max_effort: 100.0}}" +``` + #### Vision Module In order to access the Kinova Vision module's depth and color streams for the camera-equipped Gen3 arm models, please refer to the following github repository for detailed instructions: [ros2_kortex_vision](https://github.com/Kinovarobotics/ros2_kortex_vision) @@ -349,16 +363,7 @@ ros2 topic pub /joint_trajectory_controller/joint_trajectory trajectory_msgs/Joi }" -1 ``` -Depending on your robot type and its DoF, you will need to adapt the `joint_names` and `positions` properties accordingly. For the Gen3 Lite arm, the integrated gripper is considered as a joint, so to command it, it must be included in the `joint_names` array. (`0.0=open`, `1.0=close`): - -```bash -ros2 topic pub /joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{ - joint_names: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6, right_finger_bottom_joint], - points: [ - { positions: [0, 0, 0, 0, 0, 0, 1], time_from_start: { sec: 10 } }, - ] -}" -1 -``` +Depending on your robot type and its DoF, you will need to adapt the `joint_names` and `positions` properties accordingly. You can also command the arm using Twist messages. Before doing so, you must active the `twist_controller` and deactivate the `joint_trajectory_controller`: ```bash diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro index be1ecf97..f6e12d1a 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro @@ -145,15 +145,17 @@ - - + + + + + diff --git a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro index f1b5b029..76cd92d8 100644 --- a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro +++ b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro @@ -107,11 +107,11 @@ Kortex/Gray - + - - + + @@ -174,13 +174,13 @@ Kortex/Gray - + - + - + diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/robot.launch.py b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/robot.launch.py index aa0ac44f..c411cc67 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/robot.launch.py +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/launch/robot.launch.py @@ -56,7 +56,7 @@ def launch_setup(context, *args, **kwargs): .planning_scene_monitor( publish_robot_description=True, publish_robot_description_semantic=True ) - .planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"]) + .planning_pipelines(pipelines=["ompl"]) .to_moveit_configs() ) @@ -68,6 +68,7 @@ def launch_setup(context, *args, **kwargs): output="screen", parameters=[ moveit_config.to_dict(), + {"default_planning_pipeline": "ompl"}, ], ) diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/robot.launch.py b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/robot.launch.py index b96f990b..0a175afb 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/robot.launch.py +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/launch/robot.launch.py @@ -56,7 +56,7 @@ def launch_setup(context, *args, **kwargs): .planning_scene_monitor( publish_robot_description=True, publish_robot_description_semantic=True ) - .planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"]) + .planning_pipelines(pipelines=["ompl"]) .to_moveit_configs() ) diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml index 48687a88..9377cff7 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/config/joint_limits.yaml @@ -38,19 +38,8 @@ joint_limits: max_velocity: 3.2000000000000002 has_acceleration_limits: true max_acceleration: 8.6 - left_finger_bottom_joint: - has_velocity_limits: true - max_velocity: 0.6 - has_acceleration_limits: true - max_acceleration: 1.0 - has_position_limits: true - min_position: -0.96 - max_position: 0.09 right_finger_bottom_joint: has_velocity_limits: true max_velocity: 0.6 has_acceleration_limits: true max_acceleration: 1.0 - has_position_limits: true - min_position: -0.09 - max_position: 0.96 diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/robot.launch.py b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/robot.launch.py index 47fe489d..8b5fdcf2 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/robot.launch.py +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/launch/robot.launch.py @@ -12,13 +12,17 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os + from launch import LaunchDescription from launch.substitutions import LaunchConfiguration from launch.actions import ( DeclareLaunchArgument, OpaqueFunction, + RegisterEventHandler, ) -from launch.conditions import IfCondition +from launch.event_handlers import OnProcessExit +from launch.conditions import IfCondition, UnlessCondition from launch_ros.actions import Node from ament_index_python.packages import get_package_share_directory from moveit_configs_utils import MoveItConfigsBuilder @@ -52,7 +56,7 @@ def launch_setup(context, *args, **kwargs): .planning_scene_monitor( publish_robot_description=True, publish_robot_description_semantic=True ) - .planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"]) + .planning_pipelines(pipelines=["ompl"]) .to_moveit_configs() ) @@ -77,7 +81,6 @@ def launch_setup(context, *args, **kwargs): ) # Publish TF - """ robot_state_publisher = Node( package="robot_state_publisher", executable="robot_state_publisher", @@ -87,6 +90,7 @@ def launch_setup(context, *args, **kwargs): moveit_config.robot_description, ], ) + # ros2_control using FakeSystem as hardware ros2_controllers_path = os.path.join( get_package_share_directory("kinova_gen3_lite_moveit_config"), @@ -102,11 +106,13 @@ def launch_setup(context, *args, **kwargs): ], output="both", ) + robot_traj_controller_spawner = Node( package="controller_manager", executable="spawner", arguments=["joint_trajectory_controller", "-c", "/controller_manager"], ) + robot_pos_controller_spawner = Node( package="controller_manager", executable="spawner", @@ -125,7 +131,6 @@ def launch_setup(context, *args, **kwargs): arguments=["fault_controller", "-c", "/controller_manager"], condition=UnlessCondition(use_fake_hardware), ) - """ # rviz with moveit configuration rviz_config_file = ( get_package_share_directory("kinova_gen3_lite_moveit_config") + "/config/moveit.rviz" @@ -145,7 +150,7 @@ def launch_setup(context, *args, **kwargs): moveit_config.joint_limits, ], ) - """ + joint_state_broadcaster_spawner = Node( package="controller_manager", executable="spawner", @@ -155,9 +160,8 @@ def launch_setup(context, *args, **kwargs): "/controller_manager", ], ) - """ + # Delay rviz start after `joint_state_broadcaster` - """ delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler( event_handler=OnProcessExit( target_action=joint_state_broadcaster_spawner, @@ -165,17 +169,16 @@ def launch_setup(context, *args, **kwargs): ), condition=IfCondition(launch_rviz), ) - """ + nodes_to_start = [ - # ros2_control_node, - # robot_state_publisher, - # joint_state_broadcaster_spawner, - # delay_rviz_after_joint_state_broadcaster_spawner, - rviz_node, - # robot_traj_controller_spawner, - # robot_pos_controller_spawner, - # robot_hand_controller_spawner, - # fault_controller_spawner, + ros2_control_node, + robot_state_publisher, + joint_state_broadcaster_spawner, + delay_rviz_after_joint_state_broadcaster_spawner, + robot_traj_controller_spawner, + robot_pos_controller_spawner, + robot_hand_controller_spawner, + fault_controller_spawner, move_group_node, static_tf, ] From 3e13951da1942a54b75c1c88e8bcbd6003c04a48 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Mon, 17 Nov 2025 19:18:24 -0500 Subject: [PATCH 18/42] fixed the gen3_lite fake_hardware issue (#319) * fixed gen3_lite moveit issues * rectified format * fixed the gen3_lite fake_hardware issue * rectified format --- .../arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro | 2 ++ .../grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro | 3 --- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro index f6e12d1a..ffb723a8 100644 --- a/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro @@ -157,11 +157,13 @@ + + diff --git a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro index 1712fde0..dfe059a7 100644 --- a/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro +++ b/kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f.ros2_control.xacro @@ -72,7 +72,6 @@ ${prefix}right_finger_bottom_joint -1 - @@ -81,7 +80,6 @@ ${prefix}right_finger_bottom_joint -1 - @@ -90,7 +88,6 @@ ${prefix}right_finger_bottom_joint -1 - From 6a9960eb8c672ef32f7f12a90e12dad4d797df06 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Wed, 19 Nov 2025 10:36:25 -0500 Subject: [PATCH 19/42] fixed bringing up the Gen3 wo gripper issue (#321) --- .../arms/gen3/6dof/urdf/gen3_macro.xacro | 4 +++- .../gen3/6dof/urdf/kortex.ros2_control.xacro | 19 ++++++++++++------- .../arms/gen3/7dof/urdf/gen3_macro.xacro | 4 +++- .../gen3/7dof/urdf/kortex.ros2_control.xacro | 3 +++ kortex_description/robots/kortex_robot.xacro | 1 + 5 files changed, 22 insertions(+), 9 deletions(-) diff --git a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro index 50b32df9..3cb50d9b 100644 --- a/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/gen3_macro.xacro @@ -19,6 +19,7 @@ session_inactivity_timeout_ms:=6000 connection_inactivity_timeout_ms:=2000 use_internal_bus_gripper_comm:=false + gripper gripper_joint_name gripper_max_velocity:=100.0 gripper_max_force:=100.0 @@ -54,7 +55,8 @@ use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" gripper_max_velocity="${gripper_max_velocity}" gripper_max_force="${gripper_max_force}" - gripper_joint_name="${gripper_joint_name}"/> + gripper_joint_name="${gripper_joint_name}" + gripper="${gripper}"/> diff --git a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro index 2d890845..fd380c63 100644 --- a/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/6dof/urdf/kortex.ros2_control.xacro @@ -20,6 +20,7 @@ port_realtime session_inactivity_timeout_ms connection_inactivity_timeout_ms + gripper gripper_joint_name gripper_max_velocity:=100.0 gripper_max_force:=100.0 @@ -122,13 +123,17 @@ - - - - - - - + + + + + + + + + + + diff --git a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro index e1d8427b..d504ab45 100644 --- a/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/gen3_macro.xacro @@ -19,6 +19,7 @@ session_inactivity_timeout_ms:=6000 connection_inactivity_timeout_ms:=2000 use_internal_bus_gripper_comm:=true + gripper gripper_joint_name gripper_max_velocity:=100.0 gripper_max_force:=100.0 @@ -54,7 +55,8 @@ use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" gripper_max_velocity="${gripper_max_velocity}" gripper_max_force="${gripper_max_force}" - gripper_joint_name="${gripper_joint_name}"/> + gripper_joint_name="${gripper_joint_name}" + gripper="${gripper}"/> diff --git a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro index 6dc5f133..09144395 100644 --- a/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro +++ b/kortex_description/arms/gen3/7dof/urdf/kortex.ros2_control.xacro @@ -20,6 +20,7 @@ port_realtime session_inactivity_timeout_ms connection_inactivity_timeout_ms + gripper gripper_joint_name gripper_max_velocity:=100.0 gripper_max_force:=100.0 @@ -134,6 +135,7 @@ + @@ -142,6 +144,7 @@ + diff --git a/kortex_description/robots/kortex_robot.xacro b/kortex_description/robots/kortex_robot.xacro index b9ac9adf..db9a9935 100644 --- a/kortex_description/robots/kortex_robot.xacro +++ b/kortex_description/robots/kortex_robot.xacro @@ -55,6 +55,7 @@ sim_isaac="${sim_isaac}" isaac_joint_commands="${isaac_joint_commands}" isaac_joint_states="${isaac_joint_states}" + gripper="${gripper}" gripper_joint_name="${gripper_joint_name}" gripper_max_velocity="${gripper_max_velocity}" gripper_max_force="${gripper_max_force}" From 3d4c4cbb0918928ae54b49e2b5e033cd212bad6f Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 12:57:15 -0500 Subject: [PATCH 20/42] Added ros2 jazzy CI workflow --- .github/workflows/README.md | 8 +-- ...inary-build.yml => jazzy-binary-build.yml} | 16 ++--- .github/workflows/jazzy-semi-binary-build.yml | 59 +++++++++++++++++++ ...ource-build.yml => jazzy-source-build.yml} | 14 ++--- 4 files changed, 78 insertions(+), 19 deletions(-) rename .github/workflows/{humble-binary-build.yml => jazzy-binary-build.yml} (88%) create mode 100644 .github/workflows/jazzy-semi-binary-build.yml rename .github/workflows/{humble-source-build.yml => jazzy-source-build.yml} (83%) diff --git a/.github/workflows/README.md b/.github/workflows/README.md index cff94d7a..9e13d7ad 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -6,10 +6,10 @@ A RED job might not mean that this package is currently broken but that an depen To avoid overloading users viewing the main README page a full list of build statues can be kept here for package maintainers -ROS2 Distro | Humble | Iron | Rolling -:---------: | :----: | :--: | :-----: -| **Branch** | [`main`](https://github.com/PickNikRobotics/ros2_kortex/tree/main) | [`main`](https://github.com/PickNikRobotics/ros2_kortex/tree/main) | [`main`](https://github.com/PickNikRobotics/ros2_kortex/tree/main) -| **Build Status** | [![Humble Binary Build](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/humble-binary-build.yml/badge.svg?branch=main)](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/humble-binary-build.yml?branch=main)
[![Humble Source Build](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/humble-source-build.yml/badge.svg?branch=main)](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/humble-source-build.yml?branch=main) | :construction: | [![Rolling Binary Build](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml/badge.svg?branch=main)](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml?branch=main)
[![Rolling Semi-Binary Build](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=main)](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml?branch=main)
[![Rolling Source Build](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-source-build.yml/badge.svg?branch=main)](https://github.com/PickNikRobotics/ros2_kortex/actions/workflows/rolling-source-build.yml?branch=main) +ROS2 Distro | Jazzy | Rolling +:---------: | :---: | :-----: +| **Branch** | [`jazzy`](https://github.com/Kinovarobotics/ros2_kortex/tree/jazzy) | [`main`](https://github.com/Kinovarobotics/ros2_kortex/tree/main) +| **Build Status** | [![Jazzy Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml?branch=jazzy)
[![Jazzy Semi-Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-semi-binary-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-semi-binary-build.yml?branch=jazzy)
[![Jazzy Source Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml?branch=jazzy) | [![Rolling Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml?branch=main)
[![Rolling Semi-Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml?branch=main)
[![Rolling Source Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-source-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-source-build.yml?branch=main) ### Explanation of different build types diff --git a/.github/workflows/humble-binary-build.yml b/.github/workflows/jazzy-binary-build.yml similarity index 88% rename from .github/workflows/humble-binary-build.yml rename to .github/workflows/jazzy-binary-build.yml index a7984242..a78cdf3d 100644 --- a/.github/workflows/humble-binary-build.yml +++ b/.github/workflows/jazzy-binary-build.yml @@ -1,27 +1,27 @@ -name: Humble Binary Build +name: Jazzy Binary Build on: pull_request: branches: - # try to keep humble and rolling(main) in sync - - humble + # try to keep jazzy and rolling(main) in sync + - jazzy - main push: branches: - - humble + - jazzy - main schedule: # Run every morning to detect flakiness and broken dependencies - cron: '13 4 * * *' jobs: - humble_binary: - name: humble binary build + jazzy_binary: + name: jazzy binary build runs-on: ubuntu-latest strategy: matrix: env: - - {ROS_DISTRO: humble, ROS_REPO: main} - - {ROS_DISTRO: humble, ROS_REPO: testing} + - {ROS_DISTRO: jazzy, ROS_REPO: main} + - {ROS_DISTRO: jazzy, ROS_REPO: testing} env: UPSTREAM_WORKSPACE: ros2_kortex-not-released.${{ matrix.env.ROS_DISTRO }}.repos ROSDEP_SKIP_KEYS: gz_ros2_control diff --git a/.github/workflows/jazzy-semi-binary-build.yml b/.github/workflows/jazzy-semi-binary-build.yml new file mode 100644 index 00000000..8ca92b00 --- /dev/null +++ b/.github/workflows/jazzy-semi-binary-build.yml @@ -0,0 +1,59 @@ +name: Jazzy Semi Binary Build +on: + pull_request: + branches: + - jazzy + - main + push: + branches: + - jazzy + - main + schedule: + # Run every morning to detect flakiness and broken dependencies + - cron: '13 4 * * *' + +jobs: + jazzy_semi_binary: + name: jazzy semi-binary build + runs-on: ubuntu-latest + strategy: + matrix: + env: + - {ROS_DISTRO: jazzy, ROS_REPO: main} + - {ROS_DISTRO: jazzy, ROS_REPO: testing} + env: + UPSTREAM_WORKSPACE: ros2_kortex.${{ matrix.env.ROS_DISTRO }}.repos + ROSDEP_SKIP_KEYS: robotiq_description + CCACHE_DIR: ${{ github.workspace }}/.ccache + BASEDIR: ${{ github.workspace }}/.work + CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }} + steps: + - uses: actions/checkout@v3 + # The target directory cache doesn't include the source directory because + # that comes from the checkout. See "prepare target_ws for cache" task below + - name: cache target_ws + if: ${{ ! matrix.env.CCOV }} + uses: pat-s/always-upload-cache@v2.1.5 + with: + path: ${{ env.BASEDIR }}/target_ws + key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }} + restore-keys: | + target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} + - name: cache ccache + uses: pat-s/always-upload-cache@v2.1.5 + with: + path: ${{ env.CCACHE_DIR }} + key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} + restore-keys: | + ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }} + ccache-${{ env.CACHE_PREFIX }} + - uses: 'ros-industrial/industrial_ci@master' + with: + config: ${{toJSON(matrix.env)}} + - name: prepare target_ws for cache + if: ${{ always() && ! matrix.env.CCOV }} + run: | + du -sh ${{ env.BASEDIR }}/target_ws + sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete + sudo rm -rf ${{ env.BASEDIR }}/target_ws/src + du -sh ${{ env.BASEDIR }}/target_ws diff --git a/.github/workflows/humble-source-build.yml b/.github/workflows/jazzy-source-build.yml similarity index 83% rename from .github/workflows/humble-source-build.yml rename to .github/workflows/jazzy-source-build.yml index 40839999..d91cf092 100644 --- a/.github/workflows/humble-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -1,21 +1,21 @@ -name: Humble Source Build +name: Jazzy Source Build on: push: branches: - # try to keep humble and rolling(main) in sync - - humble + # try to keep jazzy and rolling(main) in sync + - jazzy - main schedule: # Run every morning to detect flakiness and broken dependencies - cron: '43 1 * * *' jobs: - humble_source: - runs-on: ubuntu-22.04 + jazzy_source: + runs-on: ubuntu-24.04 strategy: fail-fast: false env: - ROS_DISTRO: humble + ROS_DISTRO: jazzy steps: - uses: ros-tooling/setup-ros@v0.6 with: @@ -24,7 +24,7 @@ jobs: - uses: ros-tooling/action-ros-ci@0.3.2 with: target-ros2-distro: ${{ env.ROS_DISTRO }} - # Currently main is compatible with Humble + # Currently main is compatible with Jazzy ref: main import-token: ${{ secrets.GITHUB_TOKEN }} # build all packages listed in the meta package From fbd7d39500b507605a573982135ac62b3e0048f3 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 13:00:37 -0500 Subject: [PATCH 21/42] CI workflow rectifications --- .github/workflows/jazzy-source-build.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index d91cf092..041223e5 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -35,7 +35,7 @@ jobs: https://raw.githubusercontent.com/ros2/ros2/${{ env.ROS_DISTRO }}/ros2.repos file://${{ github.workspace }}/ros2_kortex.${{ env.ROS_DISTRO }}.repos colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: actions/upload-artifact@v1 + - uses: actions/upload-artifact@v3 with: - name: colcon-logs-${{ matrix.os }} + name: colcon-logs path: ros_ws/log From ce361a725741fe17c9c01d32f44953ac5c86a122 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 13:03:53 -0500 Subject: [PATCH 22/42] CI workflow rectifications --- .github/workflows/jazzy-source-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index 041223e5..f1e8c051 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -35,7 +35,7 @@ jobs: https://raw.githubusercontent.com/ros2/ros2/${{ env.ROS_DISTRO }}/ros2.repos file://${{ github.workspace }}/ros2_kortex.${{ env.ROS_DISTRO }}.repos colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: actions/upload-artifact@v3 + - uses: actions/upload-artifact@v4 with: name: colcon-logs path: ros_ws/log From 52e8561cb3df41f48725c1582959f69454f1911f Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 13:06:57 -0500 Subject: [PATCH 23/42] CI workflow rectifications --- .github/workflows/jazzy-source-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index f1e8c051..dfb3c4d9 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -17,7 +17,7 @@ jobs: env: ROS_DISTRO: jazzy steps: - - uses: ros-tooling/setup-ros@v0.6 + - uses: ros-tooling/setup-ros@v0.7 with: required-ros-distributions: ${{ env.ROS_DISTRO }} - uses: actions/checkout@v3 From a8284249758d53f62ae87d3058b383fcdba0c91b Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 13:12:58 -0500 Subject: [PATCH 24/42] CI workflow rectifications --- .github/workflows/jazzy-source-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index dfb3c4d9..2d154005 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -21,7 +21,7 @@ jobs: with: required-ros-distributions: ${{ env.ROS_DISTRO }} - uses: actions/checkout@v3 - - uses: ros-tooling/action-ros-ci@0.3.2 + - uses: ros-tooling/action-ros-ci@v0.4 with: target-ros2-distro: ${{ env.ROS_DISTRO }} # Currently main is compatible with Jazzy From 0c3c9e370789cf40a69b06fb311faa34f2fc1fe8 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 8 Dec 2025 16:03:15 -0500 Subject: [PATCH 25/42] removed semi-binary build --- .github/workflows/jazzy-semi-binary-build.yml | 59 ------------------- 1 file changed, 59 deletions(-) delete mode 100644 .github/workflows/jazzy-semi-binary-build.yml diff --git a/.github/workflows/jazzy-semi-binary-build.yml b/.github/workflows/jazzy-semi-binary-build.yml deleted file mode 100644 index 8ca92b00..00000000 --- a/.github/workflows/jazzy-semi-binary-build.yml +++ /dev/null @@ -1,59 +0,0 @@ -name: Jazzy Semi Binary Build -on: - pull_request: - branches: - - jazzy - - main - push: - branches: - - jazzy - - main - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '13 4 * * *' - -jobs: - jazzy_semi_binary: - name: jazzy semi-binary build - runs-on: ubuntu-latest - strategy: - matrix: - env: - - {ROS_DISTRO: jazzy, ROS_REPO: main} - - {ROS_DISTRO: jazzy, ROS_REPO: testing} - env: - UPSTREAM_WORKSPACE: ros2_kortex.${{ matrix.env.ROS_DISTRO }}.repos - ROSDEP_SKIP_KEYS: robotiq_description - CCACHE_DIR: ${{ github.workspace }}/.ccache - BASEDIR: ${{ github.workspace }}/.work - CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }} - steps: - - uses: actions/checkout@v3 - # The target directory cache doesn't include the source directory because - # that comes from the checkout. See "prepare target_ws for cache" task below - - name: cache target_ws - if: ${{ ! matrix.env.CCOV }} - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.BASEDIR }}/target_ws - key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }} - restore-keys: | - target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} - - name: cache ccache - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.CCACHE_DIR }} - key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} - restore-keys: | - ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }} - ccache-${{ env.CACHE_PREFIX }} - - uses: 'ros-industrial/industrial_ci@master' - with: - config: ${{toJSON(matrix.env)}} - - name: prepare target_ws for cache - if: ${{ always() && ! matrix.env.CCOV }} - run: | - du -sh ${{ env.BASEDIR }}/target_ws - sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete - sudo rm -rf ${{ env.BASEDIR }}/target_ws/src - du -sh ${{ env.BASEDIR }}/target_ws From 5c86362c80eb9fe9605a1e3714aaeeafaf0a9964 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Tue, 9 Dec 2025 09:25:33 -0500 Subject: [PATCH 26/42] ci-ros-lint update --- .github/workflows/ci-ros-lint.yml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml index ea071bb7..288499e2 100644 --- a/.github/workflows/ci-ros-lint.yml +++ b/.github/workflows/ci-ros-lint.yml @@ -11,8 +11,8 @@ jobs: matrix: linter: [cppcheck, copyright] steps: - - uses: actions/checkout@v3 - - uses: ros-tooling/setup-ros@v0.6 + - uses: actions/checkout@v4 + - uses: ros-tooling/setup-ros@v0.7 - name: Set environment variable for cppcheck 2.7 run: echo "AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS=1" >> $GITHUB_ENV - uses: ros-tooling/action-ros-lint@v0.1 @@ -32,8 +32,8 @@ jobs: strategy: fail-fast: false steps: - - uses: actions/checkout@v3 - - uses: ros-tooling/setup-ros@v0.6 + - uses: actions/checkout@v4 + - uses: ros-tooling/setup-ros@v0.7 - uses: ros-tooling/action-ros-lint@v0.1 with: distribution: rolling @@ -49,8 +49,8 @@ jobs: matrix: linter: [cpplint] steps: - - uses: actions/checkout@v3 - - uses: ros-tooling/setup-ros@v0.6 + - uses: actions/checkout@v4 + - uses: ros-tooling/setup-ros@v0.7 - uses: ros-tooling/action-ros-lint@v0.1 with: distribution: rolling @@ -58,4 +58,4 @@ jobs: arguments: "--linelength=100 --filter=-whitespace/newline --exclude=kortex_driver/src/kortex_math_util.cpp" package-name: kortex_bringup - kortex_driver + kortex_driver \ No newline at end of file From 8922a1ba34174991c870ecc144f9c32cc4d42129 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Tue, 9 Dec 2025 09:41:46 -0500 Subject: [PATCH 27/42] modified source build .yml --- .github/workflows/jazzy-source-build.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index 2d154005..0c6fdd52 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -1,5 +1,10 @@ name: Jazzy Source Build on: + pull_request: + branches: + # try to keep jazzy and rolling(main) in sync + - jazzy + - main push: branches: # try to keep jazzy and rolling(main) in sync From 3bff68ebc43efaa55ed5dec5821b9693330b20e2 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Tue, 9 Dec 2025 10:47:00 -0500 Subject: [PATCH 28/42] kept source build check on push only --- .github/workflows/jazzy-source-build.yml | 5 ----- 1 file changed, 5 deletions(-) diff --git a/.github/workflows/jazzy-source-build.yml b/.github/workflows/jazzy-source-build.yml index 0c6fdd52..2d154005 100644 --- a/.github/workflows/jazzy-source-build.yml +++ b/.github/workflows/jazzy-source-build.yml @@ -1,10 +1,5 @@ name: Jazzy Source Build on: - pull_request: - branches: - # try to keep jazzy and rolling(main) in sync - - jazzy - - main push: branches: # try to keep jazzy and rolling(main) in sync From 955e217e45038d54f08ac361f0df38f944ec1bd7 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Tue, 9 Dec 2025 10:48:10 -0500 Subject: [PATCH 29/42] format rectification --- .github/workflows/ci-ros-lint.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml index 288499e2..dcae879c 100644 --- a/.github/workflows/ci-ros-lint.yml +++ b/.github/workflows/ci-ros-lint.yml @@ -58,4 +58,4 @@ jobs: arguments: "--linelength=100 --filter=-whitespace/newline --exclude=kortex_driver/src/kortex_math_util.cpp" package-name: kortex_bringup - kortex_driver \ No newline at end of file + kortex_driver From 7beb7d3336a855d0658cc39e1a751dd74342e060 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Tue, 9 Dec 2025 14:00:20 -0500 Subject: [PATCH 30/42] fix deprecated hardware_interface API (#327) --- kortex_driver/include/kortex_driver/hardware_interface.hpp | 2 +- kortex_driver/src/hardware_interface.cpp | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/kortex_driver/include/kortex_driver/hardware_interface.hpp b/kortex_driver/include/kortex_driver/hardware_interface.hpp index 6bc45a69..33f37fda 100644 --- a/kortex_driver/include/kortex_driver/hardware_interface.hpp +++ b/kortex_driver/include/kortex_driver/hardware_interface.hpp @@ -84,7 +84,7 @@ class KortexMultiInterfaceHardware : public hardware_interface::SystemInterface RCLCPP_SHARED_PTR_DEFINITIONS(KortexMultiInterfaceHardware); KORTEX_DRIVER_PUBLIC - CallbackReturn on_init(const hardware_interface::HardwareInfo & info) final; + CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams & params) final; KORTEX_DRIVER_PUBLIC std::vector export_state_interfaces() final; diff --git a/kortex_driver/src/hardware_interface.cpp b/kortex_driver/src/hardware_interface.cpp index f0e856b1..4bbff4e5 100644 --- a/kortex_driver/src/hardware_interface.cpp +++ b/kortex_driver/src/hardware_interface.cpp @@ -84,15 +84,16 @@ KortexMultiInterfaceHardware::KortexMultiInterfaceHardware() } } -CallbackReturn KortexMultiInterfaceHardware::on_init(const hardware_interface::HardwareInfo & info) +CallbackReturn KortexMultiInterfaceHardware::on_init( + const hardware_interface::HardwareComponentInterfaceParams & params) { RCLCPP_INFO(LOGGER, "Configuring Hardware Interface"); - if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) + if (hardware_interface::SystemInterface::on_init(params) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; } - info_ = info; + info_ = params.hardware_info; // The robot's IP address. std::string robot_ip = info_.hardware_parameters["robot_ip"]; if (robot_ip.empty()) From 414c0bdda0fd3befbdf708690f92a7615bfc14cd Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Tue, 9 Dec 2025 14:58:55 -0500 Subject: [PATCH 31/42] Update to parallel_gripper_controller (#324) --- kortex_description/arms/gen3/6dof/config/ros2_controllers.yaml | 3 +-- kortex_description/arms/gen3/7dof/config/ros2_controllers.yaml | 3 +-- kortex_description/package.xml | 1 + 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/kortex_description/arms/gen3/6dof/config/ros2_controllers.yaml b/kortex_description/arms/gen3/6dof/config/ros2_controllers.yaml index b6396f2f..d1b41ad9 100644 --- a/kortex_description/arms/gen3/6dof/config/ros2_controllers.yaml +++ b/kortex_description/arms/gen3/6dof/config/ros2_controllers.yaml @@ -12,7 +12,7 @@ controller_manager: type: picknik_twist_controller/PicknikTwistController robotiq_gripper_controller: - type: position_controllers/GripperActionController + type: parallel_gripper_action_controller/GripperActionController fault_controller: type: picknik_reset_fault_controller/PicknikResetFaultController @@ -51,6 +51,5 @@ twist_controller: robotiq_gripper_controller: ros__parameters: - default: true joint: robotiq_85_left_knuckle_joint allow_stalling: true diff --git a/kortex_description/arms/gen3/7dof/config/ros2_controllers.yaml b/kortex_description/arms/gen3/7dof/config/ros2_controllers.yaml index bd98a73d..7c083326 100644 --- a/kortex_description/arms/gen3/7dof/config/ros2_controllers.yaml +++ b/kortex_description/arms/gen3/7dof/config/ros2_controllers.yaml @@ -12,7 +12,7 @@ controller_manager: type: picknik_twist_controller/PicknikTwistController robotiq_gripper_controller: - type: position_controllers/GripperActionController + type: parallel_gripper_action_controller/GripperActionController fault_controller: type: picknik_reset_fault_controller/PicknikResetFaultController @@ -52,6 +52,5 @@ twist_controller: robotiq_gripper_controller: ros__parameters: - default: true joint: robotiq_85_left_knuckle_joint allow_stalling: true diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 932879b1..6a6a20b3 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -21,6 +21,7 @@ for KINOVA KORTEX™ arms and supported grippers

joint_trajectory_controller robot_state_publisher robotiq_description + parallel_gripper_controller picknik_reset_fault_controller picknik_twist_controller rviz2 From 8e40a6ce41272556a35627481b4438a786b8ee06 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Wed, 10 Dec 2025 13:17:24 -0500 Subject: [PATCH 32/42] Modified CI workflow checks --- .github/workflows/README.md | 8 +-- .github/workflows/rolling-binary-build.yml | 56 ------------------ .../workflows/rolling-semi-binary-build.yml | 58 ------------------- .github/workflows/rolling-source-build.yml | 37 ------------ 4 files changed, 4 insertions(+), 155 deletions(-) delete mode 100644 .github/workflows/rolling-binary-build.yml delete mode 100644 .github/workflows/rolling-semi-binary-build.yml delete mode 100644 .github/workflows/rolling-source-build.yml diff --git a/.github/workflows/README.md b/.github/workflows/README.md index 9e13d7ad..3c88ebb7 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -6,10 +6,10 @@ A RED job might not mean that this package is currently broken but that an depen To avoid overloading users viewing the main README page a full list of build statues can be kept here for package maintainers -ROS2 Distro | Jazzy | Rolling -:---------: | :---: | :-----: -| **Branch** | [`jazzy`](https://github.com/Kinovarobotics/ros2_kortex/tree/jazzy) | [`main`](https://github.com/Kinovarobotics/ros2_kortex/tree/main) -| **Build Status** | [![Jazzy Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml?branch=jazzy)
[![Jazzy Semi-Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-semi-binary-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-semi-binary-build.yml?branch=jazzy)
[![Jazzy Source Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml?branch=jazzy) | [![Rolling Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-binary-build.yml?branch=main)
[![Rolling Semi-Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-semi-binary-build.yml?branch=main)
[![Rolling Source Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-source-build.yml/badge.svg?branch=main)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/rolling-source-build.yml?branch=main) +ROS2 Distro | Jazzy +:---------: | :---: +| **Branch** | [`jazzy`](https://github.com/Kinovarobotics/ros2_kortex/tree/jazzy) +| **Build Status** | [![Jazzy Binary Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-binary-build.yml?branch=jazzy)
[![Jazzy Source Build](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml/badge.svg?branch=jazzy)](https://github.com/Kinovarobotics/ros2_kortex/actions/workflows/jazzy-source-build.yml?branch=jazzy) ### Explanation of different build types diff --git a/.github/workflows/rolling-binary-build.yml b/.github/workflows/rolling-binary-build.yml deleted file mode 100644 index 3fda1219..00000000 --- a/.github/workflows/rolling-binary-build.yml +++ /dev/null @@ -1,56 +0,0 @@ -name: Rolling Binary Build -on: - pull_request: - branches: - - main - push: - branches: - - main - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '13 4 * * *' - -jobs: - rolling_binary: - name: rolling binary build - runs-on: ubuntu-latest - strategy: - matrix: - env: - - {ROS_DISTRO: rolling, ROS_REPO: main} - - {ROS_DISTRO: rolling, ROS_REPO: testing} - env: - UPSTREAM_WORKSPACE: ros2_kortex-not-released.${{ matrix.env.ROS_DISTRO }}.repos - CCACHE_DIR: ${{ github.workspace }}/.ccache - BASEDIR: ${{ github.workspace }}/.work - CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }} - steps: - - uses: actions/checkout@v3 - # The target directory cache doesn't include the source directory because - # that comes from the checkout. See "prepare target_ws for cache" task below - - name: cache target_ws - if: ${{ ! matrix.env.CCOV }} - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.BASEDIR }}/target_ws - key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }} - restore-keys: | - target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} - - name: cache ccache - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.CCACHE_DIR }} - key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} - restore-keys: | - ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }} - ccache-${{ env.CACHE_PREFIX }} - - uses: 'ros-industrial/industrial_ci@master' - with: - config: ${{toJSON(matrix.env)}} - - name: prepare target_ws for cache - if: ${{ always() && ! matrix.env.CCOV }} - run: | - du -sh ${{ env.BASEDIR }}/target_ws - sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete - sudo rm -rf ${{ env.BASEDIR }}/target_ws/src - du -sh ${{ env.BASEDIR }}/target_ws diff --git a/.github/workflows/rolling-semi-binary-build.yml b/.github/workflows/rolling-semi-binary-build.yml deleted file mode 100644 index c88c9cf6..00000000 --- a/.github/workflows/rolling-semi-binary-build.yml +++ /dev/null @@ -1,58 +0,0 @@ -name: Rolling Semi Binary Build -on: - pull_request: - branches: - - main - push: - branches: - - main - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '13 4 * * *' - -jobs: - rolling_semi_binary: - name: rolling semi-binary build - runs-on: ubuntu-latest - strategy: - matrix: - env: - - {ROS_DISTRO: rolling, ROS_REPO: main} - #TODO(moriarty): re-enable rolling testing after rolling feature freeze, known failure upstream - #- {ROS_DISTRO: rolling, ROS_REPO: testing} - env: - UPSTREAM_WORKSPACE: ros2_kortex.${{ matrix.env.ROS_DISTRO }}.repos - ROSDEP_SKIP_KEYS: robotiq_description - CCACHE_DIR: ${{ github.workspace }}/.ccache - BASEDIR: ${{ github.workspace }}/.work - CACHE_PREFIX: ${{ matrix.env.ROS_DISTRO }}-${{ matrix.env.ROS_REPO }} - steps: - - uses: actions/checkout@v3 - # The target directory cache doesn't include the source directory because - # that comes from the checkout. See "prepare target_ws for cache" task below - - name: cache target_ws - if: ${{ ! matrix.env.CCOV }} - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.BASEDIR }}/target_ws - key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }} - restore-keys: | - target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} - - name: cache ccache - uses: pat-s/always-upload-cache@v2.1.5 - with: - path: ${{ env.CCACHE_DIR }} - key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} - restore-keys: | - ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }} - ccache-${{ env.CACHE_PREFIX }} - - uses: 'ros-industrial/industrial_ci@master' - with: - config: ${{toJSON(matrix.env)}} - - name: prepare target_ws for cache - if: ${{ always() && ! matrix.env.CCOV }} - run: | - du -sh ${{ env.BASEDIR }}/target_ws - sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete - sudo rm -rf ${{ env.BASEDIR }}/target_ws/src - du -sh ${{ env.BASEDIR }}/target_ws diff --git a/.github/workflows/rolling-source-build.yml b/.github/workflows/rolling-source-build.yml deleted file mode 100644 index d55a3a3a..00000000 --- a/.github/workflows/rolling-source-build.yml +++ /dev/null @@ -1,37 +0,0 @@ -name: Rolling Source Build -on: - push: - branches: - - main - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '43 1 * * *' - -jobs: - rolling_source: - runs-on: ubuntu-22.04 - strategy: - fail-fast: false - env: - ROS_DISTRO: rolling - steps: - - uses: ros-tooling/setup-ros@v0.6 - with: - required-ros-distributions: ${{ env.ROS_DISTRO }} - - uses: actions/checkout@v3 - - uses: ros-tooling/action-ros-ci@0.3.2 - with: - target-ros2-distro: ${{ env.ROS_DISTRO }} - import-token: ${{ secrets.GITHUB_TOKEN }} - # build all packages listed in the meta package - package-name: - kortex_bringup - kortex_driver - vcs-repo-file-url: | - https://raw.githubusercontent.com/ros2/ros2/master/ros2.repos - file://${{ github.workspace }}/ros2_kortex.repos - colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: actions/upload-artifact@v1 - with: - name: colcon-logs-${{ matrix.os }} - path: ros_ws/log From 2a381a169bd3b75eb92ddc679edd398cc6edf94f Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Wed, 10 Dec 2025 13:27:02 -0500 Subject: [PATCH 33/42] modified README of the build checks --- .github/workflows/README.md | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/.github/workflows/README.md b/.github/workflows/README.md index 3c88ebb7..ef4def62 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -13,15 +13,10 @@ ROS2 Distro | Jazzy ### Explanation of different build types -**NOTE**: There are three build stages checking current and future compatibility of the package. +**NOTE**: For the jazzy branch, there are two build stages checking current and future compatibility of the package. 1. Binary builds - against released packages (main and testing) in ROS distributions. Shows that direct local build is possible. Uses repos file: `src/$NAME$/$NAME$-not-released..repos` -1. Semi-binary builds - against released core ROS packages (main and testing), but the immediate dependencies are pulled from source. - Shows that local build with dependencies is possible and if fails there we can expect that after the next package sync we will not be able to build. - - Uses repos file: `src/$NAME$/$NAME$.repos` - -1. Source build - also core ROS packages are build from source. It shows potential issues in the mid future. +2. Source build - also core ROS packages are build from source. It shows potential issues in the mid future. From 9067c264e3a3e3bfb390fa10a3ad2be3f42b8ab5 Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 15 Dec 2025 18:34:28 -0500 Subject: [PATCH 34/42] updated the CHANGELOG.rst files --- kortex_api/CHANGELOG.rst | 10 ++++++++ kortex_bringup/CHANGELOG.rst | 12 +++++++++ kortex_description/CHANGELOG.rst | 25 +++++++++++++++++++ kortex_driver/CHANGELOG.rst | 13 ++++++++++ .../CHANGELOG.rst | 15 +++++++++++ .../CHANGELOG.rst | 15 +++++++++++ .../CHANGELOG.rst | 16 ++++++++++++ 7 files changed, 106 insertions(+) create mode 100644 kortex_moveit_config/kinova_gen3_lite_moveit_config/CHANGELOG.rst diff --git a/kortex_api/CHANGELOG.rst b/kortex_api/CHANGELOG.rst index d57ea4b1..8ff5385d 100644 --- a/kortex_api/CHANGELOG.rst +++ b/kortex_api/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package kortex_api ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* modified the kortex trademark name (`#305 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Package version updates +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ diff --git a/kortex_bringup/CHANGELOG.rst b/kortex_bringup/CHANGELOG.rst index 8ed636bb..57ebdf38 100644 --- a/kortex_bringup/CHANGELOG.rst +++ b/kortex_bringup/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package kortex_bringup ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (`#228 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Fixed the Gazebo Fortress Simulation + Separated the arm and gripper control for Gen3_Lite + Fixed bugs (`#252 `_) +* Added the empty gripper option for gen3.launch.py (`#242 `_) +* Fix mock_hardware and enable simulating gen3_lite (`#196 `_) +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ diff --git a/kortex_description/CHANGELOG.rst b/kortex_description/CHANGELOG.rst index d0c01e78..f28a2511 100644 --- a/kortex_description/CHANGELOG.rst +++ b/kortex_description/CHANGELOG.rst @@ -2,6 +2,31 @@ Changelog for package kortex_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* Update to parallel_gripper_controller (`#324 `_) +* fixed bringing up the Gen3 wo gripper issue (`#321 `_) +* fixed the gen3_lite fake_hardware issue (`#319 `_) +* fixed gen3_lite moveit issues (`#318 `_) +* Modifications to fix moveit issues while controlling Gen3_lite (`#316 `_) +* modified the kortex trademark name (`#305 `_) +* Fixed pi issue #295 (`#296 `_) +* Replaced file:// with package:// + Added temporary repositories as dependencies (`#275 `_) +* Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (`#228 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Fixed the Gazebo Fortress Simulation + Separated the arm and gripper control for Gen3_Lite + Fixed bugs (`#252 `_) +* Added the empty gripper option for gen3.launch.py (`#242 `_) +* Modified the joint limits of Gen3 and Gen3 Lite robots as per the values in the User Guides (`#241 `_) +* Added .STL files for the Gen3 7dof meshes (`#235 `_) +* Added a Moveit2 package for Gen3-Lite (`#231 `_) +* Update gripper descriptions for use on HW (`#206 `_) +* Update gen3 lite and gripper macros (`#191 `_) +* Cleanup robots for visualization & sim (`#180 `_) +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ * Refactor MoveIt Launch files (`#162 `_) diff --git a/kortex_driver/CHANGELOG.rst b/kortex_driver/CHANGELOG.rst index d45751da..855bdeab 100644 --- a/kortex_driver/CHANGELOG.rst +++ b/kortex_driver/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package kortex_driver ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* fix deprecated hardware_interface API (`#327 `_) +* Fixed pi issue #295 (`#296 `_) +* modified the kortex trademark name (`#305 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Add force and velocity hardware interfaces (`#204 `_) +* Changing the list of packages maintainers +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ * cxx: remove unused-but-set-parameter (`#164 `_) diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/CHANGELOG.rst b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/CHANGELOG.rst index 14f86d9f..35db6258 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/CHANGELOG.rst +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package kinova_gen3_6dof_robotiq_2f_85_moveit_config ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* fixed gen3_lite moveit issues (`#318 `_) +* Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (`#228 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Update planner_plugin parameters (`#199 `_) +* Remove outdated config artifacts (`#198 `_) +* Cleanup robots for visualization & sim (`#180 `_) +* Update planning pipeline configurations (`#187 `_) +* Changing the list of packages maintainers +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ * specify planning pipelines to use (`#157 `_) diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/CHANGELOG.rst b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/CHANGELOG.rst index 36e7f51e..327a698a 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/CHANGELOG.rst +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package kinova_gen3_7dof_robotiq_2f_85_moveit_config ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.2.4 (2025-12-15) +------------------ +* fixed gen3_lite moveit issues (`#318 `_) +* Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (`#228 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Update planner_plugin parameters (`#199 `_) +* Remove outdated config artifacts (`#198 `_) +* Cleanup robots for visualization & sim (`#180 `_) +* Update planning pipeline configurations (`#187 `_) +* Changing the list of packages maintainers +* Contributors: Abed Al Rahman Al Mrad + 0.2.2 (2023-08-09) ------------------ * specify planning pipelines to use (`#157 `_) diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/CHANGELOG.rst b/kortex_moveit_config/kinova_gen3_lite_moveit_config/CHANGELOG.rst new file mode 100644 index 00000000..cc746042 --- /dev/null +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/CHANGELOG.rst @@ -0,0 +1,16 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package kinova_gen3_lite_moveit_config +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.2.4 (2025-12-15) +------------------ +* fixed gen3_lite moveit issues (`#318 `_) +* Modifications to fix moveit issues while controlling Gen3_lite (`#316 `_) +* Remove Gazebo Classic support and Update for MoveIt Jazzy/Rolling (`#228 `_) +* Contributors: Abed Al Rahman Al Mrad + +0.2.3 (2025-02-27) +------------------ +* Fixed the Gazebo Fortress Simulation + Separated the arm and gripper control for Gen3_Lite + Fixed bugs (`#252 `_) +* Added a Moveit2 package for Gen3-Lite (`#231 `_) +* Contributors: Abed Al Rahman Al Mrad From 23d21663535330cb13b45a44aca85a884ca0c22c Mon Sep 17 00:00:00 2001 From: Abed Al Rahman Al Mrad Date: Mon, 15 Dec 2025 18:34:45 -0500 Subject: [PATCH 35/42] 0.2.4 --- kortex_api/package.xml | 2 +- kortex_bringup/package.xml | 2 +- kortex_description/package.xml | 2 +- kortex_driver/package.xml | 2 +- .../kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml | 2 +- .../kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml | 2 +- kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/kortex_api/package.xml b/kortex_api/package.xml index bca4bd08..a4207df5 100644 --- a/kortex_api/package.xml +++ b/kortex_api/package.xml @@ -1,7 +1,7 @@ kortex_api - 0.2.3 + 0.2.4 KINOVA KORTEX™ API Marq Rasmussen diff --git a/kortex_bringup/package.xml b/kortex_bringup/package.xml index c1460ba7..0ee35602 100644 --- a/kortex_bringup/package.xml +++ b/kortex_bringup/package.xml @@ -2,7 +2,7 @@ kortex_bringup - 0.2.3 + 0.2.4 Launch file and run-time configurations, e.g. controllers. Marq Rasmussen diff --git a/kortex_description/package.xml b/kortex_description/package.xml index 6a6a20b3..8bcfcb87 100644 --- a/kortex_description/package.xml +++ b/kortex_description/package.xml @@ -2,7 +2,7 @@ kortex_description - 0.2.3 + 0.2.4

URDF and xacro description package for KINOVA KORTEX™ robots

This package contains configuration data, 3D models and launch files diff --git a/kortex_driver/package.xml b/kortex_driver/package.xml index c77fb935..e3dfbb0b 100644 --- a/kortex_driver/package.xml +++ b/kortex_driver/package.xml @@ -2,7 +2,7 @@ kortex_driver - 0.2.3 + 0.2.4 ROS2 driver package for the Kinova Robot Hardware. Alex Moriarty Martin Leroux diff --git a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml index 89978b4f..04784a76 100644 --- a/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_6dof_robotiq_2f_85_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_6dof_robotiq_2f_85_moveit_config - 0.2.3 + 0.2.4 An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework diff --git a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml index 630457b1..ced1e26a 100644 --- a/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_7dof_robotiq_2f_85_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_7dof_robotiq_2f_85_moveit_config - 0.2.3 + 0.2.4 An automatically generated package with all the configuration and launch files for using the gen3 with the MoveIt Motion Planning Framework diff --git a/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml b/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml index 4a806840..8a0f61b8 100644 --- a/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml +++ b/kortex_moveit_config/kinova_gen3_lite_moveit_config/package.xml @@ -2,7 +2,7 @@ kinova_gen3_lite_moveit_config - 0.2.3 + 0.2.4 An automatically generated package with all the configuration and launch files for using the gen3_lite with the MoveIt Motion Planning Framework From 50681544cf74750b601b55e7e62271db3716aba3 Mon Sep 17 00:00:00 2001 From: aalmrad Date: Mon, 5 Jan 2026 20:22:12 -0500 Subject: [PATCH 36/42] updated the kortex api fetching technique (#332) --- kortex_api/CMakeLists.txt | 2 +- kortex_api/linux_x86-64_x86_gcc.zip | Bin 0 -> 6898420 bytes 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 kortex_api/linux_x86-64_x86_gcc.zip diff --git a/kortex_api/CMakeLists.txt b/kortex_api/CMakeLists.txt index ddf42b71..4e0ebeb2 100644 --- a/kortex_api/CMakeLists.txt +++ b/kortex_api/CMakeLists.txt @@ -3,7 +3,7 @@ include(FetchContent) #include(ExternalProject) FetchContent_Declare( kinova_binary_api - URL https://artifactory.kinovaapps.com:443/artifactory/generic-public/kortex/API/2.5.0/linux_x86-64_x86_gcc.zip + URL ${CMAKE_CURRENT_SOURCE_DIR}/linux_x86-64_x86_gcc.zip URL_HASH MD5=64bd86e7ab8bda90ef1fc7d6a356e080 ) diff --git a/kortex_api/linux_x86-64_x86_gcc.zip b/kortex_api/linux_x86-64_x86_gcc.zip new file mode 100644 index 0000000000000000000000000000000000000000..6a9285a15b09105e93ac6cac23710da09a80ebce GIT binary patch literal 6898420 zcma%ibC732*5$8k+qP}nw(Y7en_aeTqsw-eZC7>Kwza*p-^MqyyEC!xkIWY@@5{KE z5hwHJ&2toGKtNFe|MP*>{Gso8(90{v@cYi0Z& zED-*w9}`UOw|I2qF6Bkz_7Y8R1&%d8dME)@c%0Eo# zEr-;tY;c$mKW)FE69Vc*eq{gj8#Q9YDTA6)$_9~!6iywEJ*hd6*5)8O=yh*OTbb^l zBN}`$WXt5Zo{Dao@4%%3A`!M?XluXR)P)No=zG-)=>0l`<11(o1k>75A=-MleZq~Z$QiCls}ebo%qn ze*)2+^~KcQO94y{&Ik{AccZu~!cf!8PQqh9#ZyKe7l25ml5VN|_ISsh-=sDqPUWn5 zMsy@fWyNkWr>*wIa&-9HbgSrCO;;D~tr9(x#?sI{?V+bGtc|!W+Q5cZ_JFIp_ zloQJSAq~z8TJCH>IMKcUOxz|1k@2~U%Ooz1&r{co4S9UnyyQo8Xml`0N%+V5rS!w&rWeDSG?Zz0zCJEkZ7D0X+;Pp)$@3CT{g}wG{^ysl;Wa z*&zih4XPpyx%Vr#L{h&qoVPLUu-kKatHh&Rr10IO;5{!BXTLW6(~CMon9cLhz9;8t zm&r-=jNF;05iI9Bz4iuNFq(fA(?#)+6IgK5|JG&~Zvl^(mw2W695bV3FV~)_bW<*9 z_|u_4laZ#u?Xra{LSw%xI|{+!i2mYhm%ZDGrme9sevqD`(iMA&;W|mF5D3NSPMb{3 zmC0f^Mu+3N=6JX0MWloCN>{mQpApJ=Y3L?-FeIux(x5!8w#Y6@>TE7K$_s4vn&4 zv4f9`lf7a7=F2UVWm(Fa-4i~dMYtn;afc*Uau;hTRR7#*6Izw>ti*8cK*^zPJ>Gp& znfO*;TppsWoXu;$HT3eN@KQ(AIs*O-^lE8}ijg%nRs~01D9F-^KQ2fmgA_FbBmA!A z7&~q8Bh`D;L7x5J#OHY2s|0-80-OdJ2cL5zRYhaFQ*+)Arzm$fw8OISPqW7}fVj`y zH&aCNg@VcKBo74KI-+~~t=}yQ^!5}je8J+4b`)l*Jr>++?AWlPn&Zo;2~j~gc(K}pmpXx`7->h1YCWyoY)c3u@w>@_-0q~=CM(82EpPmWzQ;v zc+-&HThvg>HxDhE8_Qex(j*L-!<5nJm}E-fy}o@+;#h^%bR30Jk%@~qarXcT$hmMJ zudtTZZAS1Xhy~B^*r?eaGW~u_-6wQ&gcVM{h#W8}|35|?F~-Y|-|v=rpV*hQp7Kq+ z5IjNIano^xPF*Z#5{~I$c4IHHsOlpxy2&0Wbk$68G(HTXfowhu8a|1xFg;n8;(rof zmm*(N$?x9>&2Gadjs!$)Q7Ggcg>k(?e2);%_GsH>u2zWqoBzZP=7@YEdIE=0#C}`G!2k%O3*`@~mqh;&#xRH!7RU07fMv ziBf^nJ2&`Tjcdm}0ZziqC5qgzLE7e2*;_0KgR2vE38&i3JpfD?8C6aL;Or8f;Ch1y zL6~7`1uSI^&bgAcljcdaBmoi$^CgSn6aAxKG35z5NIDoQBnXDf5@_H*enrvrW-jrn z9hmZu7CsiFgKYkmLiP-r()e?zn_kQttjM1?jTLMG;T9>(({~%x_5wd5W#2uQ1-ClG zJ3RK40zSzNY{Pvnu6CA%Z<05pG;R#!ZL+1YPR&aPj$p^(J-uq|-9s%#Uvpd;NgeOsTE>j@%H&~56HCjj3_)QXODtLVyvb%02wO(1taBKFj#0>8hT za{A;BeJNVLVk_4@$!;t~Aol8yd9AQ*WU~u@eINb$NwfkqXwoT<_=o3800(G7ed#du zhHjh`9WQP#-4&ALR0g>L2aIVUg3T{FZQGSsHeTe3jmoroN8%?UTQL#@^u764pTV4pQ zBt0G_P$xs49=^uomb1!PUUp_)GkhLnCr{XTANDCOl-B6pyW6E)J=3ZJ2HE2>-ojz z=mr~bHTQ|Qh0E@etXUOJQ~Hw@mokb#AU3ND66Hi?kgb_JO!qkrEP(BCZaX{E^qL-v zZM3|ULLXAfb@>ymDfCziv4(Suzrm~o1@z|4t(^%Xb9F0Q`GZTAwxIX>CRc zCQmM5lZh&jXc%2m?26gp#DX~?Ev}BepL@S@4cgJ4oo)_mcB}CijepYVi=~+3S3}mj z+{pF{&T)%L*-TBR{@i(ppWEor2ymo6J~sgUQvjGXb%oFc1W$3*y3V4jW6E23%x=$E z*DU()Y0{5Y3ayWy%F&rn*%B(gQEsc4Z$K~D)I*nNc6*tIrfC8)(|=ZL!!l-Q8mS5* zOZlo^KyJ7cLFS*0aR0dUP!^`>XfW#p3Pp+holMf}Gw(2#)PM7aL7`@P*`^c>-b-rL zXN+5{o2Egx$kMeXWx}R;RQxrCOA=A1swl3(+I}Qi9l&bk=h`H{hzC>`-2o^Un_EoB zb{9WBS8}0@;g+OR4}kHG=`7m-gTW3L*8@qFwTY_ebiPRX(=o;tRX@PtK`~EBN+_is z6N<+h@l)(^-Rb?xFwG(Y&fYFM1jS=$-Zm77RErJUjV(KQhW^38)CHm&Tk-rVU{XBU zNoRq#xU%pUHyID6s;j~AuXmp^p3HKX9diyT^A({fIEDK|M0Cq)jn1Ee&pL+%RkZ`w zRl-~=-*uR*@3PUf*{E?Efp~kQj-@ZCJovHK*#RELNZ#u2OA#jvm&>be?;QG>G>_bF#dH{CMle)qWT*T!~BhhssG)sENtX#_Wy{5b!14GQ2p%v z#mW`6sk*7&6`S)-I#bo$t<*F{g)_64>sT_bNEg(KzkL;smQQ2Qv{LjXr!U{9$ynBs zP{<60DfxKt9<%eN4}bR=T)&0tD{B7{$x*G7(fgAW*;xQ^`XxuW)RdJZD~tkON3HZn z(twGBA%p^+h34vLFXavBKA#_Fg+PYu6l-CJ*IDCEw0XDQm>=`4An>;%8D(Q-$5TwU zUZ3{!AarUzxtoQV(+;#S!Z4{tJz&}FZx}i}0 zm>zXrzUmt65#n+#j6UW#CJJe(l7?vYP4iyStxL?)>SyYx zssxd1uK_$-&>tEz0mo1uApTJ@uyzS-wgYQONQe2s*{EnOIy0CMcXHJJ(~%5ZbEmR< zJ$0zG6lI!%Vg+-A!x&$zgt-C`g}w-1yutv|LKVs%238_XNICMn>%oYJBv~lR)OZCz zenKJmrxYT-G$G;{F?xVMutvxMexmP33qp-+woA*bvDcoQ9vMR3oB0TY!_nX4wD9c0 z!Rs$uTr9MWTutmz!G!J^%k7K%KjRw~!OQZJI2RPDoo7o!Jyb;)({Qf{XVWpn?eV(% zeGFOpzR9!?nh&!J;?|S#(dK;6U%)xxB}U$AaJN4}*NS-8M>g2$qGgN3?6A}X)r-vO#z<#u zgIPZLyr9pRZ}-90dt@Xqr&CVhfyk-7(q&G{w5EE)VO;0RsUebc}I06lU5fb`!1PSwoW<)5Qp?Qew*PSo%A zPa4{I#VACBj!id>7U}Y2xJ^S8)TaSfu|7|`YBKp5`Hq5!@6X&zR>yhNHb;1O6P#P` z89xI5-0i3w(y;19G?wM21-^ zNmWp*->TpEDy#+7Pcfb5_BXb}zUT|m#k7N)1x~69Eb~|}O$*t;LKLT*Agl;DFICm_ zey|+oW6H!cKY}pgnuqn73x28cC&|y&;#U6~r`~5GiXD%KQ)5LXcXKWj zVUK9et;CoZ5!T}Wl zhHfcG;+_-m#Et9NjpUY-wUs}ERTxuQ1>)}tzJ3C;{2;k9!b*=1>f8lOeBt2Jm{*PT z%?s2%L>NR8B4eXdtD4%JDInBOM^91~U9f?SnKH)Mz^{A!<%@WDE)jZ@R}wvLDD%RI8Q559i@$XmbMeXPO0mdPQH8iECJrrwVk# zUflieT3)lWY072URNWI7@lZz~WaI*MBK}Gnu{QV!QL_^;x z1a<~03v-#Z(g+)t{1}cws=~7xzA~+mmy;F;N}KH53pCwOSW9}5udbEd)%tqg)UTwB ziW=FUDg97#@;_q}3A%(|McF#nRcw$N1AbAFn@zgnclHX+r$gcm)v2|lV zlKE9Z@c5}=pRlT%e>oEoC*~;e=ozTg!;;jFkS_7b*mZl_DnY#H>ef!?A@VS*rIFL5 zqsL4*!L%Z4DOHazWyi5qZUk;a^j68uNAMH+0!+`;J!FYTFjN+VTsq%za(%USYiGGQ%g1^{%;g*1eBnfSv2wEPY$F`ok26v^sjZLpIF-)N zfFJ%0N(xzx8Mq=R+x7)0ABRnCRC!C4>TXww4wsuX8q>#mzt|o@duxQv4(C68#YoDX z{1H&gU<^#^N#Oa~UNRH5wWZt5~%*!Wy+RLij^*)?0cC!9- z>uf`$+tTn;{1`a%3Zoxw?piYS+U+2UeZ;`U$x~*EBMWYQYNbcv6|AuP7H=Jodh}cM zl+A^nwSy%HyXq0#P~05S?S-{~aao;#kuvS-fe-*FbqP&T&TVVkB}mFYsy$PzZRq={ zHFkE&v^I3P_s0|9qjL zCsn!$&-UZH+eQUTPt4*mHvj%)luO9s)N{G-kRNB4`?y}2u5xoqOl2&y#37~_IsTZQ z;Fr(tuA`eFMW26MxShH@oqDwO@n!4gB=GM^*WEnHbLoB$+HB=h9+~$w@(yiehI&I3 zUwlf<6s%XDi$u=Y!%DdHUPY=nC=&vfUk3H`R*BSeLZpT7xrSO)A<^C)Ei>6}yfE|X zWR=EtV!GErDli!#*C*ZXxFgwUfSXM5@6SC&%pBj3WdgQ9yYrWP504Ek(ikY3X;+yh zH!x4SJ)Js$_5F;LMON%TKt%C<2fsN?M#J+ttHvtXyF6;6!_RL63P|_cpeA+Wt2^t{}K!F&C1K3X>LP;yzkKzTr zs7aZ*Z)G>mylDRz1;7P;weWr8yZgfwFZ?!N!3!ibQ)nHqcY{YzI>`D;Bwp#IpnTA~ z+vh0&9g6418+h)A3`y{GN-X9S9=*pZjI(sO<})$$k7#w8W0kwo*?`50nYco9bCfS! z$aC|s(;|uxX19GoK?oa|^BZOi!-{nZ#p*kXQTWzLU~;AxwlLdD-`!MEYB{+&qKI6LjLUqNAr7Qhckt=j8UeGCOZMN%Y%vQv}aq!lA*GpsP zxooHD!f?#@5Q1I(x;PBio7rWkt+-H6GOuENEHqc6Zo{sMuAT;#;*?frkT2H`Yt}j5~E8Z<_UK3JgJ=#I^x%@hP{kf6z^0v z(GtK>Y&gd$71y27eEEK;6vI#iG>-rVmCG9Y!IiOY(?#puRdHU>hIWHwl4yePqr*@- zDVOs#S`QVH4#xLvey@QO^j_RSZl1jZ1_ty`-B>B7YuIO%58_lV9r)UPa_S2rf!C1R zuNFp~p{Lh$6LxoAQbMiL3^2KlKs<}U82|TM=`=QL0>#M<1yp&;M=J&uhUhD}_)uo3 zcSzBkSBlhWoB@O&Ks6*pSTCK`p$Htff@aI8`qd-QgSLr zbd9F@MxUzI4>Zo9{*4TVp>}Co2~u4ss-FiV8kH3CN-Vg_m??W1DnV+ohBmo-fRLE= zkP&TujtqfAzT7>1k=aGV;b1yTbYjg^b)>{f77E*f~*P{Kd)`kHmK?I!vEmuJj(oi{ioLk;%9BAN;;Vrf)-XpDQWXA#2nhs zUOd?np)kitqU{U@FbiM^bX9i${C(_BNigjP{8ndVFf-Q0}DY)j<5ZQ`vvFMy>h zI=4y)_PgD&0Kf`r)P4`@>Z=Evs5?{UJckX0)xc&lwGsFGMXxQiWvKc#!w<^_D94uL z8=E6QYCXGpBq^=!JkJ(aio1*rt_ z3psC{Dd(?B@Zt{W6XM3p2pcAvK)oq>q%)Uu=LyHcBOTXa<;)hLR|kJz4qA*gdRgX* z-ci7h$0Y()O_AW2|77tUpg4=Ct%g)SHBIy9BK8q0?9!r%{|z1 zk;2>~dljvdI>B?ZRrx?A`??158ih-{b@;h`a%1-N`rOwCx?1XiRyfVz)is>?`OW+rjsogwDrz zcbjvsw-;#(`vwg3{#{)@A8>MTCd3xJU*yrBmRN|#1fB^Yx6LrhM-#>wNZH8mV(EkW zpekc|{8CyCFyr1%iJmZbwB25A_n^f+_jlY%g<`>Fd5LC14O*y)ZNIg8$;CJkeB;z! zi!dON#wzbH&;79JoSy_nKFjWX9KH>&Um0QmTLgK&+_`vqxV`RQj|>!qR^paiq(8ns z9l)jzNA3|iqdwlK$mx?-F-Qy5QuDw%)6xk1K6yL4d@3t1@8)UB18ON1($c1{>~+>v z(0p|ozeI9pdWI?ab7$!N1-^=fkPrpNRrW*xG-nz<%IZ_r(-D>UauKXKgF>ACxGJv4 z6~`#Y$Bgp!-6Q^i#YL>ey#&orljisWg;H@n-&<6PgzeMWVooyIyjt;{IEhGMAf6AS z3VU5Y?ub3!TUaed9QT6vUdrwd#t@PNzS0IKLY$Sc?v5Ept*~j{kqQLNu?jwXr={Fd z$?h4A4X!?4eHA?aPyU83n38?;g)33)UrM+ z$8tA4ZrQl*?>^|qf=DeRcoAyTGQvi+jdI)*UgK?3Y0)Rzpz-8Quni`yAe?c%HSFHs3sd&2w$4F-fe1Fe zj0PLN^O>YYn8QeEk6Cjm)_{fhEXBM~L8B$d=K6XJLA}P0AvIB#RD;vD(wBfNeFe?XQbmFAuM@ur^`yhYU}ddEWfdTM_C$I! z5M5shf7+v;guy$-$xtQb5*2=>f~pWFHR?ql$PVX;kL6Z`3PT|nS|JqmkwfH{cg#gb zJ^&u)fCxuinh`)eH6VUN&`MWcL5kQaH&kyTuzKjpAD%@d2ttl3GDJcTf$%EgD6f}@ zU5{@v=8|4G`SK8Iu&F%pw$u#E_lyWn%kh{fw*+;2(X|{sLoXuo0E0?qgfI9+Jtpmx z6NM(lBm+wp&x+A~MFdCYYDRF{b7U!KMrU-ndjjmLC9*OM+bBKW0D04EBfpHNK@pr zAQha|D3ks54BD5F!>r?4dw}|9r@I!WE{E5R&?MSXq)+iA^EJk}f6}+`^a%Ey4qXHP z4sFqEluN}mxKFV%wiBpKuVQE*e|XzV-3}*w?6I@{pCMoAMFKqQ^|a~Cc!%cnxJKGB z{sh)B?TE=obkE#Lm^JjEZuqE0p9Ti4;?SFR+XQUsiv&5Dumd2R`yIhe)-wT*h>hPc zd#@aZO}GJ;p>B4{Zs%<-s7hf~82Vo&R@ESzi||F(;er${$0cV$H}d(#u6on%>3UpY_KKSt%WtEz_k{5_s4 z*2$nS6J`MtL%={N0TZmoATo~Z!MK!CnHOn%uysVs4-?kL^l#~jes*@74R=1au8wor;r_1Um4x>kwqMfJL(YL8As?(DDFlHEFEF7gILR$+A zHi+q*zr*kk%6@SaeK&Y6iOf*bIK{9={WP1Z?wYFE8^x>UmM@tt_P zCiQzqpNvVHe21Y`ACDjb5i#taJ;ZHeinN&{ycAF9Pv z1B||yrzXV|@FPQ3Q+q>i;)G}&C)ZT96IflT6(`_o6I)OZju}!hfQAXQ+E|;~(uI(& zNglZdy;?47Ex#|`QDK8s@Q}AsmA3gB+a5FcOj``$)^2!k_-hK5Rf5jBPpV{E*&(yhOg zkz&i&U3W9pn}abbeSjP6f?=LJvutUM_-vYzaLR#}EDNxLDL`bUk=0BklG~*38wSfL zC*5}I$a&^b&seGDyXG*b;C6m_-2szbaa!HK`=2_%G=gCUupTx7>tDCYkfj-MtEC)N zW(YNkK7r9iUzC;lqg7U)`|o3gpH`@Hu96Wzsq|Nwz{AeZ>ke^CUx9Pa?zZlp)kLCo z^J!wVF{Uw^WhoM|TBG62_{-{CVghGlAj!LHr{f`6<1$JRJ2%2Ti`|nEOBOL{HD{rK znW$+G`9Io>XeIk=hIdv{i`6D2JgDOsJEspTBGm+-zGb5Y0&Q~bMBmp$ZeoX*z&Go7 zW6PdfJCWdZK$Z!+KY>z+W|MT_1J{AAY;bnqEwu_#G9s-A8@62N;)D?<-Ii1;W126v zvS@}goK=E@q61#U?Qo#Uuz5>OAesCuhzHq{wL6AnQXDx{-GmPB

yS`61;46~>G@MbutV=mt6>SS9m8sw zQ;0hTX<{xgm>z+z1fV+a|78QY)CoOh$ zAmOWf+8@o~=z#Pnw0cnF|g`_QrLn&yLO%O&8Zv3O$jE8;5y0FTNg+@ZnZ%*r- zt8QpM>V&q$rAlfS4StnB=h-SW8D4JC~t3c{2hidWs^=vO)gpYb!&s1WmOA%y) zLFDTv2sEaJ>hB`DDkB5lqfg!%pa_qAl|Mp${D97dNw8gV=ZIA-+x=yDz^WbwX|vrX z^2Yr{{#Cc#>Qu*oYHyUTRg#5 z&cTG8VXy_=TPM9b0&%O!)^DO(j;Rnk23ontRNGa^bx6bY*>n?V@K6DUuN*pQ7190Y zIp1>p8CI!81*XOnsO?~NRI45N1GmL9_89YSD^AGiWgtRQ%z6NH(b;gtmthQha8)v2 zhi-vkXH9VJO{Em*13xLW4RICw{7|GN{l@-S9hECHShe-Mw(-Ry;KW5hiP6nqF=kq^ zc2T1Cr|d6@zANffiR*!23#^xiiWl3EF@Vx9o8Qy;U@!xym6W3?K-e)|%8Ld>ewehI5Ymy?P%oVa%eWeh2rA2N2z)94Wy9`3<5C+53}>-6L_0%Oj@8 zCty}O@%t$_4}+RLEl-4MA31)!s6f^MkcQm!>}})paBbHc?p*DCXlqSObvFeiHe6vX zwLkK*ntSg7)vP z$HNm;SP?miza%whhH`_#i_vpk*-tPC6y=`gwn%bQm-&y1)|(tjLqP%iBWxfmn` z6hCt;-36K&Bzd4J#8rX?L-mp)`POXfslkMr`OEF4@0OYK=^wFF!JH`aOIKjvA7&#S4Ihpjo(Eq~u=X0M>h7)yy%sLn30R!HO4HRV9L5Bb)c9J^~NbPb3 z7N9^f5HT1~WNov{i~x6KaGvXLwWQ_#potkSy}+XQt-Ff}Al1PJ1Y$$L`sc5}S>Fl) z)xf9b6d=~#@{*B`I$pyvyW!enbA20iIiw;*_?3s5clfIt{^U1TGnce12it*kSr7gl zeXa~6Q>z?3(KTSyB@#otd|+vwElkTkC|WhQ=)LF7&CGMqzQoRm9doLR^+uT(*^@8>C+o&TBWuS za_(mzX+lOKR*DnZ!Cqz>hFRi8T5ExrooDS3(2u{!9Q^7&MWbtH=Q-Dj^rFKp`>!(r zBXC4MxZYy}@+)_r3eyc^2FnnpNTi3tE82-_; z<@5*zcbfvU)86e8;+cKO>qx#Tn|7zZqFQSV4o+=iF(Zw-`cFEhyAJY`t`u{gkCsA@ zbb20}*sC2Krg4!qyPBLTref`|I4J7aQ2j%&i65N+Y__$Q!ux(2NKBkXsZQdBMlHYQ5y@0}G?Xn&l^dqXIiHpvbpST}w1`U!AI*Ex%6X zhM&nDm8u$GTjP5(lQO4ap005oeCT2ki|Jjg7QMb-8!w%JayP5uUf`_L_fIBH)}U4f zHvWj8m4`q)%N4tG(c(Iv7CLpSp>i$x%(`GTNbXL5LX?`E3cj5^{j%9ngIzDa;`Gr! zkm>t_(38nv%G!v|T>Z6m^${5i&%b?SoTml$`-I@h^(J_Gw%e&XVaJA7Z;cel4Z$^O zf(pvSM3o$DEW-ItC66^kQ~#tiG#+U2MZXh|eRYziR_m}cqD3>&+3Jze-1?(kQV7Iv zFi$}rNEw*@tl04hK!YLnU8O7j9bJWzR83yrH4B7eo58M5QeNph>bnDMg2Ul$99Vk%dMjE1T7hqCifGiDNJ{hBM=aI(C8&HUXc1*dnF*F{qH=Y!p$=y4}4Yz>q*fW7eI z4q|z{7+U_dC>O46ua|Z*Uy!sAzmxFMKAUKJ02Nl|2a{pB!US-#%NzeBn=~Js<=8GS zsa6b)t@0#)A1F~p^G1vvE1k(fLuPeUlbSnUysbZ0E{hEfHX=?lfkR=c`6@&mCY*0R zOY38y)p3Ha48W|flRe`un5+%?DdI)L8EZyMJb`Y$Yk z0H@UwUj&O0OSpOmfISv`z(7ZrYbI6qkmW1slRca^r~CxSr%rqQNxk`_v!>E%fo=3L zW4j;u@GYf7`-`rtDFs|#D0Y9xga6pg(=l%^EJ1DJ$Qoa*LU?SFh%*5pg3?wQ2`zcl za-u17ce)y`l#64n_|Z_WQ)v&#TGttJ%x$BkCup2y>i}@nL)OCoWo3@POMajS*dp11nHw!GlhUOhp6f<=%TcR z+F`B3wd!u6zRsxXZr{>V*I~AL+&=}bH0U0phq~7hra~`;ph9Y~c06tgveG*5rLs$I zlMN>>3#8Rj66k8^G(X_jb&k=|XxC5#g8ozL)K!bIyRqXZ#G}wD)CnN3Fb%LPvfZGz z#?7*Aga#r%G~u*;6Wpbm-wEAQ0s5cNDLtUxLOu)epoDD$@g9 zMZmuw)`=7F@>Vrh3^ABi9HSglSy4T*h2tKy8ncPNe8%*BFtjqr1r3~BIqMO-LK%PL zyr_xuNPuLO22%~<8DldcdJ5NFFH1X;lCjXfJvxqv&P>P*whI62=|Wt5-Hhv#D9eCG zDBTsDsWN&){XQ0NU3)Gz+tY|#(^fiZ@~MNkZrWTVYS!|dL1>Y?R}Lx?FZ4blc1MHr zL$V+xd{Wb;oKM0s}Sic~}ff~a&FEePSDiCY(f_*-p2BO^d; zt_4Q}YJ-beZX~T<&e5<$kc;RWJSaQYq{`85vzbHv%C!5r|6O?6gkj1d@y)F0jRH*h z(@Zr4F|e2u3^i$7STjEIVl=pb8>(?ACoREUru1`LD%JT7p;+-4GuK*GgWE7wNpF_X zu42N8=O!~xo%bv0r71w5>s_@Sp<{YyVtiWfkp>!00KGJXtlM!baHe?X6sQnm`ck?U ziNHJGR?L=VyiIM8t=p(7_y=>*a-4o<=&h@3()POGnWQs14s3^~L;fEDTG15(V z<|X)YC)e;0>^uu~e@dW8hz^EDiDgKljwm3;Y=}C!63`gS%%NH=9Z?8;8D2GV=Kkze z?^f+m-29e%{(x6EqLp{u$nK!AjAwI)H!+S3vA^xIy};k%wa>S_!M^g?x%^P(gwg|! z@7F0TW_0`sZ8o*BF0hM|xc4gVTszHh|GH1xcJKeU2W zQ44kZf>0D&Gf>>+DFRi~+L8eqT9M*=dR8Fq?y!nXJOD-g3n_QF)rC-j6fE!SV~eH> zkKzM)_Pez}9V((+9ckX{eTIe$VV;We_tHQ}Wiuf^cmsat_m!B@?~Twi549A*ogKeF zYshGY)$+-#JoaqNST9{aOIbChW>Lx2E4}L`XpDEFM1`q`2JM-5ptxk}98);U4d%b3 zJ<#nD!d~K;N8<6^9d#XjPuUi0))=L$nw#~t0~>HYrlBbZ)r1-w_CNKSNW~ISIU0Ue zG`M9~aW55CRm4lCHU0`*t~;jMEqvD;PND6MmH-OeCMs%x7|^(Kv2Ohi;ifKt@6?n~ zN~{vIo|dDkVTEz9B6Gm;q?63`UOAB110%KRyp<-V$Y?c0ad>6>K0h^>e%|I5Lnd9x zxW8CqIo`O=>9tbwS4sW$oBXyB&6GPj|Y%^jD|9^w)nYN|A7~`tif; z|D^`A`^$hu{QC11ng5po+pN}((1RMQ-JI>EY_Nj}WyM^*>(=Nk)lwGz{Ym~lzgfM} zDKa>Z!Jg!KAL*#buMf^+4V`*;3eAU@`IE$( z;|oGfB)(7B5Pm~Ssgv6Q`zu>|8uuAXr5_|`*ja7200Zlp}M^f8PgVuqc8R3@)q)|MZ2ssH4gp+cAbKeMLkkAgY{LFm3r748Em-wmEf^HmUmk3w z;q(~;*usk9URx@TbX1xCK>PX=dwn3JdFD$WZa9?B%O@nZSVjLWZlK=z71O@r|lD|Y)p{yu95Zq{^%0Avg|L2O8bGOd!r};&~8(&?Y_L1p^ z5vYK4#xEB4HD44`X7-!7472uyTxTyiF{d~zl^VeYGUoc>J^me1DbB?4t1CqrA8WxG zvM`=m@P&bs?w{X32-L+R=4m=6P#O1i|dCSa7LOp~m z9QH+!f2tf8ECGN0%Z$!WYl~@(bIB2CxDKmnQyzb(RZ=ee0_dz*1>G0T)s@CrDe><>(QgSQ^8B`9pqnehh)^Hi})9J>M#HR#lK_0s{EC3S~=MN z6A^YuT}OfVFXueeV9rn&T%@gh4MG+9XSwK5OgY0atB5yv7T)?=%RmRy$Fm*JfG%jm zIr#-R(GySFb#|=<_ofL@86sgc#lV=U3kUw6=+J!#pAbja8BENun3gmAebQ*Ee3TNh z{YF0^C}TVsN|J0#@-_l=B@Yrrtu}*Ejn4QlTl;7 z=A8~(Y?vuvai0mVLuc$D*?TQGNz~zSKc#O}JeLlMoS#{;q4&Eh@4Gt}Mjo-bc}O9W zL1Q4O-CedfeXU6{4mIX64bH%8kdSa@$l`p_3?p$M(KuPFj8DyT9@bv{n4bE%)%9Zn z7F+ly7wjFnLzkujd7;lbmHC3gXh2lxH#lE#L{QCU>U9woGU7i$%4o}-8aJu$pz>{o zhx%)KF!CG2GhE3a=IbleVYRJV6VO#BNi(Cs2+59a_R&ZQHDpSJK{c?c z=)2>fpaWx!MYL#GX5+Gb<935ikREBbK8K{ZHs8Hzft>or7 ztTK58ZEvy)Do7Sy#wm|e&uC?BOk6f=koby_TliMYt@U%d>rI&`q2UeMqHit#ope1b zug1VkUU;oMdQrDt5{Wg|o4{DMQQ`M0PKamzG7#ZJ0RY;62P#oBH!Bmf|4U#wrK{txAo)Ml97E-jYC)Ck zRxq@I&5Lpi$aJX5s2+l&P8U+v)eg~@z`~!`JUw~0xM9mie=HdyEv65%uCv>{{!l#4 zH=ZP(yuBVQxbR~2_I9M}$8O70Xso>9=xzJ<+t|gi!(8y!^DRWsN$ZCpHFl?fOQ$-b zvQVdbn47-m?*3MO8z>f1{srXijWPM-)ToZLYYn92_+gp-boDv)iMlq~1vKPzGLB?? zI99G(^4DMLp|@3*_}*L0t`@vmdv`E0%a1+A*Emc6r2W1dmmeQ3qz68CM(kL5dJ5Bj z8RvtAKt+Gxn@3k_!=u0K{nnfZ)C^FkBaz|Gexzk&E-gGxRK=O-U7KvVY=(2r!EBN1 zQFQB@RmY8K=`_J0ut{RVo1nC`}|4{h(wleY?{imM@78zB3 z4&K6Ze|T^L8@Ac09OSJ}?6E^b>vJT`jeiA3=K-<8MO+KoUBloL{2@XbYv#}v&$hHG zxPU%9_|IJ-C9X7@ID`Q6(C0S`#ihL8Z!lTy+i>CnO6X48C9_nhZzInnBOJ8jXT~%6 znnC^Tk(*#ST)zuF`GVs zV0#5{v*UUb33H6)#D>+AW+Gu zRwh`!oZ;^+6gS>{i}+XIGY2};DbV{iPYi(^Nh}^TPE*dIErTgIZ`atD&S>eCqA}oZ z$f_MYJ)NlsxDl{d+b%|m6Yyol@nV>>HhW3E-f%G(kjH&4?#nY#sU}I(F1A{ZjqVUi zz%kwIXk9N1skSM6TtK9KHnYA&yTzYm-y~engSek>px+c`h3?bB-uLQr@1sREuaKsk zn@!InIrO^ZSY16wh(lk31QpV~NYYWj46L*_fD>WvD$J`*it`8XI2?r56qJ}S19Hs2gmH?Nd^no@*5rcc#s(lftet(k1@>zhGY zi;I?|f4>~`ni=Buu=4l1lC>l-K5cLHP1li;)Ss@OXw4D>aV$C%L=_vg?H1`-C=vvS zw;2*>)?R|2F@I^7k_^|DGz2coxPwN5ZnY+PBSG)fhK*Lb0{!WrnXkjRqo4{sSmeu?3+e*;7No1JTEa{i7v6U@e)R|22S%VeHJDZRdlZ(M?%cxGNB0$)9GcK51P?eF3@HS#Jk}N8F z02_a?R{8)IN#to-SY~@qc|dYy)Vt}mwVC>`T(^=tkd~Cln04cOK4kI>g>Z)erY{^` zi7Xu`?C5C_Pd1#7>I=_8C5oIbG`icJA_eJ0U`S1c5J=MQZwnZdE|*Z6dg7{bXD07v zVk{MmK2MNU_;7jAn-T2-Tt9#x%@J%jtztIK+qzF6 z-58zuZ;@tB&if15rp(`3U@GI$a0V-F@$Oq>oGh>zi*bO-=p^_{o2+qCj>#QR`Be^e z>4Kc4+)Sw!m=-En9Ol0_ZkZ4c7oM2)*IrhRk@*ADsgSgKls#oF60C>Zu zn&Jyueri)Y=53|H*pWw>wde;DgEhQklpsI zMcPyxIa6ol68S}z~b1H#-Rr z4Yjic77p!uND1NCE%au9Rq>;({v|4>c5%;p&*j{!b-&vpNv~h|7 zNI|pD*C0(n!hWage*Fjhf09j>6P=u&d74%lDF?r|x1LC?JmqAs4ITH-*4#f`jyVt1 zn#ZEnnM6vsb2ej21}esk**cGWr$;ac6b|MNmpj>}o;g;C(NxQuTA+vI%|Usf(-clO z70DXng87Zf(OCDDCX|YAQ3r&>;D>gW+icrvd)!vPn~Nn!lKf-&q=6gqCCrQoD$wW} zOqCfALqtM>OxB9SM@FOcWq?{6%dY$gKTxImVJYDT5n1>Pd~R-aYQCxErq@nAcyMyI zW2R?Q8An5c5jPQ6PcPJ>W8U753l1P2Y*e{XpkeLYMn@;F(~gG@ZOk)tbl4Ueu@qiF zcM>fMDLHOey}?UnRQ7t3a?3RtDS(iDrhG zw$=#TKg4y8O_~bjmJKP2BqKPezOZ{N&I)2z00r)47jkYJA(pl*c1ZW_#_*3t6}HD_ z3P$k=pt}2(Z}_T@0BU2BZYvtOl_F(iPSY5jp9@Tag52}w(3_gS{hVU~e%jqt@t!Zp zadOy2ViZxp?oAfY#bi^J4IBb=`#rF4)=?)G0b(d;{>g}PU9LQoH7sF5sU&?}DF296 zt2%CSd>f?&-a^I0(|&rfYv)$UgdMU4Spu z7hw`-Rn0YTEsQV67z&rF7%q7cf}M$QwRm?zfR(*;EA!**PjC<)6)AT*b84anE>*D4 z&NoA>3ouNwP&!$Au-#S5(bpuqh?lt-r`o9=Z{<{_X_}~DqFcd)-qtLgtKd?BzYPgh zbk<}`(ev+eyQ=B14MT=?&*^>uzdO%n1b1>L_!F$*9)m_wJrW&&E7F6XOa@<~ebtkS z6@O48sCHppHW<1@#L0`On%Wl6OTkLi?x=QipGm1-eM0_M(?dsGvuC8ZEk5|4xF?U^ znfVDybgND%k4H;mwHOooV_CO$)1er@?wA130xwUby?xzRM8cyz>dHU&w6}zA0^6gK zsZiZmNO#5%7d0C8ZBgh&ADU9>>&t%NWsihv!I)$y&dq-nG+Uw&2k~~M%&(grj+1981wc;%d*)bN1`TX)ScMa?jvm+qTGNkq?75?9LdZ#&GkLrH#T;mY`!A1P9 z#!Jq?=7&n<@c-~Mn*IQ6*O`#M;Cl8&$&>zsrMj$>t&N# zHOQv<`e0z3Es|^TP8U}6>OL7dX^35vmeB?_GO}gHc3;@Db~~Dq;6$}`8L7suAe?KQ ze+`X#kDu?4CGT&mi=V#`BCd}B;2Cfi1grQT`!Gi+fDDlFQr)sMkaqXEv|9UGp%oZy z()cS^zu^>mJ;Rp;rA-E|8nWG^TWaNGfU8y|?S?b@KV}xVaE!y~) z*EQKs}*DFgYfkk zfFgGOQxPtR3;W~72w2$x%>rY$`-vY!p`3>DZ1&;Y#BKkB1cqOfPz9=Fgz<3c^bHQNMm@H>oejRs#N-; z9*V3#I%R%VP9j!6?AD9-8`AFMqNVrqhlu4P}8Ew2Ujp}7*33cz*{yxHl zW?|RLxkOZIzkE^RpeG@9w{(aNO**W}Hhj{{AUBf~@1N3*aZE)gM;W;n@~(1O)PT!C zhg`L+jN)W{c?&bw^eI5zAuTyY>kVVu>va))QxE(M@su-*5Mx9@Sz9V2wrx9;AD;v) zjrWaJ(mmzNjeEG^?K%o)Pva{g`6!Mk;4JM0@hLCS+`Oh{3{)KUnl_z7rTg*m*#=|_ z`YiPWF8ko$opsBG-KM{ekEP4g;aH9T&j0S@UErPmE&GAW1>pY&(?QkZe;9fH$I_z) zK;eMv|2EKJV96Fqz`$Kzu3@yGlQ9amzz1b|Dpi&2D0D7Re&JH`$%lP+yJQu~A2jmG z`$u379k{!j4zo5V0``?Kd5t$vFQ(hOadh>ft0MQ*tel)}_10ZHwI)$up5U$k!gaZ= ze)8^k$UOMwXpG^BP~&J3M*U?67k}LPk)-bh7h2e3vVfikM*ih$;W!Jo>f^DT$6Ih{ z#8X47x6p+Xy-kA{6vBXt z{WR$(sbZ01w|w;IZG(_ZKxWK-v;+y(Amc2V;DNP)08;9Y-roXYZVh}zpfZbh3k&AO zOz0|&{U2K5q^<0Td)~cz0VSQw2LycJF2{6q@HYQ%Ujad6fYThNH6bhqdZ8x^1ml#-ug&6jqc8!B_`t0Uppe71JU>KuA(&N()r zbMypOow3&#O0;+A!#v4vIr16KSTRNB-&PdFZ2bK7Mrf;e1=xK|$Pp@?2nx&kE!ut5 zUl-56xkXk`em6? z3ddKB3z{383*GX2#!$WTQ9IJje-&&piPYB}e8eJrdCFN^yo_>oD<{!RiApF97GyKv zGFMsfRwdpRERr?#E<>0^I*@di-?iD~^tZ6^IR<6QLW?<_NfI`b*Xkv`2TZ8WCO zsoCaascB}$Uc2(T4!cKpmq)^3QIR<90ML||pGI)qShE?3247*P2--qN+#ZERcbv_n z|B_$ToN`6q_C-pd&|KbhK0Nnebq{a-3wriY8g)HF&Y@#|hUZFh;+~eaV9ij^TqMnl zik=p364k#;%^hD^|Ajb=!4icPE2sRYd=9U3-6j2P_7aq)v#Y|lE0fYSgddY|=6rn! zFniw)hl2)xuKzcPLp!x3YVjj#_iXCI!2;r&b}{6loZD?}?;32I`B298aeDb>i-L>hwGn1^WV-y|pDj?dz7QRg9@Yx%Ec_&d>dehE3eR{S`1!_sE zuE?b5osbpR{}mlBQ6yQ;)2nZeiW1Xlp>eV(PSR@b1rID{bb$N*N+o{CXUA{JafMm# zW-CZI<*p7hC_5e2Kzy zdXD9RTyeK&@DK>)JMmiVAc~C@?PUXd1P$QjOV&S~+InfPp^P@MGpvWZWil2d%n7@64*Cwr1SK?Q=N)JMw1 zy7fE&7|TqQ@#9QZ=^U|BEE~e?oDw z{vUS6|K!8kIoLYc8akW)2dXUbf2cCD1=v|wn>hT3a@_w=ZejZ$3JLy0;r|yl_eWp- zFTC%6zf)%?3+w-N+5f_A!ZjW*MMM9fD1OEoi2g&VfsH$Zogstyl;)f5z9hz1c29w+ zW(1UUqEX}gI5!&`Hv|AgiD-)tr>e4_p*O-_quK$bdFbovr{qdcHs<+TbXXaYdYu+VnY+6)bEw zthYWA~_$@`$R=zNYUK4Ccv>#75EY(%P}4a#oV zC81kwvMy~bO0s^furlcij79^elOSeZa)uEk>=lIo36v$B%zL6rT~qNgG{!tPzq}h+>6Fx8kg_BjGL+%pjnpvS7?r_m|ZSmKOKSgsQqPZj{!K%v1 z*nT8PegL0uouyD*(I_%)EaU~EeYvibD-Imw5XHgO1u7~cQ_#~qLSa|NeX?-7umE?w z1nzJy3|u0@e!`&B2eU(EG^Lo|6fo(%-;OMV6CA<~&K!|KxHKwh z2hSV>|q`keyC!i*pgcz68=@oxV?g< zEBP4Apixx`ps~>)RcCP>lRdxLA&<*Ri0BcEj5ql7OHE+z=1*vEDL$Ljsdm>aJ5}zy zx-4@>RyR`eP^e<+aHP!Z_Tt4*L(nZ6$|ee#Ag@NhfRJ_duYa^HAOAk~^0#%(Sq_TxZwR?|o10@phT)QuW`w=a^BTE}g+Sa`gIqKzz1Nso=$rPThX)$lAMkbbHtx1RcT#+Cj zofpWQh))xDHEg&`dY^Add&fhO0jk!^^(iz*hRl>mj6}JV!VSIJY&^<1o`&Ysq^kAT z5y-}A{u|eIiE|pP7dF^HYZ~=wRCe{E-Pu5L5nfL@XD`2?Zpvv0GuQh8ODPAkN0zGa zKr0H?5WMt@lnTpyT8^oFbEE=MrNSk?zTWWBjf+H;7#Kt9B#N+O57KppS_Bws%~XiN z>f{kNk}Tvm1r}39pK;V{6@o>ukg|St0entE&{+v&aj)ckYO@d^3=(=6S#Wy??9nB~ z`RzZ)@!sMYR4fc9i8%HUeacXn$xhXh-^4ahev zbA`qoah2YxHk(*DK4(-p2Ba&o=j0Q1gPElvpr>WY(m^Q={2Dz~*11FMRIwBUT(dv_Qsd{vGQF+R;pzGv0IO)7YG#; z3`Len0?Wf3G7ZqX{x;9Y?ZiSY-%Fv)T)_!Y|Bd)O3SpW)qcTN)%4x9QE=9y&@r#H) zEr8(C9f-kh(jz%RHWtUmr5V_rw^8E(tfci=1y}-Q%@-*&;e#y6Y}JP*=389q2n}!y zk)I*cYkWD;UmVLNyHw;Wl%Qv+uG3M!8aGrA;4Ax3wduof@PyzpVWs*Uy+T|NP*F3i znA1j;4(p`QMy=mCU@FS#tfYCaH~9fwjRWAgrjx?sk_(#_$4^Y$|Iz4Hn?9AXRcI;; zNiSupohZ}SBu;*Y6sJ$ZQX7}04r?DuJESF2N$UG+rDxMPSwh>G zq>4eL!Fz;DQS2eNJyRLJnXai%>Qsgoi<}|sS`DXJ)gd7~8x9Zlj9Z?EZ1Wj9G6d0xY^~D&# z5HSbA1)Q*Xu>iW~Y>cf0{$KgLBl)kvBI1Yc0Oq9Zf|g>~o9ySteaI#s7)>6=;2d%iQ4vWy3tl^Vao8y&bcnt($)^^P%j== z&Trjhz+jOdY-?4u#2)7izuj6y7fKpm)oPpj9T6O{V&mapPyBA#5E*zxgTCYYvZV(X zUQ1d-D#{24E+8XHhl(vA)g!`I!L~)V6$z`yKc)yEs%$WBk11Wo#4Q|s3sgM>Arobf z_lYaAzpa%6MTh3RAL58tlp(Xk^-NGB2pElat<;;xm=S76p*i+lN_oOqM zk1qE6bdD>T$Bg?#dwq?o-bDK*{WYM-2RZlKjpiPdL^>>td#uswPhn3(MnJe?G*{~j?j)rKOA z4H;+&#c_N`N|7q}If)AI0V~wJs1}BW3rt;?i|fA7@6TQ+a^piImEUE8$xYJ5v)e+4 z@3YAMv>0xJUaN%Rnng2cycG4K_3;El=%*kst!X4Q^L5E&!yqKN+p95l!)gm3+k+^t zUYyvzjgZTN+CKdvGLIv!xfIV&Q-3z2LP4$e!?w-+mgbxc^`=V>!bPmVRviUDC481~ zy-}70ZYWX?!tO*@TUtj&e!#h#?a?S)X2{IQc@IG_8g?boYo7u5*J^NOS!=r#Qs zwU*^PP<$dab;7E-KU|z$d$pDfci20zmC$R79BSH{vyHCYjgoj;ziKH}eWgv&bKmVq zlJJ_t;~mYO0A3+_bXZH7UY5AcF;B7B&wKe;k2anwwRKO!445-h2e{Q#>w}cZaBT6u!3>jYI#UgP)+=QoEK(UAb;`eKofs;_WDK zRaa@nm!D?4o5j5&IikYnx~|kqxp+77;W=O>L!R^;Iys4^`RHIXlk}1!KX;ai5p-+EDv3SK7ZG;|zK-P;>XnA{^m8EcH9Nkq7 z<32D+l3(%eC3V>=B|fU&?acoc4-q4dI1;=Im>mgT5W%i1oZ@hvS8u;)A^A8!@e6$j zB6L!9{(Hv(NWd?APmMzF%Prwj{0E76@<(nWN$>Ap)VzXMdR+a?AuS;A0G$^qrY?2y zYc10bjtO+J>p*o~W)j-TDRlSYfwo~Q^a8CbZ;28$w61BRTA`*4rO{`V%N{;t##d0^ zH|*dTnoZvLGcWS3Qk{{9)z!p^qIMhb$V<&ixIQ|Ms71#?5B74wTcFj~N>+(KYw%XB zvk%}LEeU;_4We}^@ukg&dcrtPa*@A0ewPvZAwT*E66M(sm3{LBySWfm1 z2O5jwNT<>fJ5er}9THG+kUQ0jTe7-f3Ywt1(HbU$UBEXAJty?COHn9;@(e<|G%Oru zB;<%&Mr~2o&|H$%i2l9^#s@3pfRZu?;X;f`2LUEI6T8>Q1=2Wp@0Kqxp`*L^NjW$DlMwB`tY(sn1R%ufKo; zE>ywR$oQ~{AR6kibqne+Wcq;wp^K?j`CRKP-SX_~sjBe0E_;}viNH0v8I7J zUj(A}NL>_jd4hFEj)BHg_8Z~=LW%DaH%C%Xi|In_ONH);o@=NhpdlLz4?gnHBk}r6 z)BHYf*G<=tqXvAVmqa@pp2z^Yx1goJ9B+Hihg=eWH zL!-I^wK8xvn)|j)&eAbJzd9076#K>P7wg9}uYQFC!_raW)M}bXt;r5QZHaSPw*ffr zs&uvFg(8_crlTbQB-$EIvmN3PUy9vj-MBwepwp(t^bkuofCh#!a4-{{fKi8zta~Rt zzWFBrp$jGwAPX~RT@A}PhzY~ztKEf`Uo zJai3Ke!E6$ITrGnE`D0VVFG?@01w^Y1hw=fzD;76REe-c1FRs%!O|1BG%jrn&+>`6 z7$QZ$6}gl9S!w$Swk?q~;6_;19#1SIgN`qon+6H#hhVUa(QBF+k60`hlZJb2%r3R5 z-{!c}-~~{#N;dPOf=W6Ww_^P@*Jw+>{qnC`;|R1fOt(2GbJFxWMF?t&3E!`L9%{WK zJxAK&dZjA0$i_h(qeTCB#&*>H-pRWspr@2A39R7y<0y)Y6C!4D{GmCSv>$vxTbF@8Z-F}$%JA&EzvamwkUP{tgDMU^PgSVV=I1kN7Xmw*d&t-x#jI<< zJE+oGr1xOyQ?b?z!hzWTQr@{;at-RwIAn7)=rM{Q_abZ*vmQ@b1v;EG#WmrSwK6qk z<2ZAo&+0Iv_wAan1ZpSj2n$Uo1_>(&(f#>Y=;km`bvQcytP7r7{5|jzJtg4fYyO}h z&>i)lC_drD9!GqRKdT)qncH}c*F!&dp4@P7*x3+|E#!b-aaGdJ{KAmhDs6KBji<^g znc+f{GS7_>MP_Qp*(j6^>s^0<@R-=_lqLAgE#3C zCSblk%?3qNdfcwO|2s7cweBDLif+ZBHK967N1$tS@SUvATRTuo8o#B4g{{l0>8Xt0 zA?mo8X4|9xn5YNcH_yPPn5B4a``?esbnKu-x{l3g^;~aAZ?pHBWH`>x>Aj_uur=AX z4-eHl(siYk!T>2Oof8!Jo&GIu=WYHzzvTP2#hv2=tb8T2m?<}+Jgs-ty!Nek^*uPV zKt{YZS*egu`ElzkMUrh+11{N}NF!IXYM{1nS*%J4;NXBEGLxumWgf3cttFXh#d1w> zs{%KKKE0MOQ^W8xz|na`|(6oa&p5-$Ap2JHEC8L3l?0guE>PJ29MTmIT$A8Ouj zHNvOl2pLusM{T#pFwjR0!x^CbpnTM9k>`RA`Q=~AZcuh>1w+3Z} zj`w7#ZlT|*H?5DEFmHAu=d8IVAFM=z=VGlEJ$vDTw zhW3CUKw%S)*i0dH+&leIsdf-uka7xt8QL6k@aK5b{u9|nC|~d~!`dvaisg~|n(zi* z2{RjA-|4)ges{2c;0LE)U%z1QafoF*B6j!GKfE4%5_989^1@b25tYUvHZ%@#wm36y zJyTiGnd>d6!tU`pgC$}jD=1dp%)ajuHR(*;Bice1g0U00FXpVnGgwcm#q2A z!Kd6fbM6Ux*-%6%%xfxX%U0PLEtit;$SxHkYVrl%G#DTvbVPbmp9uxGjK1ZBT#BR< z#Z{w{J+&vccVL;RX|)n`TG}3EEkQrKc#+OY4voNXQg-JbK0i&57B^}{Pclf<^c|zw zNV;6IIKC+(63gW(s&mPfM1{sdznrI#K14jM&L*upvu|MB%6zj>D~Y7lX)`Z^8d<7Om*f+93~AqEiQAzLb7u_I!jObxZla5 zimq2^s7wRFOXMk=MCdSrwlnj)@p3{F0cy3yZ3kt>31i7&D8aO?0lE{4irWL z$S=q!DL+v4TQ=Mth}yAVEtG!Xu&)kj?Qi?SpPatr#4y7A-w;pTEATZXwr4Sv>S3zz zs-{(npmEAZ%D2bEfBQP_IRdej&cm^i#4TFjPS`P4knk+AMkVHKGin76&F`%+@G~SE zK;YC+*9~5qhE5(3j~^`3xrM4Aeo)L(rdCOlaPL+PjBK&f0%_Yw#P|5&zgUzv8M~N` zjlo&`wtDK`1vnAz0QrU&bga**^)c;UUgj3VJt=Gz2vE2@_!(F!TlZHJ!2|;9d=Jg2 z4mwV&yqoRoZ3J1%y&oH6| zId*b%^1}(GM9b4Js{)_*J3lH0*`{A`2qNyeyJOY^SZrd=Bz24yNn zmq#pmi>+N8$GT`%o(}p|+?AG|tty|Nu)uw

p7RBXB zuFrd^xPj>*JGNCQaUu7ZA%pwp;6I9e*+gT8nVD&?uR#%JNYg2aek%_{7mk&Hte9jX zGrs_Jj2F=K!9FfI5M*Y~dkq@yu%RMJqu7N}uCPrvq5CliPlN<&ROWx^)MLL;eVCwm zF)i5Aa2+8&&4d!{a)D1udqWw=7UgyY7Fpqj9Fh1~6hwXeBvInSP!y({%wM@RP!w61 z$H*RnX4dGEp;w9Rg$#?XVun!VEk1~|CCU6paGCHWF+iA$l#cP2_s zfkVhUj060dePH^3V8H&`Spwv+zvngI`(?~{r8g%n%ytohS(yW&_U(5=>X~@C;V9w- zH9`{{ya|vvP+~W+CF;hNFvAUFypYI#TVPN-fEaonGpwc=efpsU+>M4R#pHt&Op5lW z*CU8lBeDqZ)JU%W@eYy-bcT2#q<=VGHfRadU8%KRzIHWeyiq@1n#ESA4>Yg!8Xj+X&wzRK_FBH+FVx~rUb=b=RIl||Fy-~VgF=QsPX1Z|mNc6s zTCPa5wwtn~F^s)je>z;Zmcff_Vl<@E#J(leA=_1|hlLeU3dE(|DDUGH0(?wXX#k z1tt89BRSg5$wT1<*@2b!XXAZ!));W0C*l_0f?^UBMl1m=_PLit15q%Ch5&JSL|&P-LO1lG<6Wl zCg}}`@UE615VGim_8pqTE>C8o?sE9ek?rR9;L>SKzCoQ=5jyPqh*ATtg{M__FJtEwLo~6A zGVt4o;R1R><{U4lZ#Lf;z4}o2GehJ2W9u0)M`Kz3F7PI|>#%T0&``uCL^aQ@H=@xD{RAT7_MIJm{M?@VF|2`anKs*{zZhq(eP)`C#Nd zufj8o8U17;)F()3$yb)KHjXUxAzlNeaRWzp1zG*-wqUp^t7TCt1Q%c}8EfXXs$myp z#Oc?B)32GmiL`U1&C27BmW{X-4yHc~ zxEd*#qJ3y;LuVneptJ=tB-vDl#_aZg`Z z8H#?Hr@j+qh~)Nks^&vrW3&Rf4-8`G8Iz-+KSQ`H&K8IJqsQr}|q+5yWAsJdvNl7Dcmi9t1puE?St^@_P8GEms$g8WvnVkDmdx7Hz+Y~YO;(&&+KiM1v)KVH2h2TwqN1RyZqPm0 zvgxvt*w=@Fcw=ciURPJ;sF3kk_<<j#k(Y1K?{rH2vo0D|xz!>Qz=rw7&LEhFIuG1Q}oWGdh z9xT@NPjX*m?zyL1=cy>rZ@*|vT6#<6QWrsUY^dH^j+#x{%K2`dO;j1l*SZdrJ@eLs{1M4l@?V#Dj%sWhuiZXJ zYmAs_KZU?zmMWqLa1Dj6u9w(OD$x<5eJ(P-Wmi7o>T>P5s67=a_%GS*aX4Q~tNsQX zU6DAez*kWi7Te$rk>Q-xzXp}F?|9Y1WZ#5=Vi{XJ)h80r7# z5Aj4`X_dT-aDE0cWIG{pFf7CsmFKY&+S@3q_zX$DX922=bzy=9-TVmkY-Z5r1fl6Z zDnChM3{>-cH^HH*DaoMx8>SYpI@;{0C;C5DDd$g3w)7A$jA z^G+*I8|RIhm^(N zY;Q}e)*n8<;DSSqnzC9TszSAAYj zMro~gt7osqe7S$j2#$$;*O7we-pA83F&jb5!zSZ$B`DLee{NO`z>8}~>O;I8@ssMW zWJ2H_f!>&bpK(-KI78m-NPe# zM5@-d?~1h2m3kjpz}=LK*SKsoGbisUuMvZV-(l+=1Sne*$S;$z&?9^SV}2%Oo8#AC zKH-p}*fP9Gv6fan-9L#ws#lnm>enP1vDV$zq?NU9%xP6Rq0>^Aa@|hgMmw~Rxq*m1 zu2p&5Xx~R*1B=Xa)EsC04#|N0W;p!(62YeLpa*AZJ^2)taecab92b3Fd^a}{@0wV? z8MLr@(R%vtxh!=A;xX&bPvp(Yfq?$gbly+j!(e{oZKZ}Q(R}LaBevGS5MPV5YwX|% zW}X69U&W5aB{?`YH8p2hgz}ibRCQ+K&mR7;apSYtKq$<`U*p_m3gV=8wccd4;|T4B6n|`Ai6*0z>#P{;WE@g))sxpnVtsWPSnqpdUnVVW?P&_e#Sf6^87p~Rj*#W zccsIidvo)h*B&OsYXLhKNg{N^5>)-N{`(3IX;PGBAx$o!9PPm*1r+}th)I04Pww8Y2JIh`eAeNfX!EXfS~!#+F`Vn6 zo2DSFc$TOTSE@w^0W#KXexx{<=`S4+2MA0s{nk zNQ!tUY=ymYQB~kS$5IU7%8*>HFkB!95!juAT%xgb=|{1nyb%qe&2gxQw5OOP1I43C z%nzz5<=FZ!b02+*aE#kA{Lj_zAU-{v?XUKB>jLPuJ|U^z_73)M4@XxtD!yE3m}-W%d-v8rxB7k++i&Kx zgw2DypNE(4PIh0_oPiB}r)D_! zSNcvd16^IM!h(GEYaKZ7^3^jQYWw%^=l6!Im|Q&zeYb~|oUgM208j*`>eKI40mAUT zkL|T|0i7VnySq-`U`M-B+U-Z+h3(7+egugIK78#b1#vF=j}2%fXZ?8j>Y8^#Bv+!b+xICuHY}ak_x-J* zA?kSV)t+~IyLm!_h=xdFc1?Fx@PE*cyoRn_3O zBeu_CK?n7kAbqe9&_0mfy1t5v60`N=*EQwh$J~hubE8Wy~#(-RY z5etKyup|IW2JaF>E3M>38I27wVXaU*$q30a97vi5y+-6S+7{ReqXcRe76GM)Q2}Eh zh|{Ny9Lj@X^Itj<1ejBgtU{VUq}pK&FpZkrOurlH=gkdeUbGw_c1_%U+__yaMu}W` z0wF0BkelZgD#EWg=ZF!TcURJa%}>lfj4)|I#A6*#Sfs`2y1pB;xC;5X#q@hEIfojW zbeE=@Fixa$t`VF*bC33QTxX;RwsNWO9I6g;A#>wTxN#F6yk7hQQbyt)(QlU}RZOzd zVy$)+atXa^mW-qWQB2%a{5;KHCT>6uWGN$U~cqMwbyuDah# z`KQy+XFwjsKUqgBh#bIxV!%;CY;hdQ;9#6NRBPI!0?ciKeoUk+Sk**6*%NC(vySmJ+xrDibM67BF>B{fN+yR-6HVgWz7%rUSTlj&vXe z<)RE>cY?$6C0kedvnEWArc92BXXW{s&?dPCJ%i?zes%oo%ytWx{Aw;Pa)#sr&deVz z7OJH@4P=|J012J`h#w`(7&r&-RNBQUIpL^?WCk{;4kP`S)WM1V;Ov$bvhaWLbxzH> zFu@j%ZSL5%ZQHhO+qScl?AW&T#rv5O~1g2A`n?6L~p3kJv{#&%r6R(d1za~tnrZZ;ydfD5UqUF?M1ih zfbaa$$x@KYp9t}2pvR52vS<~Q&$T3=T*C`VKwrBF`e#T28CwW*C7olEQ~d)!C3M(; z1mLzE9rwYk#h7$PP>*?=GD>$FgMxIJr2w(k^D|Q@z&7Ua66X8TJ@ue01PgG3Mf=`cyPc1ObjK?`$wXh(3p0EzsT7zVQ zoM4>7>Bkd;-p=Ri8#KiA{CX7!LT45i%@}%Iq-;#B^;}dHR*Dnv3sLNc2l%0Vws}sq ziY^zJk-SkJRD1l``#vlxKtjUEi7J{v`PO9i6rGJ12?>DbDy`0jtr3ClXMVD9=Y_>G zTWOmn07U|-UUj|#N@Ev5M%g^q?yd4MM~!vZ=I`$DOu`(h8mfnyLao4SV=I2@7DT~f zq&_h79XK~1Qt@w(gt|3PLb@-RLcH7QczFhS!{Xmv+D!xCIm(ftik0F5+GDtZk@K?j z)1wK+tz<H-EIGGY{qj|1tqTR*VpLiq9|#?@pzkn;-X~d#~m~dF(EY-C0Q8 z!ymmhk#=l$OQ&wO#qf$vf?@xcSaWbjwXal0y0=dGLe_5Aqn>(Mi*EC%(#G4EbaFC3 zudr=5Y2dxf&9mBV;sxfc`FB;AA?1c1C!CXb#TeLQF@9|m+2gG5=BfbPl!GkmjAi)9 zHZf9%k+I-4Coo!bf(px=!_aMjBz8Rol0(iELj7NuNe*j|o|yCFZGYEwV<_D?#3*mX zG!vGB;0|uZx*N{F_=X3Q_cfq-Dc!^=>~ycJY4aLh^?DVlJB&LEBOnTVLSNuTnMFgl z=1_M5P2@*X5b4Hw#AI_7t8~daEX~jvYc*=(2-$KMwYLT){JzigvU{uFYJrOc0R-{e z(LuoPd4iDA_fOZNWus=SQ|S3xEQ0Z<5u=P6#&n$6^%8=R7_gk&F2qbF7C|kj_&>=y z^zvXAp{GK#@L$YrlY8&qJ;UEk7U0Uyuv{UgAulG}S9*ro4>{ZC0O+;O*3+I87VFNF z-9^O@f^Z6rkV&QA?sGerlHA#p3S6c9kRSWD&3^tit<~D@b#(Y`cgPHU9Xkh;Payxt zmqRJEz`jSjPoJLQF`f}kE(e65?ihMxTj`xGaf!$g!pZc7fsaYRgZ$1RTr2e2|n0Zpab(qn}Mil%( zgF|_oVEVRvC7;5J3%sD9H0Z{JadKHH?-Sy4ArDSS1`P=!n2h??!g|ZDop~r|0X*H7 z{a;NjX0cEf!P5%~(sATUolq6Xq)F_wTh*=`2Y0o5qci3v{f%+kX9U)gU@K2mKVy6` zC8c;$QI+5#{+8k4UJwf6AQvv-7h+f%5s;|Pa9F$E-+3{O+t@>l^`(T;i zF6p1IMe{GGe}$^*T{vq@58KjmtG;!*{S+es_ZA}o4d!1I33`ze;&f9X3Zw%#!^prh zAb>$mEIfNM8BHW})4dG@SKDAII)XWC2*wmvA@A%#$e{%xm|5k__`F1Dy-N#nn@JTRBCDbV`$p#9mEcfQ^MmXj3}Y9GIE~ zAx9ex$<=((RS+rN08sis;r&$YrUXiYkdOgT6v+UiTOf4>5G%}fYb&TBTO3Hx&aX(9 zMIzT-fa7jw!}(|WDKl?AxSxRiR*1_Bqdl*t$;vf}hWq@p^KJrS8vK59h392lcwdGP zpDNo9dkyThbdH!3>oEV0CBmsHj97-a-eoq1R-C%dTn9zDkE^+d1IQEIDF8&%`oGXq z;Nc)6A`Q60M41+w1=YeM_8doxVE&E}|1lo4!{HQ zNaKG=D^RSq9A#3#!Q6#GL=L(5@z5%it^++ghyKd0u_K-)`?*1cnkz7&)lkOxBSz$B zC=J;l?{#qC`FI8Cg`tjvEPm5_0?lzvy@G}x85v0A2!St-JxF420RJ<}CoBS9Zw9zx z6g#^mb`R1aY=rh;7L4|3!Z`sA72A#n&|-OQCmZz(c(cr)Mu#-E!0Hx_C`z23vO|xvmv;M7%jB@jfhmF)88o+Qo2G zN+n{n(QTK3d1D0pf&Xq`K5w0TeV9; zqwwQ)2jqchThTb0Sc+vZqwXpDzL5Tqd6%^q`(UrM5$_wV*U)E1IvVwYT4(u-TI=7%zab6;OP4!^Cy;aJAkKR7oC zgIq0a{f%0B+ie>L&ss@%$c7X*S#{2ZSQ_AqcS6ak@C!hdz1ckAyJP0H^vXdA{+B|< zKIa_uh)ggasZW1LI)VGk7%+IS|HSMW1GxjCPfeu|_WQFd%P7qzXG9P|g{6CRK$Z0G zo;;ia5)upzl~L`LVB=sg`ER^BGa(tH+?aWjO*v}QUA+uhttnj(F4m{BbSkB~<-X*I z+I_ny{5ON${AoLHBh~n8IK+-g3#y?c$llp9&1{J5%uF`Cy;3Rj{e)}t*TV|w>!x5yPO-pYE=SD@f zr5!JMk;=?`H(C=XTJbfL$QfZ<5G6QpeP_n1goCUNE;}SXvb%b+yW%fadGj1j#&EYk zqxr!1YFAjl0e`sP8)(>0Vw@vqd8qmW%5XCl{CQq&z5b|;Eb*GaDKPgNcl{!bgo6cM zAAP0a+40pY{XZ6r!hOeh$VGjU+hkqB2_d-s{jUTS%<-+zaUU~FCmroN?q{?w%e ziLm>iNYMDL$T?|n=sFWnBs4H>dL?N0Lg!4?8_ z4m!ZUHIUq7i$zqT5tjVu)i3v?Y4k%wfr`#qr-o;7f2}eVx82`v-+YT?PrZn&hKNQ< zxEJVBJdYcUqvY~d`X)mDYEHNghvNaw1C7U%kxAG|F(pZo0D_lbC}eoc%486_%L!@b z--K3Am8>sSK!-wabxL^u9UJ`{S5W1g(IEf}set?GM1mEnLY?xIq9gITj}Tw`Mx$or+{>8U!J825wG!DiScX#6^M;n;OWd-u+pFZ`~&{rQ7awuH(j|n><&bU{jvo=@t(OD>8ghqE;i9!G}132>0g`Z)(=Ve4hVY z3BPrnDB0{mJ8-Saf9$|!jD^_fD z8T4w!KyXRw?J&-a2Ce?6+pc{OUN7QjLY6(Gc|{9I?VX97`y^k zDce~f;^R~#JA93$C14RcQwUwku3s-j4oEf(i4GC!{Vk%+kUC>ciY!K4KRw}4H!)GK zbe;RratY$Hc?vpj@?ELnF^-=D-rHI(7Evrt;Ysa`d$(_sH{G(h z0-!tIb9~8&9v|FB%Q*rVjmehpA-NTNgDW&DZrZ=3E_`O=Yr8h@hWI$=CgFehz6WFw z0;Wex*doeyKr_I<8qyA$&vC=Sw^D?ImBVDGG^Zy2C?;$e>2=6>qn&-1aHi75;ej{2 zqq#$5(ctl{ELqe>~1a{S#b`A=Ne)h3os_Bs0c+ZkIrJ1~Zles<9!hrCqXgH>pn=Q+q{X z4D1qU4|(B~)t>{(%@=0sJm-}V|M$oyRQH3tsni|Z^3CZnl`@1c;Lm=O?x>`OI0 zDmSg$j)vN0Lq}E`c~ag7E;?Y^ni#pes-|sVc1_t1ZyLKjHTdtt8o2Lb!((dJfKt_7 z?`6k*A{T1sA|IW!2@=sXd8gIv`BJIy^~|jY6V+4d6IKKZ6B8G<))p8p+AIC#mUcwk zhO@~Sje~rxhHd|<)1OBBH4MmF`})OiY#v04=Zmx~dS&%%KIvY%y$<)>I@mxOi;trh zx`nOnvYlKyk<~;zc`n-PduMXmzM2Dx3_PYkjcuT<0(w4c>yK-Tm#MRufuWH4ks5U{ zh-esd?aId%>(25?YB?wyeUA;?8H&9!ylnW$pNv|deQ{x><_ ziGH{^zRGT;{Uj-Zhmtkm;tiCswu;?<6qwA7F%nV6(QqrOqwwN&ZGI#17)L=-nm?-t z<1W@7A+5Sr?36u5Z}U5JZM^?*iQ*r}HL?4|G47*PDQm{m)=MR5 z1$kpk)wX?BB!YKNXDXBOm^M{31xrW|#NGZ4MV959!MpHbZ7>%-{u$xBngB&VGc5zK z<^Lmlb>tm{b-dd3;ar&i>%%TG!kB`gU`asL26TpYLWha(OaU>d+5*eVL8ovWLreUk zUnpRLJP%!G$%-U7BwVD0F0s-sE~#H?Ce^HllG^6Je4D37?3a3W{z02|>}kqbCXB^y z57_ieBIjW2NP`94RwSyOvPb@nXXDKDV~J-^c8S}Phz&;(8#z)fM=FDjXHeuDD5s&_ z4hkXf7;4uz`qyFpV$by^>iaXsMM2NXYqA?R;8TI9VL1d1dC%OETF`T1#lo_|7R+8u zCf*+R&skEFXZ#ETf8}c31okJQ9@_}pE^tA?Kbt1wSn$B9Yz4w2lK;kg*as=Bdz>UA>D7>eBIQ*Vo+UWK;s%g zFCIQ=?&=5q+4m5l=9Ij5vyQB6w@P-Wa}m^p6?XQ1%hW8h6=$>G?N2#+?VbDF5iLVU zf+5Z=nQcwudToIB>4tAzx_U_mKd< z!0yQu`oAjGbQ0S>%y<%-CUaQG9D0MztrZBy<9Xys?C#e<@eO&@Iq-Nct-_3f)MYNa0x?4B}duDDNg9Ruy! z)M@lPm@~zg&-7%98KY|;xypW1hzGl1wc@I9z?o{KT=x-)DmQNdn&Dqyx($Zq;B%Tc z>=F#*vML6=baZ0EcSDUukUNW$q4F*eK7kC%i?j7R4sRgKPFz>Yx>u%tmo_xo+%zGL zN0zZ!@Ra6jFNT$1j~Ljg5Fak_D_QxN8+dXgE(TtsD_iH-L<3WSKHxKQu6Jm@jDN5V$8+B2Ns?sQs&ruBU$eh1 z9E@h2M!+@QtMx~_fj<(;Ja@ZxV)S){Oaq{R^)w(?@KC67HW)a*?&U%(TC8 zOwDmXqwV9mNg$o_lS+5bzw;*C3Ba+fWXK5?b|p zDlZi!{zd03m%%-xQ;sgu)b)3GCmh(=sZ>wAQD^^wN63*LHQX+jpWB~JSfj385dY0B zOlOFAcOK`W@)_0j6yH0O84wS<1C3`N;|F^`s--uT*6#hYQMT}B4Tp2`7R54=fc`1 zP~$^?id1XF>stJ9EJivKerZoPG%&RWqKsY--NXP!CB^$9!hzRjD@l}2B6ex5?s?;S zEukdsp($6@ez;~5@J|d|))n2;ttAo)rD9XcgPSTZzJ=>L-cJ(NoZ5vp7+yRSIfAHF82fZ z?pB0t7{*QO@PkwRxtDgmcQyes)$oVusEw8`sXuK>A!PsbIS#4VG<4MfU*qpW#GKKW zR@LU>_B2!K1vGLKcX8G{rzp26=4CBuWGNqqQfquQZD+Tj(+Os#R%(qY#1PJ?vLax! z)@#P>$h0Ug7Ic8?(U|EJMn6Y8!D_&0E|0a+ol|AN)Pwy;TIg6{Xh+GZ-oNM(6bVA# z04M9fAsfmd-!+MgR*HQrE^J8ODP_Mx)$eJm9zKNLCI0pvqBa++fHku@7x8`L73)q4 zlU6etT=TspTe7;Uw!#e_L{WKJjAck#cyq1#$1tc?lXw|`8P&BiQR7t3Xp((k=SE#w zO2CupW}l_KXFY#4X4dtj!J09Z38N`OlyguT%-;`0F^N_pT->`Bn4z>}N5;%x+@#_g zLo4pWG#HcX>w~y2{}kta0k?EwX^U|(DVVmV)(_E<-zBJv_pgpLxB{CjAyZ3a*=xVd z%O7)R$4wSDqLyJ(k~xc!C0_F(tkjfQ%Q#x>hq5Hz+uYU>Su}(kUWnu-1?y0=MG)8J zn6VHBMv~ry`SF|S%W=dO>z-?r7K&sUoL4FFC@?y_tWxxz48Id5Mq^`ea~oDK6LefK zP2g&~vDLF_K}vkaYK%B)V0>Z)29S&+$=p)N_-1m2;uN)9Ql3;5C9Rv2aMZ zQSo)iBVO^N9M(}`4yq3{J&Pp4y97tkv?8Wm6A@)^VOnbxA>hb*-x^B^^Rgz*g{VlC zy4{qkib}}{USgQ%2Yj1yXah>qca{&bl2!Pbc)y|hujRP^bEKE+RVm0-)N1eWM9w_r z+^-wJy+)FRR?|?S2rhEXjT(|T=9f3N^Jm)KVFUqZt5^Ip48PcU!a)4bEC{V+cb?lQu!`B7TmK!UV5I$((hJS$INE1$V5kZGt9(3M#y=P zZmoh{g|N!{__?AJiDzyZUBfMn?T3?m;MD`EAv>7*^G=Rrk!2XTAz6NFChK`>yN+d$ zVZZogB~P{Z>5&MtUz!`NST`N%bJr#3*`lHrFo)=(0~DQjITx5M5RC{E3|=g?70d|& zw~#7lMb?1Wl67pq$M*rLcGz}B(kU+SaHte39?R&3NgB76y*4&NP5YKQ<(g9e7{>~Y zOn_?IDy6aT>&;3k=zF1VowB?|xx*XYK%GR``CyZUse4v09df!b>K@gMskXfa42r6F zEeDXEHDqQT58dNMF6Xx|jB1XrkIVi+d9y2zun^_W0^6Crt2qEz6Y_&te&wfzxI z>S3LHYW@jr^Oi&gQ=?J*1TgRUbGK7>Ee?VPoVP6_Tob^2ug?&}re1@phb^Yj--f5n zphZon>vaV8%z-&s;(!5vuH*QGU!_mw$r9C+9m&#+RDa2ld||^wSikzTMh^2dM)J8Z zYhPMOm~8JFON4B0VEH+k#j=voz&~DQo>u0C?cH~6mh>q}6F&Of2Ro-s@2k}AQ7aIX zBld0n!?bfj!9U`GThie@W#&fWUYpWDi$jO-GW@etniQZ~&2=`35K^XIjs`w^Ukvzklx5ue=F`8N1e4wPw*15sAc({0$d z4GQ@P8cQ!{Cg^QE*RL05`^g2@ur`Sji;6*CTwAA#Fr&e2QREIg4p8gwFclvm6_Il6 z1dmxdBd4f3g&?+5I^)WOXXaQ9cBl#PV&vj<5pw#Px zb+xf{U7i1h_pVB<8%toTb3}E5Ti?k=>nn7S<(1`=B%4FObdfi^8?58?fzy);TM0ze--|cQ;8s{BO|~0^?X1LtaO}44(wK!; z{Nu$<;{JF@JQ9QUJY~CAI9o_k< zLm*zDVke{}(RUPa0RIQu@r`~@@I5T^3>Ch*SJw`M>PmHuKS<(zqU2#y>yaU{mdbnG zTOqC??0=wfOk7r%cU_)?m^#LT7;(WvFYDQ^pW=2=%Fy;^1c$Zhwu|3Ax&Oo<-8QCG z+woJokvM9b4;)3OnY=Z31Cv3%p5+U6tPkV2Y1WUk_;llsBC8VbMcceg1*3FQan=W1ohP4ujtL+zeT(~$J+{D`|i$tEy}52IH?`XBMB)yrath|?Jh3c+GPpWvu0 zdDQ-ggp=@|OQ&glK}4SyGD-l`fl=_HXlKw@=aM7RomQ14*Q2TrFv4~O!X$S%>uH1h z4sM^p!E?Oj%0DD4vuR!C{1=RZ@0gHD9-|DZi03x9ORk160mTx>4g(SEnLmFHDQx4# z^-7G{yFg;5>E6P#gitNz-ROGH@af8Pfxb8fET%-CV(Ib9X=0D>iEEV;HR|Fg@4?B7 zeWM0yq>ib|vmH~L^KWE=PoGfgY>XRO&}AVd;0OkqL@*Z_84lVZx^{h!AM!$wn?AIX zw-_*WN(kRpNe?Rk+Pi#%vtf%Rt0uxS%drm)Epfl(^++p1aeGd+^>qMu7bc4nL$PfL zlN$6_3{u$Q51WghUA^ZdQEIL#RO-Hwf%5F$6KX@VSZ`D?93sC=`CByshf?V#r7&cj z&Fl3;WF!yC7Ev{~xXSUj5*|mFEH%UWbotpLMf4}@N?R_mLTgD?rH}DvAk7VGQM+F@ z{v?PFNBeFr9-+7)Ax@7?mwk$Kg&B)U*k{j`auM+sVT&dCu1fP%At47p9K2QF{9$H- zqd$aY<@H&K-ctm-mgnjqotc$fsezRSln{f#SivP+?0lpQ#aiZY(jk9zYH4BQO7ra0 z4wUvc7+Tvn>C3@o_%gyM599hm!qSxa>;TKQKSk`z{>S0-VwurGd!Pp7nh)<{*%(pd zO(XZ$qnqm>hY2CZRjrri_!#CPCEdxg4yvp2C-ZZc_ios%tF~%tGSc_)@0(`$Zk$uQ z?n+w+OI0PKqcHiCfAY5PW&i3dEB-y9Gulp~^Rxc5bFhuIwz2Zy)+_7KEACJs*=7yY zWOplfz8GWOcW03c2l7>xjeKEebQpme%$jkJ)^X0~*7hO(jh#;3Adz}BJsG_CpFV(!+=(vq+G07u3+ zPkOJO{f)hWYZJ0Pk^YYHDC6%h>u8W=gjAO5imQ8ow6f>t0pyTGZtYP7Tsr``abO7&30p0g8c{P{^Wu_2MpHPTGID5(F z#}?1O1eA>)R2obiE=m$Z?U%Td-`0-bY z3N#3MU$|B7*Y^9jgusBQi2=c&YOmaaS7Kfe^747N*g1D$w*aFo!9E?+*kc#V_XV)3 zVwVnSC1xSX9OuM721Kra3m$N$ZYvNxE$jNEgQw9_6kiX^YXE~drbF#+yucIv=^TZ{FQ*SfzUWbNEu2^UPe&~AI8P*B-Rci;a7!65lcvhm*}mZV|S;BI#Wi)$A= z2Wvr&B=*1&_)(7V#9ve37^7slvQ&|N3@bDhe>g|3P=F(xMn=!QM~yoU*rcZ*UnUcK zjFryqklr<;$WSEN=!aa@Gf@^f(Z7N1Z%5v*FURX__@DJ9J3yU%N`UyY&h9OI=Xb

J)#PL5&Q9DLb;As!tI16x%tPefVJZPgODNO+kS+7uBA z0+^XdRS`Gpf7=XP-T4*!GaV;QPSZKbNDXr=9!zAx!s+2-Qw3*y@el^&My$&df07iG z-rQR3eLx@Q+_3G7Fe_0aeieqd+~x61;Ffjq!BuQFb?+e(B;dC37Uo9J@=XhJ^c7?| z<;E~b$rrMqU06O~slom#8K5-B5rFQuW9d8mg9_b9^qL74zDV3bB8pM5mQzEBc zb|yAbCVgT^;WleS3(2XVtYwu=jIoD-|0u(GM-}rDF^R^omcnL9%7GDOaYpZ-K?y@Z zrzAq7SEKzhoEaCYAd8T|l0Nz5Jq~q!cyn|U3~F`+n5O?)14D&j8^X(ng3YoVc;%+d zJQCA{pKc@5m+u7B*aA}`CzQWE?*7|$q;EW>jE4@;f+SskoG}E4h%}VPJepn9BVv8j z!D%=Ax;pT*@DfjzAdUa2@-sW8?qhy$BeM-}7sxfL_-njnCBnc{BY_d7mfHh0C_@c` zUy|(95TK~AE<@}kRYn?9(%#&#I!L(bmQa|GtcjPiX}c*fhpZ9NY)j|n-OFSpJ#Idh zv~EM`i!~$)<(R``GppWsFC(o7;;xMzT`@6`Qfjx?B__aHRjDeO47PN;bn#&gploV! zuXN7&z0FH!lLeXd()oje(>IJFvs^Ix=JiaDHvpuU-m81~*ej-d z%bA81K2%_hyOd4#Q(;~nz|?-%nL@rcwzXJ8FBCC;5gp~qDhXv!IfU}Q7YsxJ{f9# zz*AcFqYfwCMat06fe$1mBrxQ%>&F2^lMS0!w~Cz&ldipLr53~xN~hHmEU%G!xzG0m zaaiS3GBkJw6CUzI03O&fO1&!L2)S3KoDosi0#=sAIxHd3kMVMdy-?qyt;YUo0Ek9HQDCs+|Fyjci~FDIj-3WA4RBiM1$KC77vSEYikKd zOtXu7xRw$cK8X_b8u-27s3M95o{QaznMxT8FR9HBM3;$g<6K1v1;I!#&zfZAU2^_E z>$YEPq*+I7);7FU*=Vx$)0VB*$f`t-+G<)QcD~Mp#gks*im11n>=I*j(dB{Yf8}9g zj~b3@sZjp4h(`o(<7=dh0qqN&XF!U#zsfIT-g1PY6B9|-5Ui2xzC6dZz*06@HSv<> zl}mn2WFg8nw!=EO*eL=Eg_A*%dd}Qn(9|)$`|!&7$ftJb_DN8A9f<(CGV28p7f` zLpwP1%}orY+MitsUA?^&B`6^hJPqks~u_eG`}zp zEn{QmRB~P(l}m$^Bo(hcl~1lFPzx^y!X7Hr7BHh)*~w#G`4=%E@M9w?E!~39q$#L) zq#-ZUW%eTYiN(aV>6`gJ(Md1nSej_EDRB{4XNi?+T^efgp+{pZ=pUjp>THL4>Ypb& z^bl=hRh>6lu6wmzhI@bxMCo|VzdAr5>g{T%6m?vNW!qy8L{80tQe!U4PF-q{d<9d` z`vyFTZ8t$aKyAVj7n;8G^xUp?q&5L=XSlU9q6gIZ4{&QvYnHiOsBBE2U)OgPJ_Z4C zADaU69A@yR*+#m1b!j|tyQ*MQ-xRHUEo6IZ!p2mN7TU;Plh|w?6}8$UYAk1AGwOvg zHKGRG3^gma%zF{H&CC*qVoYtAe++|V9< z7@^oJ6?SWu3sopfzSx1uC&?6(5|+`!&4qk=@0?Vb`oNTyUO7)b5nym|}N`Z?Kt2c^ppBY67+d(9IkK6gb zfF4Ksp>+z+^T@}a?Xn;rH$Ifr@0~D~KhZbW;JiI}@LNsy|Ka|LGgr5XWc}rCJKOR? zA78tISa73%1lu`0_%QbXAR#x`V{YMe`#ZU>BbYbWYBE4@PMZWoiMc+9@rFm`yM-l} zEMmXPTbv<}Hg6kzEt`40Vf+i*$9)>A1qoAh{PLSzv zqZWfnJlF}iPRq9jNShHedm%nIaJy0Z0g|yehuS~QKWVc z{>BJEa=$Ebb-urmb~+7J1!nkMM{n@-Neu`b-X zT*_1b--uI;B`LT{7&IMC4*g!)5J*KInk>erLV^7ugX!Y|pNGcux9pthp|Gbput0ng zztjs7?wMeuR9wphEGjTY-|`*Dy#*QNuWCEAKS8X|_@w8W3R90^n0OQmk3FA?3nvy2 zGVZ<#P)+k-(Z48D#0E2p?zP@CU_-`B0yqZp;xoGvsEPO4H?8_-zp?!eqm{+(u|w)?Em=|GO3oGsu!@LByM3u79l z`04m-0{GOu+6hmro|b&@#&7gsYwfJ)^2tNvTxq%mYk&jgbRT! zEDdqla7}V)P3LVM2OR&ymof(Fk~Ej>jRbnd?YTvd_(lKB@xB0~DBN~fh#La9gKm&X z1fP=c!NlnwKN&OK^^rF}yjrJ%=(;J84rApL-)Im&;)|v- z+yG*XqXUN-mx3txJ0;Ceopy9jpxdSPW)Jv-V8Mp~Szu$Jh^7ss#!Z<<1*A!Xud*v^ zXvNVA=#~CRTmqSl*EJf(t9?E18?gK`EfUihxH+=$KyC!2jtD{Egvhyu!%HVpZF|#h z&APncNXdbR9Pnh7?8h|#QaRpDP(Iq!CRsvM4LF&?yJf9sTK)I~qJj>kt;}dTS<2fH zeq1V&iM!l}NAxAc44`iZ(D6^|2nmL%k{{ui7*+%N!N6|t@UXh(k2!`-kY*Gx1k28h zg~5<=#ZeQSz~irA#e`kuvmwWu>vKvIZcDJ1@vOuWODk94H3J4jmN2qPiv%I2QebiF za#x}|6sqzFV;ua${!=?b`~X3qt|1GB(nnhmAET>l2{HBQT zLuqm5dmtX>f%Ipj113pH>K{FvO`tu_Ld6M7nzVJw&1jV3;KS%X700l6OLkmY#@m$G zAJ*a91Bn3xO&4jN!J(hPfb4@R5Ez4vOjUqNOdhg&(Yh~1FB9$377-LNr&hP7tF~4V zWW4M_7>0M@J?O#e7s-c3iWg}r$-H4Vi4*P40QML>nvHXsvawjWll4&&3eYYYdEgG~ zU^7VYJH&6m;;54;Gz(7cP&;@6b5KZDFds;$c#LJl=}u8=-^J0Wr)5hCSpeRb)?JUGR%Q$Fblw(@{dlW8p4_U-A^(9)&_ z31qvr1X1(eHf{XL2b0&35Aw@YM|YCOWUA5aT*MtO;gpW{&h~Ng5yCkfnDnfhM3L{~ zv9~GDrWKJ;7nysi+f*hW3?@zS@6{~^noFq@eozZ>T)2}%q>>LQMa<ufC z<3$U=?%-3S$ZW)8p*poRbI+#I>@q^`(&TagQPtqGV}IS3O#@kVFM|H=uGX6p=(lw5 zFSPFB>aN#v&0$mXvzf6%*ZKZ=HT7t>$nVm+sHw7W2?}Kp{s258yK`MN-e&1UyOKhj zrxeC&zMWHiV1+MxO4#z74H<iL!0`oA&7hs~DH63U2t5KmA zvL>d5s%smO#YyuM3;Nyss15Ow4n{vel8+eaW{wqLOtOhN7+IF4YM5AH$ffkdN_AT( z559gaCGN}P!@>ATut3iX@#Gs-m+I*@MY-w!+I%hEVZRe*DZ2cP@*~Q;hbkn575pSN z)g&BZ$CC~G4})iJA~XP6qJ)iHjEzx_k{SOuw@g!Uo6-(bHgwz73p}Ir)zMuf1;q>% zMB}I)jT`mzTJ%dF`&+)Gf)%1RZFvNNNO=eZy@AjI=llo)o%S!On7n4$&tG|X1RV`& z!Ez0_F0OI`zuh*iz6!M5B9zqYh&fa~c-@WuwYe+ewHUd^)kkt+y*vUGd}X zC{Cv(?37DQqB671Lx05Jh(>pzz7@f#5U+ZXB(-saU#t{SK>{4jXkUF zQQN9?X#0YLg9JG*DkAK2RFZvRqe9Ou!5Wi!Z zL;U*o-LMT1uXm-!&1PS2PI}c!?ho1IL`?5oYSoq41uxQ0m`oej87&}zmmayuTf$m0Cj}rr>x%fPm zKK4$du05nsh1&}mhW!h^w)n?%B}j1_pSE|+P1RDQYpLQBjfRxf^b?TCrSdODW==SN zQx+ADHUTdd$`cqFn5~}pP>H*cie1@ULAjAx_av%76#!_Qc&ZDa%Q7e*NnxKnaE9Mh ze91be+`B>3hVGM_@F%<=_U#@A&ODnTVB?MCyvrVna@gcF|GV@17r}v*b9yvqqp#ds z^07l?vaK_*Vs&*xwrLO>&B0$Mr{>9t9M&c(7z0taV2X?f$(+3dnOn)=gR|8rNAO@9 z{|U2t+k~-xdaX4_k#QNnzD^Do?-e5#<1Kmq}pF+1~SXoeC z%|0JHr=e3@*aadxVU}?i7Mua$1|}j zcObMOH40aWE3^&Fa*1^l*3v<=Gu<&Lzw+jQJuu!qz8y$D3i@gGHGWyZv%LJDZs)&V zm*nkkVfk0M(GN{7ifYXeo#r=DRH2ETYX+WZ+1==@oTb8b^6a5%_#H+7)=~UmY0LjY zH;&~?SIedJP3{S_ruk(C^n|SV|4Bn9FA0bIWX-%>rekMG(&#@6U#;sUEifn+xzt;I zU)LtiO_ovN!{F4oBllU2*gf0iuBJCdm^}SPj?f#_r6Yht3|jdg+?CQ0M-DEYN5QeFG3D=GQI)TveWqW6|mF&&VT z-27Uj>vQTu?(VOr^yy?8*I8)0K0z6^syYzx&tyFERxIL4F&*R+Q412K-)Qvr;LIq#tF416Sw}Y-v zLccI4x3hAujPo<(@X$v2mu;1=Hp^Fd|Kio1{TNo%O)wHT%n0x{uF0$0Ypux|7cXlW z+v>~B=|g+ux{%&}zfW9hkGEo>g4BJyWIddN(N0H4qn%DVg*bt(LA~GN&z$O`t3cbq zXQJ}$82jNhtTgjGorSl2zy7SXw)#z{MwHIU+g8tSyd^JEeX5*tjY>Kxm4xq5%C%xU zR;laiHKQW_;rlm1R5VVT%O&;eIr06UplwvDbO!tNUQX zbMG-=$DaaFfaQGg&_!f6K=_Vjbn*2c0N?M3w?F+1LI}>j_=<-QgwJh$f>V6qpJgS0}Ok>;e@Kr>2Aa~tm%Gy zO3txXX4)a99j(i{(kGqH1zsIf)y*bDZ2)HEES28jy^|uTo)+9q^-`2WVG#8NYk_y8 zX|vi@P2F)0rWCU(NDK;$PS9Cb=!z_gx_qwC#-u=5(wh1{{1cY`SnOIbUv9!uu?3s% z0ZruPCGbzPpmt*h2Q=)Gy&G8-dlH+LR^8S$2`J`6V z2~v;TAhlnTs)%)AF$QJ_Gxmx1cRP@KLouvZtT4Q%V0&inqLvg05|q%T5zz1qfB?ubg8_fYq3`|V{ftsR%h&4r^?~;)|QvRKg*>w9A5%gHLU0&h= zc9+vASs4uQ=B_3KMde7_J1~%xay-VK3-)Nsm~-#+TE~+uWgt6I_t` zQ6lAbf+_~wTPaO3 z*0K;SB>?pMJ*eIFkun^C@PeJ;2pmFEW=3N%)PPgg96w{eJdQJdV_kdJ;IR9YWNc2w zU7V~Qwd?zTgdD*Spo?#5^~1Br8(3G(6nF6lh>S$*_M0W!0&*9p5GR(HVVoGGovE26 zfy7F+$@8*Nv3Co>@NT8paE(rm5i-i5DdTV5@U7)m8OolbQx-YBmUX7i6G=5Zy1B^c zd3y7W7?~#~nk#Us>>XruWXYIB#>l(r7dD*h;Xancq#j3GAKNj1vLN)jk2L)f7 zmQtaOwZQYkr7bILAm;h;k?B}_qB1LK;3ZaH_`FN}<(w2;QZU`*jW(>jH~2;TzSL7; z-P;Cea4uj>O{dZ?@}#4f_*4FQo+Ac2nd%2t??m|pHBgivt!rkSgTYY-2EFst4ly*@&il75$pJfw02aQ?)fWG`u=fB5I^AytVTDf|if)#3*#!=!)?| zy=yfz;mZkPI>8s**&u6uVz)>LRs?j4jdOy*tR=izW-Bxn@#9nMx~9ZAW||sJ4JfgH zS_OpQ92;xMHMv7y!3)({X<+t}vW)5HV5wB(Tuwh*l&+h`ouT-mppm{#mOKzCqz6?J z**_|p3RBfB2pb3sgUjQk@;Hc66ktryhpVE?K{fYa5z6x)gOu{Lrh~#uOy!1RajS0^ zeRc$ly%)whmVco^q7+S~sg5fzAENg-!ZM9jt+h~jLkxa{9;}k0D&x*QlnO%*mvlF? z53!tBouCY!p2(n{#x!;oAzrwJG`%hb8S{nN4fTz zKBtj`eF+x^Z1ExT6 zkCe%oAoAKw?_nsF16ej6>S0CwRu!(*VN}*rwHF&sU~OEfOt|^A1Zk|lt<)+jZxb1M zU%)Yj2s`6nx~q@DeZ!u#2|Bu{v}93Bdu7WxNWrx?{oJV}P*~!n9bIzHScRS(-K)F= zCnSsHE{~yBGmx-)(o_G%&E{lyj_NhbBR~p&q%U5moO2xFmCnU72=VeKb%2Yj^K@6aWAK2mlON+*HDW8ixu>005C(0RSWb003!jV{CO~WiMxM zZ)a>}FK}{ibZ=sHW-nxAb7OL8aCC2SE@4}B7FRn@oN56EQ{z}85K#H6mOGB7u(!c)uKFn@??^{O|pCeopo=hU3Z+% zo-72BgApV01e##0%Vd(4RgsRCRhrMEcs_}iWddkLWxg!N2|XF5^SD?Meq|?mmsYn? zUeM2cN%+q4Njgo(F~aCXagjvO|17PlWD-HoZ_^3YKqc$B}zS3*C8GtaAZoOIxIT1FWF zLl}0?^NEKR^f=Dqbe0s|W<;Pvi!KTg80};U$Z1>$gc!6+;9%VkQ-XZe{XGP^A86#go zyA&C&K#rO-Zge>;9WKH-|Ng9ZiDR&b8$IsC5&-*Gj(8+j;}9!uMu}3 z$<_7qt3iKoJ?KR*&(BYY>{q?Z@A}8Rt7p;a`4tiF`l?6BoE!~~sC$3{go7{O_vhDF zeIjB1Y|y*ByuKLp&(HQ?&c6o=0j5XL`h;kGeuiUa-szoR{(zv79yA-B==)bacz%iG zC8`}EIj(?u#{>H_=n{xY12f}|&U!CT`!9QE$36Vu907gbzv}J54 z)7Wv+05_Vh7cM(@Xm+Fii|FX&yFTJC-vd8f^@V+ie8;bZ`rRGkpCzoK;xKvxf+C;) zU$YrRyZ=d#qVM8j67P`|cpl@bg=aYkDiCW~ee0SeWqJcbZ$%BR;`!fTy}!IoX7RhY z>O}vMOsCOF65|E{QjDZgsTU}&?`fJPBr!l(mk~&{vIJrB?lv9YBJeQ?5)hhEwOWw; zQCk-531u1IBqXkW$d}PLp3^23t2d8JX}_pYPUTUS#0AJj5Xj4U1+o)5fj_2cl1)f# zrIo=0k$tDOChVK!8;}lq;1;+y!Nxm)_piA_7R4ZFr!j7kS((FsKwy{A3h)C2CM%GX zupwsIDvHNrXhr?dKDmOXlN3brGR_c?bTV2+3!n(fe8l7hK0Ps`BAf&x>IDTQ;gFQD z%`!%c+^=)kS%5?^YwuFf7hu}~sui>)fm}7jg6({ijANuGKwt6KC}(Bgf*n>1VHnmp zDQKtFQ^WKk5@O3Toh@L*0!~dag1SlONfDzy0OQ1W8U!%p0vMx!t*J=HRklJMXYw|l zkCTZS!)+eDi|4eP0~V;<04U_vxEQ5XftxU6vWp{qGtb}A>fM|KnLQb@4Lfr}6Ag4taK}gX5GI5H&6mVsIq3$qMmUf7eVKz+b&J1c>6;`>eZ@I1 zfYo4mCGTVG5l3>HzaxH|kphDqIP6m3ot*QOLhM z?F~VG56+)ozZjnMu8uGJ7a&lFuZF{&PvDz$o^1LIz|F_m5<35Smdx^E^{wt;2pi&M z?__u}fKRROSQ4^I4C?TcvRaPHC*>{BY%*L_MfVn9fcBD3twv>1eQW;-YR~+}e)1NW zH!r^3*bh*A2Aa$5<}YWAxb_&Oe+UxBbZ zRtjgF!J{HCabAFGNHpDk=ac2!dq6aaBDW2&K+`QKg7Y3E&l;hD(i8Za5B z#~=;+^J!k2bS(&7YOG_9@wmnr&zETiJ5`w4gLsrBfU0aZSF715z2 zPzI>c(JPvgT06aw4`nFBBAI3&`_LQ%5N7QYiBOaLS>V1@O=ZxRy5X~(UrDUg8~fd( z^aOQdn8AagR>6=)rmfZ}RL95M=oH%YRg-#`s+ld)%rp#_bF@A|ull(*9Rqk=hZkt; zj|S{o#0R*+8hNgJxZu|T>f{9J?0ERsEClykG*}^tJ$LK@H7H1jrjPDr^(@IaENOnOC46rdj>n9FC~@^gpf@f+bwu|D=!=$dg02l_g3 zBdQ2Zre1P;fIaH5bKxkPIEt2|1S!3o=OZQ-n-UHgaBL&kY8ADd83(w1u%U`2;F)CU zgqd(u#As)X^2tg&*RXeC9u1LN3~!2jxftTd&)gR|ZdLLE-qh!DcW;MWZP8&3xm_as zUPnHNYJD|)VEU8~qMv_NjC#bj7n&WnAo(&LESYC0!p3o#h%J-FKczr=SRii_+a4mz z6paD3WwBjOe3O>*$1owV2~}FpPuXdR+GI)4VC>|mVf!8!ZJs3Ljl{JRM++q0E$}TP zFhpn*Sb7T(Fv)xj>^h8aS0Zy(SQO0l3XG|g?8q2dx1!aS&YeZJb`v`7Ki8&2?=KhU zmxJgu{%K`d+OXml%Tbn&4~1($ct_LaoOUXtC}4t?eL`|B#kXqo&Qcc-1JHrt#9l|p zTW|ApLLC5~|4j31?HbWH(b@Is=`(tcLvo*>*6%(+b=rRN>yDDRAR=&<-lCeMTnQGc zDLQmbl|+#W4?i_%k=M;r*!koablBqA>O6HQL|XqRklYlq&q`rCWvlO>&V=mqCjxDBxa15kZ;yWKqo=V94lugxTf z$psO6K=ikmK>8p;if;@Wd8@%{ut534&CvJ(>{7#CZ1Em^-HcmZH#CGFdn{c^S-%e z&m35BM8wC|Avz>6SPR0nl7bX2$N3`Zdi=s70merU)#^vk(`A;e4*tH3Gg^IXx+1_R z?b2DwDkDQ#Bt@D}V7DQUr&eGcUFXq@Jbz^Lmq`MYD8z7!$8RtWK(HQ-;^GmB5yXp; z!Dn4;4?Xm!iWwh0kAHf^x)3_;h2t0seB6oP{bL3*Brx!)g4D&f%#SxDjx%wj0~?cU zkG-O z5En%(Vh(u#fQROnZ9N7Io$wT}wPH^Y?1Re134}RAV}*2|?pi5Q8=?%(V&{n^MP#a& zo#;bL4!c3^(u{~WRCD`IB zx#A`+Mlwj+i!oDZkneiE?MLD)X**DmZF-!*^S8@cJU>9ii71ZRaW^_AJDfq0iUjDC z%d}FT0H)*s5wlsmFRm@`;By5s8Fycxj`LLq^e9lRCn`pPf-Zi82CHz-ZqmK!c3L?` zFsMg(?}c&t9>kb3(baPFZFkK%9{ySnEtaC810_?G8MvsD+Z=tgtR`rGtE^Irha(Xg zlCqU(ZsO8FbIeH;?BY>!cX2f*)h#bWap0aJro5RGd)EK6kmRcQlWhr+NOSj6lD%(AT;|72gPnKy+VP`vchp zIV>>PQK*@6wWTFHx*BkK0VvSJ=c_Y$qCjLH`dhW1W&~Xf(We0?P zkdE~Jf$2z_$h&xD?at_2CzWZ&PD!wC(g`Lsz#i!1SazDo&agfR?T-~5nrZKnDxkL- zVMor{^}>$*wjMGV39m5^T%}=tXPRH8$_PSobI@=%|TO z$Ayno7A_m@nC454NpUe06SV89m0Fhy6|tz$bLi&Uh?5!#i5X