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

実機動作に必要なパラメータ追加 #7

Merged
merged 9 commits into from
Nov 6, 2023
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
8 changes: 8 additions & 0 deletions sciurus17_description/robot_description_loader.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@ def __init__(self):
get_package_share_directory('sciurus17_description'),
'urdf',
'sciurus17.urdf.xacro')
self.port_name = '/dev/sciurus17spine'
self.baudrate = '3000000'
self.timeout_seconds = '1.0'
self.manipulator_config_file_path = ''
self.use_gazebo = 'false'
self.gz_control_config_package = ''
self.gz_control_config_file_path = ''
Expand All @@ -21,6 +25,10 @@ def load(self):
return Command([
'xacro ',
self.robot_description_path,
' port_name:=', self.port_name,
' baudrate:=', self.baudrate,
' timeout_seconds:=', self.timeout_seconds,
' manipulator_config_file_path:=', self.manipulator_config_file_path,
' use_gazebo:=', self.use_gazebo,
' gz_control_config_package:=', self.gz_control_config_package,
' gz_control_config_file_path:=', self.gz_control_config_file_path
Expand Down
25 changes: 25 additions & 0 deletions test/test_robot_description_loader.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,31 @@ def test_change_description_path():
assert e.value


def test_port_name():
# port_nameが変更され、xacroにポート名がセットされることを期待
rdl = RobotDescriptionLoader()
rdl.port_name = '/dev/ttyUSB1'
assert '"port_name">/dev/ttyUSB1' in exec_load(rdl)


def test_baudrate():
rdl = RobotDescriptionLoader()
rdl.baudrate = '4000000'
assert '"baudrate">4000000' in exec_load(rdl)


def test_timeout_seconds():
rdl = RobotDescriptionLoader()
rdl.timeout_seconds = '3.0'
assert '"timeout_seconds">3.0' in exec_load(rdl)


def test_manipulator_config_file_path():
rdl = RobotDescriptionLoader()
rdl.manipulator_config_file_path = 'test/config/file/path'
assert '"manipulator_config_file_path">test/config/file/path' in exec_load(rdl)


def test_use_gazebo():
# use_gazeboが変更され、xacroにign_ros2_controlがセットされることを期待
rdl = RobotDescriptionLoader()
Expand Down
226 changes: 226 additions & 0 deletions urdf/sciurus17.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,226 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="sciurus17_ros2_control_settings">

<ros2_control name="sciurus17" type="system">
<hardware>
<plugin>sciurus17_hardware/Sciurus17Hardware</plugin>
<param name="port_name">${PORT_NAME}</param>
<param name="baudrate">${BAUDRATE}</param>
<param name="timeout_seconds">${TIMEOUT_SECONDS}</param>
<param name="manipulator_config_file_path">${MANIPULATOR_CONFIG_FILE_PATH}</param>
</hardware>

<joint name="${NAME_JOINT_BODY}">
<command_interface name="position">
<param name="min">${NAME_JOINT_BODY_LOWER_LIMIT}</param>
<param name="max">${NAME_JOINT_BODY_UPPER_LIMIT}</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">3.60</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">3.60</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">3.60</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.00</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<joint name="${NAME_JOINT_HAND_R_A}">
<command_interface name="position">
<param name="min">${JOINT_HAND_R_LOWER_LIMIT}"</param>
<param name="max">${JOINT_HAND_R_UPPER_LIMIT}"</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">3.60</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">3.60</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.00</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<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>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

<joint name="${NAME_JOINT_HAND_L_A}">
<command_interface name="position">
<param name="min">${JOINT_HAND_L_LOWER_LIMIT}"</param>
<param name="max">${JOINT_HAND_L_UPPER_LIMIT}"</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
</joint>

</ros2_control>
</xacro:macro>
</robot>
15 changes: 15 additions & 0 deletions urdf/sciurus17.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">

<xacro:include filename="$(find sciurus17_description)/urdf/sciurus17.ros2_control.xacro"/>
<xacro:include filename="$(find sciurus17_description)/urdf/sciurus17_body.xacro"/>
<xacro:include filename="$(find sciurus17_description)/urdf/sciurus17_head.xacro"/>
<xacro:include filename="$(find sciurus17_description)/urdf/sciurus17_right_arm.xacro"/>
Expand All @@ -17,8 +18,16 @@
<xacro:include filename="$(find sciurus17_description)/urdf/sciurus17.gazebo_ros2_control.xacro"/>

<xacro:arg name="use_gazebo" default="false" />
<xacro:arg name="port_name" default="/dev/sciurus17spine" />
<xacro:arg name="baudrate" default="3000000" />
<xacro:arg name="timeout_seconds" default="1.0" />
<xacro:arg name="manipulator_config_file_path" default="" />
<xacro:arg name="gz_control_config_package" default="" />
<xacro:arg name="gz_control_config_file_path" default="" />
<xacro:property name="PORT_NAME" value="$(arg port_name)"/>
<xacro:property name="BAUDRATE" value="$(arg baudrate)"/>
<xacro:property name="TIMEOUT_SECONDS" value="$(arg timeout_seconds)"/>
<xacro:property name="MANIPULATOR_CONFIG_FILE_PATH" value="$(arg manipulator_config_file_path)"/>
<xacro:property name="GZ_CONTROL_CONFIG_PACKAGE" value="$(arg gz_control_config_package)"/>
<xacro:property name="GZ_CONTROL_CONFIG_FILE_PATH" value="$(arg gz_control_config_file_path)"/>

Expand Down Expand Up @@ -172,6 +181,12 @@

<xacro:sciurus17_left_hand/>

<xacro:unless value="$(arg use_gazebo)">

<xacro:sciurus17_ros2_control_settings/>

</xacro:unless>

<xacro:if value="$(arg use_gazebo)">

<xacro:gazebo_robot_settings/>
Expand Down