Closed ashBabu closed 1 year ago
I'm wondering if this is an issue with the physics and wheel surface parameters or if it is a problem elsewhere. To debug this, can you try lifting the wheels off the ground and plotting the joint states after sending a /cmd_vel
? If the wheels spin at different rates when it's off the ground, then it may be a physics issue.
To lift the wheels off the ground, you can try placing the robot body on a box so that the wheels can spin freely, or by setting gravity to 0 and raising the vehicle off the ground
Looking at your robot_diff_drive.xacro file, I don't see any friction parameters specified. You can use parameters from the diff_drive example in gz-sim as a starting point: https://github.com/gazebosim/gz-sim/blob/9d79b629c9e0fed1c8635e30f06b2c61462f32d8/examples/worlds/diff_drive.sdf#L149-L155
@scpeters : I have tested with gravity = 0, raising the vehicle above ground. The resulting video is here. A rosbag of the /joint_states
is available here and seems empty.
@azeey : I have added the friction parameters and tested but the result looked exactly the same as before.
Out of curiosity, I send a linear only Twist msg to the robot when gravity=0 and robot at 2.5m above ground and it still moved forward video. If friction with ground is necessary for rotation of wheel, this should not happen rt?
I think gravity has no effect. Even though I have set <gravity>0 0 -9.8</gravity>
in the world file, the robot doesn't fall to the ground quickly when I set initial position.z = 1. It's falling down so slow.
https://github.com/gazebosim/gz-sim/assets/10324110/775f71ea-09fe-439a-9b0b-9c609cb9b36f
can you try to see if the wheels on the left and right side of the vehicle are spinning at different rates? For a diff-drive, when you command a twist with a non-zero angular z component, there should be a difference in the left and right wheel spin rates
can you try to see if the wheels on the left and right side of the vehicle are spinning at different rates? For a diff-drive, when you command a twist with a non-zero angular z component, there should be a difference in the left and right wheel spin rates
have you had a chance to try my last suggestion?
Apologies for the delay. The wheels seem to rotate at different velocities.
https://github.com/gazebosim/gz-sim/assets/10324110/40142514-94ff-4e0c-b80a-c569a18bfb59
https://github.com/gazebosim/gz-sim/assets/10324110/477dae6b-530e-45ff-bb66-2dd47f80a4f7
odom
--> base_link
from diff drive plugin not working/tf
tree has only base_link
--> drivewhl_l/r_joint
.I have setup the ros-gz-bridge as shown here.
ok, it does look like your wheels are spinning properly. Looking at your xacro file once more, I see that your joint axes are 0 1 0
, so can you try changing the fdir1
parameter from 0 0 1
to 0 1 0
? Those should match
Thanks @scpeters : It works now. Closing this
I have the same problem. I have the same friction parameters (except my joint axes are "0 0 1"), and I have made sure the fdir1 parameter matches this.
The only difference is that I am using a URDF with <gazebo>
tags like so:
<gazebo reference="left_wheel">
<surface>
<friction>
<ode>
<mu value="1.0"/>
<mu2 value="1.0"/>
<slip1 value="0.035" />
<slip2 value="0" />
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="0 0 1"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</ode>
</friction>
</surface>
</gazebo>
Edit: I realise you were also using a URDF file
Update: I fixed my issue as my joint limits (velocity + effort) were too low.
Ubuntu 22.04, ROS2 Humble, Gazebo Fortress. Installed everything from
apt
reposI have added a diff_drive plugin for my robot as shown in here. Then I launch the simulation using this launch file and press play button (this is done after commenting out the odometry and velocity plugins in the urdf). After which I tried both the following separately.
ign topic -t "/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 1.0}, angular: {z: 1.0}"
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 1.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 1.0}}"
Even though I have specified the angular velocity component, the robot moves only straight as shown in the video. I am also expecting an
odom
-->base_link
transform to be published but is missing.All the work that I am doing is available in my repo skidy and the README provides additional information