Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
37 commits
Select commit Hold shift + click to select a range
9b5f18d
saving changes
Apr 19, 2026
56a0d14
changed broadcaster to controller and included other telemetry inform…
IshanDutta11 Apr 20, 2026
6dc2cca
odrive upgrades
IshanDutta11 Apr 7, 2026
c397571
saving progress
IshanDutta11 Apr 20, 2026
99d13f6
added request services
Apr 20, 2026
4511973
included status decoding in RMDs
IshanDutta11 Apr 20, 2026
0da4b27
decode error value and warn/error out depending on response
IshanDutta11 Apr 20, 2026
28937b2
reformatted rmd HWI
Apr 21, 2026
60ccc04
saving some one shot progress
IshanDutta11 Apr 22, 2026
ca20393
all i know is pain (i think i got encoding and decoding across comman…
Apr 23, 2026
b53bdbc
holy fucking shit it worksgit status Need to implement Torque control…
IshanDutta11 Apr 24, 2026
f3376a2
saving smc progress
Apr 24, 2026
986d243
im sorry to whoever is reading this
IshanDutta11 Apr 24, 2026
87a924e
saving some progress
IshanDutta11 Apr 25, 2026
0bfbf9f
updated smc hwi, issue with servo hwi
Apr 26, 2026
f1fe0d0
fixed state issue, accepts all state interfaces and filters accordingly
IshanDutta11 Apr 26, 2026
ff1fea5
saving progress, killswitch seems to not be sending can messages for …
IshanDutta11 Apr 27, 2026
83bca6c
saving changes, for some reason I cant see power module can commands …
IshanDutta11 Apr 29, 2026
bde369c
Power module and SMCs seem to be working, initial implementation of L…
IshanDutta11 Apr 29, 2026
abcf1dc
led hwi looks like its working
IshanDutta11 Apr 30, 2026
4b68325
added limit switch and rotary encoder HWI, included all necessary HWI…
May 2, 2026
d2a82cd
fixed motor status controller, manually choose command and state inte…
May 2, 2026
2eb57c9
3dof specific fixes
May 2, 2026
addeb36
motor status controller includes gpios, removing unnecessary gpio con…
IshanDutta11 May 3, 2026
cc00e00
Added DC Motor HWI
HGardiner1 Mar 31, 2026
39d0f2f
Small changes to DC Motor HWI
HGardiner1 Apr 3, 2026
57ee329
Fixing HWI issue
HGardiner1 Apr 3, 2026
bbc9f8b
Small Fix
HGardiner1 May 3, 2026
6bb312e
First test for steppers
HGardiner1 May 1, 2026
dd8c1e5
Moved revised athena_science code to monorepo
HGardiner1 Nov 13, 2025
e2e3064
Fixing Science Controller + HWI Templates for Steppers & Servos
HGardiner1 Nov 17, 2025
3a42683
Restore accidentally deleted science.mock.ros2_control.xacro
HGardiner1 May 1, 2026
edcd603
stepper stuff like kinda works??
IshanDutta11 May 2, 2026
d8f3610
implemented and tested in virtual can servo, stepper, and dc HWIs
IshanDutta11 May 4, 2026
af76517
working arm and steppers/DC motors
IshanDutta11 May 9, 2026
d1b7a00
WORKING DRIVE AND ARM
umdloop-admin May 10, 2026
0d359a2
uhh quick random fixes lul
umdloop-admin May 10, 2026
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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ build/
install/
log/
.vscode/
.codex

# Byte-compiled / optimized / DLL files
__pycache__/
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="base_arm_limit_switch_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>limit_switch_ros2_control/LimitSwitchHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_id">0x130</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
<param name="logger_state">0</param>
</hardware>

<gpio name="limit_switch_0">
<param name="node_id">0</param>
<state_interface name="status"/>
<command_interface name="status_request"/>
</gpio>

<gpio name="limit_switch_1">
<param name="node_id">1</param>
<state_interface name="status"/>
<command_interface name="status_request"/>
</gpio>
</ros2_control>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="end_effector_limit_switch_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>limit_switch_ros2_control/LimitSwitchHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_id">0x60</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
<param name="logger_state">0</param>
</hardware>

<gpio name="limit_switch_2">
<param name="node_id">2</param>
<state_interface name="status"/>
<command_interface name="status_request"/>
</gpio>

<gpio name="limit_switch_3">
<param name="node_id">3</param>
<state_interface name="status"/>
<command_interface name="status_request"/>
</gpio>

<gpio name="limit_switch_4">
<param name="node_id">4</param>
<state_interface name="status"/>
<command_interface name="status_request"/>
</gpio>
</ros2_control>
</xacro:macro>
</robot>
18 changes: 17 additions & 1 deletion src/description/ros2_control/arm/arm.rmd.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,29 +7,45 @@
<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">can1</param>
</hardware>

<joint name="shoulder_pitch">
<param name="node_id">0x144</param>
<param name="gear_ratio">100</param>
<param name="joint_orientation">1.0</param>
<param name="operating_velocity">150</param> <!-- motor dps -->
<command_interface name="position" />
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="elbow_pitch">
<param name="node_id">0x149</param>
<param name="gear_ratio">100</param>
<param name="joint_orientation">-1.0</param>
<param name="operating_velocity">150</param> <!-- motor dps -->
<command_interface name="position" />
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rotary_encoder_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>rotary_encoder_ros2_control/RotaryEncoderHardwareInterface</plugin>
<param name="can_interface">can1</param>
<param name="can_id">0x130</param>
<param name="update_rate">10</param>
<param name="logger_rate">5</param>
<param name="logger_state">0</param>
</hardware>

<joint name="base_yaw_encoder">
<param name="node_id">5</param>
<param name="rotary_encoder_id">0</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="state_request"/>
</joint>

<joint name="elbow_pitch_encoder">
<param name="node_id">5</param>
<param name="rotary_encoder_id">1</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="state_request"/>
</joint>

<joint name="shoulder_pitch_encoder">
<param name="node_id">5</param>
<param name="rotary_encoder_id">2</param>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="state_request"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>
47 changes: 45 additions & 2 deletions src/description/ros2_control/arm/arm.servo.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<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">can1</param>
<param name="can_id">0x80</param>
</hardware>

Expand All @@ -20,7 +20,50 @@
<param name="joint_type">prismatic</param> <!-- revolute or prismatic -->
<command_interface name="position" />
<command_interface name="velocity"/>
<state_interface name="position" />
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="status"/>
</joint>

<joint name="cam_0">
<param name="node_id">0x2</param>
<param name="gear_ratio">1</param>
<param name="max_pos">180</param> <!-- degrees -->
<param name="servo_type">standard</param> <!-- standard or continuous -->
<param name="joint_type">revolute</param> <!-- revolute or prismatic -->
<command_interface name="position" />
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="status"/>
</joint>

<joint name="cam_1">
<param name="node_id">0x3</param>
<param name="gear_ratio">1</param>
<param name="max_pos">180</param> <!-- degrees -->
<param name="servo_type">standard</param> <!-- standard or continuous -->
<param name="joint_type">revolute</param> <!-- revolute or prismatic -->
<command_interface name="position" />
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="status"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
24 changes: 21 additions & 3 deletions src/description/ros2_control/arm/arm.smc_2dof.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,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">can1</param>
</hardware>

<joint name="base_yaw">
Expand All @@ -17,36 +17,54 @@
<param name="operating_velocity">300</param> <!-- motor dps -->
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="wrist_pitch">
<param name="node_id">0x145</param>
<param name="node_id">0x147</param>
<param name="gear_ratio">40</param>
<param name="joint_orientation">1.0</param>
<param name="operating_velocity">1000</param> <!-- motor dps -->
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="wrist_roll">
<param name="node_id">0x147</param>
<param name="node_id">0x145</param>
<param name="gear_ratio">40</param>
<param name="joint_orientation">1.0</param>
<param name="operating_velocity">1000</param> <!-- motor dps -->
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,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">can1</param>
</hardware>

<joint name="base_yaw">
Expand All @@ -17,11 +17,18 @@
<param name="operating_velocity">300</param> <!-- motor dps -->
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<command_interface name="maintenance_request"/>
<command_interface name="maintenance_frame_high"/>
<command_interface name="maintenance_frame_low"/>
<command_interface name="maintenance_data_count"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

</ros2_control>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -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">can1</param>
</xacro:unless>
</hardware>

Expand All @@ -32,8 +32,12 @@
<param name="kF">0.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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">can0</param>
<param name="can_interface">can1</param>
</xacro:unless>
</hardware>

Expand All @@ -30,10 +30,12 @@
<param name="kF">0.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="wrist_motor_b">
Expand All @@ -51,10 +53,12 @@
<param name="kF">0.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="wrist_motor_c">
Expand All @@ -72,10 +76,12 @@
<param name="kF">0.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>

<joint name="gripper_claw">
Expand All @@ -94,8 +100,12 @@
<param name="kF">0.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="status_request"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<state_interface name="status"/>
</joint>
</ros2_control>
</xacro:macro>
Expand Down
Loading
Loading