Connecting working Rviz/Moveit setup with Sim custom arm
Hey friends,
I have a custom 4DOF arm I have whipped up and have been slogging through the tutorials but I feel like I am getting turned around easily now.
I am running Kinetic on Ubuntu 16.04 and have my Rviz and Moveit! setup working nicely. It can take plans and execute them as well as work quite nicely with my move group python interface. I have used the MSA to setup my Moveit files, and now would like to simulate my movements in gazebo and eventually tie in the custom arm.
My issue pops up when trying to run the files that were created by the MSA. Running demo_gazebo.launch from /arm_moveit_config yields this error:
[ERROR] [1588933219.280616367]: Failed to build tree: child link [base_link] of joint [dummy_joint] not found
[ERROR] [1588933219.518289973]: Failed to build tree: child link [base_link] of joint [dummy_joint] not found
[ERROR] [1588933219.520045115]: Unable to parse URDF from parameter '/robot_description'
[robot_state_publisher-7] process has died [pid 17994, exit code 255, cmd /opt/ros/kinetic/lib/robot_state_publisher/robot_state_publisher __name:=robot_state_publisher __log:=/home/homefolder/.ros/log/83c0a11e-9115-11ea-ad2a-001c429fcd02/robot_state_publisher-7.log].
log file: /home/homefolder/.ros/log/83c0a11e-9115-11ea-ad2a-001c429fcd02/robot_state_publisher-7*.log
[robot_state_publisher-7] restarting process
process[robot_state_publisher-7]: started with pid [18108]
Which continues to repeat until the program is killed. The Rviz and Gazebo windows pop up, but the model does not appear and they both show signs of error. After killing the program, there is also a warning that pops up before it dies:
Which I am unsure is a contributing factor to the first errors, or a product of them.
I have included my arm.xacro file below as well the launch file I am attempting to call.
Any suggestions or help is greatly appreciated.
m
arm.xacro
<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find version1_desc)/urdf/links_joints.xacro" />
<xacro:include filename="$(find version1_desc)/urdf/arm.gazebo" />
<create/>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/arm</robotNamespace>
</plugin>
</gazebo>
<!--Dummy Link-->
<link name="dummy_link"/>
<!-- Dummy End Effector -->
<joint name="dummy_joint" type="fixed">
<parent link="dummy_link"/>
<child link="base_link"/>
</joint>
<!--Base Link-->
<m_link_mesh_c name = "base_link"
origin_rpy = "0 0 0" origin_xyz = "0 0 0" mass = "1.0"
meshfile = "package://version1_desc/meshes/base_link.dae"
meshscale = "1 1 1"
ixx = "0.00153508333333" ixy = "0" ixz = "0" iyz = "0"
iyy = "0.00153508333333"
izz = "0.00245"
radius = "0.07" length= "0.061"/>
<!--Plat Joint-->
<joint name="plat_joint" type="revolute">
<parent link="base_link"/>
<child link="plat_link"/>
<origin rpy="0 0 0" xyz="0 0 0.0305"/>
<limit lower="-1.5" upper="1.5" effort="1000" velocity="0.5"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name = "trans_plat">
<type> transmission_interface/SimpleTransmission</type>
<joint name= "plat_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name = "motor_plat">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
< ...
I haven't checked your complete URDF, but it's very likely the changes the MSA did to make it "Gazebo compatible" are not complete/entirely correct.
I would suggest to post an issue about this on the MoveIt issue tracker as it should work.
Thank you sir I will do that.
I just wanted to add that I was building the Moveit! package from the arm.xacro file itself. I have a feeling that this may be what is causing some issues with gazebo. I actually used the function in the MSA to create a new "gazebo ready" URDF file for the original arm.xacro file and saved it to my URDF directory. I then used that URDF instead of the .xacro to build a new Moveit! package...
The MSA would make a demo_gazebo.launch with this line:
instead of this one
I was able to get the model to spawn into gazebo.
Is this an appropriate ...(more)
If I understand you correctly, the URDF is the one the MSA makes for you. It includes a nr of changes which are needed for Gazebo.
If your
.xacro
already contains those changes, then it would work of course.Ok thank you again for the prompt reply.
Since you posted a follow-up question it seems like this problem is solved. Please summarize the solution and post it as an answer so others can benefit from it.