Skip to content
Open
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
6 changes: 3 additions & 3 deletions src/description/config/odrive.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="odrive_ros2_control" params="name">
<xacro:macro name="odrive_ros2_control" params="name can_interface:=can0">

<ros2_control name="${name}" type="system">
<hardware>
<plugin>odrive_ros2_control_plugin/ODriveHardwareInterface</plugin>
<param name="can">can0</param>
<param name="can">${can_interface}</param>
</hardware>

<!--
Expand Down Expand Up @@ -39,4 +39,4 @@

</xacro:macro>

</robot>
</robot>
9 changes: 9 additions & 0 deletions src/description/launch/display.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,12 @@

def generate_launch_description():
model_arg = DeclareLaunchArgument('model', default_value='', description='Model argument')
can_interface_arg = DeclareLaunchArgument(
'can_interface',
default_value='can0',
description='CAN interface to use for hardware interfaces.',
)
can_interface = LaunchConfiguration('can_interface')

# Get URDF path
robot_description_path = PathJoinSubstitution([
Expand All @@ -25,6 +31,8 @@ def generate_launch_description():
" ",
robot_description_path,
" use_mock_hardware:=true",
" can_interface:=",
can_interface,
]
)

Expand Down Expand Up @@ -120,6 +128,7 @@ def generate_launch_description():

return LaunchDescription([
model_arg,
can_interface_arg,
robot_state_publisher_node,
ros2_control_node,
joint_state_broadcaster_spawner,
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="base_arm_limit_switch_ros2_control" params="name">
<xacro:macro name="base_arm_limit_switch_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>limit_switch_ros2_control/LimitSwitchHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x130</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="end_effector_limit_switch_ros2_control" params="name">
<xacro:macro name="end_effector_limit_switch_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>limit_switch_ros2_control/LimitSwitchHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x60</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
Expand Down
4 changes: 2 additions & 2 deletions src/description/ros2_control/arm/arm.rmd.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rmd_ros2_control" params="name">
<xacro:macro name="rmd_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>rmd_ros2_control/RMDHardwareInterface</plugin>
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="shoulder_pitch">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rotary_encoder_ros2_control" params="name">
<xacro:macro name="rotary_encoder_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>rotary_encoder_ros2_control/RotaryEncoderHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x130</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
Expand Down
4 changes: 2 additions & 2 deletions src/description/ros2_control/arm/arm.servo.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="servo_ros2_control" params="name">
<xacro:macro name="servo_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>servo_ros2_control/SERVOHardwareInterface</plugin>
<param name="update_rate">1</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x80</param>
</hardware>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="smc_2dof_ros2_control" params="name">
<xacro:macro name="smc_2dof_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>smc_ros2_control/SMCHardwareInterface</plugin>
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="base_yaw">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="smc_3dof_ros2_control" params="name">
<xacro:macro name="smc_3dof_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>smc_ros2_control/SMCHardwareInterface</plugin>
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="base_yaw">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="talon_2dof_ros2_control" params="name deactivate_talon">
<xacro:macro name="talon_2dof_ros2_control" params="name deactivate_talon can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<param name="deactivate_talon">${deactivate_talon}</param>
Expand All @@ -12,7 +12,7 @@
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</xacro:unless>
</hardware>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="talon_3dof_ros2_control" params="name deactivate_talon">
<xacro:macro name="talon_3dof_ros2_control" params="name deactivate_talon can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${deactivate_talon}">
Expand All @@ -11,7 +11,7 @@
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</xacro:unless>
</hardware>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="led_ros2_control" params="name can_interface">
<xacro:macro name="led_ros2_control" params="name can_interface:=can0">

<ros2_control name="${name}" type="system">
<hardware>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="odrive_ros2_control" params="name deactivate_odrive">
<xacro:macro name="odrive_ros2_control" params="name deactivate_odrive can_interface:=can0">

<ros2_control name="${name}" type="system">
<hardware>
Expand All @@ -14,7 +14,7 @@
<param name="update_rate">30</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can">can1</param>
<param name="can">${can_interface}</param>
</xacro:unless>
</hardware>

Expand Down Expand Up @@ -50,4 +50,4 @@

</xacro:macro>

</robot>
</robot>
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rmd_ros2_control" params="name">
<xacro:macro name="rmd_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>rmd_ros2_control/RMDHardwareInterface</plugin>
<param name="update_rate">30</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can1</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="propulsion_fl_joint">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="dc_ros2_control" params="name">
<xacro:macro name="dc_ros2_control" params="name can_interface:=can0">

<ros2_control name="${name}" type="system">

Expand All @@ -10,7 +10,7 @@
<param name="update_rate">20</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x70</param>
</hardware>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="science_led_ros2_control" params="name">
<xacro:macro name="science_led_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>led_ros2_control/LEDHardwareInterface</plugin>
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x110</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="science_limit_switch_ros2_control" params="name">
<xacro:macro name="science_limit_switch_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>limit_switch_ros2_control/LimitSwitchHardwareInterface</plugin>
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x100</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="servo_ros2_control" params="name">
<xacro:macro name="servo_ros2_control" params="name can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>servo_ros2_control/SERVOHardwareInterface</plugin>
<param name="update_rate">20</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x80</param>
</hardware>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="stepper_ros2_control" params="name">
<xacro:macro name="stepper_ros2_control" params="name can_interface:=can0">

<ros2_control name="${name}" type="system">

Expand All @@ -10,7 +10,7 @@
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x90</param>
</hardware>

Expand Down Expand Up @@ -52,4 +52,4 @@

</xacro:macro>

</robot>
</robot>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="talon_ros2_control" params="name deactivate_talon">
<xacro:macro name="talon_ros2_control" params="name deactivate_talon can_interface:=can0">
<ros2_control name="${name}" type="system">
<hardware>
<param name="deactivate_talon">${deactivate_talon}</param>
Expand All @@ -12,7 +12,7 @@
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_interface">${can_interface}</param>
</xacro:unless>
</hardware>

Expand Down
21 changes: 11 additions & 10 deletions src/description/urdf/athena_arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<xacro:arg name="simulation_controllers" default=""/>
<xacro:arg name="use_3dof" default="false"/>
<xacro:arg name="deactivate_talon" default="false"/>
<xacro:arg name="can_interface" default="can0"/>

<!-- Macro Imports -->
<!-- Import athena_arm macro -->
Expand Down Expand Up @@ -56,20 +57,20 @@
</xacro:if>
<xacro:unless value="$(arg use_mock_hardware)"> <!-- HARDWARE -->
<xacro:if value="$(arg use_3dof)">
<xacro:talon_3dof_ros2_control name="talon" deactivate_talon="$(arg deactivate_talon)"/>
<xacro:smc_3dof_ros2_control name="smc"/>
<xacro:talon_3dof_ros2_control name="talon" deactivate_talon="$(arg deactivate_talon)" can_interface="$(arg can_interface)"/>
<xacro:smc_3dof_ros2_control name="smc" can_interface="$(arg can_interface)"/>
</xacro:if>
<xacro:unless value="$(arg use_3dof)">
<xacro:talon_2dof_ros2_control name="talon" deactivate_talon="$(arg deactivate_talon)"/>
<xacro:smc_2dof_ros2_control name="smc"/>
<xacro:talon_2dof_ros2_control name="talon" deactivate_talon="$(arg deactivate_talon)" can_interface="$(arg can_interface)"/>
<xacro:smc_2dof_ros2_control name="smc" can_interface="$(arg can_interface)"/>
</xacro:unless>

<xacro:rmd_ros2_control name="rmd"/>
<xacro:servo_ros2_control name="servo"/>
<xacro:rotary_encoder_ros2_control name="rotary_encoder"/>
<xacro:base_arm_limit_switch_ros2_control name="base_arm_limit_switch"/>
<xacro:end_effector_limit_switch_ros2_control name="end_effector_limit_switch"/>
<!-- <xacro:odrive_ros2_control name="odrive"/> -->
<xacro:rmd_ros2_control name="rmd" can_interface="$(arg can_interface)"/>
<xacro:servo_ros2_control name="servo" can_interface="$(arg can_interface)"/>
<xacro:rotary_encoder_ros2_control name="rotary_encoder" can_interface="$(arg can_interface)"/>
<xacro:base_arm_limit_switch_ros2_control name="base_arm_limit_switch" can_interface="$(arg can_interface)"/>
<xacro:end_effector_limit_switch_ros2_control name="end_effector_limit_switch" can_interface="$(arg can_interface)"/>
<!-- <xacro:odrive_ros2_control name="odrive" can_interface="$(arg can_interface)"/> -->
</xacro:unless>

</robot>
Loading
Loading