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
4 changes: 2 additions & 2 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">

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

<!--
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">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>rmd_ros2_control/RMDHardwareInterface</plugin>
<param name="update_rate">2</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>
</hardware>

<joint name="shoulder_pitch">
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">
<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">can0</param>
<param name="can_interface">${can_interface}</param>
<param name="can_id">0x80</param>
</hardware>

Expand Down
4 changes: 2 additions & 2 deletions src/description/ros2_control/arm/arm.smc.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="smc_ros2_control" params="name">
<xacro:macro name="smc_ros2_control" params="name can_interface">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>smc_ros2_control/SMCHardwareInterface</plugin>
<param name="update_rate">2</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>
</hardware>

<joint name="base_yaw">
Expand Down
4 changes: 2 additions & 2 deletions src/description/ros2_control/arm/arm.talon.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="talon_ros2_control" params="name">
<xacro:macro name="talon_ros2_control" params="name can_interface">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>talon_ros2_control/TALONHardwareInterface</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">can0</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="gripper_claw">
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="killswitch_ros2_control" params="name can_interface:=can0">
<xacro:macro name="killswitch_ros2_control" params="name can_interface">

<ros2_control name="${name}" type="system">
<hardware>
Expand Down
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">

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

<joint name="steer_bl_joint">
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="rmd_ros2_control" params="name">
<xacro:macro name="rmd_ros2_control" params="name can_interface">
<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">can0</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="laser_ros2_control" params="name can_interface:=can0">
<xacro:macro name="laser_ros2_control" params="name can_interface">

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

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">
<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">1</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,13 +1,13 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="talon_ros2_control" params="name">
<xacro:macro name="talon_ros2_control" params="name can_interface">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>talon_ros2_control/TALONHardwareInterface</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">can0</param>
<param name="can_interface">${can_interface}</param>
</hardware>

<joint name="talon_auger">
Expand Down
15 changes: 8 additions & 7 deletions src/description/urdf/athena_arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,10 @@
<xacro:arg name="prefix" default=""/>
<xacro:arg name="use_mock_hardware" default="false"/>
<xacro:arg name="mock_sensor_commands" default="false"/>
<xacro:arg name="sim_gazebo_classic" default="true"/>
<xacro:arg name="sim_gazebo" default="true"/>
<xacro:arg name="simulation_controllers" default=""/>
<xacro:arg name="use_sim" default="false"/>

<!-- Derive CAN interface name from use_sim -->
<xacro:property name="can_interface" value="${'vcan0' if '$(arg use_sim)' == 'true' else 'can0'}"/>

<!-- Macro Imports -->
<!-- Import athena_arm macro -->
Expand Down Expand Up @@ -44,7 +45,7 @@
<xacro:mock_ros2_control name="mock"/>
</xacro:if>
<xacro:unless value="$(arg use_mock_hardware)"> <!-- HARDWARE -->
<xacro:smc_ros2_control name="smc"/>
<xacro:smc_ros2_control name="smc" can_interface="${can_interface}"/>
<ros2_control name="talon_mock" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
Expand All @@ -58,9 +59,9 @@
<state_interface name="velocity"/>
</joint>
</ros2_control>
<xacro:rmd_ros2_control name="rmd"/>
<xacro:servo_ros2_control name="servo"/>
<!-- <xacro:odrive_ros2_control name="odrive"/> -->
<xacro:rmd_ros2_control name="rmd" can_interface="${can_interface}"/>
<xacro:servo_ros2_control name="servo" can_interface="${can_interface}"/>
<!-- <xacro:odrive_ros2_control name="odrive" can_interface="${can_interface}"/> -->
</xacro:unless>

</robot>
12 changes: 8 additions & 4 deletions src/description/urdf/athena_drive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,12 @@

<xacro:arg name="use_mock_hardware" default="false"/>
<xacro:arg name="mock_sensor_commands" default="false"/>
<xacro:arg name="sim_gazebo" default="true"/>
<xacro:arg name="sim_gazebo" default="false"/>
<xacro:arg name="simulation_controllers" default=""/>
<xacro:arg name="use_sim" default="false"/>

<!-- Derive CAN interface name from use_sim -->
<xacro:property name="can_interface" value="${'vcan0' if '$(arg use_sim)' == 'true' else 'can0'}"/>


<xacro:include filename="$(find description)/urdf/athena_drive/athena_drive_macro.xacro"/>
Expand Down Expand Up @@ -70,14 +74,14 @@
simulation_controllers="$(arg simulation_controllers)"/>
</xacro:if>
<xacro:unless value="$(arg use_mock_hardware)">
<xacro:odrive_ros2_control name="odrive"/>
<xacro:rmd_ros2_control name="rmd"/>
<xacro:odrive_ros2_control name="odrive" can_interface="${can_interface}"/>
<xacro:rmd_ros2_control name="rmd" can_interface="${can_interface}"/>

<!-- LED status indicator (GPIO-based) -->
<xacro:led_ros2_control name="status_led" gpio_pin="25"/>

<!-- Killswitch (CAN-based) -->
<xacro:killswitch_ros2_control name="drive_killswitch"/>
<xacro:killswitch_ros2_control name="drive_killswitch" can_interface="${can_interface}"/>
</xacro:unless>


Expand Down
10 changes: 7 additions & 3 deletions src/description/urdf/athena_science.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@

<xacro:arg name="use_mock_hardware" default="false"/>
<xacro:arg name="mock_sensor_commands" default="false"/>
<xacro:arg name="use_sim" default="false"/>

<!-- Derive CAN interface name from use_sim -->
<xacro:property name="can_interface" value="${'vcan0' if '$(arg use_sim)' == 'true' else 'can0'}"/>

<xacro:include filename="$(find description)/ros2_control/science/science.mock.ros2_control.xacro"/>

Expand All @@ -28,13 +32,13 @@
<xacro:stepper_ros2_control name="stepper"/>

<!-- Import servo ros2_control description -->
<xacro:servo_ros2_control name="servo"/>
<xacro:servo_ros2_control name="servo" can_interface="${can_interface}"/>

<!-- Import talon ros2_control description -->
<xacro:talon_ros2_control name="talon"/>
<xacro:talon_ros2_control name="talon" can_interface="${can_interface}"/>

<!-- Import laser ros2_control description (CAN-based) -->
<xacro:laser_ros2_control name="spectrometry_laser"/>
<xacro:laser_ros2_control name="spectrometry_laser" can_interface="${can_interface}"/>
</xacro:unless>

</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ CallbackReturn ODriveHardwareInterface::on_init(const hardware_interface::Hardwa
return CallbackReturn::ERROR;
}

can_intf_name_ = info_.hardware_parameters["can"];
can_intf_name_ = info_.hardware_parameters["can_interface"];

for (auto& joint : info_.joints) {
axes_.emplace_back(&can_intf_, std::stoi(joint.parameters.at("node_id")), std::stoi(joint.parameters.at("gear_ratio")));
Expand Down
9 changes: 5 additions & 4 deletions src/infrastructure/umdloop_can/umdloop_can/can_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,20 +7,21 @@ class CANNode(Node):
def __init__(self):
super().__init__('can_node')

# Publisher for incoming CAN data
self.declare_parameter('can_interface', 'can0')
can_channel = self.get_parameter('can_interface').get_parameter_value().string_value

self.publisher_ = self.create_publisher(CANA, 'can_rx', 10)

# Subscriber for outgoing CAN data
self.subscription = self.create_subscription(
CANA,
'can_tx',
self.can_send_callback,
10
)

self.can_interface = CANInterface(callback=self.can_rx_callback)
self.can_interface = CANInterface(callback=self.can_rx_callback, channel=can_channel)

self.get_logger().info('CAN Node Initialized')
self.get_logger().info(f'CAN Node Initialized on {can_channel}')

# # Check for new CAN messages at 100Hz
# self.timer = self.create_timer(0.01, self.check_can_messages)
Expand Down
Loading
Loading