Hardware Requirements

You'll need a TurtleBot! Don't have one yet?

Instructions

Installation

  1. Make sure you have the OpenNI Kinect Driver Installed:
    sudo apt-get install ros-diamondback-openni-kinect
  2. You'll also need to checkout the following Clearpath Packages:
    svn co http://clearpath-ros-pkg.googlecode.com/svn/trunk/clearpath_kinect ~/clearpath-ros-pkg/clearpath_kinect
    svn co http://clearpath-ros-pkg.googlecode.com/svn/trunk/clearpath_turtlebot ~/clearpath-ros-pkg/clearpath_turtlebot
  3. Add the following line to your '.bashrc' if it does not already exist:
    export ROS_PACKAGE_PATH=${HOME}/clearpath-ros-pkg:${ROS_PACKAGE_PATH}
  4. Compile all Clearpath Stacks:
    rosmake clearpath_kinect
    rosmake clearpath_turtlebot

Demo

Make sure the robot starts with a good amount of floor area in it's view so that it can properly calibrate the floor plane.

Use the launch file

  • roslaunch turtlebot_rndmwalk rndm_walk.launch

The robot will randomly switch between moving left, straight and right. In addition the robot will stop when detecting an obstacle and turn for a random period of time before continuing safe motion. The below video shows what you should expect.

http://www.youtube.com/watch?v=P4tag8NouLA

Nodes

ClearpathTurtleRndmWalk

ClearpathTurtleRndmWalk is a ROS node that reads a frame from the Kinect PointCloud and generates a safe random motion output.

Subscribed Topics

rndmwalk_in(~in) (sensor_msgs/PointCloud2)
  • Get the Kinect Point cloud as a pcl::PointCloud<pcl::PointXYZRGB>.

Published Topics

rndmwalk_out_vel(~out_vel) (geometry_msgs/Twist)
  • Publish the commanded velocity.

Parameters

~in (string, default: "rndmwalk_in")
  • Name of the topic your XYZRGB Point Cloud is on.
~out_vel (string, default: "rndmwalk_out_vel")
  • Name of the topic your cmd_vel should go out on.
~lin_speed (double, default: 0.3)
  • The linear speed for the robot in m/s.
~ang_speed (double, default: 0.75)
  • The angular speed for the robot in rad/s.
~still_ang_speed (double, default: 2.0)
  • The angular speed for the robot in rad/s, when turning in place.
~cam_height (double, default: 0.3)
  • Approximate camera height above the floor plane.
~stop_distance (double, default: 0.8)
  • How close the robot is allowed to come to obstacles.
~stop_point_count (int, default: 50)
  • The number of points that must be inside the stop_distance to warrant an obstacle.

Wiki: turtlebot_rndmwalk (last edited 2011-08-19 00:11:09 by RyanGariepy)