Humanoid Teleoperation

Description: Control a humanoid robot using the Kinect.

Submitted By: Taylor Veltrop

Keywords: humanoid teleoperation navigation hobby kinect kondo roboard khr nao wiimote

Summary

Various methods of controlling a Humanoid robot with the Kinect plus game controllers. Arms may be controlled with a direct joint based style or inverse kinematics. The robot may be navigated with torso tracking, mouse style leg gestures, or directly with the game pad. If Wiimotes are used in combination with the Kinect, at least 12 degrees of freedom can be controlled with your arms!

Video

Other Users

Patrick Goebel's Pi Robot: http://www.pirobot.org Patrick is a user and contributer of veltrobot_teleop.

Additionally, according to various mailing lists and forums, people are using veltrobot_teleop as their starting point in Kinect based teleoperation.

Public Exposure

This ikebana video is my favorite example of the teleoperation system. More about that on Robots Dreams.

The user in the video is the editor for Japan's popular Robo Con magazine. The article accompanying this video is on Robots Dreams.

Robo Con magazine coverage of Veltrobot's appearance (Japanese).

Popular Science

New Scientist

Suicide Bots

Engadget

Joystiq

Kotaku

Plastic Pals

I Heart Robotics

Botjunkie

And much more!

How to Reproduce The Veltrobot Video

If a robot equipped with a Roboard is available you may reproduce this in full. Otherwise it can be reproduced strictly in simulation.

Code to Checkout and Build

On the desktop:

  1. Install ros-cturtle-base Note: additional packages may be required to build ni

  2. Install ni

  3. Install veltrop-ros-pkg version 0.2.1:

     svn co https://veltrop-ros-pkg.svn.sourceforge.net/svnroot/veltrop-ros-pkg/tags/0.2.1/veltrop-ros-pkg
    Add paths to veltrobot_data, veltrobot_movement, and veltrobot_teleop to ROS_PACKAGE_PATH
     rosmake veltrobot_teleop veltrobot_movement robot_state_publisher rviz

On the robot if available:

  1. Install ros-cturtle-base

  2. Install veltrop-ros-pkg version 0.2.1:

     svn co https://veltrop-ros-pkg.svn.sourceforge.net/svnroot/veltrop-ros-pkg/tags/0.2.1/veltrop-ros-pkg
    Add paths to all packages in veltrop-ros-pkg to ROS_PACKAGE_PATH
     rosmake veltrobot_teleop veltrobot_movement veltrobot_sensors roboard_sensors roboard_servos robot_state_publisher
  3. The robot may need to be configured. See http://taylor.veltrop.com/robotics/khrhumanoidv2.php?topic=veltrop-ros-pkg for slightly outdated documentation on how to do this.

Running the Demonstration

Run as Simulation Only on the Desktop

  1. Bring up the Veltrobot system:
     roslaunch veltrobot_data run_sim.launch
  2. Launch rviz in another console:
     rosrun rviz rviz

Note that at this point the robot model will not be assembled.

  1. Load up the veltrobot_data/conf/veltrobot_sim.vcg config file in rviz. Set the fixed frame to /world and set the target frame to the fixed frame.
  2. In first console press the 'i' key to send the robot model in rviz an initialization pose.
  3. Bring up the kinect teleoperation:
     roslaunch veltrobot_teleop kinect_teleop.launch

And then calibrate yourself with the Kinect.

Run With Real Robot

First set the ROS_MASTER_URI on your desktop to the address of the robot.

  1. Bring up the Veltrobot system on the robot:
     roslaunch veltrobot_data run.launch
  2. Optional: Launch rviz on the desktop computer:
     rosrun rviz rviz
  3. In first console press the 'i' key to send the robot an initialization pose.
  4. Bring up the kinect teleoperation on the desktop:
     roslaunch veltrobot_teleop kinect_teleop.launch

Note: It is possible to use a PS3 controller's L1 button to enable or disable the kinect control of the robot. The L2 button will enable direct leg control. The code for this is in the 0.2.2 tag and the trunk. The 0.2.1 instructions are given here to match the video and keep things less complicated.

How to Reproduce The NAO Video

Code to Checkout and Build

On the desktop:

  1. Install ros-cturtle-base Note: additional packages may be required to build ni

  2. Install ni

  3. Install nao

  4. Install veltrop-ros-pkg version 0.2.2:

     svn co https://veltrop-ros-pkg.svn.sourceforge.net/svnroot/veltrop-ros-pkg/tags/0.2.2/veltrop-ros-pkg
    Add paths to veltrobot_data, veltrobot_nao, and veltrobot_teleop to ROS_PACKAGE_PATH
     rosmake veltrobot_teleop veltrobot_nao
  5. Edit veltrobot_nao/launch/veltrobot_nao.launch to contain the IP address of your NAO or NAOQI.

Run With Real NAO or Simulated NAOQI

While this is running you may observe NAO and its sensors (IE: video camera) live in Choreograph or Telepathe.

  1. Bring up the kinect system:
     roslaunch veltrobot_teleop kinect_teleop.launch
  2. Bring up the NAO control system in another terminal:
     roslaunch veltrobot_nao veltrobot_nao.launch

Note: If you do not have Wii controllers you can force-enable the Kinect teleoperation by editing the kinect_teleop.launch. Otherwise the NAO's arms will not move. Change:

  • <param name="force_left_arm_enabled" value="false" />
    <param name="force_right_arm_enabled" value="false" /> 

to

  • <param name="force_left_arm_enabled" value="true" />
    <param name="force_right_arm_enabled" value="true" /> 

Dependencies

Software Required:

Software Optional:

  • nao

  • NaoQI simulation

Hardware Required:

  • Kinect

Hardware Optional:

  • Kondo Style Humanoid
  • Roboard Embedded PC
  • NAO Robot
  • 2 Wiimotes
  • PS3 Controller (Used with >= 0.2.2 Kinect teleop for Veltrobot)

How To Use veltrobot_teleop On Your Robot

Simple!

For direct kinect control write up a node that controls your robot based on joint state messages.

For IK control your robot needs to respond to a point message which contains the goal position of a hand.

For the joystick or mouse style leg gesture control you need to respond to a twist.

And for the navigation your robot needs to handle a point as a goal position.

If you can process these messages with your robot, veltrobot_teleop will do the rest.

Version History

Note: The veltrobot_nao package is exceedingly young. There are still has some hard coded nasties in it. It has a lot of useful example code for the NAO. But be warned about using it directly, as it will be overhauled with some abstraction layers to be more readily usable to the community.

0.2.2

  • Kinect Teleoperation node uses 15% less CPU
  • Kinect Teleoperation node is multithreaded
  • Integrated Pi Robot contributed 'mouse' style control
  • Experimental direct leg control
  • Enable/disable Kinect tracking with PS3 controller
  • Integration of dual Wii controllers
  • Interoperation with nao stack
  • Release of veltrobot_nao package to conrol a NAO

0.2.1

  • Fix hardcoded path to openni init xml file

0.2.0

  • Initial contest entry

Wiki: openni/Contests/ROS 3D/Humanoid Teleoperation (last edited 2011-02-02 17:06:06 by TaylorVeltrop)