Skip to content

Commit

Permalink
Merge pull request #60 from clubcapra/fix-diff-drive
Browse files Browse the repository at this point in the history
Cleaned up ros2 control xacro, added macros, fixed cmd_vel for diffdrive
  • Loading branch information
IliTheButterfly authored Jun 18, 2024
2 parents 404d289 + b4256e0 commit 81eaafa
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 86 deletions.
4 changes: 3 additions & 1 deletion src/rove_bringup/launch/rove_controller_bluetooth.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ def generate_launch_description():
parameters=[teleop_joy_params_file],
remappings=[
('/joy', '/joy'),
# ('/cmd_vel', '/model/rove/cmd_vel')
# Remap needs to happen here since the diff_drive_controller node
# is started via a spawner, thus remappings do not work on it
('/cmd_vel', '/diff_drive_controller/cmd_vel_unstamped')
],
),
Node(
Expand Down
3 changes: 3 additions & 0 deletions src/rove_bringup/launch/rove_controller_usb.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@ def generate_launch_description():
parameters=[teleop_joy_params_file],
remappings=[
('/joy', '/joy'),
# Remap needs to happen here since the diff_drive_controller node
# is started via a spawner, thus remappings do not work on it
('/cmd_vel', '/diff_drive_controller/cmd_vel_unstamped')
],
),
Node(
Expand Down
118 changes: 34 additions & 84 deletions src/rove_description/urdf/rove.ros2_control.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,14 +1,33 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rove_odrive_motor" params="position suffix id">
<xacro:macro name="track_motor_control" params="suffix nodeid">
<joint name="track_${suffix}_j">
<param name="node_id">${nodeid}</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</xacro:macro>

<xacro:macro name="track_fake_motor_control" params="suffix">
<joint name="track_${suffix}_j">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</xacro:macro>

<xacro:macro name="rove_odrive_motor" params="suffix id">
<xacro:unless value="${(id == -1)}">
<xacro:track_motor_control position="${position}" suffix="${suffix}" nodeid="${id}"/>
<xacro:track_motor_control suffix="${suffix}" nodeid="${id}"/>
</xacro:unless>
</xacro:macro>

<xacro:macro name="rove_fake_odrive_motor" params="position suffix id">
<xacro:macro name="rove_fake_odrive_motor" params="suffix id">
<xacro:if value="${(id == -1)}">
<xacro:track_fake_motor_control position="${position}" suffix="${suffix}"/>
<xacro:track_fake_motor_control suffix="${suffix}"/>
</xacro:if>
</xacro:macro>

Expand All @@ -18,91 +37,22 @@
<plugin>odrive_ros2_control_plugin/ODriveHardwareInterface</plugin>
<param name="can">can0</param>
</hardware>
<joint name="track_fr_j">
<param name="node_id">23</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="track_rr_j">
<param name="node_id">24</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>

<joint name="track_fl_j">
<param name="node_id">21</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="track_rl_j">
<param name="node_id">22</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>

<!-- <joint name="track_rl_j">
<param name="node_id">1</param>
</joint> -->
<!-- <xacro:rove_odrive_motor position="f" suffix="l" id="${fl_id}"/>
<xacro:rove_odrive_motor position="r" suffix="l" id="${rl_id}"/>
<xacro:rove_odrive_motor position="f" suffix="r" id="${fr_id}"/>
<xacro:rove_odrive_motor position="r" suffix="r" id="${rr_id}"/> -->
<xacro:rove_odrive_motor suffix="fl" id="${fl_id}"/>
<xacro:rove_odrive_motor suffix="rl" id="${rl_id}"/>
<xacro:rove_odrive_motor suffix="fr" id="${fr_id}"/>
<xacro:rove_odrive_motor suffix="rr" id="${rr_id}"/>
</ros2_control>
<!-- <ros2_control name="fake_odrive_control" type="system">

<ros2_control name="fake_odrive_control" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>
</hardware>
<<joint name="track_fl_j">
<param name="node_id">1</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="track_rl_j">
<param name="node_id">2</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="track_fr_j">
<param name="node_id">3</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="track_rr_j">
<param name="node_id">3</param>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control> -->
<!-- <ros2_control name="fake_odrive_control" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<xacro:rove_fake_odrive_motor position="f" suffix="l" id="${fl_id}"/>
<xacro:rove_fake_odrive_motor position="r" suffix="l" id="${rl_id}"/>
<xacro:rove_fake_odrive_motor position="f" suffix="r" id="${fr_id}"/>
<xacro:rove_fake_odrive_motor position="r" suffix="r" id="${rr_id}"/>
</ros2_control> -->
<xacro:rove_fake_odrive_motor suffix="fl" id="${fl_id}"/>
<xacro:rove_fake_odrive_motor suffix="rl" id="${rl_id}"/>
<xacro:rove_fake_odrive_motor suffix="fr" id="${fr_id}"/>
<xacro:rove_fake_odrive_motor suffix="rr" id="${rr_id}"/>
</ros2_control>
</xacro:macro>


<xacro:macro name="rove_ros2_control">
<xacro:odrive_control/>
</xacro:macro>
</robot>
3 changes: 2 additions & 1 deletion src/rove_description/urdf/rove.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@


<!-- <xacro:rove_ros2_control/> -->
<xacro:odrive_control fl_id="0" rl_id="-1" fr_id="-1" rr_id="-1"/>
<!-- Put these at -1 to mock the motors if working without the motors -->
<xacro:odrive_control fl_id="21" rl_id="22" fr_id="23" rr_id="24"/>


<!-- Insert ovis on top of rove -->
Expand Down

0 comments on commit 81eaafa

Please sign in to comment.