Skip to content

Commit

Permalink
ROS 2 Jazzyに対応 (#14)
Browse files Browse the repository at this point in the history
* add dependency for jazzy

* display.launchの動作確認とCIが通るようにフォーマット修正

* gz-sim対応

* プランニングできるように可動範囲を微調整

* センサ周りのgz移行もれ

* doc, ciをJazzy対応

* bug fix

* 手首の可動範囲を広げる

* fix mimic joint bug

* fix typo

* change gz_frame_id to frame_id
  • Loading branch information
chama1176 authored Nov 20, 2024
1 parent 2bfba6b commit 2d37b80
Show file tree
Hide file tree
Showing 10 changed files with 93 additions and 89 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/industrial_ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 1 addition & 0 deletions README.en.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
## サポートするROSディストリビューション

- Humble
- Jazzy

### ROS 1

Expand Down
2 changes: 1 addition & 1 deletion launch/display.launch.py
Original file line number Diff line number Diff line change
@@ -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():
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>ign_ros2_control</depend>
<depend>gz_ros2_control</depend>
<depend>joint_state_publisher_gui</depend>
<depend>launch</depend>
<depend>robot_state_publisher</depend>
Expand Down
6 changes: 3 additions & 3 deletions test/test_robot_description_loader.py
Original file line number Diff line number Diff line change
@@ -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):
Expand Down Expand Up @@ -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():
Expand Down
76 changes: 37 additions & 39 deletions urdf/sciurus17.gazebo_ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

<ros2_control name="sciurus17" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>

<joint name="${NAME_JOINT_BODY}">
Expand All @@ -22,8 +22,8 @@

<joint name="${NAME_JOINT_NECK_1}">
<command_interface name="position">
<param name="min">${JOINT_NECK_1_LOWER_LIMIT}"</param>
<param name="max">${JOINT_NECK_1_UPPER_LIMIT}"</param>
<param name="min">${JOINT_NECK_1_LOWER_LIMIT}</param>
<param name="max">${JOINT_NECK_1_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -34,8 +34,8 @@

<joint name="${NAME_JOINT_NECK_2}">
<command_interface name="position">
<param name="min">${JOINT_NECK_2_LOWER_LIMIT}"</param>
<param name="max">${JOINT_NECK_2_UPPER_LIMIT}"</param>
<param name="min">${JOINT_NECK_2_LOWER_LIMIT}</param>
<param name="max">${JOINT_NECK_2_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -46,8 +46,8 @@

<joint name="${NAME_JOINT_ARM_R_1}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_1_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_1_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_1_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_1_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -58,8 +58,8 @@

<joint name="${NAME_JOINT_ARM_R_2}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_2_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_2_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_2_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_2_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">-1.5707</param>
Expand All @@ -70,8 +70,8 @@

<joint name="${NAME_JOINT_ARM_R_3}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_3_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_3_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_3_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_3_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -82,8 +82,8 @@

<joint name="${NAME_JOINT_ARM_R_4}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_4_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_4_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_4_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_4_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">2.7262</param>
Expand All @@ -94,8 +94,8 @@

<joint name="${NAME_JOINT_ARM_R_5}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_5_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_5_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_5_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_5_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -106,8 +106,8 @@

<joint name="${NAME_JOINT_ARM_R_6}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_6_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_6_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_6_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_6_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">-2.0943</param>
Expand All @@ -118,8 +118,8 @@

<joint name="${NAME_JOINT_ARM_R_7}">
<command_interface name="position">
<param name="min">${JOINT_ARM_R_7_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_R_7_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_R_7_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_R_7_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -130,8 +130,8 @@

<joint name="${NAME_JOINT_GRIPPER_R_A}">
<command_interface name="position">
<param name="min">${JOINT_GRIPPER_R_LOWER_LIMIT}"</param>
<param name="max">${JOINT_GRIPPER_R_UPPER_LIMIT}"</param>
<param name="min">${JOINT_GRIPPER_R_LOWER_LIMIT}</param>
<param name="max">${JOINT_GRIPPER_R_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -143,16 +143,15 @@
<joint name="${NAME_JOINT_GRIPPER_R_B}">
<param name="mimic">${NAME_JOINT_GRIPPER_R_A}</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>

<joint name="${NAME_JOINT_ARM_L_1}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_1_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_1_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_1_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_1_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -163,8 +162,8 @@

<joint name="${NAME_JOINT_ARM_L_2}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_2_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_2_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_2_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_2_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">1.5707</param>
Expand All @@ -175,8 +174,8 @@

<joint name="${NAME_JOINT_ARM_L_3}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_3_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_3_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_3_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_3_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -187,8 +186,8 @@

<joint name="${NAME_JOINT_ARM_L_4}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_4_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_4_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_4_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_4_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">-2.7262</param>
Expand All @@ -199,8 +198,8 @@

<joint name="${NAME_JOINT_ARM_L_5}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_5_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_5_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_5_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_5_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -211,8 +210,8 @@

<joint name="${NAME_JOINT_ARM_L_6}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_6_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_6_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_6_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_6_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">2.09439</param>
Expand All @@ -223,8 +222,8 @@

<joint name="${NAME_JOINT_ARM_L_7}">
<command_interface name="position">
<param name="min">${JOINT_ARM_L_7_LOWER_LIMIT}"</param>
<param name="max">${JOINT_ARM_L_7_UPPER_LIMIT}"</param>
<param name="min">${JOINT_ARM_L_7_LOWER_LIMIT}</param>
<param name="max">${JOINT_ARM_L_7_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -235,8 +234,8 @@

<joint name="${NAME_JOINT_GRIPPER_L_A}">
<command_interface name="position">
<param name="min">${JOINT_GRIPPER_L_LOWER_LIMIT}"</param>
<param name="max">${JOINT_GRIPPER_L_UPPER_LIMIT}"</param>
<param name="min">${JOINT_GRIPPER_L_LOWER_LIMIT}</param>
<param name="max">${JOINT_GRIPPER_L_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
Expand All @@ -248,7 +247,6 @@
<joint name="${NAME_JOINT_GRIPPER_L_B}">
<param name="mimic">${NAME_JOINT_GRIPPER_L_A}</param>
<param name="multiplier">1</param>
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
Expand Down
Loading

0 comments on commit 2d37b80

Please sign in to comment.