Description

ROS package that will automatically dock and undock Rover Robotics rovers. The node use a front mounted camera to detect a specified Aruco Marker, center itself, and proceed towards the dock.

Running auto dock

To run the auto-docking code add the below line to your launch file.

    <node pkg="aruco_detect" name="aruco_detect" type="aruco_detect" output="screen" respawn="false">
      <param name="image_transport" value="$(arg transport)"/>
      <param name="publish_images" value="true" />
      <param name="fiducial_len" value="$(arg fiducial_len)"/>
      <param name="dictionary" value="$(arg dictionary)"/>
      <param name="do_pose_estimation" value="$(arg do_pose_estimation)"/>
      <param name="ignore_fiducials" value="$(arg ignore_fiducials)"/>
      <param name="fiducial_len_override" value="$(arg fiducial_len_override)"/>
      <remap from="/camera/compressed"
          to="$(arg camera)/$(arg image)/$(arg transport)"/>
      <remap from="/camera_info" to="/camera/color/camera_info"/>
    </node>

    <node pkg="rr_auto_dock" type="auto_dock.py" name="auto_dock_node">
      <param name="dock_aruco_number" value="102"/>
      <param name="cmd_vel_angular_rate" value="0.8" />
      <param name="cmd_search_angular_rate" value="0.4" />
      <param name="motor_response_delay" value="0.50" />
      <param name="search_turn_amount" value="0.8" />
    </node>

To start the undocking procedure publish a True std_msgs/Bool value to "/auto_dock/undock".

rostopic pub /auto_dock/undock std_msgs/Bool "true"

To start the docking procedure publish a True std_msgs/Bool value to "/auto_dock/dock".

rostopic pub /auto_dock/dock std_msgs/Bool "true"

Nodes

auto_detect_node

This node is a state machine that includes all docking and undocking behavior. It rotates by small angles until it detects a specific Aruco marker and then proceeds towards the marker until it detects that the rover is charging.

Subscribed Topics

fiducial_transforms (fiducial_msgs/FiducialTransformArray)
  • Topic that published array of transform information for detected Aruco markers from fiducials aruco_detect node.
rr_openrover_driver/charging (std_msgs/Bool)
  • Publishes charging state of the rover. True if charging.
/auto_dock/undock (std_msgs/Bool)
  • When a True message is received begin undocking routine.
/auto_dock/dock (std_msgs/Bool)
  • When a True message is received begin docking routine.
/auto_dock/cancel (std_msgs/Bool)
  • When a True message is received cancel current routine.

Published Topics

/cmd_vel/auto_dock (geometry_msgs/TwistStamped)
  • Publishes the the command velocities. Remap to target desired endpoint.
/auto_dock/state (std_msgs/String)
  • Publishes the current mode state of the auto-docking state machine. . All mode states: 'undocked', 'searching', 'centering', 'approach', 'final_approach', 'final_wiggle', 'docking_failed', 'docked', 'undock'.
/auto_dock/action_state (std_msgs/String)
  • Publishes the action state of the state machine. Actions states represent the behavior of the robot such as moving forward, counting markers, or turning. All action states: 'turning', 'count_aruco_callbacks', 'jogging', 'stopping'.

Parameters

~dock_aruco_number (int, default: 0)
  • The ID code for the Aruco marker attached to the charging dock.
~search_turn_amount (float, default: -0.8)
  • The number of radians to turn while searching for the charging dock's Aruco marker. While in search mode the robot makes incremental turns and stops. This behavior reduces the noise in Aruco detection and allows them to be detected from much further away.
~undock_distance (float, default: 1.0)
  • The distance in meters the robot reverses while undocking.
~undock_turn_amount (float, default: 3.1415)
  • The angle, in radians, to turn after reversing while undocking. The node is naive and does not account for feed back while moving, and instead is timer based. This means that depending on PID tuning, the robot may not turn to the exact angle specified.
~start_delay (float, default: 2.0)
  • The number of seconds to wait before beginning the Docking routine.
~cmd_vel_linear_rate (float, default: 0.25)
  • The linear speed, in meters per second, at which the robot moves during reversal or forward motion.
~cmd_vel_angular_rate (float, default: 0.3)
  • The speed, in radians per second, the robot turns while searching or centering. For the 4 wheel drive due to the increased friction it may be advisable to increase this value.
~motor_response_delay (float, default: 0.05)
  • This increases the duration of the turn timer to compensate for the response delay of the PID. For the 2 wheel drive robot this may be negligible. For the 4 wheel drive robot due to friction, this may be quite a bit higher for lower speeds. 0.25 is recommended for 4 wheel drive configurations.
~action_delay (float, default: 0.3)
  • The number of seconds before the Aruco detection counter begins accepting detection again after the previous action.

Wiki: rr_auto_dock (last edited 2019-12-19 19:38:44 by NicholasPadilla)