小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
moveit配置了自己的机器人后,运行demo和gazebo后,只有rviz中机器人可以动,gazebo中不能动。
-
采用ubuntu18.04 melodic版本
预期结果:用moveit配置后让自己的机械臂在rviz和gazebo一块动。
问题描述:在moveit_config配置文件里,运行demo.launch和gazebo.launch。问题1:终端警告提示节点重名。问题2:rviz中,自己的机械臂可以动,但是gazebo不能同时动。 -
1、urdf中驱动代码:
<!-- Transmissions for ROS Control -->
<xacro:macro name="transmission_block" params="tran_name joint_name motor_name">
<transmission name="${tran_name}">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="$motor_name">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro><xacro:transmission_block tran_name="tran1" joint_name="joint1" motor_name="motor1"/>
<xacro:transmission_block tran_name="tran2" joint_name="joint2" motor_name="motor2"/>
<xacro:transmission_block tran_name="tran3" joint_name="joint3" motor_name="motor3"/>
<xacro:transmission_block tran_name="tran4" joint_name="joint4" motor_name="motor4"/>
<xacro:transmission_block tran_name="tran5" joint_name="joint5" motor_name="motor5"/>
<xacro:transmission_block tran_name="tran6" joint_name="joint6" motor_name="motor6"/>
<xacro:transmission_block tran_name="tran7" joint_name="joint7" motor_name="motor7"/><!--gazebo plugin-->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/arm_z</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo> -
@1113618930 2、目录arm/src/arm_moveit_config/config下gazebo_controllers.yaml代码
# Publish joint_states joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50
-
@1113618930 3、arm/src/arm_moveit_config/config下的ros_controllers.yaml代码
arm_position_controller: type: position_controllers/JointTrajectoryController joints: - joint1 - joint2 - joint3 - joint4 - joint5 - joint6 - joint7 gains: joint1: p: 100 d: 1 i: 1 i_clamp: 1 joint2: p: 100 d: 1 i: 1 i_clamp: 1 joint3: p: 100 d: 1 i: 1 i_clamp: 1 joint4: p: 100 d: 1 i: 1 i_clamp: 1 joint5: p: 100 d: 1 i: 1 i_clamp: 1 joint6: p: 100 d: 1 i: 1 i_clamp: 1 joint7: p: 100 d: 1 i: 1 i_clamp: 1
-
@1113618930 4、arm/src/arm_moveit_config/config下的simple_moveit_controllers.yaml代码
controller_list: - name: arm_position_controller action_ns: follow_joint_trajectory type: FollowJointTrajectory default: True joints: - joint1 - joint2 - joint3 - joint4 - joint5 - joint6 - joint7
-
@1113618930 5、fake_controllers.yaml代码
controller_list: - name: fake_arm_controller type: $(arg fake_execution_type) joints: - joint1 - joint2 - joint3 - joint4 - joint5 - joint6 - joint7 initial: # Define initial robot poses per group - group: arm pose: home
-
@1113618930 6、以下是arm_src/arm_moveit_config/launch文件下的代码
demo.launch代码<launch> <!-- specify the planning pipeline --> <arg name="pipeline" default="ompl" /> <!-- By default, we do not start a database (it can be large) --> <arg name="db" default="false" /> <!-- Allow user to specify database location --> <arg name="db_path" default="$(find arm_moveit_config)/default_warehouse_mongo_db" /> <!-- By default, we are not in debug mode --> <arg name="debug" default="false" /> <!-- By default, we will load or override the robot_description --> <arg name="load_robot_description" default="true"/> <!-- Choose controller manager: fake, simple, or ros_control --> <arg name="moveit_controller_manager" default="fake" /> <!-- Set execution mode for fake execution controllers --> <arg name="fake_execution_type" default="interpolate" /> <!-- By default, hide joint_state_publisher's GUI in 'fake' controller_manager mode --> <arg name="use_gui" default="false" /> <arg name="use_rviz" default="true" /> <!-- If needed, broadcast static tf for robot root --> <group if="$(eval arg('moveit_controller_manager') == 'fake')"> <!-- We do not have a real robot connected, so publish fake joint states via a joint_state_publisher MoveIt's fake controller's joint states are considered via the 'source_list' parameter --> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" unless="$(arg use_gui)"> <rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam> </node> <!-- If desired, a GUI version is available allowing to move the simulated robot around manually This corresponds to moving around the real robot without the use of MoveIt. --> <node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" if="$(arg use_gui)"> <rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam> </node> <!-- Given the published joint states, publish tf for the robot links --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" /> </group> <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) --> <include file="$(dirname)/move_group.launch"> <arg name="allow_trajectory_execution" value="true"/> <arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" /> <arg name="fake_execution_type" value="$(arg fake_execution_type)"/> <arg name="info" value="true"/> <arg name="debug" value="$(arg debug)"/> <arg name="pipeline" value="$(arg pipeline)"/> <arg name="load_robot_description" value="$(arg load_robot_description)"/> </include> <!-- Run Rviz and load the default config to see the state of the move_group node --> <include file="$(dirname)/moveit_rviz.launch" if="$(arg use_rviz)"> <arg name="rviz_config" value="$(dirname)/moveit.rviz"/> <arg name="debug" value="$(arg debug)"/> </include> <!-- If database loading was enabled, start mongodb as well --> <include file="$(dirname)/default_warehouse_db.launch" if="$(arg db)"> <arg name="moveit_warehouse_database_path" value="$(arg db_path)"/> </include> </launch>
-
@1113618930 7、launch文件下gazebo.launch代码
<?xml version="1.0"?> <launch> <!-- Gazebo options --> <arg name="gazebo_gui" default="true" doc="Start Gazebo GUI"/> <arg name="paused" default="false" doc="Start Gazebo paused"/> <arg name="world_name" default="worlds/empty.world" doc="Gazebo world file"/> <arg name="world_pose" default="-x 0 -y 0 -z 0 -R 0 -P 0 -Y 0" doc="Pose to spawn the robot at"/> <arg name="initial_joint_positions" default=" -J joint1 0 -J joint2 0 -J joint3 0 -J joint4 0 -J joint5 0 -J joint6 0 -J joint7 0" doc="Initial joint configuration of the robot"/> <!-- Start Gazebo paused to allow the controllers to pickup the initial pose --> <include file="$(find gazebo_ros)/launch/empty_world.launch" pass_all_args="true"> <arg name="paused" value="true"/> </include> <!-- Set the robot urdf on the parameter server --> <param name="robot_description" command="xacro '$(find arm_z)/urdf/arm_z.xacro'" /> <!-- Unpause the simulation after loading the robot model --> <arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" /> <!-- Spawn the robot in Gazebo --> <node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot $(arg unpause) $(arg world_pose) $(arg initial_joint_positions)" respawn="false" output="screen" /> <!-- Load the controller parameters onto the parameter server --> <rosparam file="$(find arm_moveit_config)/config/gazebo_controllers.yaml" /> <include file="$(dirname)/ros_controllers.launch"/> <!-- Spawn the Gazebo ROS controllers --> <node name="gazebo_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_state_controller" /> <!-- Given the published joint states, publish tf for the robot links --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" /> </launch>
-
@1113618930 launch文件下move_group.launch代码
<launch> <!-- GDB Debug Option --> <arg name="debug" default="false" /> <arg unless="$(arg debug)" name="launch_prefix" value="" /> <arg if="$(arg debug)" name="launch_prefix" value="gdb -x $(dirname)/gdb_settings.gdb --ex run --args" /> <!-- Verbose Mode Option --> <arg name="info" default="$(arg debug)" /> <arg unless="$(arg info)" name="command_args" value="" /> <arg if="$(arg info)" name="command_args" value="--debug" /> <!-- move_group settings --> <arg name="pipeline" default="ompl" /> <arg name="allow_trajectory_execution" default="true"/> <arg name="moveit_controller_manager" default="simple" /> <arg name="fake_execution_type" default="interpolate"/> <arg name="max_safe_path_cost" default="1"/> <arg name="publish_monitored_planning_scene" default="true"/> <arg name="capabilities" default=""/> <arg name="disable_capabilities" default=""/> <!-- load these non-default MoveGroup capabilities (space seperated) --> <!-- <arg name="capabilities" value=" a_package/AwsomeMotionPlanningCapability another_package/GraspPlanningPipeline " /> --> <!-- inhibit these default MoveGroup capabilities (space seperated) --> <!-- <arg name="disable_capabilities" value=" move_group/MoveGroupKinematicsService move_group/ClearOctomapService " /> --> <arg name="load_robot_description" default="false" /> <!-- load URDF, SRDF and joint_limits configuration --> <include file="$(dirname)/planning_context.launch"> <arg name="load_robot_description" value="$(arg load_robot_description)" /> </include> <!-- Planning Pipelines --> <group ns="move_group/planning_pipelines"> <!-- OMPL --> <include file="$(dirname)/planning_pipeline.launch.xml"> <arg name="pipeline" value="ompl" /> </include> <!-- CHOMP --> <include file="$(dirname)/planning_pipeline.launch.xml"> <arg name="pipeline" value="chomp" /> </include> <!-- Pilz Industrial Motion --> <include file="$(dirname)/planning_pipeline.launch.xml"> <arg name="pipeline" value="pilz_industrial_motion_planner" /> </include> <!-- Support custom planning pipeline --> <include if="$(eval arg('pipeline') not in ['ompl', 'chomp', 'pilz_industrial_motion_planner'])" file="$(dirname)/planning_pipeline.launch.xml"> <arg name="pipeline" value="$(arg pipeline)" /> </include> </group> <!-- Trajectory Execution Functionality --> <include ns="move_group" file="$(dirname)/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)"> <arg name="moveit_manage_controllers" value="true" /> <arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" /> <arg name="fake_execution_type" value="$(arg fake_execution_type)" /> </include> <!-- Sensors Functionality --> <include ns="move_group" file="$(dirname)/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)"> <arg name="moveit_sensor_manager" value="arm_z" /> </include> <!-- Start the actual move_group node/action server --> <node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)"> <!-- Set the display variable, in case OpenGL code is used internally --> <env name="DISPLAY" value="$(optenv DISPLAY :0)" /> <param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/> <param name="sense_for_plan/max_safe_path_cost" value="$(arg max_safe_path_cost)"/> <param name="default_planning_pipeline" value="$(arg pipeline)" /> <param name="capabilities" value="$(arg capabilities)" /> <param name="disable_capabilities" value="$(arg disable_capabilities)" /> <!-- do not copy dynamics information from /joint_states to internal robot monitoring default to false, because almost nothing in move_group relies on this information --> <param name="monitor_dynamics" value="false" /> <!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot --> <param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" /> <param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" /> <param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" /> <param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" /> </node> </launch>
-
@1113618930
launch文件下ros_controllers.launch代码<?xml version="1.0"?> <launch> <!-- Load joint controller configurations from YAML file to parameter server --> <rosparam file="$(find arm_moveit_config)/config/ros_controllers.yaml" command="load"/> <!-- Load the controllers --> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="arm_position_controller "/> </launch>
-
此回复已被删除! -
@1113618930 终端命令
[ WARN] [1679122051.973383535]: Shutdown request received. [ WARN] [1679122051.975958574]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [17540] [ WARN] [1679122052.288484066]: Shutdown request received. [ WARN] [1679122052.291101496]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [17556] [ WARN] [1679122052.600755343]: Shutdown request received. [ WARN] [1679122052.603466136]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [WARN] [1679122052.704143, 139.932000]: Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details. [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [17572] [ WARN] [1679122052.917311873]: Shutdown request received. [ WARN] [1679122052.920810009]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [17598]
-
@1113618930 用moveit配置完之后,直接运行的denmo和gazebo,终端就提示这个命令,并且rviz与gazebo不能同时动。
-
此回复已被删除! -
@1113618930
又配置了一遍,终端又出现了错误:同样rviz与gazebo可以显示,但是不能同步运动:以下是先启动rviz 的错误:
process[joint_state_publisher-1]: started with pid [20440] process[robot_state_publisher-2]: started with pid [20441] process[move_group-3]: started with pid [20442] [ WARN] [1679125159.198086958]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. process[rviz_xp_T58_D_20414_8227358618695934036-4]: started with pid [20448] [ INFO] [1679125159.241425579]: Loading robot model 'arm_z'... [ INFO] [1679125159.243132222]: No root/virtual joint specified in SRDF. Assuming fixed joint [ INFO] [1679125159.326448510]: rviz version 1.13.29 [ INFO] [1679125159.326523079]: compiled against Qt version 5.9.5 [ INFO] [1679125159.326555090]: compiled against OGRE version 1.9.0 (Ghadamon) [ INFO] [1679125159.335935604]: Forcing OpenGl version 0. [ WARN] [1679125159.515196390]: Kinematics solver doesn't support #attempts anymore, but only a timeout. Please remove the parameter '/robot_description_kinematics/arm/kinematics_solver_attempts' from your configuration. [ WARN] [1679125159.526468378]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [WARN] [1679125159.681970, 0.000000]: The 'use_gui' parameter was specified, which is deprecated. We'll attempt to find and run the GUI, but if this fails you should install the 'joint_state_publisher_gui' package instead and run that. This backwards compatibility option will be removed in Noetic. [ INFO] [1679125159.842614301]: Stereo is NOT SUPPORTED [ INFO] [1679125159.842681098]: OpenGL device: NVIDIA GeForce GTX 1050/PCIe/SSE2 [ INFO] [1679125159.842705001]: OpenGl version: 4.6 (GLSL 4.6). [ERROR] [1679125160.246825764]: Exception while loading Hybrid: According to the loaded plugin descriptions the class Hybrid with base class type collision_detection::CollisionPlugin does not exist. Declared types are Bullet FCL [ INFO] [1679125160.246912007]: Using collision detector:FCL [ INFO] [1679125160.251768806]: Publishing maintained planning scene on 'monitored_planning_scene' [ INFO] [1679125160.253526995]: Listening to 'joint_states' for joint states [ INFO] [1679125160.256771120]: Listening to '/attached_collision_object' for attached collision objects [ INFO] [1679125160.256815314]: Starting planning scene monitor [ INFO] [1679125160.258797499]: Listening to '/planning_scene'
-
@1113618930
同时启动rviz与gazebo,终端的警告:You can start planning now! [ WARN] [1679125213.502411483]: Shutdown request received. [ WARN] [1679125213.502455394]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [20888] [ WARN] [1679125213.747132877]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125214.017575265]: Shutdown request received. [ WARN] [1679125214.017621904]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21030] [ WARN] [1679125214.255693246]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125214.525132338]: Shutdown request received. [ WARN] [1679125214.525167051]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [WARN] [1679125214.632244, 0.000000]: Inbound TCP/IP connection failed: connection from sender terminated before handshake header received. 0 bytes were received. Please check sender for additional details. [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21054] [ WARN] [1679125214.753356317]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125215.033524088]: Shutdown request received. [ WARN] [1679125215.033575148]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21128] [ WARN] [1679125215.269981472]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125215.660710581]: Shutdown request received. [ WARN] [1679125215.660778343]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21162] [ WARN] [1679125215.874257088]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125216.169900665]: Shutdown request received. [ WARN] [1679125216.169957554]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21181] [ WARN] [1679125216.379792363]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125216.677411048]: Shutdown request received. [ WARN] [1679125216.677442706]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21202] [ WARN] [1679125216.892892923]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125217.184628360]: Shutdown request received. [ WARN] [1679125217.184662972]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21220] [ WARN] [1679125217.411397382]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125217.691337359, 0.870000000]: Shutdown request received. [ WARN] [1679125217.691380020, 0.870000000]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21238] [ WARN] [1679125217.906539940]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125218.198077086, 1.375000000]: Shutdown request received. [ WARN] [1679125218.198118254, 1.375000000]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21257] [ WARN] [1679125218.415009234]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125218.704655363]: Shutdown request received. [ WARN] [1679125218.704693599, 1.881000000]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21275] [ WARN] [1679125218.920581471]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125219.211322184, 2.386000000]: Shutdown request received. [ WARN] [1679125219.211363367, 2.386000000]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21293] [ WARN] [1679125219.425836472]: The root link arm_base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [ WARN] [1679125219.825154504, 2.985000000]: Shutdown request received. [ WARN] [1679125219.825194354, 2.985000000]: Reason given for shutdown: [[/robot_state_publisher] Reason: new node registered with same name] Property::loadValue() TODO: error handling - unexpected QVariant type 0. Property::loadValue() TODO: error handling - unexpected QVariant type 0. [ INFO] [1679125219.951226849, 3.111000000]: Loading robot model 'arm_z'... [ INFO] [1679125219.951290314, 3.111000000]: No root/virtual joint specified in SRDF. Assuming fixed joint [robot_state_publisher-2] process has finished cleanly log file: /home/xp/.ros/log/5bc78226-c54d-11ed-ac96-80fa5b4f16d1/robot_state_publisher-2*.log [robot_state_publisher-2] restarting process process[robot_state_publisher-2]: started with pid [21314]