Single primatic joint breaking in cartesian prismatic model

asked 2020-10-08 07:01:59 -0500

hamishCurtin gravatar image

I am currently trying to simulate a fully prismatic cartesian robot in gazebo. My URDF appears to be completely fine in RViz as all joints move the correct way however, when I open it in gazebo the movement in the x axis joint (horizontal bearing movement joint in URDF) will disconnect and the child link and all the ones following it will float away up and down in the y direction (global z but y direction with respect to the child link).

This issue is the last in a long list where I originally had every joint completely disconnecting and falling to the global origin.

I believe this is a URDF issue as the same issue occurs with or without controllers loaded. I have written my URDF below, the broken joint is "horizontal_bearing_movement_joint" I have tried numerous things over a number of week and nothing seems to work. I have triple checked the inertias, all the origins and the link origins when converting STL to dae.

Any help would be amazing as I am losing my mind trying to figure this out. Let me know if more info is required.


<robot name="cartesian_pharmacist">

<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotnamespace>/cartesian_pharmacist</robotnamespace> </plugin> </gazebo>

<link name="world"/>

<joint name="world_joint" type="fixed"> <parent link="world"/> <child link="left_base_link"/> </joint>

<link name="left_base_link"> <inertial> <origin xyz="0.050610 0.063905 0.924653" rpy="0 0 0"/> <mass value="6.945958"/> <inertia ixx="2.254456" ixy="-0.000174" ixz="0.000138" iyy="2.249698" iyz="-0.001422" izz="0.006965"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <mesh filename="package://cartesian_pharmacist_description/meshes/left_base_link.dae"/> </geometry> <material name=""> <color rgba="0.89804 0.91765 0.92941 1"/> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <mesh filename="package://cartesian_pharmacist_description/meshes/left_base_link.dae"/> </geometry> </collision> </link>

<gazebo reference="left_base_link"> <kp>10000.0</kp> <kd>10000.0</kd> <mu1>10.0</mu1> <mu2>10.0</mu2> <selfcollide>true</selfcollide> </gazebo>

<link name="right_base_link"> <inertial> <origin xyz="0.042339 0.071137 0.933934" rpy="0 0 0"/> <mass value="9.594839"/> <inertia ixx="3.049159" ixy="-0.001097" ixz="-0.01778" iyy="3.044318" iyz="0.000266" izz="0.009604"/> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <mesh filename="package://cartesian_pharmacist_description/meshes/right_base_link.dae"/> </geometry> <material name=""> <color rgba="0.89804 0.91765 0.92941 1"/> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <mesh filename="package://cartesian_pharmacist_description/meshes/right_base_link.dae"/> </geometry> </collision> </link>

<gazebo reference="right_base_link"> <kp>10000.0</kp> <kd>10000.0</kd> <mu1>10.0</mu1> <mu2>10.0</mu2> <selfcollide>true</selfcollide> </gazebo>

<joint name="right_base_link_joint" type="fixed"> <origin xyz="5.994 0 ... (more)

edit retag flag offensive close merge delete