Skip to content

AIRO-1617 Private ros params #123

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

Merged
merged 3 commits into from
Jan 24, 2022
Merged

AIRO-1617 Private ros params #123

merged 3 commits into from
Jan 24, 2022

Conversation

StephanHasler
Copy link
Contributor

@StephanHasler StephanHasler commented Jan 17, 2022

Proposed change(s)

The ROS parameters /ROS_IP and /ROS_TCP_PORT have been renamed and made private.

 self.tcp_ip = rospy.get_param("~tcp_ip", "127.0.0.1")
 self.tcp_port = rospy.get_param("~tcp_port", 10000)

Global parameters would pollute the ROS namespace and lead to conflicts.
Capital parameter names are very uncommon in ROS.
Parameter names should not include the name ROS, as this does not provide a meaning inside ROS.

The config/param.yaml was removed, as this was used to set the global /ROS_IP.

The endpoint.launch was adjusted, to set the private parameters ~tcp_ip and ~tcp_port.

For this to work, also the default_server_endpoint.py needed to be adjusted.
Before it set a fixed node name 'UnityEndpoint' like:

def main(args=None):
    tcp_server = TcpServer("UnityEndpoint")

    # Start the Server Endpoint
    rospy.init_node(tcp_server.node_name, anonymous=True)

This is basically a bug and very confusing, since it prevents that ROS launch files can set a node's name.

The correct code is:

def main(args=None):
    # Start the Server Endpoint
    rospy.init_node("unity_endpoint", anonymous=True)
    tcp_server = TcpServer(rospy.get_name())
    tcp_server.start()
    rospy.spin()

The default node name was set to 'unity_endpoint' as camel case names are very uncommon to name ROS nodes.
'unity_endpoint' is now also the name assigned to the node in the endpoint.launch. Before the two names were in conflict.

Useful links (GitHub issues, JIRA tickets, forum threads, etc.)

This resolves #115

Types of change(s)

  • Bug fix
  • New feature
  • Code refactor
  • Documentation update
  • Other (please describe)

Testing and Verification

The unittests have been executed. All 38 tests succeeded.
By using the launch file it is possible to change the ROS parameters:

roslaunch ros_tcp_endpoint endpoint.launch tcp_ip:=127.0.0.5 tcp_port:=10005
...
[INFO] [1642421762.502789]: Starting server on 127.0.0.5:10005

Test Configuration:

  • ROS Ubuntu 20.04, ROS Noetic

Checklist

  • Ensured this PR is up-to-date with the dev branch
  • Created this PR to target the dev branch
  • Followed the style guidelines as described in the Contribution Guidelines
  • Added tests that prove my fix is effective or that my feature works
  • Updated the Changelog and described changes in the Unreleased section
  • Updated the documentation as appropriate

Other comments

I think quite some rework of the documentation under:
https://github.com/Unity-Technologies/Unity-Robotics-Hub/blob/main/tutorials/ros_unity_integration/setup.md
is required.
The usage of setparam and rosrun is not correct anymore.
Preferably the use of the endpoint.launch file should be described more.
Please tell me if you like my support for this.

@LaurieCheers-unity
Copy link
Contributor

LaurieCheers-unity commented Jan 18, 2022

Hi, I'll be testing and bringing our tutorials into sync with this PR.

Removing the params.yaml file is a little awkward; currently our Docker environment overwrites this so that users don't have to manually set their IP to 0.0.0.0:
https://github.com/Unity-Technologies/Unity-Robotics-Hub/blob/main/tutorials/ros_unity_integration/ros_docker/set-up-workspace

Are you aware of a simple way to preserve this behaviour? I'm currently considering making a separate launch file for Docker users to invoke, perhaps "endpoint0.launch", that just says:

<include file="endpoint.launch"><arg name="tcp_ip" value="0.0.0.0" /></include>

@StephanHasler
Copy link
Contributor Author

StephanHasler commented Jan 19, 2022

Hi, there are different ways to achieve this:

  1. Change the default in endpoint.launch and server.py to 0.0.0.0. This means the server would per default accept connections from any in-comming IP address. Of course it makes the server more open than using 127.0.0.1. But it is e.g. done in the widely used rosbridge_websocket.launch of the rosbridge_suite.
  2. You can set an environment variable inside the docker, which overrides the default IP of the launch file.
    export DOCKER_IP_OVERRIDE=0.0.0.0
    (maybe find a better name)
    Then the launch file should look like this:
<launch>
    <arg name="tcp_ip" default="$(optenv DOCKER_IP_OVERRIDE 127.0.0.1)"/>
     ...

This is nice since it still allows to change the tcp_ip when calling the launch file.
If you like to start the node with rosrun, however, you would need to check for DOCKER_IP_OVERRIDE also in the server.py.
3. Or your solution with the special launch file.
4. Or just mention in the docs that in a docker:

roslaunch ros_tcp_endpoint endpoint.launch tcp_ip:=0.0.0.0

should be used.

Option 1 is somehow the most simple one, if you do not have security concerns.
Option 2 is convenient for a user, but adds handling of a new variable for the developers.
Option 3 and 4 expect somehow a docker-specific call from the user, which might be not so nice. But in this case I would prefer option 4 as we must only maintain one launch file.

@LaurieCheers-unity
Copy link
Contributor

Thanks for the in-depth analysis! On reflection, I think it's reasonable to change the default IP to 0.0.0.0; any users who have security concerns can set it to something sensible anyway.

@StephanHasler
Copy link
Contributor Author

This is also my preferred solution and it seems to be a common one.
I update the pull request accordingly.

@LaurieCheers-unity LaurieCheers-unity changed the title Private ros params AIRO-1617 Private ros params Jan 24, 2022
@LaurieCheers-unity LaurieCheers-unity changed the base branch from dev-ros to laurie/PrivateRosParams January 24, 2022 21:57
@LaurieCheers-unity LaurieCheers-unity merged commit c7e3ece into Unity-Technologies:laurie/PrivateRosParams Jan 24, 2022
@LaurieCheers-unity
Copy link
Contributor

Thanks for this. Merged into a side branch for testing, but if all goes well it will go into dev-ros today.

@StephanHasler StephanHasler deleted the private_ros_params branch January 26, 2022 08:41
LaurieCheers-unity added a commit that referenced this pull request Jan 26, 2022
* made ros params private
* added default to ros parameter tcp_ip
* set server default address to 0.0.0.0

Co-authored-by: StephanHasler <30526523+StephanHasler@users.noreply.github.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants