Gazebo | Ignition | Community
Ask Your Question
0

robot teleporting to origin with broken joints

asked 2021-08-04 07:38:10 -0500

antoine0richard@gmail.com gravatar image

updated 2021-08-09 07:39:34 -0500

Hi all,

From time to time, all the links of my robot teleport to the origin... I have seen the following issue on GitHub, but I don't know if it is related : https://github.com/osrf/gazebo/issues...

image description

On my robot, I am not using revolute2 joints. And the issue only occurs when the car is turning and driving at 3 m/s. It also happens when I tune the PIDs of the wheels. What am I doing wrong ? I am using Gazebo 9.0 with ROS Melodic on Ubuntu 18.04.

The code: urdf, and control is available here: https://github.com/AntoineRichard/rac...

To reproduce the issue:

roslaunch racecar_description racecar_empty.launch

roslaunch racecar_control spawn_racecar_with_controller.launch namespace:=racecar

rosrun rqt_gui rqt_gui

In the rqt_gui add a publisher plugin: using the upper navigation tabs open the plugins tab, and open the publisher plugin. Then add /racecar/cmd_drive topic, have it publishing at 20Hz. In the drive set the velocity to 1 and put a in the steering_angle: sin(i/10)

Thanks,

Antoine

edit retag flag offensive close merge delete

Comments

Is there a chance you're sending nan or inf values by accident?

azeey gravatar imageazeey ( 2021-08-05 12:18:57 -0500 )edit

As far as I am aware I do not. I checked the messages sent by ROS.

antoine0richard@gmail.com gravatar imageantoine0richard@gmail.com ( 2021-08-06 08:25:14 -0500 )edit

I couldn't replicate the problem locally. Can you provide the steps I'd follow to do to see the issue?

azeey gravatar imageazeey ( 2021-08-06 15:24:37 -0500 )edit

roslaunch racecar_description racecar_empty.launch roslaunch racecar_control spawn_racecar_with_controller.launch namespace:=racecar rostopic pub -r 50 /racecar/cmd_drive "use auto complete" and set the "speed" to 5 or 10 and the "steering angle" to 0.5 or 1.0. It should break.

antoine0richard@gmail.com gravatar imageantoine0richard@gmail.com ( 2021-08-09 04:08:23 -0500 )edit

I pulled the latest changes and tested it locally with speed 10 and steering angle 0.5. SI'm not seeing any issues image description

azeey gravatar imageazeey ( 2021-08-09 17:14:22 -0500 )edit

The very last push seems to fix the issue. The problem came from the type of controllers I had set for the hinges. I used EffortJointControllers which were sending very violent commands (through the internal PID). When I switched to a PositionJointController the only thing that could break the car was playing with the solver settings but that is expected I guess. Thanks a lot for the help :). If you are interested I'll be releasing a bunch of racetracks in a month or so when I can find the time.

antoine0richard@gmail.com gravatar imageantoine0richard@gmail.com ( 2021-08-10 02:48:48 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2021-08-10 03:52:44 -0500

antoine0richard@gmail.com gravatar image

updated 2021-08-10 04:48:33 -0500

I guess the problem came from the type of joint Controllers that were used in the package I started from : https://github.com/mit-racecar/raceca...

In this package, they used the following :

<transmission name="${name}_transmission" type="SimpleTransmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="${name}_joint">
        <hardwareInterface>EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="${name}_motor">
        <hardwareInterface>EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission>

These joints created some violent peaks inside the internal PIDs of rosControl I tried to tune them without success:

image description

Internal PID command in red. (Or I assume it is that, the commands that I send are bounded by [pi/2 -pi/2].)

When I switched from the EffortJointInterface to a PositionJointInterface these peaks disappeared and the car stopped breaking:

<transmission name="${namespace}${hinge_prefix}_hinge_trans" type="SimpleTransmission">
    <type>transmission_interface/SimpleTransmission</type>
    <actuator name="${namespace}${hinge_prefix}_hinge_motor">
        <hardwareInterface>PositionJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
    <joint name="${namespace}${hinge_prefix}_hinge">
        <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
    </joint>
</transmission>

image description

edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2021-08-04 07:38:10 -0500

Seen: 331 times

Last updated: Aug 10 '21