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 Feb 3, 2025
2 parents a767805 + e8a46f9 commit 4890139
Show file tree
Hide file tree
Showing 4 changed files with 104 additions and 144 deletions.
44 changes: 43 additions & 1 deletion src/operations/vehicle_urdf/launch/view_qev3d.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,4 +58,46 @@ def generate_launch_description():
),

# initialize the variable storing the value of the argument
prefix = LaunchConfiguration("prefix")
prefix = LaunchConfiguration("prefix")

# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("vehicle_urdf"), "urdf", description_file]
),
" ",
"prefix:=", # prefix argument is passed to xacro, WHICH IS EMPTY
prefix,
]
)
robot_description = {"robot_description": robot_description_content}

#TODO: SET UP RVIZ2 CONFIGURATION FILE
rviz_config_file = PathJoinSubstitution(
[FindPackageShare(description_package), "carlikebot/rviz", "carlikebot_view.rviz"]
)


joint_state_publisher_node = Node(
package="joint_state_publisher_gui",
executable="joint_state_publisher_gui",
condition=IfCondition(gui), # Only launch the node if gui is set to true
)
robot_state_publisher_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
condition=IfCondition(gui), # Only launch the node if gui is set to true
)

14 changes: 10 additions & 4 deletions src/operations/vehicle_urdf/urdf/qev-3d.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
<?xml version="1.0"?>
<robot name="qev-3d" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="qev-3d"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="prefix" default="" />
<!-- Get the parameters -->
<xacro:arg name="base_frame" default="base_link"/>
<xacro:arg name="display_car" default="true"/> <!--Display the car mesh-->
<xacro:property name="chassis_link" default="chassis"/> <!--Chassis link name-->
<xacro:arg name="display_car" default="true"/>
<!--Display the car mesh-->
<xacro:property name="chassis_link" default="chassis"/>
<!--Chassis link name-->

<xacro:property name="degrees_90" value="1.5708"/>
<xacro:property name="M_PI" value="3.1415926535897931" />
Expand All @@ -24,11 +27,14 @@
<color rgba="0.88 0.36 0.035 1"/>
</material>

<material name="invisible">
<color rgba="0.0 0.0 0.0 0.0"/>
</material>

<!-- Import QEV-3D ros2_control description -->
<xacro:include filename="$(find src)/control/ros2_control/description/qev3d.ros2_control.urdf.xacro"/>
<!-- Declaring wheel joints setup for the controller -->
<xacro:qev3d_ros2_control name="QEV3D" />
<xacro:qev3d_ros2_control name="QEV-3D" />


<!-- Vehicle include -->
Expand Down
44 changes: 0 additions & 44 deletions src/operations/vehicle_urdf/urdf/qev3d.materials.xacro

This file was deleted.

146 changes: 51 additions & 95 deletions src/operations/vehicle_urdf/urdf/vehicle.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,22 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- QEV-3D parameters-->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="chassis_width" value="1.6"/>
<xacro:property name="wheel_radius" value="0.5"/>
<xacro:property name="wheel_width" value="0.2"/>
<xacro:property name="wheelbase" value="1.580"/>
<xacro:property name="base_height" value="0.3"/>
<xacro:property name="base_width" value="0.6"/>
<xacro:property name="chassis_link" default="chassis"/>
<!--Chassis link name-->
<xacro:property name="steering_limit" value="0.28"/>
<xacro:property name="degrees_90" value="1.5708"/>
<!-- 90 degrees in radians -->
<material name="invisible">
<color rgba="0 0 0 0"/>
</material>

<xacro:macro name="chassis" params="base_frame display_car">
<!-- Base Frame -->
<link name="${base_frame}"/>
Expand All @@ -26,7 +9,7 @@
<parent link="${base_frame}"/>
<child link="${chassis_link}"/>
<!-- Wheel height off ground -->
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
<origin xyz="0 0 ${wheel_diameter/2}" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>

Expand All @@ -51,54 +34,58 @@
</xacro:macro>

<!-- Wheels -->
<xacro:macro name="wheels"> <!--Template for the wheels -->
<xacro:macro name="wheels">

<!-- Virtual wheel for immitation purposes -->
<link name="virtual_rear_wheel">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="0.01" radius="${wheel_radius}"/>
</geometry>
<material name="invisible"/>
</visual>
</link>
<link name="virtual_front_wheel">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="0.01" radius="${wheel_radius}"/>
</geometry>
<material name="invisible"/>
</visual>
</link>
<xacro:macro name="virtual_conponents">
<link name="virtual_rear_wheel">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="0.01" radius="${wheel_radius}"/>
</geometry>
<material name="invisible"/>
</visual>
</link>
<link name="virtual_front_wheel">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="0.01" radius="${wheel_radius}"/>
</geometry>
<material name="invisible"/>
</visual>
</link>

<joint name="virtual_rear_wheel_joint" type="continuous">
<parent link="${chassis_link}"/>
<child link="virtual_rear_wheel"/>
<origin xyz="-${wheelbase/2} 0 -${base_height/2}" rpy="0 0 ${PI/2}"/>
<axis xyz="1 0 0"/>
<limit effort="100.0" velocity="100.0"/>
<dynamics damping="0.2"/>
</joint>
<joint name="virtual_rear_wheel_joint" type="continuous">
<parent link="${chassis_link}"/>
<child link="virtual_rear_wheel"/>
<origin xyz="-${wheelbase/2} 0 -${base_height/2}" rpy="0 0 ${PI/2}"/>
<axis xyz="1 0 0"/>
<limit effort="100.0" velocity="100.0"/>
<dynamics damping="0.2"/>
</joint>

<joint name="virtual_front_wheel_joint" type="revolute">
<parent link="${chassis_link}"/>
<child link="virtual_front_wheel"/>
<origin xyz="${wheelbase/2} 0 -${base_height/2}" rpy="0 0 ${PI/2}"/>
<axis xyz="0 0 1"/>
<limit lower="-0.4" upper="0.4" effort="100.0" velocity="0.0"/>
<dynamics damping="0.2"/>
</joint>
<joint name="virtual_front_wheel_joint" type="revolute">
<parent link="${chassis_link}"/>
<child link="virtual_front_wheel"/>
<origin xyz="${wheelbase/2} 0 -${base_height/2}" rpy="0 0 ${PI/2}"/>
<axis xyz="0 0 1"/>
<limit lower="-0.4" upper="0.4" effort="100.0" velocity="0.0"/>
<dynamics damping="0.2"/>
</joint>
</xacro:macro>

<!-- ADDING VIRTUAL COMPONENTS -->
<xacro:virtual_conponents/>

<!-- Wheel visualisation description -->
<!-- Wheel description -->
<xacro:macro name="wheel" params="lr_prefix fr_prefix">
<link name="${lr_prefix}_${fr_prefix}_wheel">
<visual>
<origin xyz="0 0 0" rpy="${degrees_90} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
<cylinder radius="${wheel_diameter / 2}" length="${wheel_width}"/>
</geometry>
<material name="black"/>
</visual>
Expand All @@ -108,80 +95,49 @@
<!-- Front and rear wheel descriptions -->
<!-- Description of how a front wheel is connected to the chassis -->
<xacro:macro name="front_wheel" params="lr_prefix lr_reflect">
<!-- create a link for steering hinge -->
<link name="${lr_prefix}_steering_hinge"/>

<!-- create joint to connect corresponding {lr}_steering_hinge to the chassis -->
<joint name="${lr_prefix}_steering_hinge_joint" type="fixed">
<origin xyz="${wheelbase / 2}
${lr_reflect * ((chassis_width - wheel_width) / 2)}
0" rpy="0 0 0"/>
<parent link="${chassis_link}"/>
<!-- connect to the chassis -->
<child link="${lr_prefix}_steering_hinge"/>
<!-- connect to the steering hinge -->
<axis xyz="0 0 1"/>
<!-- axis of rotation -->
<limit lower="${-1*steering_limit}" upper="${steering_limit}" effort="10000000" velocity="1000000"/>
</joint>




<!-- create a joint connect the {lr}_steering_hinge to the {lr}_front_wheel -->
<joint name="front_${lr_prefix}_wheel_joint" type="revolute">
<!-- connect to the chassis -->
<parent link="${chassis_link}"/>
<!-- connect to the {lr}_front_wheel -->
<joint name="front_${lr_prefix}_wheel_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${lr_prefix}_steering_hinge"/>
<child link="${lr_prefix}_front_wheel"/>

<origin xyz="-${wheelbase/2} ${base_width/2} -${base_height/2}" rpy="0 0 ${PI/2}"/>
<!-- axis of rotation -->
<axis xyz="0 0 1"/>

<limit lower="-0.4" upper="0.4" effort="1000.0" velocity="0"/>
<dynamics damping="0.2"/>
<mimic joint="virtual_front_wheel_joint" multiplier="1.0" offset="0.0"/>
<axis xyz="0 1 0"/>
<limit lower="0" upper="0" effort="10000000" velocity="1000000"/>
</joint>

<!-- launch the macro to add the front wheel links pair -->
<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="continuous">
<joint name="rear_${lr_prefix}_wheel_joint" type="fixed">
<origin xyz="${-1 * wheelbase / 2}
${lr_reflect * ((chassis_width - wheel_width) / 2)}
0" rpy="0 0 0"/>
<parent link="${chassis_link}"/>
<child link="${lr_prefix}_rear_wheel"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.2"/>
<limit effort="10000000" velocity="1000000"/>
<mimic joint="virtual_rear_wheel_joint" multiplier="1.0" offset="0.0"/>
<axis xyz="0 1 0"/>
<limit lower="0" upper="0" effort="10000000" velocity="1000000"/>
</joint>


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



<!-- Add the wheels -->

<!-- left_front_wheel -->
<xacro:front_wheel lr_prefix="left" lr_reflect="1"/>

<!-- right_front_wheel -->
<xacro:front_wheel lr_prefix="right" lr_reflect="-1"/>

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


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

0 comments on commit 4890139

Please sign in to comment.