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

Plumb rclpy.init context to get_default_launch_description #193

Merged
merged 3 commits into from
Mar 7, 2019

Conversation

pbaughman
Copy link
Contributor

@pbaughman pbaughman commented Mar 2, 2019

From #189

This lets you pass a launch context to get_default_launch_description into get_default_launch_description and plumbs it all the way down to the ROSSpecificLaunchStartup launch action.

I couldn't find where rclpy.shutdown is called, so I didn't hook that up anywhere.

I also had to change rclpy.get_global_executor to constructing my own SingleThreadedExecutor because the executor needs to be built with the same context as the node.

This Incomplete!

This is about 50% of what's needed for issue 189. The other half is to make ros2 launch actually use this plumbing. A question for @wjwwood - is it necessary to shut-down the context when we're done, or is it sufficient to just pass a context here?

@tfoote tfoote added the in review Waiting for review (Kanban column) label Mar 2, 2019
Copy link
Member

@wjwwood wjwwood left a comment

Choose a reason for hiding this comment

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

A question for @wjwwood - is it necessary to shut-down the context when we're done, or is it sufficient to just pass a context here?

No need to call shutdown explicitly (it is called automatically by the pycapsule destructor), but if you create a context, it's a nice thing to do when you know it no longer should be used. I'd change this:

launch_service.include_launch_description(
launch_ros.get_default_launch_description(prefix_output_with_name=False))

To be something like this:

context = rclpy.context.Context()
rclpy.init(argv=..., context=context)
launch_service.include_launch_description( 
  launch_ros.get_default_launch_description(prefix_output_with_name=False, context=context)) 
# ...
ret = launch_service.run()
rclpy.shutdown(context=context)
return ret

launch_ros/launch_ros/default_launch_description.py Outdated Show resolved Hide resolved
Copy link
Member

@wjwwood wjwwood left a comment

Choose a reason for hiding this comment

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

lgtm

@wjwwood
Copy link
Member

wjwwood commented Mar 6, 2019

CI:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@wjwwood
Copy link
Member

wjwwood commented Mar 7, 2019

The test failures look unrelated/flaky:

@wjwwood wjwwood merged commit ba26e66 into ros2:master Mar 7, 2019
@wjwwood wjwwood removed the in review Waiting for review (Kanban column) label Mar 7, 2019
@pbaughman pbaughman deleted the launch_ros_with_context branch March 7, 2019 17:32
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.

None yet

3 participants