1. Environment Setup and Basic Shape Creation
cd ~/ros2_ws/src
ros2 pkg create --build-type ament_python urdf_tutorial
Add launch and urdf folders to the urdf_turoial folder
Modify the setup.py code in the urdf_tutorial folder
Create Xacro file in the urdf folder as described above. The code to include in the file is as follows:
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="urdf_test" >
<!-- BASE -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
</joint>
<link name="body">
<visual>
<geometry>
<box size="1 1 1"/>
</geometry>
</visual>
</link>
</robot>
Create launch file in the launch folder as described above. The code to include in the file is as follows:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
import xacro
def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time")
pkg_path = os.path.join(get_package_share_directory("urdf_tutorial"))
xacro_file = os.path.join(pkg_path, "urdf", "robot_v1.xacro")
robot_description = xacro.process_file(xacro_file)
params = {"robot_description": robot_description.toxml(), "use_sim_time": use_sim_time}
return LaunchDescription(
[
DeclareLaunchArgument(
"use_sim_time", default_value="false", description="use sim time"
),
Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="screen",
parameters=[params],
),
]
)
open the terminal and
cd ~/ros2_ws/
colcon build
source /opt/ros/foxy/setup.bash
source ~/ros2_ws/install/local_setup.bash
ros2 launch urdf_tutorial robot_v1.launch.py
open the new terminal and
cd ~/ros2_ws/
source /opt/ros/foxy/setup.bash
source ~/ros2_ws/install/local_setup.bash
rviz2
Fixed Frame 을 base_link 로 변환
Use the Add button in the bottom left to add TF.
Then, click the Add button again to add RobotModel.
In the Description Topic, select /robot_description.
You should see the cube previously defined in URDF appear
2. Create a Car and Visualize Using Rviz2
First, create a macros.xacro file in the urdf folder
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<!-- These make use of xacro's mathematical functionality -->
<xacro:macro name="inertial_sphere" params="mass radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0"
iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0"
izz="${(2/5) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_box" params="mass x y z *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
izz="${(1/12) * mass * (x*x+y*y)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_cylinder" params="mass length radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0"
izz="${(1/2) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
</robot>
Simillarly, create a robot_car.xacro file in the urdf folder.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">
<!-- MACROS -->
<xacro:include filename="macros.xacro"/>
<!-- COLOR -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="body">
<visual>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
<origin xyz="0.1 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="body"/>
<child link="caster_wheel"/>
<origin xyz="0.03 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
</robot>
Now, create a launch file in the launch folder.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
import xacro
def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time")
pkg_path = os.path.join(get_package_share_directory("urdf_tutorial"))
xacro_file = os.path.join(pkg_path, "urdf", "robot_car.xacro")
robot_description = xacro.process_file(xacro_file)
params = {"robot_description": robot_description.toxml(), "use_sim_time": use_sim_time}
return LaunchDescription(
[
DeclareLaunchArgument(
"use_sim_time", default_value="false", description="use sim time"
),
Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="screen",
parameters=[params],
),
]
)
It will have a folder structure like the above
Now,just like before, run colcon build and execute the newly created launch file. Then, launch rviz2 again, and it will look the same as above. Errors may occur in left_wheel and right_wheel, which can be resolved through the following steps.
sudo apt update
sudo apt install ros-foxy-joint-state-publisher-gui
ros2 run joint_state_publisher_gui joint_state_publisher_gui
When the code is executed, a new window will appear, and as shown in the image below, you can move the slider left and right to control the robot’s wheels.
executed rqt_graph, and we can see the graph as shown in the image above
3. Visualizing using Gazebo
Ros2 Foxy is designed to operate with Python 3.8; therefore, you should set up an Anaconda virtual environment.
conda create -n robot38 python=3.8
How to set up an Anaconda virtual environment can be found in other Google bolgs. There are many eaxy-to-follow and well-organized guides available.
Then, we create just three files: two new Xacro files and one launch file. The codes below are the Xacro code and the launch code, respectivvely.
gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<gazebo>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<!-- Wheel Information -->
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.35</wheel_separation>
<wheel_diameter>0.1</wheel_diameter>
<!-- Limits -->
<max_wheel_torque>200</max_wheel_torque>
<max_wheel_acceleration>10.0</max_wheel_acceleration>
<!-- Output -->
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
</plugin>
</gazebo>
</robot>
robot_car_gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">
<!-- MACROS -->
<xacro:include filename="macros.xacro"/>
<!-- COLOR -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="body">
<visual>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
<origin xyz="0.1 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="body">
<material>Gazebo/White</material>
</gazebo>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="body"/>
<child link="caster_wheel"/>
<origin xyz="0.03 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Blue</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
<!-- GAZEBO -->
<xacro:include filename="gazebo.xacro"/>
</robot><?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="urdf_tutorial">
<!-- MACROS -->
<xacro:include filename="macros.xacro"/>
<!-- COLOR -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<!-- BASE LINK -->
<link name="base_link">
</link>
<!-- BODY LINK -->
<joint name="body_joint" type="fixed">
<parent link="base_link"/>
<child link="body"/>
<origin xyz="-0.12 0 0"/>
</joint>
<link name="body">
<visual>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.1 0 0.03"/>
<geometry>
<box size="0.2 0.1 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.2" y="0.1" z="0.06">
<origin xyz="0.1 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="body">
<material>Gazebo/White</material>
</gazebo>
<!-- LEFT WHEEL LINK -->
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.065 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- RIGHT WHEEL LINK -->
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<origin xyz="0 -0.065 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.03"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.03" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<!-- CASTER WHEEL LINK -->
<joint name="caster_wheel_joint" type="fixed">
<parent link="body"/>
<child link="caster_wheel"/>
<origin xyz="0.03 0 0"/>
</joint>
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="0.03">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/Blue</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
<!-- GAZEBO -->
<xacro:include filename="gazebo.xacro"/>
</robot>
robot_sim.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
def generate_launch_description():
package_name = "urdf_tutorial"
rsp = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory(package_name), "launch", "robot_car_gazebo.launch.py")]
),
launch_arguments={"use_sim_time": "true"}.items(),
)
# Include the Gazebo launch file, provided by the gazebo_ros package
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory("gazebo_ros"), "launch", "gazebo.launch.py")]
),
)
# Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
spawn_entity = Node(
package="gazebo_ros",
executable="spawn_entity.py",
arguments=["-topic", "robot_description", "-entity", "with_robot"],
output="screen",
)
# Launch them all!
return LaunchDescription(
[
rsp,
gazebo,
spawn_entity,
]
)
Then, run colcon build, open four terminals, and execute the four commands
1. ros2 launch urdf_tutorial robot_sim.launch.py
2. ros2 run teleop_twist_keyboard teleop_twist_keyboard
3. rviz2
4. rqt_graph
When the second command is executed, you can see the robot moving while drawing circles.
When the third command is executed, you may see weird results. You should change the Fixed Frame to odom.
0 Comments