diff --git a/.github/workflows/industrial_ci.yml b/.github/workflows/industrial_ci.yml index 3ecf7af..268e475 100644 --- a/.github/workflows/industrial_ci.yml +++ b/.github/workflows/industrial_ci.yml @@ -14,7 +14,7 @@ jobs: strategy: matrix: env: - - { ROS_DISTRO: humble, ROS_REPO: ros, BEFORE_RUN_TARGET_TEST_EMBED: "ici_with_unset_variables source /root/target_ws/install/setup.bash" } + - { ROS_DISTRO: jazzy, ROS_REPO: ros, BEFORE_RUN_TARGET_TEST_EMBED: "ici_with_unset_variables source /root/target_ws/install/setup.bash" } runs-on: ubuntu-latest steps: - uses: actions/checkout@v4 diff --git a/README.en.md b/README.en.md index 1342b75..c35d4ce 100644 --- a/README.en.md +++ b/README.en.md @@ -13,6 +13,7 @@ See [rt-net/sciurus17_ros#134](https://github.com/rt-net/sciurus17_ros/issues/13 ## Supported ROS distributions - Humble +- Jazzy ### ROS 1 diff --git a/README.md b/README.md index 43a7768..7581430 100644 --- a/README.md +++ b/README.md @@ -13,6 +13,7 @@ ## サポートするROSディストリビューション - Humble +- Jazzy ### ROS 1 diff --git a/launch/display.launch.py b/launch/display.launch.py index 6b857b4..5058ebb 100644 --- a/launch/display.launch.py +++ b/launch/display.launch.py @@ -1,9 +1,9 @@ # Copyright 2023 RT Corporation from ament_index_python.packages import get_package_share_directory -from sciurus17_description.robot_description_loader import RobotDescriptionLoader from launch import LaunchDescription from launch_ros.actions import Node +from sciurus17_description.robot_description_loader import RobotDescriptionLoader def generate_launch_description(): diff --git a/package.xml b/package.xml index 75d7153..b7ad655 100644 --- a/package.xml +++ b/package.xml @@ -13,7 +13,7 @@ ament_cmake - ign_ros2_control + gz_ros2_control joint_state_publisher_gui launch robot_state_publisher diff --git a/test/test_robot_description_loader.py b/test/test_robot_description_loader.py index 00ecda2..02ab11b 100644 --- a/test/test_robot_description_loader.py +++ b/test/test_robot_description_loader.py @@ -1,8 +1,8 @@ # Copyright 2023 RT Corporation -from sciurus17_description.robot_description_loader import RobotDescriptionLoader from launch.launch_context import LaunchContext import pytest +from sciurus17_description.robot_description_loader import RobotDescriptionLoader def exec_load(loader): @@ -53,12 +53,12 @@ def test_manipulator_config_file_path(): def test_use_gazebo(): - # use_gazeboが変更され、xacroにign_ros2_controlがセットされることを期待 + # use_gazeboが変更され、xacroにgz_ros2_controlがセットされることを期待 rdl = RobotDescriptionLoader() rdl.use_gazebo = 'true' rdl.gz_control_config_package = 'sciurus17_description' rdl.gz_control_config_file_path = 'config/dummy_controllers.yaml' - assert 'ign_ros2_control/IgnitionSystem' in exec_load(rdl) + assert 'gz_ros2_control/GazeboSimSystem' in exec_load(rdl) def test_use_gazebo_head_camera(): diff --git a/urdf/sciurus17.gazebo_ros2_control.xacro b/urdf/sciurus17.gazebo_ros2_control.xacro index 4d28422..d5c19e2 100644 --- a/urdf/sciurus17.gazebo_ros2_control.xacro +++ b/urdf/sciurus17.gazebo_ros2_control.xacro @@ -5,7 +5,7 @@ - ign_ros2_control/IgnitionSystem + gz_ros2_control/GazeboSimSystem @@ -22,8 +22,8 @@ - ${JOINT_NECK_1_LOWER_LIMIT}" - ${JOINT_NECK_1_UPPER_LIMIT}" + ${JOINT_NECK_1_LOWER_LIMIT} + ${JOINT_NECK_1_UPPER_LIMIT} 0.0 @@ -34,8 +34,8 @@ - ${JOINT_NECK_2_LOWER_LIMIT}" - ${JOINT_NECK_2_UPPER_LIMIT}" + ${JOINT_NECK_2_LOWER_LIMIT} + ${JOINT_NECK_2_UPPER_LIMIT} 0.0 @@ -46,8 +46,8 @@ - ${JOINT_ARM_R_1_LOWER_LIMIT}" - ${JOINT_ARM_R_1_UPPER_LIMIT}" + ${JOINT_ARM_R_1_LOWER_LIMIT} + ${JOINT_ARM_R_1_UPPER_LIMIT} 0.0 @@ -58,8 +58,8 @@ - ${JOINT_ARM_R_2_LOWER_LIMIT}" - ${JOINT_ARM_R_2_UPPER_LIMIT}" + ${JOINT_ARM_R_2_LOWER_LIMIT} + ${JOINT_ARM_R_2_UPPER_LIMIT} -1.5707 @@ -70,8 +70,8 @@ - ${JOINT_ARM_R_3_LOWER_LIMIT}" - ${JOINT_ARM_R_3_UPPER_LIMIT}" + ${JOINT_ARM_R_3_LOWER_LIMIT} + ${JOINT_ARM_R_3_UPPER_LIMIT} 0.0 @@ -82,8 +82,8 @@ - ${JOINT_ARM_R_4_LOWER_LIMIT}" - ${JOINT_ARM_R_4_UPPER_LIMIT}" + ${JOINT_ARM_R_4_LOWER_LIMIT} + ${JOINT_ARM_R_4_UPPER_LIMIT} 2.7262 @@ -94,8 +94,8 @@ - ${JOINT_ARM_R_5_LOWER_LIMIT}" - ${JOINT_ARM_R_5_UPPER_LIMIT}" + ${JOINT_ARM_R_5_LOWER_LIMIT} + ${JOINT_ARM_R_5_UPPER_LIMIT} 0.0 @@ -106,8 +106,8 @@ - ${JOINT_ARM_R_6_LOWER_LIMIT}" - ${JOINT_ARM_R_6_UPPER_LIMIT}" + ${JOINT_ARM_R_6_LOWER_LIMIT} + ${JOINT_ARM_R_6_UPPER_LIMIT} -2.0943 @@ -118,8 +118,8 @@ - ${JOINT_ARM_R_7_LOWER_LIMIT}" - ${JOINT_ARM_R_7_UPPER_LIMIT}" + ${JOINT_ARM_R_7_LOWER_LIMIT} + ${JOINT_ARM_R_7_UPPER_LIMIT} 0.0 @@ -130,8 +130,8 @@ - ${JOINT_GRIPPER_R_LOWER_LIMIT}" - ${JOINT_GRIPPER_R_UPPER_LIMIT}" + ${JOINT_GRIPPER_R_LOWER_LIMIT} + ${JOINT_GRIPPER_R_UPPER_LIMIT} 0.0 @@ -143,7 +143,6 @@ ${NAME_JOINT_GRIPPER_R_A} 1 - @@ -151,8 +150,8 @@ - ${JOINT_ARM_L_1_LOWER_LIMIT}" - ${JOINT_ARM_L_1_UPPER_LIMIT}" + ${JOINT_ARM_L_1_LOWER_LIMIT} + ${JOINT_ARM_L_1_UPPER_LIMIT} 0.0 @@ -163,8 +162,8 @@ - ${JOINT_ARM_L_2_LOWER_LIMIT}" - ${JOINT_ARM_L_2_UPPER_LIMIT}" + ${JOINT_ARM_L_2_LOWER_LIMIT} + ${JOINT_ARM_L_2_UPPER_LIMIT} 1.5707 @@ -175,8 +174,8 @@ - ${JOINT_ARM_L_3_LOWER_LIMIT}" - ${JOINT_ARM_L_3_UPPER_LIMIT}" + ${JOINT_ARM_L_3_LOWER_LIMIT} + ${JOINT_ARM_L_3_UPPER_LIMIT} 0.0 @@ -187,8 +186,8 @@ - ${JOINT_ARM_L_4_LOWER_LIMIT}" - ${JOINT_ARM_L_4_UPPER_LIMIT}" + ${JOINT_ARM_L_4_LOWER_LIMIT} + ${JOINT_ARM_L_4_UPPER_LIMIT} -2.7262 @@ -199,8 +198,8 @@ - ${JOINT_ARM_L_5_LOWER_LIMIT}" - ${JOINT_ARM_L_5_UPPER_LIMIT}" + ${JOINT_ARM_L_5_LOWER_LIMIT} + ${JOINT_ARM_L_5_UPPER_LIMIT} 0.0 @@ -211,8 +210,8 @@ - ${JOINT_ARM_L_6_LOWER_LIMIT}" - ${JOINT_ARM_L_6_UPPER_LIMIT}" + ${JOINT_ARM_L_6_LOWER_LIMIT} + ${JOINT_ARM_L_6_UPPER_LIMIT} 2.09439 @@ -223,8 +222,8 @@ - ${JOINT_ARM_L_7_LOWER_LIMIT}" - ${JOINT_ARM_L_7_UPPER_LIMIT}" + ${JOINT_ARM_L_7_LOWER_LIMIT} + ${JOINT_ARM_L_7_UPPER_LIMIT} 0.0 @@ -235,8 +234,8 @@ - ${JOINT_GRIPPER_L_LOWER_LIMIT}" - ${JOINT_GRIPPER_L_UPPER_LIMIT}" + ${JOINT_GRIPPER_L_LOWER_LIMIT} + ${JOINT_GRIPPER_L_UPPER_LIMIT} 0.0 @@ -248,7 +247,6 @@ ${NAME_JOINT_GRIPPER_L_A} 1 - diff --git a/urdf/sciurus17.ros2_control.xacro b/urdf/sciurus17.ros2_control.xacro index 5de1d66..98df3d3 100644 --- a/urdf/sciurus17.ros2_control.xacro +++ b/urdf/sciurus17.ros2_control.xacro @@ -25,8 +25,8 @@ - ${JOINT_NECK_1_LOWER_LIMIT}" - ${JOINT_NECK_1_UPPER_LIMIT}" + ${JOINT_NECK_1_LOWER_LIMIT} + ${JOINT_NECK_1_UPPER_LIMIT} @@ -36,8 +36,8 @@ - ${JOINT_NECK_2_LOWER_LIMIT}" - ${JOINT_NECK_2_UPPER_LIMIT}" + ${JOINT_NECK_2_LOWER_LIMIT} + ${JOINT_NECK_2_UPPER_LIMIT} @@ -47,8 +47,8 @@ - ${JOINT_ARM_R_1_LOWER_LIMIT}" - ${JOINT_ARM_R_1_UPPER_LIMIT}" + ${JOINT_ARM_R_1_LOWER_LIMIT} + ${JOINT_ARM_R_1_UPPER_LIMIT} @@ -58,8 +58,8 @@ - ${JOINT_ARM_R_2_LOWER_LIMIT}" - ${JOINT_ARM_R_2_UPPER_LIMIT}" + ${JOINT_ARM_R_2_LOWER_LIMIT} + ${JOINT_ARM_R_2_UPPER_LIMIT} @@ -69,8 +69,8 @@ - ${JOINT_ARM_R_3_LOWER_LIMIT}" - ${JOINT_ARM_R_3_UPPER_LIMIT}" + ${JOINT_ARM_R_3_LOWER_LIMIT} + ${JOINT_ARM_R_3_UPPER_LIMIT} @@ -80,8 +80,8 @@ - ${JOINT_ARM_R_4_LOWER_LIMIT}" - ${JOINT_ARM_R_4_UPPER_LIMIT}" + ${JOINT_ARM_R_4_LOWER_LIMIT} + ${JOINT_ARM_R_4_UPPER_LIMIT} @@ -91,8 +91,8 @@ - ${JOINT_ARM_R_5_LOWER_LIMIT}" - ${JOINT_ARM_R_5_UPPER_LIMIT}" + ${JOINT_ARM_R_5_LOWER_LIMIT} + ${JOINT_ARM_R_5_UPPER_LIMIT} @@ -102,8 +102,8 @@ - ${JOINT_ARM_R_6_LOWER_LIMIT}" - ${JOINT_ARM_R_6_UPPER_LIMIT}" + ${JOINT_ARM_R_6_LOWER_LIMIT} + ${JOINT_ARM_R_6_UPPER_LIMIT} @@ -113,8 +113,8 @@ - ${JOINT_ARM_R_7_LOWER_LIMIT}" - ${JOINT_ARM_R_7_UPPER_LIMIT}" + ${JOINT_ARM_R_7_LOWER_LIMIT} + ${JOINT_ARM_R_7_UPPER_LIMIT} @@ -124,8 +124,8 @@ - ${JOINT_GRIPPER_R_LOWER_LIMIT}" - ${JOINT_GRIPPER_R_UPPER_LIMIT}" + ${JOINT_GRIPPER_R_LOWER_LIMIT} + ${JOINT_GRIPPER_R_UPPER_LIMIT} @@ -135,8 +135,8 @@ - ${JOINT_ARM_L_1_LOWER_LIMIT}" - ${JOINT_ARM_L_1_UPPER_LIMIT}" + ${JOINT_ARM_L_1_LOWER_LIMIT} + ${JOINT_ARM_L_1_UPPER_LIMIT} @@ -146,8 +146,8 @@ - ${JOINT_ARM_L_2_LOWER_LIMIT}" - ${JOINT_ARM_L_2_UPPER_LIMIT}" + ${JOINT_ARM_L_2_LOWER_LIMIT} + ${JOINT_ARM_L_2_UPPER_LIMIT} @@ -157,8 +157,8 @@ - ${JOINT_ARM_L_3_LOWER_LIMIT}" - ${JOINT_ARM_L_3_UPPER_LIMIT}" + ${JOINT_ARM_L_3_LOWER_LIMIT} + ${JOINT_ARM_L_3_UPPER_LIMIT} @@ -168,8 +168,8 @@ - ${JOINT_ARM_L_4_LOWER_LIMIT}" - ${JOINT_ARM_L_4_UPPER_LIMIT}" + ${JOINT_ARM_L_4_LOWER_LIMIT} + ${JOINT_ARM_L_4_UPPER_LIMIT} @@ -179,8 +179,8 @@ - ${JOINT_ARM_L_5_LOWER_LIMIT}" - ${JOINT_ARM_L_5_UPPER_LIMIT}" + ${JOINT_ARM_L_5_LOWER_LIMIT} + ${JOINT_ARM_L_5_UPPER_LIMIT} @@ -190,8 +190,8 @@ - ${JOINT_ARM_L_6_LOWER_LIMIT}" - ${JOINT_ARM_L_6_UPPER_LIMIT}" + ${JOINT_ARM_L_6_LOWER_LIMIT} + ${JOINT_ARM_L_6_UPPER_LIMIT} @@ -201,8 +201,8 @@ - ${JOINT_ARM_L_7_LOWER_LIMIT}" - ${JOINT_ARM_L_7_UPPER_LIMIT}" + ${JOINT_ARM_L_7_LOWER_LIMIT} + ${JOINT_ARM_L_7_UPPER_LIMIT} @@ -212,8 +212,8 @@ - ${JOINT_GRIPPER_L_LOWER_LIMIT}" - ${JOINT_GRIPPER_L_UPPER_LIMIT}" + ${JOINT_GRIPPER_L_LOWER_LIMIT} + ${JOINT_GRIPPER_L_UPPER_LIMIT} diff --git a/urdf/sciurus17.urdf.xacro b/urdf/sciurus17.urdf.xacro index 186101d..26dc666 100644 --- a/urdf/sciurus17.urdf.xacro +++ b/urdf/sciurus17.urdf.xacro @@ -121,7 +121,8 @@ - + + @@ -131,7 +132,8 @@ - + + @@ -142,8 +144,9 @@ + - + @@ -153,7 +156,8 @@ - + + diff --git a/urdf/sciurus17_gazebo.xacro b/urdf/sciurus17_gazebo.xacro index 6de8b49..5bbecfe 100644 --- a/urdf/sciurus17_gazebo.xacro +++ b/urdf/sciurus17_gazebo.xacro @@ -31,7 +31,7 @@ - + $(find ${GZ_CONTROL_CONFIG_PACKAGE})/${GZ_CONTROL_CONFIG_FILE_PATH} @@ -53,7 +53,7 @@ - + ogre2 @@ -64,7 +64,7 @@ 10 true ${NAME_HEAD_CAMERA_PREFIX} - ${NAME_HEAD_CAMERA_PREFIX}_color_frame + ${NAME_HEAD_CAMERA_PREFIX}_color_frame @@ -115,7 +115,7 @@ 10 true ${NAME_CHEST_CAMERA_PREFIX}/image_raw - ${NAME_LINK_CHEST_CAMERA} + ${NAME_LINK_CHEST_CAMERA}