Hi @ROxX ,
I saw your files that you sent over to my email. I could not see them on simulation because you did not send me the .stl
files. So the robot will load up blank in Gazebo Sim.
I did go through your files and found some issues:
- Your URDF file:
i. Remove the #include
. XML files are not C++ files!
ii. Remove the spaces in <wheelbase> 0.292 </wheelbase>
.
iii. Remove the Hz
from <odom_publish_frequency>50Hz</odom_publish_frequency>
.
iv. You must configure the Mecanum Drive topics properly for Teleop to work. Correctly define <topic>, <odom_topic>, <tf_topic>, <frame_id>, <child_frame_id>
. Default values WILL NOT WORK with teleop.
v. You have a lot of typo errors and basic mistakes all over your URDF file. Please correct them properly. Otherwise, whatever you do, your robot will never move!
<?xml version="1.0"?>
#include <--- what is this line for? remove it!
<robot name="robot">
<link name="base_link">
<origin rpy="0 0 0" xyz="0 0 0"/>
</link>
<joint name="base_to_axle" type="fixed">
<parent link="base_link"/>
<child link= "axle_frame"/>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
</joint>
<link name="axle_frame">
<inertial>
<mass value="10"/>
<origin xyz="0 0 0" rpy="0 1.57 1.57"/>
<inertia ixx="1.5417" ixy="0" ixz="0" iyy="3.467" iyz="0" izz="4.742"/>
</inertial>
<collision>
<origin xyz="0 0 0" rpy="1.57 0 1.57 "/>
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/axle_frame_dec.stl"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="1.57 0 1.57 "/>
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/axle_frame_dec.stl"/>
</geometry>
<material name="Blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
</link>
<joint name="joint_axle_left_rear_wheel" type="continuous">
<origin rpy="0 0 0" xyz="-0.146 0.110 -0.05" />
<child link="link_left_rear_wheel" />
<parent link="axle_frame" />
<axis rpy="0 0 0" xyz="0 1 0" />
<limit effort="10000" velocity="1000" />
<joint_properties damping="1.0" friction="1.0" />
</joint>
<joint name="joint_axle_right_rear_wheel" type="continuous">
<origin rpy="0 0 0" xyz="-0.146 -0.110 -0.05" />
<child link="link_right_rear_wheel" />
<parent link="axle_frame" />
<axis rpy="0 0 0" xyz="0 1 0" />
<limit effort="10000" velocity="1000" />
<joint_properties damping="1.0" friction="1.0" />
</joint>
<joint name="joint_axle_left_front_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0.146 0.110 -0.05" />
<child link="link_left_front_wheel" />
<parent link="axle_frame" />
<axis rpy="0 0 0" xyz="0 1 0" />
<limit effort="10000" velocity="1000" />
<joint_properties damping="1.0" friction="1.0" />
</joint>
<joint name="joint_axle_right_front_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0.146 -0.110 -0.05" />
<child link="link_right_front_wheel" />
<parent link="axle_frame" />
<axis rpy="0 0 0" xyz="0 1 0" />
<limit effort="10000" velocity="1000" />
<joint_properties damping="1.0" friction="1.0" />
</joint>
<link name="link_left_rear_wheel">
<inertial>
<mass value="0.16" />
<origin xyz="0 0 0" rpy="0 0 1.57" />
<inertia ixx="0.00010" ixy="0" ixz="0" iyy=".00010" iyz="0" izz=".0000416"/>
</inertial>
<collision>
<origin rpy="0 0 1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 1.57" xyz="0 0.03 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
<material name="Green">
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<link name="link_right_rear_wheel">
<inertial>
<mass value="0.16" />
<origin xyz="0 0 0" rpy="0 0 1.57" />
<inertia ixx="0.00010" ixy="0" ixz="0" iyy=".00010" iyz="0" izz=".0000416"/>
</inertial>
<collision>
<origin rpy="0 0 1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
<material name="Green">
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<link name="link_left_front_wheel">
<inertial>
<mass value="0.16" />
<origin xyz="0 0 0" rpy="0 0 -1.57" />
<inertia ixx="0.00010" ixy="0" ixz="0" iyy=".00010" iyz="0" izz=".0000416"/>
</inertial>
<collision>
<origin rpy="0 0 -1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 -1.57" xyz="0 0 0"/>
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
<material name="Green">
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<link name="link_right_front_wheel">
<inertial>
<mass value="0.16" />
<origin xyz="0 0 0" rpy="0 0 1.57" />
<inertia ixx="0.00010" ixy="0" ixz="0" iyy=".00010" iyz="0" izz=".0000416"/>
</inertial>
<collision>
<origin rpy="0 0 1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
</collision>
<visual>
<origin rpy="0 0 1.57" xyz="0 0 0" />
<geometry>
<mesh filename= "/home/tmd/ros2_ws/src/robot_description/meshes/wheel_dec.stl"/>
</geometry>
<material name="Green">
<color rgba="0 1 0 1"/>
</material>
</visual>
</link>
<gazebo>
<plugin filename="gz-sim-mecanum-drive-system" name="gz::sim::systems::MecanumDrive">
<!-- <plugin name="mecanum_drive_plugin" filename=libmecanum_drive_plugin.so> -->
<front_left_joint>joint_axle_left_front_wheel</front_left_joint>
<front_right_joint>joint_axle_right_front_wheel</front_right_joint>
<back_left_joint>joint_axle_left_rear_wheel</back_left_joint>
<back_right_joint>joint_axle_right_rear_wheel</back_right_joint>
<wheelbase> 0.292 </wheelbase> <--- you can't have irregular spaces, delete them!
<wheel_separation>0.220</wheel_separation>
<wheel_radius>0.038</wheel_radius>
<odom_publish_frequency>50Hz</odom_publish_frequency> <--- you can't have Hz here, just use 50 (without Hz)
You need to set the below topics properly, this is why you are unable to move your robot.
Your Mecanum Drive plugin is completely incorrectly configured with lot of mistakes!
<!--
<topic>: Custom topic that this system will subscribe to in order to receive command velocity messages. This element if optional, and the default value is /model/{name_of_model}/cmd_vel.
<odom_topic>: Custom topic on which this system will publish odometry messages. This element if optional, and the default value is /model/{name_of_model}/odometry.
<tf_topic>: Custom topic on which this system will publish the transform from frame_id to child_frame_id. This element if optional, and the default value is /model/{name_of_model}/tf.
<frame_id>: Custom frame_id field that this system will use as the origin of the odometry transform in both the <tf_topic> gz.msgs.Pose_V message and the <odom_topic> gz.msgs.Odometry message. This element if optional, and the default value is {name_of_model}/odom.
<child_frame_id>: Custom child_frame_id that this system will use as the target of the odometry trasnform in both the <tf_topic> gz.msgs.Pose_V message and the <odom_topic> gz.msgs.Odometry message. This element if optional, and the default value is {name_of_model}/{name_of_link}.
-->
</plugin>
</gazebo>
</robot>
- Your
setup.py
file.
I don’t find any issues here. Since you have not shared the move_robot.py
file with me, I can’t say if your python program has any issues.
- To use all the files with a folder, for example, from
meshes
folder, you can specify the glob
pattern as glob('meshes/**))
.
import os
from glob import glob
from setuptools import find_packages, setup
package_name = 'robot_description'
setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'urdf'), glob('urdf/*.urdf')),
(os.path.join('share', package_name, 'rviz'), glob('rviz/*.rviz') ),
(os.path.join('share', package_name, 'meshes'), glob('meshes/*.stl')),
(os.path.join('share', package_name, 'launch'), glob('launch/*.launch.*')),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='tmd',
maintainer_email='tmd@todo.todo',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'robot_description = robot_description.move_robot:main',
],
},
)
In summary, just like I suspected, your URDF file was configured quite bad and you need to fix it. I am surprised to see that your robot spawned correctly on Gazebo Sim. You should use a launch file to spawn your robot instead of using Gazebo Sim’s command line spawn service call.
I suggest (and highly recommend) that you take the URDF with ROS2 course, to learn how to properly write a URDF / xacro file!
Regards,
Girish