Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updating hello-ros example with basic ui #101

Open
wants to merge 12 commits into
base: kinetic
Choose a base branch
from
Open
6 changes: 6 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,9 @@ files/pluginlib_helper/pluginlib_helper.cpp
**/.catkin_tools
**/devel/*
**/logs/*

# Android Studio stuff
**/.idea/*
*.iml


42 changes: 25 additions & 17 deletions example_workspace/src/hello_world_example_app/README.md
Original file line number Diff line number Diff line change
@@ -1,36 +1,44 @@
This is a hello ROS example app. It subscribes to `/chatter` topic and when a message is received, the following message is published in `/a_chatter`:
# Hello ROS (pubsub example - native Android)

data: "hello world from android ndk __COUNTER_VALUE__"
This is a hello ROS example app. It publishes a heartbeat to `/chatter` topic; when a message is received it is also logged using `ROS_INFO`.
The heartbeat looks like this:

USAGE
-------
data: "hello world from android ndk __COUNTER_VALUE__"

1. IP addresses are hardcoded, so you must edit the master URI and the android device ip address in the following file:
## Usage

app/src/main/cpp/main.cpp
1. Build the samples with `install` script using `--samples` option.
If you already have compiled the basic catkin workspace, you can enter the docker container (`docker/run.sh`) and build the samples using `build_catkin_workspace.sh` script using `-w` and `-p` options like this (replace paths with your current configuration if necessary):

2. Build the samples with do_everything script.
/opt/ros_android/scripts/build_catkin_workspace.sh -w /opt/ros_android/example_workspace/ -p /opt/ros_android/output/ -v 1 -b Debug

3. Install the app in your android device using adb -d install as explained here:
2. The APK file should be inside `app/build/outputs/apk/debug`. Install it in your android device using adb -d install as explained here:
<https://developer.android.com/studio/build/building-cmdline>

4. Execute roscore in a terminal with ros sourced. Remember to export first your ip address:
3. Execute roscore in a terminal with ros sourced. Remember to export first your ip address:

export ROS_IP=__YOUR_IP_ADDRESS__

5. Subscribe to /a_chatter in another terminal with ros setup sourced:
4. Subscribe to /chatter in another terminal with ros setup sourced:

rostopic echo /a_chatter
rostopic echo /chatter

You should see the heartbeat coming out.

6. Publish to /chatter, in another terminal with ros setup sourced and ROS_IP exported:
5. Optionally, publish to /chatter, in another terminal with ros setup sourced and ROS_IP exported:

rostopic pub /chatter std_msgs/String "__YOUR_MESSAGE__" -r __PUBLISHING_RATE__

If all is working well, you will receive multiple messages with an incresing counter value.
The message you have sent is logged in android, you can check the result with logcat:
The message you have sent is logged in Android, you can check the result with logcat:

adb logcat

You should see the heartbeat messages as well as any message you publish to `/chatter` topic in Android's log.

### Remapping arguments

adb logcat
You can also remap topics as if you were launching a ROS console application. For example, to remap the topic enter the following:

The log will be like:
/chatter:=/custom_topic

12-13 15:53:36.449 12078 12093 I ROSCPP_NDK_EXAMPLE: __YOUR_MESSAGE__
In this case, you will see the output in `/custom_topic` instead.
Original file line number Diff line number Diff line change
Expand Up @@ -20,29 +20,16 @@ project(hello_ros)

find_package(catkin REQUIRED COMPONENTS roscpp std_msgs rosconsole)

include_directories(${catkin_INCLUDE_DIRS})

# build native_app_glue as a static lib
add_library(native_app_glue STATIC
${ANDROID_NDK}/sources/android/native_app_glue/android_native_app_glue.c)
include_directories(include ${catkin_INCLUDE_DIRS})

# now build app's shared lib
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++11 -Wall -Werror")

# Export ANativeActivity_onCreate(),
# Refer to: https://github.com/android-ndk/ndk/issues/381.
set(CMAKE_SHARED_LINKER_FLAGS
"${CMAKE_SHARED_LINKER_FLAGS} -u ANativeActivity_onCreate")

add_library(native-activity SHARED main.cpp)
add_library(native-activity SHARED src/main/jni/org_ros_android_example_hello_ros_MainActivity_RosThread.cpp src/main/cpp/main.cpp src/main/cpp/main_thread.cpp)

target_include_directories(native-activity PRIVATE
${ANDROID_NDK}/sources/android/native_app_glue)

# add lib dependencies
target_link_libraries(native-activity
android
native_app_glue
${catkin_LIBRARIES}
log
)
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ android {
compileSdkVersion 28

defaultConfig {
applicationId = 'com.example.hello_ros'
applicationId = 'org.ros.android.example.hello_ros'
minSdkVersion 24
targetSdkVersion 26
externalNativeBuild {
Expand All @@ -30,7 +30,7 @@ android {
}
externalNativeBuild {
cmake {
path 'src/main/cpp/CMakeLists.txt'
path 'CMakeLists.txt'
}
}
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#ifndef __ROS_ANDROID_MAIN_THREAD_H__
#define __ROS_ANDROID_MAIN_THREAD_H__

#include <memory>
#include <mutex>
#include <string>

namespace ros_android {
class MainThread {
public:
MainThread();
explicit MainThread(std::string);
virtual ~MainThread() = 0;

typedef std::shared_ptr<MainThread> Ptr;
static Ptr Instance(void);

virtual void run() = 0;
virtual void stop() = 0;
bool check_ros_master(const std::vector<std::pair<std::string, std::string>> remapings);
private:
std::string node_name;

static std::mutex s_instance_mutex;
static Ptr s_instance;
};
} // namespace ros_android

#define MY_ROS_ANDROID_MAIN_THREAD(class_name) \
ros_android::MainThread::Ptr ros_android::MainThread::Instance() { \
Ptr instance = s_instance; \
if (!instance) { \
std::lock_guard<std::mutex> lock(s_instance_mutex); \
if (!s_instance) { \
instance = s_instance = std::make_shared<class_name>(); \
} \
} \
return instance; \
}
#endif // #ifndef __ROS_ANDROID_MAIN_THREAD_H__
Original file line number Diff line number Diff line change
@@ -1,30 +1,23 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- BEGIN_INCLUDE(manifest) -->
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
package="com.example.hello_ros"
package="org.ros.android.example.hello_ros"
android:versionCode="1"
android:versionName="1.0">

<uses-permission android:name="android.permission.ACCESS_NETWORK_STATE"/>
<uses-permission android:name="android.permission.INTERNET"/>
<uses-permission android:name="android.permission.ACCESS_WIFI_STATE"/>

<!-- This .apk has no Java code itself, so set hasCode to false. -->
<application
android:allowBackup="false"
android:fullBackupContent="false"
android:icon="@mipmap/ic_launcher"
android:label="@string/app_name"
android:hasCode="false">
android:hasCode="true">

<!-- Our activity is the built-in NativeActivity framework class.
This will take care of integrating with our NDK code. -->
<activity android:name="android.app.NativeActivity"
<activity android:name="org.ros.android.example.hello_ros.MainActivity"
android:label="@string/app_name"
android:configChanges="orientation|keyboardHidden">
<!-- Tell NativeActivity the name of our .so -->
<meta-data android:name="android.app.lib_name"
android:value="native-activity"/>
<intent-filter>
<action android:name="android.intent.action.MAIN"/>
<category android:name="android.intent.category.LAUNCHER"/>
Expand All @@ -33,4 +26,3 @@
</application>

</manifest>
<!-- END_INCLUDE(manifest) -->
Original file line number Diff line number Diff line change
@@ -1,94 +1,52 @@
#include <stdarg.h>
#include <stdio.h>
#include <functional>
#include <sstream>
#include <map>
#include <string.h>
#include <errno.h>
#include <vector>
#include <set>
#include <fstream>
#include <android/log.h>
#include <string>

#include "ros/ros.h"
#include <ros/ros.h>
#include <ros_android/main_thread.h>
#include <std_msgs/String.h>

#include <android_native_app_glue.h>
class HelloRos : public ros_android::MainThread {
public:
HelloRos() : ros_android::MainThread("hello_ros") {}

int loop_count_ = 0;
ros::Publisher chatter_pub;
virtual void run() override {
/* Write your main code here */
ros::NodeHandle n;
ROS_INFO("Starting hello_ros main thread.");

void chatterCallback(const std_msgs::String::ConstPtr& msg){
ROS_INFO("%s", msg->data.c_str());
loop_count_++;
std_msgs::String msgo;
std::stringstream ss;
ss << "hello world from android ndk " << loop_count_;
msgo.data = ss.str();
chatter_pub.publish(msgo);
ROS_INFO_STREAM(msg->data.c_str());
}
// Creating a publisher and a subscriber; do a loopback in /chatter topic.
chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
ros::Subscriber sub = n.subscribe<std_msgs::String>("chatter", 1000, std::bind(&HelloRos::chatterCallback, this, std::placeholders::_1));

void android_main(android_app *state) {
// Rate 1Hz
ros::WallRate loop_rate(1);

int argc = 3;
int loop_count = 0;
while (ros::ok()) {
ros::spinOnce();

//*********************** NOTE: HARDCODE rosmaster ip addresses in __master, and hardcode the ip address of the android device in __ip *************************
char* argv[] = {const_cast<char*>("nothing_important") , const_cast<char*>("__master:=http://10.34.0.120:11311"), const_cast<char*>("__ip:=10.34.0.121")};
//*********************************************************************************************************************************************************
std_msgs::String msgo;
std::stringstream ss;
ss << "Hello world from android ndk " << loop_count++;
msgo.data = ss.str();
chatter_pub.publish(msgo);

for (int i = 0; i < argc; i++) {
ROS_INFO("%s",argv[i]);
loop_rate.sleep();
}
}

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

ROS_INFO("GOING TO NODEHANDLE");
std::string master_uri = ros::master::getURI();

if (ros::master::check()) {
ROS_INFO("ROS MASTER IS UP!");
} else {
ROS_INFO("NO ROS MASTER.");
virtual void stop() override {
/* Write your clean-up code here */
ros::shutdown();
}
ROS_INFO("%s", master_uri.c_str());

ros::NodeHandle n;

ROS_INFO("GOING TO PUBLISHER");

// Creating a publisher and a subscriber
// When something is received in chatter topic, a message is published in a_chatter topic
chatter_pub = n.advertise<std_msgs::String>("a_chatter", 1000);
ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);

// Rate 1Hz
ros::WallRate loop_rate(1);

while(1) {
int events;
struct android_poll_source* source;
private:
ros::Publisher chatter_pub;

// Poll android events, without locking
while (ALooper_pollAll(0, NULL, &events, (void**)&source) >= 0) {
// Process this event
if (source != NULL) {
source->process(state, source);
}

// Check if we are exiting.
if (state->destroyRequested != 0) {
ROS_INFO("APP DESTROYED BYE BYE");
return;
}
}

ros::spinOnce();

if (!ros::ok()) {
ROS_INFO("ROS ISN'T OK, BYE BYE");
return;
}

loop_rate.sleep();
void chatterCallback(const std_msgs::String::ConstPtr& msg) {
ROS_INFO("Received message: %s", msg->data.c_str());
}
}
};

MY_ROS_ANDROID_MAIN_THREAD(HelloRos)
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include <stdarg.h>
#include <sstream>
#include <utility>
#include <vector>

#include <ros/ros.h>
#include <ros_android/main_thread.h>


namespace ros_android {
std::mutex MainThread::s_instance_mutex;
MainThread::Ptr MainThread::s_instance;
MainThread::MainThread() : node_name("ros_android_node") {}
MainThread::MainThread(std::string name) : node_name(name) {}
MainThread::~MainThread() {}

bool MainThread::check_ros_master(const std::vector<std::pair<std::string, std::string>> remappings) {
bool rv;

ros::init(remappings, node_name.c_str());
rv = ros::master::check();
if (rv) {
ROS_INFO("ROS MASTER IS UP!");
} else {
ROS_INFO("NO ROS MASTER.");
}
ros::start();
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Only call ros::start() if ros::master::check() returns true?

Apparently ros::start() tries to contact the master, logs

ros.roscpp: [registerPublisher] Failed to contact master at [x.x.x.x:11311].  Retrying...

and waits forever. Android then shows the "RosHello isn't responding" dialog.

return rv;
}
}
Loading