Maintainer: Mirza A. Shah
Author: Mirza A. Shah
URL: https://github.com/mirzashah/shield_teleop
License: BSD

Overview

shield_teleop is an application for the nVidia SHIELD handheld gaming console. As the SHIELD is a 100% pure Android device, shield_teleop is an Android app. When the app starts running, it will begin publish sensor_msgs/Joy that mimic the messages produced by ps3_teleop on Ubuntu. The app all displays a video stream using image_transport's compressed image messages.

ROS API

shield_teleop

ROS interface for shield_teleop

Subscribed Topics

/usb_cam/image_raw/compressed (sensor_msgs/CompressedImage)
  • Any valid image_transport video stream which will be displayed in the main view

Published Topics

/joy (sensor_msgs/Joy)
  • Continuously publishes joystick messages representing SHIELD joystick state. Mimics PS3 controller.

Building

shield_teleop utilizes rosjava and the complimentary android_core packages in its implementation and requires them as a build dependency.

Command Line

 source ~/rosjava/devel/setup.bash
 mkdir -p ~/shield_teleop_ws/src
 cd ~/shield_teleop_ws/src
 catkin_create_android_repo
 git clone https://github.com/mirzashah/shield_teleop
 cd ~/shield_teleop
 catkin_make

Android Studio

  1. Open Android Studio
  2. Import project
  3. Select ~/shield_teleop_ws/src
  4. Select "shield_teleop" in dropdown menu
  5. Hit "Play" button, this will build and attempt to upload to either device or emulator

== Running ==

  1. On your device select "ROS SHIELD Teleop" from applications.
  2. On startup, you'll be prompted for a ROS master, choose the one that's running on the robot.
  3. You should be now publishing to topic /joy.
  4. Run either pr2_joystick_teleop or turtlebot_joystick.

Wiki: shield_teleop (last edited 2013-08-21 03:39:39 by MirzaShah)