紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
ROS2 humble spawn_entity[Err] [Visual.cc:2956] No mesh specified
-
我是ROS2的新手,近期在尝试将xacro文件导入gazebo中,urdf文件可以在Rviz中使用,但是导入gazebo的时候就不可以了,它会报如下错误
[Err] [InsertModelWidget.cc:403] Missing model.config for model "/home/wp/ros2_ws/install/manipulater/share/manipulater/__pycache__" [gazebo-1] [Err] [InsertModelWidget.cc:403] Missing model.config for model "/home/wp/ros2_ws/install/manipulater/share/manipulater/hook" [gazebo-1] [Err] [InsertModelWidget.cc:403] Missing model.config for model "/home/wp/ros2_ws/install/manipulater/share/manipulater/meshes" [gazebo-1] [Err] [InsertModelWidget.cc:403] Missing model.config for model "/home/wp/ros2_ws/install/manipulater/share/manipulater/rviz" [gazebo-1] [Err] [InsertModelWidget.cc:403] Missing model.config for model "/home/wp/ros2_ws/install/manipulater/share/manipulater/urdf" [gazebo-1] [Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call [gazebo-1] [Wrn] [FuelModelDatabase. cc:313] URI not supported by Fuel [$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [SystemPaths.cc:459] File or path does not exist [""] [$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [FuelModelDatabase.cc:313] URI not supported by Fuel [file://$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [SystemPaths.cc:459] File or path does not exist [""] [file://$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Err] [Visual.cc:2956] No mesh specified [gazebo-1] [Wrn] [FuelModelDatabase.cc:313] URI not supported by Fuel [$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [SystemPaths.cc:459] File or path does not exist [""] [$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [FuelModelDatabase.cc:313] URI not supported by Fuel [file://$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Wrn] [SystemPaths.cc:459] File or path does not exist [""] [file://$(find manipulater)/meshes/visual/con_1.STL] [gazebo-1] [Err] [Visual.cc:2956] No mesh specified
我尝试了export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/home/wp/ros2_ws/install/manipulater/share/manipulater
但是不起作用,我也将xacro文件中mesh中的filename="package://manipulater/meshes/visual/base_link.STL" 变成 filename="file://$(find manipulater)/meshes/visual/base_link.STL",但是也不起作用
我不知道问题出在哪里,感谢帮助我的人
我使用 ROS2 humbe,Ubuntu 22.04.2 ,VM16 promy directory tree
. ├── launch │ ├── display_launch.py │ ├── gazebo1.launch.py │ └── gazebo2.launch.py ├── manipulater │ └── __init__.py ├── meshes │ ├── collision │ │ ├── base_link.STL │ │ ├── con_1.STL │ │ ├── con_2.STL │ │ ├── con_3.STL │ │ ├── con_4.STL │ │ ├── con_5.STL │ │ ├── con_6.STL │ │ ├── con_7.STL │ │ ├── con_8.STL │ │ ├── link_1.STL │ │ ├── link_2.STL │ │ ├── link_3.STL │ │ ├── link_4.STL │ │ ├── link_5.STL │ │ ├── link_6.STL │ │ ├── link_7.STL │ │ └── link_8.STL │ └── visual │ ├── base_link.STL │ ├── con_1.STL │ ├── con_2.STL │ ├── con_3.STL │ ├── con_4.STL │ ├── con_5.STL │ ├── con_6.STL │ ├── con_7.STL │ ├── con_8.STL │ ├── link_1.STL │ ├── link_2.STL │ ├── link_3.STL │ ├── link_4.STL │ ├── link_5.STL │ ├── link_6.STL │ ├── link_7.STL │ └── link_8.STL ├── package.xml ├── resource │ └── manipulater ├── rviz │ └── view.rviz ├── scripts │ ├── 00_dofbot_move.py │ ├── 01_set_move.py │ ├── 02_motion_plan.py │ ├── 03_attached_object.py │ ├── 04_Set_Scene.py │ └── __init__.py ├── setup.cfg ├── setup.py └── urdf ├── manipulater.gv ├── manipulater.pdf ├── sd_mani_test.urdf ├── sd_mani.urdf └── sd_mani.xacro 9 directories, 54 files
my xacro file
<?xml version="1.0"?> <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578 For more information, please see http://wiki.ros.org/sw_urdf_exporter --> <robot name="manipulater" xmlns:xacro="http://ros.org/wiki/xacro"> <link name="base_link"> <inertial><!--旋转惯量矩阵是用于描述物体的惯性的,在做动力学仿真的时候,这些参数尤为重要--> <origin xyz="-0.40335 -4.5727E-09 -0.022176" rpy="1.5708 0 0" /> <mass value="50" /><!--描述link的质量--> <inertia ixx="2.7711" ixy="5.2286E-07" ixz="-0.013648" iyy="3.0095" iyz="1.0857E-09" izz="3.0504" /> </inertial> <visual> <origin xyz="0 0 0" rpy="1.5708 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/base_link.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision><!--我们可以可以在link标签下添加collison子标签来对物体的形状进行描述--> <origin xyz="0 0 0" rpy="1.5708 0 0" /><!--表示碰撞体的中心位姿--> <geometry><!--用于表示用于碰撞检测的几何形状--> <mesh filename="file://$(find manipulater)/meshes/visual/base_link.STL" /> </geometry> </collision> </link> <link name="con_1"> <inertial> <origin xyz="-4.147E-11 1.5501E-08 -1.3172E-07" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="4.006E-13" ixz="3.9983E-13" iyy="5.0984E-07" iyz="-8.0439E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_1.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_1.STL" /> </geometry> </collision> </link> <joint name="joint_1" type="revolute"> <origin xyz="0 0 0" rpy="1.5708 0 0" /> <parent link="base_link" /> <child link="con_1" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_1"> <inertial> <origin xyz="-0.40335 4.5727E-09 0.022176" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-5.2286E-07" ixz="0.013648" iyy="3.0095" iyz="1.0857E-09" izz="3.0504" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_1.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_1.STL" /> </geometry> </collision> </link> <joint name="joint_2" type="revolute"> <origin xyz="0 0 0" rpy="1.5708 0 0" /> <parent link="con_1" /> <child link="link_1" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_2"> <inertial> <origin xyz="-4.1467E-11 -1.2546E-08 -1.5501E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="3.9983E-13" ixz="-4.006E-13" iyy="5.0984E-07" iyz="8.0461E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_2.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_2.STL" /> </geometry> </collision> </link> <joint name="joint_3" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_1" /> <child link="con_2" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_2"> <inertial> <origin xyz="-0.53185 -0.022176 1.2375E-07" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-0.013648" ixz="-5.2286E-07" iyy="3.0504" iyz="-1.0857E-09" izz="3.0095" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_2.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_2.STL" /> </geometry> </collision> </link> <joint name="joint_4" type="revolute"> <origin xyz="0 0 0" rpy="-1.5708 0 0" /> <parent link="con_2" /> <child link="link_2" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_3"> <inertial> <origin xyz="-4.1467E-11 1.5501E-08 -1.2546E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="4.006E-13" ixz="3.9983E-13" iyy="5.0984E-07" iyz="-8.0481E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_3.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_3.STL" /> </geometry> </collision> </link> <joint name="joint_5" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_2" /> <child link="con_3" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_3"> <inertial> <origin xyz="-0.66035 1.2375E-07 0.022176" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-5.2286E-07" ixz="0.013648" iyy="3.0095" iyz="1.0857E-09" izz="3.0504" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_3.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_3.STL" /> </geometry> </collision> </link> <joint name="joint_6" type="revolute"> <origin xyz="0 0 0" rpy="1.5708 0 0" /> <parent link="con_3" /> <child link="link_3" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_4"> <inertial> <origin xyz="-4.1467E-11 -1.2546E-08 -1.5501E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="3.9983E-13" ixz="-4.006E-13" iyy="5.0984E-07" iyz="8.0388E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_4.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_4.STL" /> </geometry> </collision> </link> <joint name="joint_7" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_3" /> <child link="con_4" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_4"> <inertial> <origin xyz="-0.78885 -0.022176 1.2375E-07" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-0.013648" ixz="-5.2286E-07" iyy="3.0504" iyz="-1.0857E-09" izz="3.0095" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_4.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_4.STL" /> </geometry> </collision> </link> <joint name="joint_8" type="revolute"> <origin xyz="0 0 0" rpy="-1.5708 0 0" /> <parent link="con_4" /> <child link="link_4" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_5"> <inertial> <origin xyz="-4.1467E-11 1.5501E-08 -1.2546E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="4.006E-13" ixz="3.9983E-13" iyy="5.0984E-07" iyz="-8.0406E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_5.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_5.STL" /> </geometry> </collision> </link> <joint name="joint_9" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_4" /> <child link="con_5" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_5"> <inertial> <origin xyz="-0.91735 1.2375E-07 0.022176" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-5.2286E-07" ixz="0.013648" iyy="3.0095" iyz="1.0857E-09" izz="3.0504" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_5.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_5.STL" /> </geometry> </collision> </link> <joint name="joint_10" type="revolute"> <origin xyz="0 0 0" rpy="1.5707963267949 0 0" /> <parent link="con_5" /> <child link="link_5" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_6"> <inertial> <origin xyz="-4.1467E-11 -1.2546E-08 -1.5501E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="3.9983E-13" ixz="-4.006E-13" iyy="5.0984E-07" iyz="8.0462E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_6.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_6.STL" /> </geometry> </collision> </link> <joint name="joint_11" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_5" /> <child link="con_6" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_6"> <inertial> <origin xyz="-1.0458 -0.022176 1.2375E-07" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-0.013648" ixz="-5.2286E-07" iyy="3.0504" iyz="-1.0857E-09" izz="3.0095" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_6.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_6.STL" /> </geometry> </collision> </link> <joint name="joint_12" type="revolute"> <origin xyz="0 0 0" rpy="-1.5707963267949 0 0" /> <parent link="con_6" /> <child link="link_6" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_7"> <inertial> <origin xyz="-4.1467E-11 1.5501E-08 -1.2546E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="4.006E-13" ixz="3.9983E-13" iyy="5.0984E-07" iyz="-8.0383E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_7.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_7.STL" /> </geometry> </collision> </link> <joint name="joint_13" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_6" /> <child link="con_7" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_7"> <inertial> <origin xyz="-1.1743 1.2375E-07 0.022 176" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-5.2286E-07" ixz="0.013648" iyy="3.0095" iyz="1.0857E-09" izz="3.0504" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_7.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_7.STL" /> </geometry> </collision> </link> <joint name="joint_14" type="revolute"> <origin xyz="0 0 0" rpy="1.5708 0 0" /> <parent link="con_7" /> <child link="link_7" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="con_8"> <inertial> <origin xyz="-4.1467E-11 -1.2546E-08 -1.5501E-08" rpy="0 0 0" /> <mass value="0.011" /> <inertia ixx="8.5802E-07" ixy="3.9983E-13" ixz="-4.006E-13" iyy="5.0984E-07" iyz="8.0342E-19" izz="5.0984E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_8.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/con_8.STL" /> </geometry> </collision> </link> <joint name="joint_15" type="revolute"> <origin xyz="0.1285 0 0" rpy="0 0 0" /> <parent link="link_7" /> <child link="con_8" /> <axis xyz="0 0 1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> <link name="link_8"> <inertial> <origin xyz="-1.3028 -0.022176 1.2375E-07" rpy="0 0 0" /> <mass value="0.0865" /> <inertia ixx="2.7711" ixy="-0.013648" ixz="-5.2286E-07" iyy="3.0504" iyz="-1.0857E-09" izz="3.0095" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_8.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="file://$(find manipulater)/meshes/visual/link_8.STL" /> </geometry> </collision> </link> <joint name="joint_16" type="revolute"> <origin xyz="0 0 0" rpy="-1.5707963267949 0 0" /> <parent link="con_8" /> <child link="link_8" /> <axis xyz="0 0 -1" /> <limit lower="-0.5236" upper="0.5236" effort="2.0" velocity="0.5" /> </joint> </robot>
my launch file
import os from launch import LaunchDescription from launch.actions import ExecuteProcess from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare def generate_launch_description(): robot_name_in_model = 'manipulater' package_name = 'manipulater' urdf_name = "sd_mani.xacro" ld = LaunchDescription() pkg_share = FindPackageShare(package=package_name).find(package_name) urdf_model_path = os.path.join(pkg_share, f'urdf/{urdf_name}') # Start Gazebo servers start_gazebo_cmd = ExecuteProcess( cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], output='screen') # Launch the robot spawn_entity_cmd = Node( package='gazebo_ros', executable='spawn_entity.py', arguments=['-entity', robot_name_in_model, '-file', urdf_model_path ], output='screen') ld.add_action(start_gazebo_cmd) ld.add_action(spawn_entity_cmd) return ld
-
我遇到了一模一样的问题,兄弟后来解决了吗
-
@hitcxy2022 解决了,需要在package.xml文件的<export>标签中加入一行代码
<gazebo_ros gazebo_model_path="${prefix}/.."/>
作用为:通过该行语句可以修改ROS2的markerfile从而使得urdf文件中的package://能够正确解析到install/packagename/share中