Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

hardware_interfaceのパラメータをxacro引数から変更する #35

Merged
merged 6 commits into from
Jun 3, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ $ source ~/ros2_ws/install/setup.bash
```sh
# Connect CRANE+V2 to PC, then
$ source ~/ros2_ws/install/setup.bash
$ ros2 launch crane_plus_examples demo.launch.py
$ ros2 launch crane_plus_examples demo.launch.py port_name:=/dev/ttyUSB0

# Terminal 2
$ source ~/ros2_ws/install/setup.bash
Expand Down
45 changes: 17 additions & 28 deletions crane_plus_control/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,20 +32,6 @@ PCとCRANE+V2の設定が必要です。
$ sudo chmod 666 /dev/ttyUSB0
```

### USB通信ポートの変更

`/dev/ttyUBS0`以外の通信ポートを使用する場合は
[crane_plus_description/urdf/crane_plus.ros2_control.xacro](../crane_plus_description/urdf/crane_plus.ros2_control.xacro)
の`port_name`を変更します。

```xml
<ros2_control name="${name}" type="system">
<hardware>
<plugin>crane_plus_hardware/CranePlusHardware</plugin>
<param name="port_name">/dev/ttyUSB0</param>
<param name="baudrate">1000000</param>
```

### latency_timerの設定

CRANE+V2を100 Hz周期で制御するためには、
Expand Down Expand Up @@ -138,26 +124,29 @@ CRANE+V2の腕の制御用に`crane_plus_arm_controller`を、
## crane_plus_hardwareのパラメータ

`crane_plus_hardware`のパラメータは
[crane_plus_description/urdf/crane_plus.ros2_control.xacro](../crane_plus_description/urdf/crane_plus.ros2_control.xacro)
[crane_plus_description/urdf/crane_plus.urdf.xacro](../crane_plus_description/urdf/crane_plus.urdf.xacro)
で設定しています。

```xml
<ros2_control name="${name}" type="system">
<hardware>
<plugin>crane_plus_hardware/CranePlusHardware</plugin>
<param name="port_name">/dev/ttyUSB0</param>
<param name="baudrate">1000000</param>
<param name="timeout_seconds">5.0</param>
<param name="read_velocities">0</param>
<param name="read_loads">0</param>
<param name="read_voltages">0</param>
<param name="read_temperatures">0</param>
</hardware>
<xacro:arg name="use_gazebo" default="false" />
<xacro:arg name="port_name" default="/dev/ttyUSB0" />
<xacro:arg name="baudrate" default="1000000" />
<xacro:arg name="timeout_seconds" default="5.0" />
<xacro:arg name="read_velocities" default="0" />
<xacro:arg name="read_loads" default="0" />
<xacro:arg name="read_voltages" default="0" />
<xacro:arg name="read_temperatures" default="0" />
```

### USB通信ポート

[USB通信ポートの変更](#usb通信ポートの変更)を参照してください。
`port_name`はCRANE+V2との通信に使用するUSB通信ポートを設定します。

コマンド実行時の引数からも変更が可能です。

```sh
$ ros2 launch crane_plus_control crane_plus_control.launch.py port_name:=/dev/ttyUSB0
```

### ボーレート

Expand All @@ -178,7 +167,7 @@ USBケーブルや電源ケーブルが抜けた場合等に有効です。
`read_velocities`、`read_loads`、`read_voltages`、`read_temperatures`
は、サーボの回転速度、電圧、負荷、温度を読み取るためのパラメータです。

`1`をセットすると、サーボパラメータを読み取るみます
`1`をセットすると、サーボパラメータを読み取ります

これらのパラメータを読み取ると通信データ量が増加するため、制御周期が100 Hzより低下します。

Expand Down
19 changes: 16 additions & 3 deletions crane_plus_control/launch/crane_plus_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,30 @@
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import ExecuteProcess
from launch.actions import DeclareLaunchArgument
from launch.substitutions import Command
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
import xacro


def generate_launch_description():
# Get URDF via xacro
declare_port_name = DeclareLaunchArgument(
'port_name',
default_value='/dev/ttyUSB0',
description='Set port name.'
)

robot_description_path = os.path.join(
get_package_share_directory('crane_plus_description'),
'urdf',
'crane_plus.urdf.xacro')
robot_description_config = xacro.process_file(robot_description_path)
robot_description = {'robot_description': robot_description_config.toxml()}

robot_description = {'robot_description': Command([
'xacro ',
robot_description_path,
' port_name:=', LaunchConfiguration('port_name')
])}

crane_plus_controllers = os.path.join(
get_package_share_directory('crane_plus_control'),
Expand Down Expand Up @@ -65,6 +77,7 @@ def generate_launch_description():
)

return LaunchDescription([
declare_port_name,
controller_manager,
spawn_joint_state_controller,
spawn_arm_controller,
Expand Down
23 changes: 15 additions & 8 deletions crane_plus_description/urdf/crane_plus.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,25 @@
joint_4_lower_limit
joint_4_upper_limit
joint_hand_lower_limit
joint_hand_upper_limit">
joint_hand_upper_limit
port_name
baudrate
timeout_seconds
read_velocities
read_loads
read_voltages
read_temperatures">

<ros2_control name="${name}" type="system">
<hardware>
<plugin>crane_plus_hardware/CranePlusHardware</plugin>
<param name="port_name">/dev/ttyUSB0</param>
<param name="baudrate">1000000</param>
<param name="timeout_seconds">5.0</param>
<param name="read_velocities">0</param>
<param name="read_loads">0</param>
<param name="read_voltages">0</param>
<param name="read_temperatures">0</param>
<param name="port_name">${port_name}</param>
<param name="baudrate">${baudrate}</param>
<param name="timeout_seconds">${timeout_seconds}</param>
<param name="read_velocities">${read_velocities}</param>
<param name="read_loads">${read_loads}</param>
<param name="read_voltages">${read_voltages}</param>
<param name="read_temperatures">${read_temperatures}</param>
</hardware>

<joint name="${name_joint_1}">
Expand Down
16 changes: 15 additions & 1 deletion crane_plus_description/urdf/crane_plus.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,13 @@
<xacro:include filename="$(find crane_plus_description)/urdf/crane_plus.gazebo_ros2_control.xacro"/>

<xacro:arg name="use_gazebo" default="false" />
<xacro:arg name="port_name" default="/dev/ttyUSB0" />
<xacro:arg name="baudrate" default="1000000" />
<xacro:arg name="timeout_seconds" default="5.0" />
<xacro:arg name="read_velocities" default="0" />
<xacro:arg name="read_loads" default="0" />
<xacro:arg name="read_voltages" default="0" />
<xacro:arg name="read_temperatures" default="0" />

<!-- Link to provide the location reference for the arm -->
<link name="base_link"/>
Expand Down Expand Up @@ -100,7 +107,14 @@
joint_4_lower_limit="${JOINT_4_LOWER_LIMIT}"
joint_4_upper_limit="${JOINT_4_UPPER_LIMIT}"
joint_hand_lower_limit="${JOINT_HAND_LOWER_LIMIT}"
joint_hand_upper_limit="${JOINT_HAND_UPPER_LIMIT}" />
joint_hand_upper_limit="${JOINT_HAND_UPPER_LIMIT}"
port_name="$(arg port_name)"
baudrate="$(arg baudrate)"
timeout_seconds="$(arg timeout_seconds)"
read_velocities="$(arg read_velocities)"
read_loads="$(arg read_loads)"
read_voltages="$(arg read_voltages)"
read_temperatures="$(arg read_temperatures)" />
</xacro:unless>

<xacro:if value="$(arg use_gazebo)">
Expand Down
2 changes: 1 addition & 1 deletion crane_plus_examples/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ USB通信ポートの設定については`crane_plus_control`の
controller (`crane_plus_control`)を起動します。

```sh
$ ros2 launch crane_plus_examples demo.launch.py
$ ros2 launch crane_plus_examples demo.launch.py port_name:=/dev/ttyUSB0
```

## 準備(Gazeboを使う場合)
Expand Down
16 changes: 13 additions & 3 deletions crane_plus_examples/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,17 @@
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource


def generate_launch_description():
declare_port_name = DeclareLaunchArgument(
'port_name',
default_value='/dev/ttyUSB0',
description='Set port name.'
)
move_group = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('crane_plus_moveit_config'),
Expand All @@ -29,8 +36,11 @@ def generate_launch_description():
PythonLaunchDescriptionSource([
get_package_share_directory('crane_plus_control'),
'/launch/crane_plus_control.launch.py']),
launch_arguments={'port_name': LaunchConfiguration('port_name')}.items()
)

return LaunchDescription([move_group,
control_node
])
return LaunchDescription([
declare_port_name,
move_group,
control_node
])