osrf / rmf_demos

Demos to showcase the capabilities of RMF
Apache License 2.0
69 stars 38 forks source link

slotcar plugin for URDF #110

Closed simk0024 closed 3 years ago

simk0024 commented 4 years ago

Hi,

I am trying to run my own robot in the rmf_demo office world. And I have the slotcar plugin integrated in URDF file. However, when sending a loop command to robot, robot is not moving even though the schedule marker have show the path. I think there is a missing link between slotcar plugin to the robot model, please advise.

Thank you.

Yadunund commented 4 years ago

The slotcar plugin is designed to only work for differential drive robots with two wheels. Further, the two revolute joints connecting the wheels to the chassis must be named joint_tire_left and joint_tire_right respectively. Please ensure these criteria are met. If an error still persists, let us know.

simk0024 commented 4 years ago

The two criteria are met, as I am using differential_drive_controller plugin in my urdf. What are the functions of these subscribers and publishers? I am still trying to find out the missing link between this plugin and robot model.

  Subscribers:
    /clock: rosgraph_msgs/msg/Clock
    /map: building_map_msgs/msg/BuildingMap
    /parameter_events: rcl_interfaces/msg/ParameterEvent
    /robot_mode_requests: rmf_fleet_msgs/msg/ModeRequest
    /robot_path_requests: rmf_fleet_msgs/msg/PathRequest
  Publishers:
    /parameter_events: rcl_interfaces/msg/ParameterEvent
    /robot_state: rmf_fleet_msgs/msg/RobotState
    /tf: tf2_msgs/msg/TFMessage
Yadunund commented 4 years ago

To clarify, does your model.sdf load both the slotcar and the differential drive plugins?

simk0024 commented 4 years ago

Yes, I am using URDF instead. Snippets of my URDF.

<gazebo>
  <plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
      <ros>
        <namespace/>
        <argument>--ros-args --remap cmd_vel:=cmd_vel</argument>
        <argument>--ros-args --remap odom:=odom</argument>
      </ros>
      <update_rate>20</update_rate>
      <left_joint>joint_tire_left</left_joint>
      <right_joint>joint_tire_right</right_joint>
      <wheel_separation>0.34</wheel_separation>
      <wheel_diameter>0.14</wheel_diameter>
      <odometry_frame>odom</odometry_frame>
      <max_wheel_torque>30</max_wheel_torque>
      <max_acceleration>0.5</max_acceleration>
      <publish_odom>true</publish_odom>
      <publish_odom_tf>true</publish_odom_tf>
      <robot_base_frame>base_footprint</robot_base_frame>
    </plugin>
    <plugin name="slotcar" filename="libslotcar.so">
      <nominal_drive_speed>0.5</nominal_drive_speed>
      <nominal_drive_acceleration>0.25</nominal_drive_acceleration>
      <max_drive_acceleration>0.75</max_drive_acceleration>
      <nominal_turn_speed>0.6</nominal_turn_speed>
      <nominal_turn_acceleration>1.5</nominal_turn_acceleration>
      <max_turn_acceleration>2.0</max_turn_acceleration>
      <tire_radius>0.1</tire_radius>
      <base_width>0.3206</base_width>
      <stop_distance>0.75</stop_distance>
      <stop_radius>0.75</stop_radius>
    </plugin>
</gazebo>
Yadunund commented 4 years ago

Could you try removing the diff drive plugin and seeing if the robot moves when a task is issued through RMF? The slotcar plugin is responsible for actuating the wheels of the robot when it receives a new rmf_fleet_msgs::PathRequest message. I suspect the diff drive plugin is trying to keep the robot stationary by supplying torque to the robot wheels as no messages are published on /cmd_vel

simk0024 commented 4 years ago

I convert URDF to SDF and it works. Probably slotcar plugin not supporting URDF format...

My observation summary as below:

Yadunund commented 4 years ago

Ah yes the slotcar plugin which is a gazebo model plugin requires SDF format. My bad for overlooking the URDF in your description.

I am not sure about the consequence of having both the diff drive and slotcar plugins loaded into the same model so will advise to only have the slotcar loaded. Are you seeing the overshooting behavior even when only the slotcar is loaded? Could you enable View->Contacts in gazebo and share a recording the wheels contacts when the problem arises?

simk0024 commented 4 years ago

No problem. Currently I am running demos with no diff drive plugin. This is the video link for simulation with contacts view.

Yadunund commented 4 years ago

From the video shared, it looks like the left wheel of the robot does not have proper contact forces acting on it. (You can see the contact appear and disappear at 1:15 mark). Ideally, there should be constant contact throughout. This explains why the robot is not moving as expected. I'd suggest changing the contact geometry to a sphere (works better with the physics engine) and increasing the min_depth surface contact parameter along with tweaking kd and kp values.

Parameters for the Magni robot used in the demo can be found here https://github.com/osrf/rmf_demos/blob/6187bd8085dadc7da1da7b5fadf727accbf1b0b2/rmf_demo_assets/models/Magni/model.sdf#L250-L263

More information on contact parameters is available here http://gazebosim.org/tutorials?tut=physics_params&cat=physics

simk0024 commented 4 years ago

I have slightly increased my wheel radius to make sure it's contact the ground at all time, but this doesn't solve the problem. Actually I observed that even using magni robots, there is similar behaviour but much less serious. I would like to try running navigation stack (ROS1) instead of using slotcar plugin, Is there a guide on such implementation?

aaronchongth commented 4 years ago

Hello there, @simk0024! You can refer to ROBOTIS's guide on using ROS1 navigation stack with a robot in simulation, https://emanual.robotis.com/docs/en/platform/turtlebot3/simulation/. You will then need to refer to the turtlebot3's URDF and make the necessary adjustments to your robot.

Regarding the contact with the ground, are you sure both your wheels are in contact all the time? Because if the whole robot plus wheels is a rigid body, you will get the same results regardless of how large your wheels are, assuming it is the ground plane's geometry issue. My suggestion would be to add a prismatic joint to your wheels to be pushed downwards to ensure constant contact. The MiR100 robot is such an example, https://github.com/osrf/rmf_demos/blob/master/rmf_demo_assets/models/MiR100/model.sdf#L269-L299

You are right that the Magni will suffer the same issues, as it also does not have suspension. Thanks for pointing that out! We will look into fixing it in due time.

simk0024 commented 4 years ago

I am not sure, but when I took a horizontal view on the contact, horizontal view, both wheels seem in contact in all time. I will try adding a prismatic joint to see if problem resolved.

I simulated my robot in gazebo world, and run with teleop, i didn't observe any abnormal behaviour.

The implementation i mentioned above is referring to integration of robot running navigation stack (ROS1) with rmf_core(ROS2)

aaronchongth commented 4 years ago

You can refer to the current iteration of Free Fleet, which should allow you run a ROS 1 navigation stack and work with rmf_core. https://osrf.github.io/ros2multirobotbook/integration_free-fleet.html

Do be warned that, the interface used between rmf_core and free_fleet right now, has been deprecated. And it is advisable to write your own fleet adapters using the newest stable API by rmf_core, https://osrf.github.io/ros2multirobotbook/integration_fleets.html

In the meantime, a full rework of free_fleet is currently underway to be compliant with the newest API of rmf_core

Yadunund commented 3 years ago

Closing due to inactivity.

Feel free to open an issue/discussion here