jacknlliu / development-issues

Some issues from my development
MIT License
7 stars 1 forks source link

contact task simulation issues with gazebo and ROS #33

Open jacknlliu opened 6 years ago

jacknlliu commented 6 years ago

Reference

jacknlliu commented 6 years ago

For /joint_states published by joint_state_publisher which providing wrong data after contact, we can use gazebo plugin joint_state_publisher .

For using gazebo plugin joint_state_publisher, we should add the following lines to your URDF

  <gazebo>
      <plugin name="gazebo_joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
        <robotNamespace></robotNamespace>
        <updateRate>200.0</updateRate>
        <jointName>elbow_joint, shoulder_pan_joint, shoulder_lift_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint</jointName>
      </plugin>
  </gazebo>

NOTE: it seems can't get the velocity correctly from universal_robot, and it only gets the should_pan_joint velocity, others are all zero. But it can get the velocity correctly from iiwa robot. It is very strange!

Some useful things to deep into joint state controller issue, see namespaceangles, /joint_states from joint state controller and gazebo plugin joint state publisher.

jacknlliu commented 6 years ago

We have three main issues in this process:

jacknlliu commented 6 years ago

Physics engine will give a very large force(impulse) when robot end-effector has a collision with some fixed object, the magnitude of the force is about 1e4 (also can reference to [1]).

And the contact force will keep vibrating when has collisions, and it is not realistic in the real physical world.

We should solve the contact impulse issue if we want to simulate the contact and make the learned policies more robust.

Some tricks to solve this, for example

Reference

jacknlliu commented 6 years ago

Research about gazebo contact simulation

Reference