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

Ask for permission only when needed #272

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,10 @@ enum RosStatus {
enum TangoStatus {
UNKNOWN,
SERVICE_NOT_CONNECTED,
NEED_TO_REQUEST_ADF_PERMISSION,
ADF_PERMISSION_REQUEST_ANSWERED,
NEED_TO_REQUEST_DATASET_PERMISSION,
DATASET_PERMISSION_REQUEST_ANSWERED,
NO_FIRST_VALID_POSE,
SERVICE_CONNECTED
}
Expand All @@ -128,10 +132,6 @@ enum TangoStatus {
private boolean mMapSaved = false;
private HashMap<String, String> mUuidsNamesHashMap;
private BroadcastReceiver mRestartTangoAlertReceiver;
// True after the user answered the ADF permission popup (the permission has not been necessarily granted).
private boolean mAdfPermissionHasBeenAnswered = false;
// True after the user answered the dataset permission popup (the permission has not been necessarily granted).
private boolean mDatasetPermissionHasBeenAnswered = false;

// UI objects.
private Menu mToolbarMenu;
Expand Down Expand Up @@ -251,7 +251,8 @@ public void run() {
mTangoLightImageView.setImageDrawable(getResources().getDrawable(R.drawable.btn_radio_on_orange_light));
} else if (status == TangoStatus.SERVICE_CONNECTED) {
mTangoLightImageView.setImageDrawable(getResources().getDrawable(R.drawable.btn_radio_on_green_light));
} else {
} else if (status == TangoStatus.SERVICE_NOT_CONNECTED ||
status == TangoStatus.NO_FIRST_VALID_POSE) {
mTangoLightImageView.setImageDrawable(getResources().getDrawable(R.drawable.btn_radio_on_red_light));
}
}
Expand Down Expand Up @@ -419,6 +420,12 @@ public void onTangoStatus(int status) {
Log.e(TAG, "Invalid Tango status " + status);
return;
}
if (status == TangoStatus.NEED_TO_REQUEST_ADF_PERMISSION.ordinal()) {
getTangoPermission(EXTRA_VALUE_ADF, REQUEST_CODE_ADF_PERMISSION);
}
if (status == TangoStatus.NEED_TO_REQUEST_DATASET_PERMISSION.ordinal()) {
getTangoPermission(EXTRA_VALUE_DATASET, REQUEST_CODE_DATASET_PERMISSION);
}
if (status == TangoStatus.SERVICE_CONNECTED.ordinal() && mTangoStatus != TangoStatus.SERVICE_CONNECTED) {
saveUuidsNamestoHashMap();
mParameterNode.setPreferencesFromParameterServer();
Expand Down Expand Up @@ -528,9 +535,8 @@ protected void onActivityResult(int requestCode, int resultCode, Intent data) {
getString(R.string.pref_log_file_default));
mLogger.setLogFileName(logFileName);
mLogger.start();
getTangoPermission(EXTRA_VALUE_ADF, REQUEST_CODE_ADF_PERMISSION);
getTangoPermission(EXTRA_VALUE_DATASET, REQUEST_CODE_DATASET_PERMISSION);
updateSaveMapButton();
initAndStartRosJavaNode();
} else if (requestCode == startSettingsActivityRequest.STANDARD_RUN) {
// It is ok to change the log file name at runtime.
String logFileName = mSharedPref.getString(getString(R.string.pref_log_file_key),
Expand All @@ -550,20 +556,11 @@ protected void onActivityResult(int requestCode, int resultCode, Intent data) {
displayToastMessage(R.string.tango_permission_denied);
}
if (requestCode == REQUEST_CODE_ADF_PERMISSION) {
// The user answered the ADF permission popup (the permission has not been necessarily granted).
mAdfPermissionHasBeenAnswered = true;
mTangoServiceClientNode.publishTangoStatus(TangoStatus.ADF_PERMISSION_REQUEST_ANSWERED.ordinal());
}
if (requestCode == REQUEST_CODE_DATASET_PERMISSION) {
// The user answered the dataset permission popup (the permission has not been necessarily granted).
mDatasetPermissionHasBeenAnswered = true;
if (requestCode == REQUEST_CODE_DATASET_PERMISSION) {
mTangoServiceClientNode.publishTangoStatus(TangoStatus.DATASET_PERMISSION_REQUEST_ANSWERED.ordinal());
}
if (mAdfPermissionHasBeenAnswered && mDatasetPermissionHasBeenAnswered) {
// Both ADF and dataset permissions popup have been answered by the user, the node
// can start.
Log.i(TAG, "initAndStartRosJavaNode");
initAndStartRosJavaNode();
}

}
}

Expand Down Expand Up @@ -685,8 +682,7 @@ public void startMasterChooser() {
boolean appPreviouslyStarted = mSharedPref.getBoolean(getString(R.string.pref_previously_started_key), false);
if (appPreviouslyStarted) {
mLogger.start();
getTangoPermission(EXTRA_VALUE_ADF, REQUEST_CODE_ADF_PERMISSION);
getTangoPermission(EXTRA_VALUE_DATASET, REQUEST_CODE_DATASET_PERMISSION);
initAndStartRosJavaNode();
} else {
Intent intent = new Intent(this, SettingsActivity.class);
startActivityForResult(intent, startSettingsActivityRequest.FIRST_RUN);
Expand All @@ -697,6 +693,7 @@ public void startMasterChooser() {
* This function initializes the tango ros node with RosJava interface.
*/
private void initAndStartRosJavaNode() {
Log.i(TAG, "initAndStartRosJavaNode");
this.nodeMainExecutorService.addListener(new NodeMainExecutorServiceListener() {
@Override
public void onShutdown(NodeMainExecutorService nodeMainExecutorService) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,20 +63,47 @@ public void onStart(ConnectedNode connectedNode) {
setPreferencesFromParameterServer();
}

public Boolean getBoolParam(String paramName) {
Boolean booleanValue = mConnectedNode.getParameterTree().getBoolean(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), false);
return booleanValue;
}

public Integer getIntParam(String paramName) {
Integer intValue = mConnectedNode.getParameterTree().getInteger(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), 0);
return intValue;
}

public String getStringParam(String paramName) {
String stringValue = mConnectedNode.getParameterTree().getString(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), "");
return stringValue;
}

public void setBoolParam(String paramName, Boolean booleanValue) {
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), booleanValue);
}

public void setIntParam(String paramName, Integer intValue) {
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), intValue);
}

public void setStringParam(String paramName, String stringValue) {
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), stringValue);
}

// Set ROS params according to preferences.
public void uploadPreferencesToParameterServer() {
for (String paramName : mParamNames.keySet()) {
if (mParamNames.get(paramName) == "boolean") {
Boolean booleanValue = mSharedPreferences.getBoolean(paramName, false);
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), booleanValue);
setBoolParam(paramName, booleanValue);
}
if (mParamNames.get(paramName) == "int_as_string") {
String stringValue = mSharedPreferences.getString(paramName, "0");
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), Integer.parseInt(stringValue));
setIntParam(paramName, Integer.parseInt(stringValue));
}
if (mParamNames.get(paramName) == "string") {
String stringValue = mSharedPreferences.getString(paramName, "");
mConnectedNode.getParameterTree().set(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), stringValue);
setStringParam(paramName, stringValue);
}
}
}
Expand All @@ -86,15 +113,15 @@ public void setPreferencesFromParameterServer() {
SharedPreferences.Editor editor = mSharedPreferences.edit();
for (String paramName : mParamNames.keySet()) {
if (mParamNames.get(paramName) == "boolean") {
Boolean booleanValue = mConnectedNode.getParameterTree().getBoolean(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), false);
Boolean booleanValue = getBoolParam(paramName);
editor.putBoolean(paramName, booleanValue);
}
if (mParamNames.get(paramName) == "int_as_string") {
Integer intValue = mConnectedNode.getParameterTree().getInteger(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), 0);
Integer intValue = getIntParam(paramName);
editor.putString(paramName, intValue.toString());
}
if (mParamNames.get(paramName) == "string") {
String stringValue = mConnectedNode.getParameterTree().getString(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(paramName), "");
String stringValue = getStringParam(paramName);
editor.putString(paramName, stringValue);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
import org.ros.node.ConnectedNode;
import org.ros.node.service.ServiceClient;
import org.ros.node.service.ServiceResponseListener;
import org.ros.node.topic.Publisher;
import org.ros.node.topic.Subscriber;

import java.util.List;
Expand Down Expand Up @@ -58,6 +59,7 @@ public class TangoServiceClientNode extends AbstractNodeMain {
ConnectedNode mConnectedNode;
private Log mLog;
CallbackListener mCallbackListener;
Publisher<Int8> mStatusPublisher;

public interface CallbackListener {
void onSaveMapServiceCallFinish(boolean success, String message, String mapName, String mapUuid);
Expand All @@ -81,15 +83,23 @@ public void onStart(ConnectedNode connectedNode) {
mConnectedNode = connectedNode;
mLog = connectedNode.getLog();

Subscriber<Int8> subscriber = mConnectedNode.newSubscriber(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(TANGO_STATUS_TOPIC_NAME), Int8._TYPE);
subscriber.addMessageListener(new MessageListener<Int8>() {
mStatusPublisher = mConnectedNode.newPublisher(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(TANGO_STATUS_TOPIC_NAME), Int8._TYPE);
Subscriber<Int8> statusSubscriber = mConnectedNode.newSubscriber(NodeNamespaceHelper.BuildTangoRosNodeNamespaceName(TANGO_STATUS_TOPIC_NAME), Int8._TYPE);
statusSubscriber.addMessageListener(new MessageListener<Int8>() {
@Override
public void onNewMessage(Int8 status) {
mCallbackListener.onTangoStatus(status.getData());
}
});
}

public void publishTangoStatus(int status) {
if (mStatusPublisher == null) return;
Int8 statusMessage = mStatusPublisher.newMessage();
statusMessage.setData((byte) status);
mStatusPublisher.publish(statusMessage);
}

/**
* Wrapper function for ROS service call to avoid code duplication in try catch block.
* @param serviceName Name of the ROS service to be called. Used for error logging.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud2.h>
#include <std_msgs/Int8.h>
#include <tango_ros_messages/GetMapName.h>
#include <tango_ros_messages/GetMapUuids.h>
#include <tango_ros_messages/SaveMap.h>
Expand Down Expand Up @@ -104,6 +105,10 @@ enum LocalizationMode {
enum class TangoStatus {
UNKNOWN = 0,
SERVICE_NOT_CONNECTED,
NEED_TO_REQUEST_ADF_PERMISSION,
ADF_PERMISSION_REQUEST_ANSWERED,
NEED_TO_REQUEST_DATASET_PERMISSION,
DATASET_PERMISSION_REQUEST_ANSWERED,
NO_FIRST_VALID_POSE,
SERVICE_CONNECTED
};
Expand Down Expand Up @@ -192,6 +197,12 @@ class TangoRosNode : public ::nodelet::Nodelet {
bool TangoConnectServiceCallback(
const tango_ros_messages::TangoConnect::Request &request,
tango_ros_messages::TangoConnect::Response& response);
// ROS subscriber callback from tango status topic.
void TangoStatusCallback(const std_msgs::Int8::ConstPtr& msg);
// Request ADF permision via tango status topic and wait until user answers the request.
void RequestADFPermissionAndWaitForAnswer();
// Request dataset permision via tango status topic and wait until user answers the request.
void RequestDatasetPermissionAndWaitForAnswer();

TangoConfig tango_config_;
ros::NodeHandle node_handle_;
Expand Down Expand Up @@ -231,6 +242,7 @@ class TangoRosNode : public ::nodelet::Nodelet {
double laser_scan_min_height_ = -1.0;

ros::Publisher tango_status_publisher_;
ros::Subscriber tango_status_subscriber_;
TangoStatus tango_status_;
bool tango_data_available_ = true;

Expand Down
42 changes: 35 additions & 7 deletions tango_ros_common/tango_ros_native/src/tango_ros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include <dynamic_reconfigure/server.h>
#include <pluginlib/class_list_macros.h>
#include <sensor_msgs/image_encodings.h>
#include <std_msgs/Int8.h>

PLUGINLIB_EXPORT_CLASS(tango_ros_native::TangoRosNode, nodelet::Nodelet)

Expand Down Expand Up @@ -160,6 +159,9 @@ void TangoRosNode::onInit() {
tango_status_publisher_ =
node_handle_.advertise<std_msgs::Int8>(TANGO_STATUS_TOPIC_NAME,
queue_size, latching);
tango_status_subscriber_ = node_handle_.subscribe<std_msgs::Int8>(
TANGO_STATUS_TOPIC_NAME, queue_size, &TangoRosNode::TangoStatusCallback, this);

start_of_service_T_device_publisher_ =
node_handle_.advertise<geometry_msgs::TransformStamped>(
START_OF_SERVICE_T_DEVICE_TOPIC_NAME, queue_size, latching);
Expand Down Expand Up @@ -295,6 +297,20 @@ TangoErrorType TangoRosNode::OnTangoServiceConnected() {
return TANGO_SUCCESS;
}

void TangoRosNode::RequestADFPermissionAndWaitForAnswer() {
UpdateAndPublishTangoStatus(TangoStatus::NEED_TO_REQUEST_ADF_PERMISSION);
while (tango_status_ != TangoStatus::ADF_PERMISSION_REQUEST_ANSWERED) {
ros::Duration(0.1).sleep();
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Is it possible to implement this using a service call? Sleeping does not look like an elegant solution. Why did you choose not to request permissions before connecting on the Java side.

Copy link
Author

Choose a reason for hiding this comment

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

I chose to trigger permission request from the C++ side because this is where we know exactly when and which permission we need. For example, if the user reconnect to Tango using the ros command line tool, the Java side does not know that a service call to /tango/connect has been made.
Here we are using the /tango/status topic to trigger the permission request from C++ to Java, and know when the request has been answered.

Copy link
Contributor

Choose a reason for hiding this comment

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

Is abusing the /tango/status the best way to do this? Why not using a ros service call between the java side (server) and the c++ side (client)?

}

void TangoRosNode::RequestDatasetPermissionAndWaitForAnswer() {
UpdateAndPublishTangoStatus(TangoStatus::NEED_TO_REQUEST_DATASET_PERMISSION);
while (tango_status_ != TangoStatus::DATASET_PERMISSION_REQUEST_ANSWERED) {
ros::Duration(0.1).sleep();
}
}

TangoErrorType TangoRosNode::TangoSetupConfig() {
const char* function_name = "TangoRosNode::TangoSetupConfig()";

Expand All @@ -314,6 +330,8 @@ TangoErrorType TangoRosNode::TangoSetupConfig() {
}
bool create_new_map;
node_handle_.param(CREATE_NEW_MAP_PARAM_NAME, create_new_map, false);
if (create_new_map)
RequestADFPermissionAndWaitForAnswer();
const char* config_enable_learning_mode = "config_enable_learning_mode";
result = TangoConfig_setBool(tango_config_, config_enable_learning_mode, create_new_map);
if (result != TANGO_SUCCESS) {
Expand All @@ -337,6 +355,7 @@ TangoErrorType TangoRosNode::TangoSetupConfig() {
return result;
}
if (localization_mode == LocalizationMode::LOCALIZATION) {
RequestADFPermissionAndWaitForAnswer();
std::string map_uuid_to_load = "";
node_handle_.param<std::string>(LOCALIZATION_MAP_UUID_PARAM_NAME, map_uuid_to_load, "");
const char* config_load_area_description_UUID = "config_load_area_description_UUID";
Expand Down Expand Up @@ -388,12 +407,15 @@ TangoErrorType TangoRosNode::TangoSetupConfig() {
}
std::string dataset_uuid;
node_handle_.param(DATASET_UUID_PARAM_NAME, dataset_uuid, std::string(""));
const char* config_experimental_load_dataset_UUID = "config_experimental_load_dataset_UUID";
result = TangoConfig_setString(tango_config_, config_experimental_load_dataset_UUID, dataset_uuid.c_str());
if (result != TANGO_SUCCESS) {
LOG(ERROR) << function_name << ", TangoConfig_setString "
<< config_experimental_load_dataset_UUID << " error: " << result;
return result;
if (dataset_uuid != "") {
RequestDatasetPermissionAndWaitForAnswer();
const char* config_experimental_load_dataset_UUID = "config_experimental_load_dataset_UUID";
result = TangoConfig_setString(tango_config_, config_experimental_load_dataset_UUID, dataset_uuid.c_str());
if (result != TANGO_SUCCESS) {
LOG(ERROR) << function_name << ", TangoConfig_setString "
<< config_experimental_load_dataset_UUID << " error: " << result;
return result;
}
}
if (point_cloud_manager_ == nullptr) {
int32_t max_point_cloud_elements;
Expand Down Expand Up @@ -508,6 +530,10 @@ void TangoRosNode::UpdateAndPublishTangoStatus(const TangoStatus& status) {
tango_status_publisher_.publish(tango_status_msg);
}

void TangoRosNode::TangoStatusCallback(const std_msgs::Int8::ConstPtr& msg) {
tango_status_ = static_cast<TangoStatus>(msg->data);
}

TangoErrorType TangoRosNode::ConnectToTangoAndSetUpNode() {
if (tango_status_ == TangoStatus::SERVICE_CONNECTED) {
// Connecting twice to Tango results in TANGO_ERROR. Early return to avoid
Expand Down Expand Up @@ -1151,6 +1177,7 @@ bool TangoRosNode::SaveMap(tango_ros_messages::SaveMap::Request &req,
}

std::string TangoRosNode::GetAvailableMapUuidsList() {
RequestADFPermissionAndWaitForAnswer();
char* uuid_list;
TangoErrorType result = TangoService_getAreaDescriptionUUIDList(&uuid_list);
if (result != TANGO_SUCCESS) {
Expand All @@ -1167,6 +1194,7 @@ std::string TangoRosNode::GetAvailableMapUuidsList() {
}

std::string TangoRosNode::GetMapNameFromUuid(const std::string& map_uuid) {
RequestADFPermissionAndWaitForAnswer();
size_t size = 0;
char* value;
TangoAreaDescriptionMetadata metadata;
Expand Down