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

support services run with multiple threads #315

Open
wants to merge 10 commits into
base: master
Choose a base branch
from

Conversation

iuhilnehc-ynos
Copy link

@iuhilnehc-ynos iuhilnehc-ynos commented May 24, 2021

Fixes #314
Signed-off-by: Chen Lihui lihui.chen@sony.com

Chen Lihui added 4 commits May 24, 2021 17:53
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
…ubsciption

Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
@iuhilnehc-ynos
Copy link
Author

This patch is to:

  • make ros2 client call ros1 service via ros1_bridge at the same time if ros1 service is supported with multiple threads (Multi-threaded Spinning).

https://github.com/iuhilnehc-ynos/ros_tutorials/blob/44666088677028f4edeb6246b9f791c489dbb653/roscpp_tutorials/add_two_ints_server/add_two_ints_server.cpp#L57-L59

running ros2 run examples_rclcpp_minimal_client client_main& ros2 run examples_rclcpp_minimal_client client_main to expect this service can serve multiple requests at the same time.

[ INFO] [1621936604.891178820]: request: x=41, y=1
[ INFO] [1621936604.891784270]:   sending back response: [42]
[ INFO] [1621936604.892629346]: request: x=41, y=1
[ INFO] [1621936604.892643574]:   sending back response: [42]
              ^^^^^^^^^//\   the timestamp of two requests are almost same.

without this patch, the log as following,

[ INFO] [1621933196.546494184]: request: x=41, y=1
[ INFO] [1621933196.546513489]:   sending back response: [42]
[ INFO] [1621933198.556169433]: request: x=41, y=1
              ^^^^^^^^^^^^^^^^^^^^^/\   2 sec after to process the next request
[ INFO] [1621933198.556201921]:   sending back response: [42]
  • make ros1 client call ros2 service via ros1_bridge at the same time if ros2 service is supported with multiple threads(MultiThreadExecutor and a callback with reentrant).

https://github.com/iuhilnehc-ynos/ros2-examples/blob/0acb1b892f318ec7898b812d10765f538c93ebc7/rclcpp/services/minimal_service/main.cpp#L44-L46

running rosservice call /add_two_ints '{a: 3, b: 4}'& rosservice call /add_two_ints '{a: 3, b: 4}' expect to get the service log as following

[INFO] [1621936929.275491886] [minimal_service]: request: 3 + 4
[INFO] [1621936929.275632310] [minimal_service]: request: 3 + 4

without this patch, the log as following,

[INFO] [1621937408.339715576] [minimal_service]: request: 3 + 4
[INFO] [1621937410.340892268] [minimal_service]: request: 3 + 4

Notice that supporting the service with running multiple threads is for not only the one service(a custom callback group with reentrant set by user) but also multiple different services.

Could somebody help to review this PR?

@iuhilnehc-ynos iuhilnehc-ynos marked this pull request as ready for review May 25, 2021 10:13
Chen Lihui added 2 commits May 27, 2021 18:11
and resotre the original main loop logic

Signed-off-by: Chen Lihui <lihui.chen@sony.com>
to fix 'Not all nodes were finished before finishing the context'
since ros2 PublisherBase passed into ros1 subscriber as parameter
which might be freed after ros2 context.

Signed-off-by: Chen Lihui <lihui.chen@sony.com>
@iuhilnehc-ynos
Copy link
Author

The failure about The following signatures were invalid: EXPKEYSIG F42ED6FBAB17C654 Open Robotics <info@osrfoundation.org> was mentioned on https://answers.ros.org/question/379190/apt-update-signatures-were-invalid-f42ed6fbab17c654/, I'll run retest this please after the CI is fixed.

Chen Lihui added 2 commits May 31, 2021 16:39
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
auto group = node_base->get_default_callback_group();
if (topic_name.empty()) {
// create a callback group with Reentrant for creating ros2 clients and services
static auto s_shared_callbackgroup =
Copy link
Collaborator

Choose a reason for hiding this comment

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

do we need this static memory? how about returning ros2_node->create_callback_group(rclcpp::CallbackGroupType::Reentrant) instead?

Copy link
Author

Choose a reason for hiding this comment

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

I want to reuse only one callbackgroup for all services and clients.

include/ros1_bridge/factory.hpp Outdated Show resolved Hide resolved
}

typedef std::map<std::string, rclcpp::CallbackGroup::SharedPtr> TopicCallbackGroupMap;
static TopicCallbackGroupMap s_topic_callbackgroups;
Copy link
Collaborator

Choose a reason for hiding this comment

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

instead of introducing static auto s_shared_callbackgroup, can we have everything in this map including rclcpp::CallbackGroup::SharedPtr for service and client?

Copy link
Author

Choose a reason for hiding this comment

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

Using a specific string as a key is difficult and seems a little ugly, that's the reason why I introduce another static variable. If we can make an agreement, I'll update it. To use shared-callbackgroup as a key, which is not a valid topic name due to the character -, after that, it will not conflict with other topic names. what do you think?

Copy link
Author

Choose a reason for hiding this comment

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

Maybe I can just use the empty string as the key

@@ -784,11 +787,11 @@ int main(int argc, char * argv[])


// ROS 1 asynchronous spinner
ros::AsyncSpinner async_spinner(1);
ros::AsyncSpinner async_spinner(0, &ros1_callback_queue);
Copy link
Collaborator

Choose a reason for hiding this comment

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

this will use the all cores in the system to spin. i think using Single or Multi threaded executor is dependent on the use case. for example, someone just bridge the certain topic only, in that case we do not need Multi threaded executor.

i think at least we would want to provide the option for user, then user can decide what they need.

Copy link
Author

Choose a reason for hiding this comment

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

OK, I'll introduce an option, and also append an argument (bool multithread = false) to some methods to check if it's necessary to create a custom callbackgroup or not.

async_spinner.start();

// ROS 2 spinning loop
rclcpp::executors::SingleThreadedExecutor executor;
rclcpp::executors::MultiThreadedExecutor executor;
Copy link
Collaborator

Choose a reason for hiding this comment

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

same here.

@fujitatomoya fujitatomoya added the enhancement New feature or request label Jun 8, 2021
Chen Lihui and others added 2 commits June 8, 2021 15:24
Co-authored-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Copy link
Collaborator

@fujitatomoya fujitatomoya left a comment

Choose a reason for hiding this comment

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

overall this looks good to me. but i guess we need to discuss on the changes in community.

@@ -119,6 +123,7 @@ bool parse_command_options(
bool bridge_all_topics = get_flag_option(args, "--bridge-all-topics");
bridge_all_1to2_topics = bridge_all_topics || get_flag_option(args, "--bridge-all-1to2-topics");
bridge_all_2to1_topics = bridge_all_topics || get_flag_option(args, "--bridge-all-2to1-topics");
multi_threads = get_flag_option(args, "--multi-threads");
Copy link
Collaborator

Choose a reason for hiding this comment

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

option either all core will be used or single thread would be okay, but how about option to choose number of threads? 0 means all core threads, and if more threads are specified than platform possesses then print warning to use all core threads.

Copy link
Collaborator

Choose a reason for hiding this comment

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

I think this needs to be discussed.

Copy link
Author

Choose a reason for hiding this comment

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

Yeah, maybe some guys want to set two different values for the threads count of ros1 and ros2 spinner.

@fujitatomoya
Copy link
Collaborator

@clalancette @sloretz friendly ping.

@fujitatomoya
Copy link
Collaborator

@gbiggs you might want to take a look, this fixes #314

@joelbudu
Copy link

Any chance in this getting merged? @iuhilnehc-ynos @sloretz @clalancette

@iuhilnehc-ynos
Copy link
Author

@joelbudu

I am sorry about not figuring out an elegant fix for this. The answer is no for this PR, at least.



// ROS 1 asynchronous spinner
ros::AsyncSpinner async_spinner(1);
async_spinner.start();
std::unique_ptr<ros::AsyncSpinner> async_spinner = nullptr;

Choose a reason for hiding this comment

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

May be we create one more thread here and use ros::MultiThreadedSpinner?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

Successfully merging this pull request may close these issues.

ROS1 Bridge doesn't work with Multithreaded Executor on a ROS2 service
5 participants