justagist / panda_simulator

A Gazebo simulator for the Franka Emika Panda robot with ROS interface, supporting sim-to-real code transfer (Python). Exposes customisable controllers and state feedback from robot in simulation.
Apache License 2.0
210 stars 61 forks source link

Velocity Control Doesn't Work in Simulation #3

Closed peasant98 closed 4 years ago

peasant98 commented 4 years ago

Velocity Control doesn't work in simulation. The Panda just seems to sink down. How can we fix this?

justagist commented 4 years ago

Do you see any error messages? If not, it could be part of the bug that should now be fixed (in 3c923424a85c8b2ddcf525cabe509a3212bb52c9).

peasant98 commented 4 years ago

Hi, I didn't see any error messages, but when I send all zero velocities, the Panda just seems to sink down. Here is a script I put together:

import franka_interface
import rospy
import franka_tools
import time
if __name__ == '__main__':
    rospy.init_node('hiro_panda')
    panda = franka_interface.ArmInterface()
    x = franka_tools.FrankaControllerManagerInterface(ns="panda_simulator",
                                                      sim=True)
    print(x.list_controllers())
    print(x.list_active_controllers(only_motion_controllers=True))
    x.stop_controller(x.joint_position_controller)
    x.start_controller("panda_simulator/velocity_joint_velocity_controller")

    t = 3
    now = time.time()
    while True:
        if time.time() - now >= t:
            break
        panda.set_joint_velocities(dict(zip(panda.joint_names(), [0.0,0.0,0.0,0.0,0,0,0])))
        time.sleep(0.001 / t)

How does it look on your end? Using VelocityJointInterface for me was much better.

justagist commented 4 years ago

Ah, I had forgotten about this.. This is because the gravity compensation controller of the robot is not perfect (especially when it has the gripper), because the dynamic properties of the robot is not provided by the manufacturers, and I use experimentally determined values. The effect of this is evident if you're using velocity or torque controllers on the simulated robot. If you do need gravity, disabling the gripper (use the load_gripper:=false argument when launching panda.world) might improve the performance. However, the best solution would be disabling gravity for your simulation (this is what I have been doing): change value of gravity to zero in panda_gazebo/worlds/panda.world.

By the way, you don't need to explicitly switch controllers; the interface would deal with it automatically, both in simulation and for real robot :) It would automatically choose which controller to use depending on the command you use (set_joint_velocities,set_joint_positions,set_joint_torques, etc.). All you would need to do is:


if __name__ == '__main__':
    rospy.init_node('hiro_panda')
    panda = franka_interface.ArmInterface()

    while True:
        panda.set_joint_velocities(dict(zip(panda.joint_names(), [0.0,0.0,0.0,0.0,0,0,0])))
        time.sleep(0.001)

Also, it is better to get the FrankaControllerManagerInterface associated with the robot directly from the ArmInterface instance to avoid ROS conflicts, than creating a new instance of the controller manager interface. The robot's CM interface can be accessed using the get_controller_manager method.

a-nooj commented 4 years ago

Looks like doing load_gripper:=false results in the entire robot not showing up.

Also, what tuning procedure did you use to converge on the PID gains?

justagist commented 4 years ago

Please make sure you're using the latest update of the repo. The pid gains are the values the franka controller is set to on the actual robot.

a-nooj commented 4 years ago

Ah gotcha.

What about the dynamic properties of the robot? You mentioned you experimentally determined the values -- did you follow a certain procedure or was it trial-and-error?

justagist commented 4 years ago

The dynamics parameters were based on this paper.