Skip to content

Commit

Permalink
Merge branch 'feature/ros2_control_migration_setup' of https://github…
Browse files Browse the repository at this point in the history
….com/QUT-Motorsport/QUTMS_Driverless into feature/ros2_control_migration_setup
  • Loading branch information
PeterLiao2004 committed Jan 31, 2025
2 parents 4e9923e + 553b038 commit 69afe5a
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,20 +4,24 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="qev3d_ros2_control" params="name prefix">
<xacro:macro name="qev3d_ros2_control" params="name prefix"> <!--Template for the QEV-3D ros2_control description -->

<ros2_control name="${name}" type="system">
<hardware>
<plugin>ros2_control_demo_example_11/CarlikeBotSystemHardware</plugin>
<param name="example_param_hw_start_duration_sec">0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
</hardware>
<joint name="${prefix}front_wheel_joint">
<joint name="${prefix}virtual_front_wheel_joint">
<command_interface name="position"/>
<param name = "min">-0.28</param>
<param name = "max">0.28</param>
<state_interface name="position"/>
</joint>
<joint name="${prefix}rear_wheel_joint">
<joint name="${prefix}virtual_rear_wheel_joint">
<command_interface name="velocity"/>
<param name = "min">-10</param>
<param name = "max">10</param>>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
Expand Down
6 changes: 4 additions & 2 deletions src/operations/vehicle_urdf/urdf/vehicle.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -74,11 +74,13 @@
<limit lower="0" upper="0" effort="10000000" velocity="1000000"/>
</joint>

<!-- Add the wheel -->
<xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="front"/>
</xacro:macro>

<!-- Description of how a rear wheel is connected to the chassis -->
<xacro:macro name="rear_wheel" params="lr_prefix lr_reflect">

<joint name="rear_${lr_prefix}_wheel_joint" type="fixed">
<origin xyz="${-1 * wheelbase / 2}
${lr_reflect * ((chassis_width - wheel_width) / 2)}
Expand All @@ -101,10 +103,10 @@
<!-- right_front_wheel -->
<xacro:front_wheel lr_prefix="right" lr_reflect="-1"/>

<!-- left_rear_wheel -->
<!-- left_rear_wheel -->
<xacro:rear_wheel lr_prefix="left" lr_reflect="1" />

<!-- right_rear_wheel -->

<xacro:rear_wheel lr_prefix="right" lr_reflect="-1" />
</xacro:macro>
</robot>

0 comments on commit 69afe5a

Please sign in to comment.