Hi,
I am currently working with ROS Kinetic and Gazebo 7 in a vehicle model.
To simplify things, the model has 4 continuous joints to apply a certain velocity to the model. With the <transmissions>
tag I linked the joints in gazebo with a velocity_controller
interface from ROS_control. In a planar environment the controller just works fine, the problem comes when I test the controllers on terrain with slopes. The vehicle model is huge and has a high mass value (2000 Kg), and that may be the problem.
If I input, let's say and X velocity to the controller, it is unable to reach the target velocity. And it get worse when the model is in a slope and I command it to stop (0 velocity), because the model is unable to stop having always a very small velocity that moves the model very slowly in Gazebo.
I tried to adjust the pid gains of gazebo_ros_control
but always with the same effect depending on the environment: The higher the slope is the more velocity error It outputs.
I am just wondering if there is a way to decrease error in this environment of there are similar problems or works in this community.
I will post here the config file for controllers:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
control_vel:
type: velocity_controllers/JointGroupVelocityController
joints:
- front_left_wheel_joint
- back_left_wheel_joint
- front_right_wheel_joint
- back_right_wheel_joint
/gazebo_ros_control:
pid_gains:
front_left_wheel_joint:
p: 2000.0
i: 0.0
d: 0.0
back_left_wheel_joint:
p: 2000.0
i: 0.0
d: 0.0
front_right_wheel_joint:
p: 2000.0
i: 0.0
d: 0.0
back_right_wheel_joint:
p: 2000.0
i: 0.0
d: 0.0
And the joint description:
<joint name="wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="cont_wheel"/>
<origin xyz="0 0 0" rpy = "0 0 0"/>
<axis xyz="0 1 0" rpy="0 0 0" />
<limit effort="1000" velocity="20"/>
<dynamics damping="0.1" friction="0.1"/>
<joint_properties damping="1.0" friction="1.0"/>
<safety_controller k_velocity="200"/>
</joint>
<transmission name="wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="wheel_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
Thanks in advance.
Originally posted by Weasfas on ROS Answers with karma: 1695 on 2019-10-24
Post score: 0
Original comments
Comment by gvdhoorn on 2019-10-24:
Just a note: velocity_controllers/JointGroupVelocityController is a forwarding command controller. It's in => out
. There is no actual control loop there. So PID values are ignored.
If you want / need a closed-loop controller, you'll have to either switch your vehicle to an effort interface and use effort_controllers/JointVelocityController, or you could create a customised version ..
Comment by gvdhoorn on 2019-10-24:
.. using the ClosedLoopHardwareInterfaceAdapter.
I tried to adjust the pid gains of
gazebo_ros_control
but always with the same effect depending on the environment: The higher the slope is the more velocity error It outputs.
are you referring to the p
, i
and d
values in your .yaml
configuration? As I wrote above, those are not used by the JointGroupVelocityController
that you're using.
Comment by Weasfas on 2019-10-25:
Hi @gvdhoorn,
Thanks for your answer. I decided to implement a new controller to have a close loop. The problem is that Gazebo is always reporting a small velocity on the joint and I am unable to control the platorm in a planar ground.
Besides, I do not understand the difference betweern the gazebo_ros_control
pid gains and the effort_controller
pid gains. I can confirm the pid gains defined in the file I posted are used by gazebo to output new velocity commands because depending on the values I assing there, I have different velocity output for the joint.
Comment by gvdhoorn on 2019-10-26:
Gazebo runs PID controllers itself, internally, depending on how the hardware_interface
interfaces with Gazebo itself.
I don't know how that is implemented. But I can definitely state that PID gains are not used at all by fowarding command controllers (ie: those in ros_controllers
).
Comment by Weasfas on 2019-10-26:
Ok, I am going to try to implement a custom controller knowing this.
Thanks..
Comment by gvdhoorn on 2019-10-26:
Is there anything preventing you from switching your simulated vehicle to an effort interface? That would seem to offer a way forward without requiring any custom code. You'd just have to switch the Gazebo description to an effort hardware_interface
and use effort_controllers/JointVelocityController
in your gazebo_ros_control
configuration.
If your response is going to be: but my actual hw only has a velocity interface, then I don't think that would matter, depending on the level at which you are simulating your vehicle.
In the end the controllers should bring your vehicle to a desired velocity, exactly as it would when using the hardware_interface/VelocityJointInterface
it would seem to me.