Gazebo | Ignition | Community
Ask Your Question
0

Velocity controllers and missing P gain

asked 2019-01-04 06:09:58 -0500

kumpakri gravatar image

I am using the VelocityJointController from velocity_controllers to control a robot loaded in Gazebo simulation. I specify PID gains in a .yaml file. However when I launch the simulation, the error pops out

[ERROR] [1546601044.601198350, 0.165000000]: No p gain specified for pid.  Namespace: /robot/gazebo_ros_control/pid_gains/joint_rear_left_wheel

And no metter what PID gains I set, the robot behaves always the same. The PID gains set in .yaml configuration file has no effect on the simulation.

my transmission:

<transmission name="tran_rear_left_wheel">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="joint_rear_left_wheel">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_rear_left_wheel">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
</transmission>

control yaml

imow:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  # Velocity Controllers -----------------------------------------
  joint_rear_left_wheel_controller:
    type: velocity_controllers/JointVelocityController
    joint: joint_rear_left_wheel
    pid: {p: 1, i: 1, d: 1}

What is happening?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2019-10-24 11:00:24 -0500

kumpakri gravatar image

updated 2019-10-24 11:00:57 -0500

Since Weasfas brought this old question up, I can tell now, that velocity_controllers does not use PID for commanding velocity, because the input already is the velocity. It uses PID for controlling positions, however. So if I had controller of type velocity_controllers/JointPositionController, I would need to specify PID parameters and the behavior of the robot would depend on those values.

edit flag offensive delete link more

Comments

not sure how this answers the question. From Control systems perspective, you are right the position part is not needed but how to fix this in Gazebo?

CroCo gravatar imageCroCo ( 2022-05-20 14:55:33 -0500 )edit
0

answered 2019-10-24 05:58:34 -0500

Weasfas gravatar image

Just for the record, with velocity controllers you can define the gains like this:

/gazebo_ros_control:
  pid_gains:
      joint_rear_left_wheel:
          p: 1.0
          i: 1.0
          d: 1.0
edit flag offensive delete link more

Comments

If this required format for velocity controllers?

kumpakri gravatar imagekumpakri ( 2019-10-24 06:24:24 -0500 )edit

but how do you declare that in roslaunch file?

igricart gravatar imageigricart ( 2021-04-06 09:08:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-01-04 06:09:58 -0500

Seen: 2,460 times

Last updated: Oct 24 '19