ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

ROS Services working with ROSJava on Android

asked 2019-07-08 18:46:51 -0500

Tav_PG gravatar image

I have written an Android app. to control a squad of robots using ROSJava. I can create nodes, publish and subscribe to ROS topics, but I am having difficulty in connecting to ROS Services.

I have created a working simple ROS service (client and server) in C++ on ROS Kinetic on the robots (Ubuntu). Now I want to leave the server ROS service on the robot (C++|ROS|Ubuntu) and move the client ROS service onto the Android app. (Kotlin|ROSJava|Windows) that controls to robot.

I have followed the same code structure as best I can in the documentation:

http://rosjava.github.io/rosjava_core...

, and also the rosjava_tutorial_services at:

https://github.com/rosjava/rosjava_co... (but converted from Java to Kotlin).

In my Kotin code, I am missing the part where I compile my equivalent..

rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse

for ServiceClient (and request object), and...

rosjava_test_msgs.AddTwoInts._TYPE

for connectedNode.newServiceClient

Server Code (C++ on ROS Ubuntu)

#include "ros/ros.h"
#include "android_listener/ControlOwner.h"
#include <cstdlib>
#include <string>
#include <iostream>

using namespace std;

string owner = "0.0.0.0";

bool getOwner(  android_listener::ControlOwner::Request &req,
                android_listener::ControlOwner::Response &res) {

    if (req.mode == "?" || req.mode == "?.?.?.?") {
        res.ipaddress = owner;
    } else {
        if (owner == "0.0.0.0" || req.mode == "0.0.0.0") {
            owner = req.mode.c_str();
            res.ipaddress = owner;
        } else {
            res.ipaddress = owner;
        }
    }
    return true;

}

int main(int argc, char **argv) {

    ros::init(argc, argv, "ownership_server");
    ros::NodeHandle nh;
    ros::ServerServer serviceOwner = nh.advertiseService("ownership", getOwner);
    ROS_INFO("Ownership Service is Ready!");

    ros::spin();

    return 0;
}

Client Code (Kotlin on ROSJava Windows)

import org.ros.exception.RemoteException
import org.ros.exception.RosRuntimeException
import org.ros.exception.ServiceNotFoundException
import org.ros.namespace.GraphName
import org.ros.node.AbstractNodeMain
import org.ros.node.ConnectedNode
import org.ros.node.NodeMain
import org.ros.node.service.ServiceClient
import org.ros.node.service.ServiceResponseListener
import android_listener.OwnershipRequest    // Error!
import android_listener.OwnershipResponse   // Error!

/**
 * Client ROS Service
 *
 *  Adapted from: https://github.com/rosjava/rosjava_core/blob/kinetic/rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java
*  @original_author damonkohler@google.com (Damon Kohler)
*/
class SrvClient : AbstractNodeMain() {

    override fun getDefaultNodeName(): GraphName {
        return GraphName.of("ownership_client_test")
    }

    override fun onStart(connectedNode: ConnectedNode?) {
        val serviceClient: ServiceClient<android_listener.OwnershipRequest, android_listener.OwnershipResponse> // Error!
        try {
            serviceClient = connectedNode!!.newServiceClient<OwnershipRequest, OwnershipResponse>("ownership", android_listener.Ownership._TYPE)    // Error!
        } catch (e: ServiceNotFoundException) {
            throw RosRuntimeException(e)
        }

        val request = serviceClient.newMessage()
        request.mode = "?.?.?.?"
        serviceClient.call(request, object : ServiceResponseListener<android_listener.OwnershipResponse> {  // Error!
                override fun onSuccess(response: android_listener.OwnershipResponse) {  // Error!
                    connectedNode.log.info(
                            String.format("%d = %d", request.mode, response.ipaddress))
                }

                override fun onFailure(e: RemoteException) {
                    throw RosRuntimeException(e)
                }
        })
    }
}

So my question is how to I get the android_listener.OwnershipRequest and android_listener.OwnershipResponse dependences from C++ ROS on Ubuntu to Kotlin ROSJava on Android Stuidio (Windows)? Have I missed a step in the documentation? Does anyone know a youTube tutorial on this?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-10-21 08:34:39 -0500

rosmax gravatar image

Hey, I don't really understand your problem. What exactly does your error look like? As far as I understood you seem to ask how to implement a custom service into Android Studio right?

I also had some struggles on how to do it but I found a working solution for it here.

Create your .srv files as you usually would do it in your rosjava workspace. Then run catkin_make to generate your .jar artifacts. After that import your .jar file into your libs folder within Android Studio that is located in your app modules folder where src and build is located too. If that libs folder is nonexistent just create it. So once your .jar file is in libs folder open your module's build.gradle and add the following implementation if it's not already done:

implementation fileTree(include: ['*.jar'], dir: 'libs')

Just build your project and you should be able to use your custom service in your application.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2019-07-08 18:46:51 -0500

Seen: 1,064 times

Last updated: Oct 21 '19