diff --git a/README.md b/README.md index 4f386f3..dc815e5 100644 --- a/README.md +++ b/README.md @@ -78,6 +78,7 @@ In this file, write the path to your Android SDK and NDK in the following way e. ndk.dir=/opt/android-ndk-r10b sdk.dir=/opt/android-sdk-linux ``` +If you haven't installed the SDK and NDK already, follow the instructions in section [Developing with Android Studio](#developing-with-android-studio). Install catkin tools if necessary. ``` @@ -107,6 +108,12 @@ sudo apt-get update sudo apt-get install openjdk-7-jdk echo "export JAVA_HOME=/usr/lib/jvm/java-7-openjdk-amd64/" >> ~/.bashrc ``` +In case the build insists of using Java 8 when using Ubuntu 14.04, +check and point to the version installed by android-studio: +``` +cat /opt/android-studio/jre/release +echo "export JAVA_HOME=/opt/android-studio/jre/" >> ~/.bashrc +``` Subsequently, download Android Studio from [here](https://developer.android.com/studio/index.html) and unzip (for example) to /opt/android-studio: @@ -136,7 +143,7 @@ source ~/tango_ros_ws/devel/setup.bash studio.sh ``` -After launch, open the Configure -- SDK Manager. From SDK Platforms, install Android 4.4 and 5.1 (API level 19 + 22). From SDK Tools, install `NDK` and `Android SDK Build-Tools 21.1.2`. +After launch, open the Configure -- SDK Manager. From SDK Platforms, install Android 4.4 and 5.1 (API level 19 + 22). From SDK Tools, install `NDK` and `Android SDK Build-Tools 21.1.2 + 25.0.2 + 25.0.3`. Now extend your PATH variable so that ```ndk-build``` can be executed: ``` diff --git a/TangoRosStreamer/build.gradle b/TangoRosStreamer/build.gradle index 8b0f2d1..1331df9 100644 --- a/TangoRosStreamer/build.gradle +++ b/TangoRosStreamer/build.gradle @@ -5,7 +5,10 @@ buildscript { jcenter() } dependencies { - classpath 'com.android.tools.build:gradle:2.1.2' + classpath('com.android.tools.build:gradle:2.3.2') { + // In case of versions conflict version above wins. + force = true + } // NOTE: Do not place your application dependencies here; they belong // in the individual module build.gradle files diff --git a/tango_ros_common/tango_ros_native/src/tango_ros_node.cpp b/tango_ros_common/tango_ros_native/src/tango_ros_node.cpp index f072eca..f8b4bf5 100644 --- a/tango_ros_common/tango_ros_native/src/tango_ros_node.cpp +++ b/tango_ros_common/tango_ros_native/src/tango_ros_node.cpp @@ -172,12 +172,6 @@ void TangoRosNode::onInit() { area_description_T_start_of_service_publisher_ = node_handle_.advertise( AREA_DESCRIPTION_T_START_OF_SERVICE_TOPIC_NAME, queue_size, latching); - point_cloud_publisher_ = - node_handle_.advertise( - POINT_CLOUD_TOPIC_NAME, queue_size, latching); - laser_scan_publisher_ = - node_handle_.advertise( - LASER_SCAN_TOPIC_NAME, queue_size, latching); image_transport_.reset(new image_transport::ImageTransport(node_handle_)); try { @@ -187,23 +181,10 @@ void TangoRosNode::onInit() { fisheye_rectified_image_publisher_ = image_transport_->advertise(FISHEYE_RECTIFIED_IMAGE_TOPIC_NAME, queue_size, latching); - color_camera_publisher_ = - image_transport_->advertiseCamera(COLOR_IMAGE_TOPIC_NAME, - queue_size, latching); - color_rectified_image_publisher_ = - image_transport_->advertise(COLOR_RECTIFIED_IMAGE_TOPIC_NAME, - queue_size, latching); } catch (const image_transport::Exception& e) { - LOG(ERROR) << "Error while creating image transport publishers" << e.what(); + LOG(ERROR) << "Error while creating fisheye image transport publishers" << e.what(); } - mesh_marker_publisher_ = - node_handle_.advertise( - COLOR_MESH_TOPIC_NAME, queue_size, latching); - - occupancy_grid_publisher_ = node_handle_.advertise( - OCCUPANCY_GRID_TOPIC_NAME, queue_size, latching); - get_map_name_service_ = node_handle_.advertiseService(GET_MAP_NAME_SERVICE_NAME, boost::bind(&TangoRosNode::GetMapNameServiceCallback, this, _1, _2)); @@ -263,6 +244,46 @@ TangoRosNode::~TangoRosNode() { } TangoErrorType TangoRosNode::OnTangoServiceConnected() { + const uint32_t queue_size = 1; + const bool latching = true; + // Advertise topics that need depth camera and/or color camera only if cameras are enable. + if (enable_depth_) { + point_cloud_publisher_ = + node_handle_.advertise( + POINT_CLOUD_TOPIC_NAME, queue_size, latching); + laser_scan_publisher_ = + node_handle_.advertise( + LASER_SCAN_TOPIC_NAME, queue_size, latching); + } else { + point_cloud_publisher_.shutdown(); + laser_scan_publisher_.shutdown(); + } + if (enable_color_camera_) { + try { + color_camera_publisher_ = + image_transport_->advertiseCamera(COLOR_IMAGE_TOPIC_NAME, + queue_size, latching); + color_rectified_image_publisher_ = + image_transport_->advertise(COLOR_RECTIFIED_IMAGE_TOPIC_NAME, + queue_size, latching); + } catch (const image_transport::Exception& e) { + LOG(ERROR) << "Error while creating color image transport publishers" << e.what(); + } + } else { + color_camera_publisher_.shutdown(); + color_rectified_image_publisher_.shutdown(); + } + if (enable_depth_ && enable_color_camera_) { + mesh_marker_publisher_ = + node_handle_.advertise( + COLOR_MESH_TOPIC_NAME, queue_size, latching); + occupancy_grid_publisher_ = node_handle_.advertise( + OCCUPANCY_GRID_TOPIC_NAME, queue_size, latching); + } else { + mesh_marker_publisher_.shutdown(); + occupancy_grid_publisher_.shutdown(); + } + TangoCoordinateFramePair pair; pair.base = TANGO_COORDINATE_FRAME_START_OF_SERVICE; pair.target = TANGO_COORDINATE_FRAME_DEVICE;