Gazebo | Ignition | Community
Ask Your Question
1

My robot blows up when I launch the controllers [update 2]

asked 2013-08-07 09:36:15 -0600

Arn-O gravatar image

updated 2013-08-12 11:43:08 -0600

EDIT2: I have forked the gazebo_ros_demos package to try a velocity control on the rrbot simple robot.

Here is the link to my repo: https://github.com/Arn-O/gazeborosdemos.git

I have changed something in the configuration files.

VelocityJointInterface and no longer EffortJointInterface:

  <transmission name="tran2">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint2"/>
    <actuator name="motor2">
      <hardwareInterface>VelocityJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

\velocitycontrollers and no longer \effortcontrollers:

rrbot:
  joint1_position_controller:
    type: effort_controllers/JointPositionController
    joint: joint1
    pid: {p: 100.0, i: 0.01, d: 10.0}
  joint2_velocity_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint2
    pid: {p: 100.0, i: 0.01, d: 10.0}

The robot does not explode with this configuration, but I do not have the expected effect. The joint2 is not animated.

EDIT: this is related to the velocity controller. I had another issue before the upgrade, see answer.

Hello.

I have upgraded the source code of the package required for the installation of Gazebo 1.9 and ROS, and now my robot blows up when I launch the controllers. (EDIT: it is fine without the velocity controllers).

Before the controllers:

image description

After:

image description

It looks like everything has collapsed to the origin point of my robot, like if there were no joints.

It was working fine before the update (expect the velocity controller). (EDIT: I had the usse described in the following answer).

Any idea?

Thx in advance!

EDIT: additional details.

Here is the definition of the elements of my robot related to this topic.

...
<joint name="wheel_joint_fl" type="continuous">
  <axis xyz="0 1 0"/>
  <limit effort="${wheel_joint_effort}" velocity="${wheel_joint_velocity}"/>
  <origin xyz="${wheel_offset_x} ${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
  <parent link="caster_link_fl"/>
  <dynamics damping="${wheel_joint_damping}" friction="${wheel_joint_friction}"/>
  <safety_controller k_velocity="${wheel_joint_safety_k_velocity}"/>
  <child link="wheel_link_fl"/>
</joint>
...

Definition of the transmission:

...
<transmission name="wheel_trans_fl">
  <type>transmission_interface/SimpleTransmission</type>
  <joint name="wheel_joint_fl"/>
  <actuator name="wheel_motor_fl">
    <hardwareInterface>EffortJointInterface</hardwareInterface>
    <mechanicalReduction>${wheel_mechanical_reduction}</mechanicalReduction>
  </actuator>
</transmission>
...

Launch file for the controllers:

...  
<node name="controller_spawner" pkg="controller_manager"
    type="spawner" respawn="false" output="screen"
    ns="/youbot" args="--namespace=/youbot
        wheel_joint_fl_velocity_controller
        wheel_joint_fr_velocity_controller
        wheel_joint_bl_velocity_controller
        wheel_joint_br_velocity_controller
        caster_joint_fl_position_controller
        caster_joint_fr_position_controller
        caster_joint_bl_position_controller
        caster_joint_br_position_controller
        arm_joint_1_position_controller
        arm_joint_2_position_controller
        arm_joint_3_position_controller
        arm_joint_4_position_controller
        arm_joint_5_position_controller
        gripper_finger_joint_l_position_controller
        gripper_finger_joint_r_position_controller" />

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find youbot_control)/config/youbot_control.yaml" command="load" /> 
  ...

And parameters of the controllers:

youbot:
  wheel_joint_fl_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint:  wheel_joint_fl
    pid: {p: 100.0, i: 0.01, d: 10.0}
  wheel_joint_fr_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint:  wheel_joint_fr
    pid: {p: 100.0, i: 0.01, d: 10.0}
  wheel_joint_bl_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint:  wheel_joint_bl
    pid: {p: 100.0, i: 0.01, d: 10.0}
  wheel_joint_br_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint:  wheel_joint_br
    pid: {p: 100.0, i: 0.01, d: 10.0}
    ...

I have no error message when the bug is triggered. I do not know if there is a useful log somewhere.

I can create a simple rrbot like with a velocity controller to investigate the point (the tutorial has been very helpful).

edit retag flag offensive close merge delete

Comments

Can you explain what controllers you are running, and how you are running them. What version of ROS are you using? We'll also need to see the controllers.

nkoenig gravatar imagenkoenig ( 2013-08-08 10:44:22 -0600 )edit

Hello Nate. Gazebo = 1.9.5, ROS = hydro, and the controllers come from the source on GitHub. I hope that answer your question, there should be a way to have a detailed log, but I did not find it. I will update the above message with my tries on rrbot.

Arn-O gravatar imageArn-O ( 2013-08-12 11:29:18 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
0

answered 2013-11-15 10:45:54 -0600

frist gravatar image

Hi Am-O, did you manage to solve the problem?

Looks like I have the very same problems here.

See you Flo

edit flag offensive delete link more

Comments

1

Yes, it was related to the inertia values. Some values can crash the robot, especially when they are too small.

Arn-O gravatar imageArn-O ( 2013-11-17 15:04:04 -0600 )edit

Hi, I see. Would you mind posting a working configuration? Thanks.

frist gravatar imagefrist ( 2013-11-17 15:05:59 -0600 )edit

On the same robot ?

Arn-O gravatar imageArn-O ( 2013-11-17 15:14:32 -0600 )edit

On the same robot ?

Arn-O gravatar imageArn-O ( 2013-11-17 15:15:03 -0600 )edit

Hi, yes, on the same robot. This is youbot, right. I'm basically trying to follow the 'quick start' guide at: https://github.com/micpalmia/youbotrostools

Launching 'roslaunch youbot_gazebo youbot.launch' results in a shacking youbot that almost disintegrates.

frist gravatar imagefrist ( 2013-11-17 15:17:46 -0600 )edit
0

answered 2013-08-13 09:29:06 -0600

Igor gravatar image

Hi, I had similar problem in past and in my case the solution was to make PID values smaller.

edit flag offensive delete link more

Comments

_ArnO_ , did this solve your problem?

nkoenig gravatar imagenkoenig ( 2013-09-15 19:48:58 -0600 )edit

At that time it did not solve the issue. My test repo is posted above, open to anyone willing to try. I'm a little bit short of time right now. I gonna have a look at it this evening (french hours).

Arn-O gravatar imageArn-O ( 2013-09-17 02:59:38 -0600 )edit

I cloned your repo and found only a pendulum. Did you push in all of your local changes?

nkoenig gravatar imagenkoenig ( 2013-09-17 09:28:10 -0600 )edit

I will check this evening. I do not see my modification from the GitHub web interface.

Arn-O gravatar imageArn-O ( 2013-09-17 09:37:23 -0600 )edit

Meanwhile, can we clarify something? The basic requirement is to control the velocity of a revolute joint. Do I have to use the plugin effort_controllers/joint_velocity_controller or the plugin velocity_controllers/joint_velocity_controllers?

Arn-O gravatar imageArn-O ( 2013-09-17 09:49:00 -0600 )edit

effort_controllers/joint_velocity_controller will adjust effort (force), using a PID controller, applied to a joint(s) in order to reach a desired velocity. velocity_controllers/joint_velocity_controllers will pass the commanded joint velocity to the joint. The choice of controller depended on your robot.

nkoenig gravatar imagenkoenig ( 2013-09-17 10:31:07 -0600 )edit

I guess this is obvious when you are used to work with real robot. ;) The repo is updated. The idea is to use the effort to control the velocity of the joint1. The robot is the rrbot. With the configuration of the repo, I'm not able to start the controllers (error messages). EDIT: no error message (I have restarted the simulation) but the robot blows up.

Arn-O gravatar imageArn-O ( 2013-09-17 15:51:06 -0600 )edit
0

answered 2018-10-03 10:48:57 -0600

kumpakri gravatar image

updated 2019-08-22 10:14:21 -0600

Thanks everybody for the input. I had the same problem. The model worked fine with every kind of controller except the effort_controllers/joint_velocity_controller. When I wanted to use it, my model kind of exploded or imploded in the simulation. I compute the inertia in the .urdf model automatically according to the mass and size of the links. Only by adjusting the mass the problem disappeared.

The Gazebo has a problem with inertia values or PID values too small or too large. So try to play around with those.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2013-08-07 09:36:15 -0600

Seen: 19,679 times

Last updated: Aug 22 '19