Gazebo 9 crash when setting fixed joint with <preserveFixedJoint>
Gazebo multi-robot simulator, version 9.19.0 ROS Melodic, Ubuntu 18.04.
I am trying to set up a fixed joint as the reference of a Force/Torque Sensor, but when I try to set up the tag
auto-starting new master
process[master]: started with pid [4092]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to d219c242-244d-11ec-860c-004e01bbb965
process[rosout-1]: started with pid [4106]
started core service [/rosout]
process[gazebo-2]: started with pid [4116]
process[gazebo_gui-3]: started with pid [4121]
process[robot_controllers-4]: started with pid [4128]
process[robot_state_publisher-5]: started with pid [4166]
[ INFO] [1633267721.136272631]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1633267721.137314809]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
process[spawn_gazebo_model-6]: started with pid [4193]
[ INFO] [1633267721.248146082]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1633267721.249568248]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[INFO] [1633267721.252466, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1633267721.585929, 0.000000]: Loading model XML from ros parameter robot_description
[INFO] [1633267721.598564, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[ INFO] [1633267722.318645109]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1633267722.319363061]: Attach service at: /link_attacher_node/attach
[ INFO] [1633267722.319962222]: Detach service at: /link_attacher_node/detach
[ INFO] [1633267722.319982246]: Link attacher node initialized.
[ INFO] [1633267722.331300949]: Physics dynamic reconfigure ready.
[INFO] [1633267722.504385, 0.000000]: Calling service /gazebo/spawn_urdf_model
gzserver: /usr/include/boost/smart_ptr/shared_ptr.hpp:734: typename boost::detail::sp_member_access<T>::type boost::shared_ptr<T>::operator->() const [with T = gazebo::physics::Link; typename boost::detail::sp_member_access<T>::type = gazebo::physics::Link*]: Assertion `px != 0' failed.
Service call failed: transport error completing service call: unable to receive data from sender, check sender's logs for details
[ERROR] [1633267722.882935, 0.000000]: Spawn service failed. Exiting.
Aborted (core dumped)
[gazebo-2] process has died [pid 4116, exit code 134, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -u -e ode /root/ros_ws/src/ros_ur3/ur3_gazebo/worlds/cubes_task.world __name:=gazebo __log:=/root/.ros/log/d219c242-244d-11ec-860c-004e01bbb965/gazebo-2.log].
log file: /root/.ros/log/d219c242-244d-11ec-860c-004e01bbb965/gazebo-2*.log
[spawn_gazebo_model-6] process has died [pid 4193, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -urdf -param robot_description -model robot -x 0.11 -z 0.69 -Y -1.5707 -J shoulder_pan_joint 1.57 -J shoulder_lift_joint -1.57 -J elbow_joint 1.26 -J wrist_1_joint -1.57 -J wrist_2_joint -1.57 -unpause __name:=spawn_gazebo_model __log:=/root/.ros/log/d219c242-244d-11ec-860c-004e01bbb965/spawn_gazebo_model-6.log].
log file: /root/.ros/log/d219c242-244d-11ec-860c-004e01bbb965/spawn_gazebo_model-6*.log
[WARN] [1633267751.451230, 0.000000]: Controller Spawner couldn't find the expected controller_manager ROS interface.
This is how I am defining it:
<!-- Robotiq Coupler -->
<!-- + Height added by the coupler: 8mm -->
<!-- + Reference frame: at the middle (4mm) -->
<link name="robotiq_coupler">
<visual>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
<material name="flat_black"/>
</visual>
<collision>
<geometry>
<mesh filename="package://robotiq_description/meshes/robotiq_85_coupler.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="2.073e-05 1.45286e-03 -1.1049e-03" rpy="0 0 0" />
<mass value="0.168" />
<inertia ixx="6.69695624e-05" ixy="5.21511788e-09" ixz="-2.74383009e-08"
iyy="7.85088161e-05" iyz="5.41105193e-07" izz="1.41819717e-04"/>
</inertial>
</link>
<joint name="robotiq_coupler_joint" type="fixed">
<origin xyz="0 0 0.004" rpy="0 0 ${-pi/2.0}" />
<parent link="tool0"/>
<child link="robotiq_coupler"/>
</joint>
<gazebo reference="robotiq_coupler">
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<material>Gazebo/FlatBlack</material>
</gazebo>
<!-- Equivalent to the OpenRAVE manipulator denso_robotiq_85_gripper -->
<link name="ur_gripper_tip_link" />
<joint name="manipulator_dummy_joint" type="fixed">
<origin xyz="0 0 0.1441" rpy="0 0 0" />
<parent link="robotiq_coupler"/>
<child link="ur_gripper_tip_link"/>
</joint>
<!-- Attach the robotiq 85 gripper -->
<xacro:robotiq_85_gripper prefix="" parent="robotiq_coupler" >
<origin xyz="0 0 0.004" rpy="0 ${-pi/2} ${pi}"/>
</xacro:robotiq_85_gripper>
<!-- Gazebo Force/Torque sensor plugin -->
<gazebo reference="robotiq_coupler_joint">
<provideFeedback>true</provideFeedback>
</gazebo>
<gazebo reference="robotiq_coupler_joint">
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>
<gazebo>
<plugin name="ft_sensor" filename="libgazebo_ros_ft_sensor.so">
<updateRate>500.0</updateRate>
<topicName>ft_sensor/raw</topicName>
<gaussianNoise>0.0</gaussianNoise>
<jointName>robotiq_coupler_joint</jointName>
</plugin>
</gazebo>
It used to work just fine, I am trying to update my setup to the changes on the ur_description.
did something change on how to preserve a fixed joint?
or am I doing something wrong? (probably)
Asked by cambel07 on 2021-10-03 08:42:01 UTC
Comments
have you solved this problem?
Asked by CroCo on 2023-05-13 05:13:52 UTC