Note: This tutorial assumes that you have completed the previous tutorials: building native ROS packages.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Simple Native Activity Application

Description: This tutorial shows how to create a sample Android native application running ROS native nodes, and run it on an Android device

Keywords: Native Activity

Tutorial Level: BEGINNER

Next Tutorial: move_base Native Activity Application

Simple Native Activity Application

The Code

If you've followed the previous tutorial, the sample app code can be found in:

~/ros-android-ndk/roscpp_android/files/sample_app/jni/src/test.cpp

Here you can see the code:

https://raw.githubusercontent.com/creativa77/roscpp_android/master/files/sample_app/jni/src/test.cpp

  11 #include "ros/ros.h"
  12 #include <std_msgs/String.h>
  13 
  14 #include <android_native_app_glue.h>
  15 
  16 int loop_count_ = 0;
  17 ros::Publisher chatter_pub;
  18 
  19 void log(const char *msg, ...) {
  20     va_list args;
  21     va_start(args, msg);
  22     __android_log_vprint(ANDROID_LOG_INFO, "ROSCPP_NDK_EXAMPLE", msg, args);
  23     va_end(args);
  24 }
  25 
  26 
  27 // from android samples
  28 /* return current time in seconds */
  29 static double now(void) {
  30 
  31   struct timespec res;
  32   clock_gettime(CLOCK_REALTIME, &res);
  33   return res.tv_sec + (double) res.tv_nsec / 1e9;
  34 
  35 }
  36 
  37 #define LASTERR strerror(errno)
  38 
  39 void chatterCallback(const std_msgs::StringConstPtr& msg){
  40     ROS_INFO("%s", msg->data.c_str());
  41     loop_count_++;
  42     std_msgs::String msgo;
  43     std::stringstream ss;
  44     ss << "hello world from android ndk " << loop_count_;
  45     msgo.data = ss.str();
  46     chatter_pub.publish(msgo);
  47     log(msg->data.c_str());
  48 }
  49 
  50 void android_main(android_app *papp) {
  51     // Make sure glue isn't stripped
  52     app_dummy();
  53 
  54     int argc = 3;
  55     // TODO: don't hardcode ip addresses
  56     char *argv[] = {"nothing_important" , "__master:=http://192.168.1.100:11311", "__ip:=192.168.1.101"};
  57     //strcpy(argv[0], 'nothing_important');
  58     //argv[1] = '__master:=http://10.52.90.103:11311';
  59     //argv[2] = '__ip:=10.52.90.246';
  60     //argv[3] = '__hostname:=10.52.90.246';
  61     log("GOING TO ROS INIT");
  62 
  63     for(int i = 0; i < argc; i++){
  64         log(argv[i]);
  65     }
  66 
  67     ros::init(argc, &argv[0], "android_ndk_native_cpp");
  68 
  69     log("GOING TO NODEHANDLE");
  70 
  71     std::string master_uri = ros::master::getURI();
  72 
  73     if(ros::master::check()){
  74         log("ROS MASTER IS UP!");
  75     } else {
  76         log("NO ROS MASTER.");
  77     }
  78     log(master_uri.c_str());
  79 
  80     ros::NodeHandle n;
  81 
  82 
  83     log("GOING TO PUBLISHER");
  84 
  85     chatter_pub = n.advertise<std_msgs::String>("a_chatter", 1000);
  86     ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  87     ros::WallRate loop_rate(100);
  88 
  89     log("GOING TO SPIN");
  90 
  91     while(ros::ok() && !papp->destroyRequested){
  92         ros::spinOnce();
  93         loop_rate.sleep();
  94     }
  95 }

The Code Explained

Now, let's break the code down.

  12 #include "ros/ros.h"
  13 #include <std_msgs/String.h>
  14 

We include the usual ROS header ros/ros.h and a message header.

  15 #include <android_native_app_glue.h>
  16 

Android header for using a native activity.

  40 void chatterCallback(const std_msgs::StringConstPtr& msg){
  41     ROS_INFO("%s", msg->data.c_str());
  42     loop_count_++;
  43     std_msgs::String msgo;
  44     std::stringstream ss;
  45     ss << "hello world from android ndk " << loop_count_;
  46     msgo.data = ss.str();
  47     chatter_pub.publish(msgo);
  48     log(msg->data.c_str());
  49 }

We define a callback function for our subscriber.

Our simple node will listen to messages published on the ´chatter´ topic and when it receives a message, we will publish a message to the topic ´a_chatter´.

Main entry point

  51 void android_main(android_app *papp) {
  52     // Make sure glue isn't stripped
  53     app_dummy();
  54 
  55     int argc = 3;
  56     // TODO: don't hardcode ip addresses
  57     char *argv[] = {"nothing_important" , "__master:=http://192.168.1.100:11311", "__ip:=192.168.1.101"};
  58     //strcpy(argv[0], 'nothing_important');
  59     //argv[1] = '__master:=http://10.52.90.103:11311';
  60     //argv[2] = '__ip:=10.52.90.246';
  61     //argv[3] = '__hostname:=10.52.90.246';
  62     log("GOING TO ROS INIT");
  63 
  64     for(int i = 0; i < argc; i++){
  65         log(argv[i]);
  66     }
  67 
  68     ros::init(argc, &argv[0], "android_ndk_native_cpp");
  69 
  70     log("GOING TO NODEHANDLE");
  71 
  72     std::string master_uri = ros::master::getURI();
  73 
  74     if(ros::master::check()){
  75         log("ROS MASTER IS UP!");
  76     } else {
  77         log("NO ROS MASTER.");
  78     }
  79     log(master_uri.c_str());
  80 
  81     ros::NodeHandle n;
  82 
  83 
  84     log("GOING TO PUBLISHER");
  85 
  86     chatter_pub = n.advertise<std_msgs::String>("a_chatter", 1000);
  87     ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  88     ros::WallRate loop_rate(100);
  89 
  90     log("GOING TO SPIN");
  91 
  92     while(ros::ok() && !papp->destroyRequested){
  93         ros::spinOnce();
  94         loop_rate.sleep();
  95     }
  96 }

This is the main entry point of the activity.

  57     char *argv[] = {"nothing_important" , "__master:=http://192.168.1.100:11311", "__ip:=192.168.1.101"};

Here you need to specify "master" to be the URI of your workstation. You also need to set "ip" to the IP address of your Android device.

  68     ros::init(argc, &argv[0], "android_ndk_native_cpp");

Like any ROS program, we do a ´ros::init()´, passing the configuration arguments previously defined and also specifying the name of the node.

  72     std::string master_uri = ros::master::getURI();
  73 
  74     if(ros::master::check()){
  75         log("ROS MASTER IS UP!");
  76     } else {
  77         log("NO ROS MASTER.");
  78     }
  79     log(master_uri.c_str());
  80 
  81     ros::NodeHandle n;

We do a test to check if the specified ROS master is running before creating the nodeHandle.

  86     chatter_pub = n.advertise<std_msgs::String>("a_chatter", 1000);
  87     ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  88     ros::WallRate loop_rate(100);

We create a publisher to the topic ´a_chatter´, a subscriber to the topic ´chatter´ and set the loop time.

  92     while(ros::ok() && !papp->destroyRequested){
  93         ros::spinOnce();
  94         loop_rate.sleep();
  95     }

Lastly we start spinning to get the callback function called when a new message arrives.

Installing app on Android device

First, install android-tools-adb by running:

  • $ sudo apt-get install android-tools-adb

After setting the correct master URI and IP, you need to re-build the app, the easiest way is to run the ´do_docker.sh´ again.

To install the sample app into your Android device, connect the device via an USB cable to your PC (you need to enable Development Mode) and run

  • $ adb install -r output/sample_app/bin/sample_app-debug.apk

Running the sample app

First, launch the roscore in a new terminal window:

  • roscore

Next, run the application on the Android device. Make sure it is on the same network as the ROS Master.

Next, in a new terminal,send a message to the sample app :

  • rostopic pub /chatter std_msgs/String "Hello!" -r 1

Finally, in a new terminal, listen to the published topic from the sample app.

  • rostopic echo a_chatter

You should see something like:

  • hello world from android ndk 1
    hello world from android ndk 2
    hello world from android ndk 3
    hello world from android ndk 4

Congratulations, your ROS Native Activity is running on Android.

Wiki: android_ndk/Tutorials/SimpleNativeActivityApplication (last edited 2015-09-29 14:14:43 by ErnestoCorbellini)