本リポジトリはROBOTIS Dynamixelアクチュエタを動作させるためのros2_controlのSystemInterfaceを提供します.
ros2_controlのアクチュエータにより全のDynamixelアクチュータ対応きると思われます.
Important
オリジナルのパッケージと異り本フォークは異なるアクチュエータにおける複数制御方法に対応しています. また,ギア比の設定やオフセット等にも対応しています. その一方,制御方法の切り替えはできなくなっております.
(上に戻る)
ここで,本レポジトリのセットアップ方法について説明します.
(上に戻る)
まず,以下の環境を整えてから,次のインストール段階に進んでください.
| System | Version |
|---|---|
| Ubuntu | 22.04 (Jammy Jellyfish) |
| ROS | Humble Hawksbill |
| Python | 3.10 |
Note
UbuntuやROSのインストール方法に関しては,SOBITS Manualに参照してください.
(上に戻る)
-
ROSの
srcフォルダに移動します.$ cd ~/colcon_ws/src/
-
本レポジトリをcloneします.
$ git clone https://github.com/TeamSOBITS/dynamixel_hardware
-
レポジトリの中へ移動します.
$ cd dynamixel_hardware/ -
依存パッケージをインストールします.
$ bash install.sh
-
パッケージをコンパイルします.
$ cd ~/colcon_ws/ $ colcon build --symlink-install $ source ~/colcon_ws/install/setup.sh
(上に戻る)
- ロボットのURDFにアクチュエータのコントローラを設定します.
| パラメータ | 型 | 一例 | 説明 |
|---|---|---|---|
| port_name | string | /dev/ttyUSB0 | USBポート名 |
| baud_rate | int | 1000000 | Dynamixelの通信速度 |
| use_dummy | bool | true | ダミーアクチュエータを使用するかどうか |
| id | int | 1 | DynamixelのID |
| control_mode | int | 0 | 制御モード |
| interface | string | rs | インターフェース |
制御モードは以下の通りです.
control_mode |
値 |
|---|---|
| Position Control | 0 |
| Velocity Control | 1 |
| Torque Control | 2 |
| Current Control | 3 |
| Extended Position Control | 4 |
| Multi Turn Control | 5 |
| Current Based Position Control | 6 |
| PWM Control | 7 |
インターフェースは以下の通りです.
interface |
値 |
|---|---|
| RS485 | rs |
| TTL | ttl |
Goal_CurrentのようなDynamixel Workbenchから提供されているパラメータも設定できます.
詳しくは,Dynamixel Workbenchにてご確認ください.
設定の一例はこちらとなります.
<?xml version="1.0" encoding="UTF-8" ?>
<robot name="robot_name" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="controllers">
<ros2_control name="dynamixel_control" type="system">
<hardware>
<plugin>dynamixel_hardware/DynamixelHardware</plugin>
<param name="port_name">/dev/ttyUSB0</param>
<param name="baud_rate">1000000</param>
<!-- <param name="use_dummy">true</param> -->
</hardware>
<!-- 位置制御 -->
<joint name="joint_1">
<param name="id">1</param>
<param name="control_mode">0</param>
<!-- <param name="gear_ratio">2.0</param> -->
<param name="interface">rs</param>
<command_interface name="position">
<param name="min">-3.141592654</param>
<param name="max">3.141592654</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<!-- 速度制御 -->
<joint name="joint_2">
<param name="id">2</param>
<param name="control_mode">0</param>
<param name="interface">rs</param>
<command_interface name="velocity"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<!-- 力により位置制御 -->
<joint name="joint_3">
<param name="id">3</param>
<param name="control_mode">6</param>
<param name="Goal_Current">50</param>
<param name="interface">rs</param>
<param name="gear_ratio">-59.504383354</param>
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
...
</ros2_control>
</xacro:macro>
</robot>- 次は
controller managerの設定となります.使用されるコントローラ・アクチュエータの数に応じて設定を変更してください.
/**/controller_manager:
ros__parameters:
update_rate: 10 # Hz
velocity_controller:
type: velocity_controllers/JointGroupVelocityController
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
/**/velocity_controller:
ros__parameters:
joints:
- joint_2
/**/joint_trajectory_controller:
ros__parameters:
joints:
- joint_1
- joint_3
command_interfaces:
- position
state_interfaces:
- position
- velocity
allow_partial_joints_goal: true- 最後に,設定したパラメータ等をロボットを実行する際に,コントローラを立ち上げます.
robot_description = os.path.join(get_package_share_directory(
'sobit_light_description'),
'robots.urdf.xacro'
)
robot_description_config = xacro.process_file(
robot_description
)
controller_config = os.path.join(get_package_share_directory(
'robot_control'),
'config',
'real_controllers.yaml'
)
controller_manager = Node(
package="controller_manager",
executable="ros2_control_node",
namespace=robot_name,
parameters=[controller_config],
remappings=[
("controller_manager/robot_description", "robot_description"),
],
output="screen",
)
joint_state_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller',
'--set-state', 'active',
'--controller-manager', robot_name+'/controller_manager',
'joint_state_broadcaster'
],
output='screen'
)
joint_trajectory_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller',
'--set-state', 'active',
'--controller-manager', robot_name+'/controller_manager',
'joint_trajectory_controller'
],
output='screen'
)
velocity_controller = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller',
'--set-state', 'configured',
'--controller-manager', robot_name+'/controller_manager',
'velocity_controller'
],
output='screen'
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
namespace=robot_name,
parameters=[
{"frame_prefix": robot_name + '/'},
{"robot_description": robot_description_config.toxml()},
],
output="screen",
)(上に戻る)
- 異るアクチュエータの制御方法設定に対応
- ギア比の設定
- [] 複数御御方法の切り替え
現時点のバッグや新規機能の依頼を確認するためにIssueページ をご覧ください.
(上に戻る)
(上に戻る)