Skip to content

Commit

Permalink
almost
Browse files Browse the repository at this point in the history
  • Loading branch information
ARK3r committed Jun 29, 2023
1 parent 255178e commit 6e37b75
Show file tree
Hide file tree
Showing 7 changed files with 378 additions and 105 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,19 +8,26 @@
<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>
<param name="is_simulation">1</param>
</hardware>
<joint name="${prefix}left_wheel_joint">
<command_interface name="velocity"/>
<joint name="${prefix}left_steering_hinge_joint">
<command_interface name="position"/>
<state_interface name="position"/>
</joint>
<joint name="${prefix}right_steering_hinge_joint">
<command_interface name="position"/>
<state_interface name="position"/>
</joint>
<joint name="${prefix}rear_left_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="velocity"/>
</joint>
<joint name="${prefix}right_wheel_joint">
<joint name="${prefix}rear_right_wheel_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>

</xacro:macro>

</robot>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -6,17 +6,14 @@
<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>
<param name="is_simulation">0</param>
</hardware>
<joint name="${prefix}left_wheel_joint">
<command_interface name="velocity"/>
<joint name="${prefix}steering_joint">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="${prefix}right_wheel_joint">
<joint name="${prefix}drive_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
Expand Down
6 changes: 4 additions & 2 deletions example_11/description/urdf/carlikebot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,18 @@
<xacro:arg name="prefix" default="" />
<xacro:arg name="sim" default="false" />

<xacro:include filename="$(find ros2_control_demo_example_11)/urdf/carlikebot_description.urdf.xacro" />

<!-- Import Rviz colors -->
<xacro:include filename="$(find ros2_control_demo_example_11)/urdf/carlikebot.materials.xacro" />

<!-- Import carlikebot ros2_control description based on sim arg -->
<!-- Import carlikebot description and ros2_control based on sim arg -->
<xacro:if value="$(arg sim)">
<xacro:include filename="$(find ros2_control_demo_example_11)/urdf/carlikebot_ackermann_description.urdf.xacro" />
<xacro:include filename="$(find ros2_control_demo_example_11)/ros2_control/carlikebot_ackermann.ros2_control.xacro" />
</xacro:if>

<xacro:unless value="$(arg sim)">
<xacro:include filename="$(find ros2_control_demo_example_11)/urdf/carlikebot_bicycle_description.urdf.xacro" />
<xacro:include filename="$(find ros2_control_demo_example_11)/ros2_control/carlikebot_bicycle.ros2_control.xacro" />
</xacro:unless>

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,214 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="carlikebot" params="prefix">

<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="base_mass" value="4.0" /> <!-- arbitrary value for base mass -->
<xacro:property name="base_width" value="0.260" />
<xacro:property name="base_length" value="0.525" />
<xacro:property name="base_height" value="0.060" />
<xacro:property name="wheelbase" value="0.325" />
<xacro:property name="wheel_mass" value="0.34055" /> <!-- arbitrary value for wheel mass -->
<xacro:property name="wheel_len" value="0.045" />
<xacro:property name="wheel_radius" value="0.05" />

<!-- Base Link -->
<link name="${prefix}base_link" />

<!-- Chassis -->

<link name="${prefix}chassis_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${base_width} ${base_length} ${base_height}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${base_width} ${base_length} ${base_height}"/>
</geometry>
<material name="orange"/>
</visual>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${base_mass}"/>
<inertia
ixx="${base_mass / 12.0 * (base_length*base_length + base_height*base_height)}" ixy="0.0" ixz="0.0"
iyy="${base_mass / 12.0 * (base_height*base_height + base_width*base_width)}" iyz="0.0"
izz="${base_mass / 12.0 * (base_width*base_width + base_length*base_length)}"/>
</inertial>
</link>

<joint name="${prefix}chassis_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}chassis_link"/>
<origin xyz="0 0 ${base_height/2 + wheel_radius}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<dynamics damping="0.2"/>
</joint>


<!-- rear wheels -->

<!-- rear right wheel -->

<link name="${prefix}rear_right_wheel">

<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
<material name="black"/>
</visual>

<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
</inertial>

</link>

<joint name="${prefix}rear_right_wheel_joint" type="continuous">
<parent link="${prefix}chassis_link"/>
<child link="${prefix}rear_right_wheel"/>
<origin xyz="${base_width/2} -${wheelbase/2} -${base_height/2}" rpy="0 0 0"/>
<axis xyz="-1 0 0"/>
<dynamics damping="0.2"/>
</joint>

<!-- rear left wheel -->
<link name="${prefix}rear_left_wheel">

<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
<material name="black"/>
</visual>

<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
</inertial>

</link>

<joint name="${prefix}rear_left_wheel_joint" type="continuous">
<parent link="${prefix}chassis_link"/>
<child link="${prefix}rear_left_wheel"/>
<origin xyz="-${base_width/2} -${wheelbase/2} -${base_height/2}" rpy="0 0 0"/>
<axis xyz="-1 0 0"/>
<dynamics damping="0.2"/>

</joint>

<!-- front wheels -->

<!-- front right wheel -->

<link name="${prefix}right_steering_hinge">

<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
<material name="black"/>
</visual>

<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
</inertial>
</link>

<joint name="${prefix}right_steering_hinge_joint" type="revolute">
<parent link="${prefix}chassis_link"/>
<child link="${prefix}right_steering_hinge"/>
<origin xyz="${base_width/2} ${wheelbase/2} -${base_height/2}" rpy="0 0 0"/>
<axis xyz="0 0 -1"/>
<limit lower="-0.4" upper="0.4" effort="0.0" velocity="0.0"/>
<dynamics damping="0.2"/>
</joint>


<link name="${prefix}left_steering_hinge">
<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
<material name="black"/>
</visual>

<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 ${PI/2}"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
</inertial>

</link>

<joint name="${prefix}left_steering_hinge_joint" type="revolute">
<parent link="${prefix}chassis_link"/>
<child link="${prefix}left_steering_hinge"/>
<origin xyz="-${base_width/2} ${wheelbase/2} -${base_height/2}" rpy="0 0 0"/>
<axis xyz="0 0 -1"/>
<limit lower="-0.4" upper="0.4" effort="0.0" velocity="0.0"/>
<dynamics damping="0.2"/>
</joint>

</xacro:macro>

</robot>
Loading

0 comments on commit 6e37b75

Please sign in to comment.