jesseweisberg / moveo_ros

ROS packages and Arduino scripts that can be used to control the BCN3D Moveo robotic arm in simulation and real-life.
MIT License
297 stars 126 forks source link

Can't get working in Gazebo #21

Open MrDadaGuy opened 5 years ago

MrDadaGuy commented 5 years ago

I wasn't able to get a gazebo render of the moveo, so I used moveit setup assistant to create a new moveit config directory. This did create a demo_gazebo.launch file and give me an updated URDF containing gazebo meta data. When I bring up rviz it looks good, but in gazebo all of the pieces are jumbled in a pile, not linked properly. Any thoughts? Thanks!

jesseweisberg commented 5 years ago

This may have to do with the fact that the moments of inertia in the URDF's are not accurate and throwing off Gazebo. The physics really have to be accurate for it to work in Gazebo, since it's a physics emulator, as opposed to just a visualization tool like RVIZ.

One solution would be to open the moveo model in a CAD program like SolidWorks that provides accurate moments for each link, and put those correct values into the URDF.

kgjeep commented 3 years ago

this urdf works for me. I have changed the inertias. But the control is not working. I ama working on it.

<?xml version='1.0'?> <robot name="moveo_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">

<link name="base_link">

<collision>
  <origin
    xyz="0 0 .13"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/base_link_col.STL" />
  </geometry>
</collision>
<inertial>
  <origin
    xyz="0.034155 -0.20591 -0.049641"
    rpy="0 0 0" />
  <mass
    value="8.0643" />
  <!--inertia
    ixx="0.11291"
    ixy="0.00066071"
    ixz="-0.00030472"
    iyy="0.089946"
    iyz="0.011461"
    izz="0.19187" /-->
    <inertia
    ixx="0.446"
    ixy="0.0"
    ixz="0.0"
    iyy="0.446"
    iyz="0.0"
    izz="0.853" />
</inertial>

<link name="odom">

<joint name="odom_joint" type="fixed"> <origin xyz="0 0 0" rpy="0 0 0" /> <parent link="odom" /> <child link="base_link" />

<link name="Link_1">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_1.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.75294 0.75294 0.75294 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_1_col.STL" />
  </geometry>
</collision>

<joint name="Joint_1" type="revolute"> <origin xyz="0 -0.2425 .13" rpy="1.5708 9.5417E-17 2.7766" /> <parent link="base_link" /> <child link="Link_1" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Link_2">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_2.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.75294 0.75294 0.75294 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_2_col.STL" />
  </geometry>
</collision>

<joint name="Joint_2" type="revolute"> <origin xyz="0 0.18264 0" rpy="-3.1416 0.95134 1.5708" /> <parent link="Link_1" /> <child link="Link_2" /> <axis xyz="0 -1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Link_3">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_3.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.75294 0.75294 0.75294 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_3_col.STL" />
  </geometry>
</collision>

<joint name="Joint_3" type="revolute"> <origin xyz="0 0 -0.22112" rpy="-3.1416 0.98126 -3.1416" /> <parent link="Link_2" /> <child link="Link_3" /> <axis xyz="0 -1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Link_4">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_4.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.29412 0.29412 0.29412 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_4_col.STL" />
  </geometry>
</collision>

<joint name="Joint_4" type="revolute"> <origin xyz="0.16988 -0.00099213 0" rpy="3.1416 -1.2279 1.5708" /> <parent link="Link_3" /> <child link="Link_4" /> <axis xyz="0.010353 -0.99993 -0.0059382" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Link_5">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_5.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.79216 0.81961 0.93333 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Link_5_col.STL" />
  </geometry>
</collision>

<joint name="Joint_5" type="revolute"> <origin xyz="-0.0021346 0.053041 0.0016936" rpy="-1.5639 -0.091135 -0.00062919" /> <parent link="Link_4" /> <child link="Link_5" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Gripper_Servo_Gear">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Gripper_Servo_Gear.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.9098 0.44314 0.031373 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Gripper_Servo_Gear_col.STL" />
  </geometry>
</collision>

<joint name="Gripper_Servo_Gear_Joint" type="revolute"> <origin xyz="-0.05013 0.01413 0.041516" rpy="0.9321 0.032705 -1.5268" /> <parent link="Link_5" /> <child link="Gripper_Servo_Gear" /> <axis xyz="0 1 0" />

<limit
  lower="0"
  upper="1.5707"
  effort="5"
  velocity="1" />

<link name="Tip_Gripper_Servo">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Tip_Gripper_Servo.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.6 1 0.27843 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Tip_Gripper_Servo_col.STL" />
  </geometry>
</collision>

<joint name="Tip_Gripper_Servo_Joint" type="continuous"> <origin xyz="-0.039906 -0.004 -0.0027473" rpy="-3.1416 -1.5569 -2.0392E-12" /> <parent link="Gripper_Servo_Gear" /> <child link="Tip_Gripper_Servo" /> <axis xyz="0 1 0" />

<limit
  lower="0"
  upper="1.3"
  effort="5"
  velocity="1" />
<mimic joint="Gripper_Servo_Gear_Joint" multiplier="1" offset="0"/> 

<link name="Gripper_Idol_Gear">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Gripper_Idol_Gear.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.058824 0.64706 1 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Gripper_Idol_Gear_col.STL" />
  </geometry>
</collision>

<joint name="Gripper_Idol_Gear_Joint" type="revolute"> <origin xyz="-0.052696 -0.01387 0.038065" rpy="2.2091 -0.040996 1.626" /> <parent link="Link_5" /> <child link="Gripper_Idol_Gear" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5707"
  upper="0"
  effort="5"
  velocity="1" />

<link name="Tip_Gripper_Idol">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Tip_Gripper_Idol.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.79216 0.81961 0.93333 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Tip_Gripper_Idol_col.STL" />
  </geometry>
</collision>

<joint name="Tip_Gripper_Idol_Joint" type="revolute"> <origin xyz="-0.039906 -0.000125 -0.0027473" rpy="3.1416 0.5236 3.1416" /> <parent link="Gripper_Idol_Gear" /> <child link="Tip_Gripper_Idol" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5"
  upper="0"
  effort="5"
  velocity="1" />
<mimic joint="Gripper_Idol_Gear_Joint" multiplier="-1" offset="0"/>

<link name="Pivot_Arm_Gripper_Servo">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Pivot_Arm_Gripper_Servo.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.79216 0.81961 0.93333 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Pivot_Arm_Gripper_Servo_col.STL" />
  </geometry>
</collision>

<joint name="Pivot_Arm_Gripper_Servo_Joint" type="revolute"> <origin xyz="-0.068745 0.00713 0.05" rpy="0.93142 -0.0083007 -1.582" /> <parent link="Link_5" /> <child link="Pivot_Arm_Gripper_Servo" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />
<mimic joint="Gripper_Servo_Gear_Joint" multiplier="1" offset="0"/> 

<link name="Pivot_Arm_Gripper_Idol">

<visual>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Pivot_Arm_Gripper_Idol.STL" />
  </geometry>
  <material
    name="">
    <color
      rgba="0.79216 0.81961 0.93333 1" />
  </material>
</visual>
<collision>
  <origin
    xyz="0 0 0"
    rpy="0 0 0" />
  <geometry>
    <mesh
      filename="package://moveo_urdf/meshes/Pivot_Arm_Gripper_Idol_col.STL" />
  </geometry>
</collision>

<joint name="Pivot_Arm_Gripper_Idol_Joint" type="revolute"> <origin xyz="-0.06867 -0.00687 0.0501" rpy="0.93138 1.7645E-12 -1.5708" /> <parent link="Link_5" /> <child link="Pivot_Arm_Gripper_Idol" /> <axis xyz="0 1 0" />

<limit
  lower="-1.5707"
  upper="1.5707"
  effort="5"
  velocity="1" />
<mimic joint="Gripper_Idol_Gear_Joint" multiplier="1" offset="0"/> 

transmission_interface/SimpleTransmission hardware_interface/PositionJointInterface hardware_interface/PositionJointInterface 1 transmission_interface/SimpleTransmission hardware_interface/PositionJointInterface hardware_interface/PositionJointInterface 1 transmission_interface/SimpleTransmission hardware_interface/PositionJointInterface hardware_interface/PositionJointInterface 1 transmission_interface/SimpleTransmission hardware_interface/PositionJointInterface hardware_interface/PositionJointInterface 1 transmission_interface/SimpleTransmission hardware_interface/PositionJointInterface hardware_interface/PositionJointInterface 1