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

Service Type Adaptations #2285

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

Conversation

CursedRock17
Copy link
Contributor

This pull request is a larger one in response to issue #1666 which was to add Type Adaptations to Services/Clients, Type Adaptation were originally added to rclcpp with PR #1557 in 2021. Type Adaptations were a whole design document, which is what I tried to follow when implementing this for services and clients, If we're able to do this we can also have a strong resource for the Actions side of things.

At the original time of this PR you can see it doesn't work, I wanted to figure out the direction we needed to take with how we implemented the Type Adaptations. In the documentation, the given example was:

using MyAdaptedRequestType = TypeAdapter<std::string, std_msgs::msg::String>;
using MyAdaptedResponseType = TypeAdapter<bool, std_msgs::msg::Bool>;

struct MyServiceTypeAdapter {
   using Request = MyAdaptedRequestType;
   using Response = MyAdaptedResponseType;
};

auto client = node->create_client<MyServiceTypeAdapter>("service");

where the original thought was to just make a struct that replicates a service with a Request and Response, that's what I applied. There are two spots, currently where this doesn't work -

These issues highlight the difficulties with using the strategies in the current design docs, which is: the proxy struct that you pass to be a service isn't actually a service. In the case of the rosidl_typesupport, currently this generated method was what I found allowed any services to pass through with this:

  • @('::'.join([package_name] + list(interface_path.parents[0].parts)))::@(service.namespaced_type.name)

being passed as the type, afaik there is only one to change this and enable it as a message which where GetTypeDescription__C comes into to play, it creates a different method:

// Helper function for C typesupport.
namespace rosidl_typesupport_cpp
{
template<>
rosidl_service_type_support_t const *
get_service_type_support_handle<GetTypeDescription__C>()
{
  return ROSIDL_GET_SRV_TYPE_SUPPORT(type_description_interfaces, srv, GetTypeDescription);
}
}  // namespace rosidl_typesupport_cpp

calling ROSIDL_GET_SRV_TYPE_SUPPORT. Circling back to get_service_type_support_handle, we don't where the user is going to get these services from, at least I don't think, so that we could apply this type. Then, GetTypeDescription__C doesn't pass to the Service it's used in because, the Request and Response aren't technically messages again, they are the generated type that the compiler deciphers, this was all added in the Type Description design and creation. There is also a similar version of type support in rosidl_runtime_c

So I submitted the pr early, to try and gain some sort of insight that I could just be missing and find out the direction we want to go. Technically speaking, we could work by creating another TypeAdaptation struct that could take in some form of AdaptedStruct and just do what TypeAdapter does know, but with Response and Request, but this isn't very effective because we're generating way more code, we'll have to do it with 3 things when we add Actions, and I don't even know if it will work entirely. Let me know what direction we want to take on this, anything I missed, and if anything needs to be cleared up

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
@alsora
Copy link
Collaborator

alsora commented Aug 24, 2023

We identified type adaptation as the main culprit for the build time increase between Galactic and Humble.
I would strongly recommend to profile the build time changes caused by this build and NOT merge this PR if it's too large.

@roncapat
Copy link

@alsora could you quantify the time increase?

@alsora
Copy link
Collaborator

alsora commented Aug 25, 2023

@roncapat please refer to this Discourse post: https://discourse.ros.org/t/compilation-bloat-issue/30345/7
Considering a relatively small example repository, the commit that introduced type adaptation caused an increase in build time of almost 20%.
This increase grows even more the larger the codebase being compiled is.

It's now too late to revert that commit, as too many things have been built on top of it, but we should not repeat the same mistake and carefully profile this type of changes.

@roncapat
Copy link

Clear, thanks. But it is my undestanding (and experience) that:

  • templates induce growing build times
  • type adaptation is I think one of the most powerful features of rclcpp

... so I see the point of trying to optimize before merge, but not to the point of not implementing type adaptation for services and actions anytime soon. Just my two (maybe useless) cents here of course :)

@alsora
Copy link
Collaborator

alsora commented Aug 25, 2023

templates induce growing build times

Absolutely! That's why we should be careful in how we use them.

type adaptation is I think one of the most powerful features of rclcpp

I would say that this is debatable. Not everyone uses or will use type adaptation, but everyone needs to compile their applications that depend on rclcpp.

If we want ROS 2 to be become a mature and adopted software in the industry, we can't compromise on stability or allow major regressions for the sake of adding new features.

As a company using ROS 2 in production (iRobot), we can't move from Galactic to Humble due to the aforementioned build time increase, which would cost us huge amounts of money in infrastructure costs (building our software with ROS 2 Galactic takes 1h30m, which become 2h in ROS 2 Humble, with no changes to the source code, just a different version of ROS 2 being linked. Multiply that for hundreds of builds run every day and the $$$ adds up very quickly).

The solution will not be to "not do type adaptation", but rather to "implement type adaptation in a different way".

However, before derailing this PR too much with "philosophical discussions", we should simply run extensive profiling of the proposed solution and then, depending on the results, evaluate what to do.

@clalancette
Copy link
Contributor

If we want ROS 2 to be become a mature and adopted software in the industry, we can't compromise on stability or allow major regressions for the sake of adding new features.

I think we have to be measured in our response here. We can't absolutely prevent new features because it might increase compile times. While that is certainly "a" metric we should keep an eye on, it is (in my opinion) lower on the priority list than other things like runtime performance, user experience, and the like.

However, before derailing this PR too much with "philosophical discussions", we should simply run extensive profiling of the proposed solution and then, depending on the results, evaluate what to do.

And this I totally agree with. If we know how much this increases compile times, then we can make an informed decision on the utility of the change.

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>

finished_service_side

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>

Small Reversion

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>

More specialization

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
@CursedRock17
Copy link
Contributor Author

Sorry for the delay, but I've got a solid chunk of the altered design implemented.

Build Times with Adapted Services

These were just quick build times from my local machine so they should be taken with a grain of salt.
Branch Min (sec) Max (sec) Mean
Service_Type_Adapt 188.94 219.26 199.90
Rolling 174.87 200.63 192.57

That 7.33 seconds puts us at an increase in build time at 3.8% increase, certainly better that the ~18% jump from the original implementation of Type Adaptions, but still an increase, even though we expected it. Though any other additions in the methods that we change, may increase these compile times because they're so reliant on templates.

Runtimes

Another issue that may arise are runtimes, while most of these services are passed by some form of shared_ptr it seems that PR #2199 and this repository highlight the slowing of templating functions. These may not be directly related to this, but I figured it's best to acknowledge that damage could be inflicted. That being said, I didn't do any testing related to this so I cannot be perfectly sure how that will change.

Design Differences

If you take a look at test_client_with_type_adapter you'll notice how I changed from making a structure which takes in the request and response to just taking in the whole service.

struct rclcpp::TypeAdapter<CustomBool, rclcpp::srv::SetBool>

Additionally, the custom structures now mimick services:

struct CustomBool
{
  struct SetBoolResponse
  {
    bool success;
    std::string message;
  };

  using Request = bool;
  using Response = SetBoolResponse;
};

We also changed from converting to custom_type or ros_type, instead we can convert to a ros_service_request, ros_service_response, custom_service_request, and custom_service_response i.e:

  static void
  convert_to_ros_service_request(
    const custom_type::Request & source,
    ros_message_type::Request & destination)
  {
    destination.data = source;
  }

The reason this occurred, was confirmed by my doubts earlier, we cannot create mimickable service requests and responses. There isn't type support to enable each Request and Response to be a message, while allowing the custom Service to be a service. Since ROS works by generating the Service through ROSIDL we would have to do that for each custom Service Request and Response by building a fake Service, which can't happen since we have no location information. The user would also have to override all the type traits like is_message for each each response and request, which might allow incorrect styles of code to pass through. I hope that I didn't explain that too incorrectly or weird.

While the user does have to set up the Adapted Type Structure a bit differently, this does allow us to keep it more concise, gives us more control over the types, and should work better this way. A slight issue I should address is naming conventions, really just using ros_message_type could become ros_type since that's how the custom side is already set up. This way we don't have to alter the TypeAdapter class.

Callback Mixing

As of right now the entire Service side would be ready to go, with the able to call any combination of custom and ROS alongside request and response. Though, on the Client side, I'm trying to get this implementation just right, right now we can only support callbacks which totally share their type with the request or response. For example
async_send_request which has both a request and some form of callback with a request type. The actual implementations don't work because of template specialization, the compiler (in my case Clang) recognizes that the function signature would be the same, although it wouldn't seem to be the case. Past these weird implementation details if we did get it to work, our callbacks cannot have different types than our promises.

To extend of that, converting between futures seems difficult to since many of them start out as empty and returning a different type than the user wants(i.e custom when they want ROS) is not something we want to do.

For now though, a lot of our cases are covered. One last thing that does come as a result of all these different cases is template specialization. While the compile times didn't increase absurdly, there is quite a bit of code that could be seen as bloat for those trying to work on the codebase and decipher where their types are coming from. There was a large increase in the original pull request that added adaption, but this would be another one, and this would be a repeated process if we add Type Adaptions for actions as well. I am looking for optimizations and places that we can remove code, such as conversion for futures, but in the mean time this would be a large piece of templated and specialized code.

@alsora
Copy link
Collaborator

alsora commented Oct 11, 2023

@CursedRock17 thank you a lot for the analysis, I will need to take some time to digest it and give a more meaningful feedback.
However, I want to point out something wrt the build time increase.

What these type of changes really affect is not the build time of rclcpp (which yes, it is affected, but this is IMO a minor and unavoidable problem because you are adding new features), but rather the build time of C++ applications using rclcpp.
The more correct benchmark to run should consists of an application that creates a bunch of ROS 2 servers and clients which do not require type adaptation (for example a main.cpp creating 30 clients and 30 servers with a bunch of different service types)

What's important to minimize is the impact on those users that don't care about the new features being added.

We can also measure the impact when switching from the standard service type to type-adapted ones

Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
@CursedRock17
Copy link
Contributor Author

CursedRock17 commented Nov 12, 2023

Ok, I went and did some testing using ClangBuildAnalyzer and this repository if needed to recreate. During the testing I found that the previous iteration that I had didn't even work, as create_request and handle_request used a voided type that then moves to a ROS type.

After fixing those previous errors I have acquired the following testing results from ClangBuildAnalyzer

service_type_adapt branch client side no adapters

**** Time summary: Compilation (2 times): Parsing (frontend): 2.7 s Codegen & opts (backend): 0.3 s

**** Files that took longest to parse (compiler frontend):
2502 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o
159 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
282 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Templates that took longest to instantiate:
143 ms: rclcpp::create_client<diagnostic_msgs::srv::AddDiagnostics> (2 times, avg 71 ms)
143 ms: rclcpp::create_client<std_srvs::srv::SetBool> (2 times, avg 71 ms)
141 ms: rclcpp::create_client<lifecycle_msgs::srv::ChangeState> (2 times, avg 70 ms)
141 ms: rclcpp::create_client<lifecycle_msgs::srv::GetState> (2 times, avg 70 ms)
137 ms: rclcpp::create_service<std_srvs::srv::Empty, std::__bind<void (Empty... (2 times, avg 68 ms)
128 ms: rclcpp::create_client<std_srvs::srv::Empty> (2 times, avg 64 ms)
127 ms: rclcpp::create_client<std_srvs::srv::Trigger> (2 times, avg 63 ms)
121 ms: rclcpp::create_service<lifecycle_msgs::srv::GetState, std::__bind<vo... (2 times, avg 60 ms)
118 ms: rclcpp::create_service<std_srvs::srv::SetBool, std::__bind<void (Set... (2 times, avg 59 ms)
108 ms: rclcpp::create_service<std_srvs::srv::Trigger, std::__bind<void (Tri... (2 times, avg 54 ms)
106 ms: rclcpp::create_service<lifecycle_msgs::srv::ChangeState, std::bind... (2 times, avg 53 ms)
105 ms: rclcpp::create_service<diagnostic_msgs::srv::AddDiagnostics, std::
... (2 times, avg 52 ms)
71 ms: rclcpp::Node::create_client<diagnostic_msgs::srv::AddDiagnostics> (1 times, avg 71 ms)
71 ms: rclcpp::Node::create_client<std_srvs::srv::SetBool> (1 times, avg 71 ms)
71 ms: rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics>::make_shared<rc... (1 times, avg 71 ms)
71 ms: rclcpp::Client<std_srvs::srv::SetBool>::make_shared<rclcpp::node_int... (1 times, avg 71 ms)
71 ms: std::make_shared<rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics... (1 times, avg 71 ms)
71 ms: std::make_shared<rclcpp::Client<std_srvs::srv::SetBool>, rclcpp::nod... (1 times, avg 71 ms)
71 ms: rclcpp::Node::create_client<lifecycle_msgs::srv::ChangeState> (1 times, avg 71 ms)
71 ms: std::allocate_shared<rclcpp::Client<diagnostic_msgs::srv::AddDiagnos... (1 times, avg 71 ms)
70 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::SetBool>, std::al... (1 times, avg 70 ms)
70 ms: rclcpp::Node::create_client<lifecycle_msgs::srv::GetState> (1 times, avg 70 ms)
70 ms: rclcpp::Client<lifecycle_msgs::srv::ChangeState>::make_shared<rclcpp... (1 times, avg 70 ms)
70 ms: std::make_shared<rclcpp::Client<lifecycle_msgs::srv::ChangeState>, r... (1 times, avg 70 ms)
70 ms: rclcpp::Client<lifecycle_msgs::srv::GetState>::make_shared<rclcpp::n... (1 times, avg 70 ms)
70 ms: std::make_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, rclc... (1 times, avg 70 ms)
70 ms: std::allocate_shared<rclcpp::Client<lifecycle_msgs::srv::ChangeState... (1 times, avg 70 ms)
70 ms: std::allocate_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, ... (1 times, avg 70 ms)
69 ms: std::__shared_ptr_emplace<rclcpp::Client<std_srvs::srv::SetBool>, st... (1 times, avg 69 ms)
69 ms: std::__shared_ptr_emplace<rclcpp::Client<diagnostic_msgs::srv::AddDi... (1 times, avg 69 ms)

**** Template sets that took longest to instantiate:
562 ms: std::make_shared<$> (28 times, avg 20 ms)
558 ms: std::allocate_shared<$> (28 times, avg 19 ms)
496 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (13 times, avg 38 ms)
414 ms: rclcpp::Node::create_client<$> (6 times, avg 69 ms)
413 ms: rclcpp::create_client<$> (6 times, avg 68 ms)
411 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 68 ms)
397 ms: rclcpp::Client<$>::Client (6 times, avg 66 ms)
349 ms: rclcpp::Node::create_service<$> (6 times, avg 58 ms)
349 ms: rclcpp::create_service<$> (6 times, avg 58 ms)
285 ms: std::function<$>::function<$> (15 times, avg 19 ms)
283 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 18 ms)
231 ms: std::__function::__func<$>::__func (15 times, avg 15 ms)
204 ms: std::unordered_map<$>::unordered_map (6 times, avg 34 ms)
197 ms: std::variant<$> (19 times, avg 10 ms)
180 ms: std::__hash_table<$>::~__hash_table (6 times, avg 30 ms)
180 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 30 ms)
179 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 29 ms)
173 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
170 ms: std::unordered_map<$> (26 times, avg 6 ms)
166 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (19 times, avg 8 ms)
163 ms: rclcpp::Client<$>::handle_response (6 times, avg 27 ms)
156 ms: std::forward_as_tuple<$> (69 times, avg 2 ms)
146 ms: std::__hash_table<$> (26 times, avg 5 ms)
146 ms: std::tuple<$> (95 times, avg 1 ms)
145 ms: std::__variant_detail::__impl<$>::__assign<$> (6 times, avg 24 ms)
144 ms: std::__variant_detail::__assignment<$>::__assign_alt<$> (6 times, avg 24 ms)
130 ms: std::__hash_value_type<$> (11 times, avg 11 ms)
129 ms: std::pair<$> (21 times, avg 6 ms)
127 ms: std::__hash_node<$> (6 times, avg 21 ms)
125 ms: rclcpp::Service<$>::make_shared<$> (6 times, avg 20 ms)

**** Functions that took longest to compile:
1 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<std_srvs::srv::SetBool>::handle_response(std::__1::sh... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: TriggerClientNode::TriggerClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: SetBoolClientNode::SetBoolClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: GetStateClientNode::GetStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: EmptyClientNode::EmptyClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: ChangeStateClientNode::ChangeStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: AddDiagnosticsClientNode::AddDiagnosticsClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics>::handle_respons... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<std_srvs::srv::Empty>::handle_response(std::__1::shar... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<lifecycle_msgs::srv::GetState>::handle_response(std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<lifecycle_msgs::srv::ChangeState>::handle_response(st... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<std_srvs::srv::Trigger>::handle_response(std::__1::sh... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: bool std::__1::__cxx_atomic_exchange[abi:v15006](std::__1::__c... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::__hash_iterator<std::__1::__hash_node<std::__1::__hash_val... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)

**** Function sets that took longest to compile / optimize:
4 ms: rclcpp::Client<$>::handle_response(std::__1::shared_ptr<$>, std::__1... (6 times, avg 0 ms)
3 ms: std::__1::pair<$> std::__1::__hash_table<$>::__emplace_unique_key_ar... (6 times, avg 0 ms)
0 ms: bool std::__1::__cxx_atomic_exchange[abi:v15006]<$>(std::__1::_cxx... (1 times, avg 0 ms)
0 ms: std::__1::__hash_iterator<$> std::__1::__hash_table<$>::find<$>(long... (1 times, avg 0 ms)

**** Expensive headers:
825 ms: /Users/cursedrock17/documents/coding/cpp/ros2/rclcpp/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 825 ms), included via:
1x:

160 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 160 ms), included via:
1x:

35 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 35 ms), included via:
1x:

33 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 33 ms), included via:
1x:

33 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 33 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 28 ms), included via:
1x:

27 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 27 ms), included via:
1x:

26 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 26 ms), included via:
1x:

done in 0.0s.

rolling branch client side no adapters

**** Time summary: Compilation (2 times): Parsing (frontend): 2.5 s Codegen & opts (backend): 0.2 s

**** Files that took longest to parse (compiler frontend):
2350 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o
132 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
239 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Templates that took longest to instantiate:
133 ms: rclcpp::create_client<std_srvs::srv::Trigger> (2 times, avg 66 ms)
115 ms: rclcpp::create_service<diagnostic_msgs::srv::AddDiagnostics, std::__... (2 times, avg 57 ms)
115 ms: rclcpp::create_service<lifecycle_msgs::srv::ChangeState, std::__bind... (2 times, avg 57 ms)
113 ms: rclcpp::create_client<lifecycle_msgs::srv::GetState> (2 times, avg 56 ms)
110 ms: rclcpp::create_client<std_srvs::srv::SetBool> (2 times, avg 55 ms)
109 ms: rclcpp::create_service<std_srvs::srv::SetBool, std::__bind<void (Set... (2 times, avg 54 ms)
107 ms: rclcpp::create_service<lifecycle_msgs::srv::GetState, std::__bind<vo... (2 times, avg 53 ms)
106 ms: rclcpp::create_service<std_srvs::srv::Empty, std::__bind<void (Empty... (2 times, avg 53 ms)
104 ms: rclcpp::create_client<diagnostic_msgs::srv::AddDiagnostics> (2 times, avg 52 ms)
103 ms: rclcpp::create_service<std_srvs::srv::Trigger, std::__bind<void (Tri... (2 times, avg 51 ms)
101 ms: rclcpp::create_client<lifecycle_msgs::srv::ChangeState> (2 times, avg 50 ms)
97 ms: rclcpp::create_client<std_srvs::srv::Empty> (2 times, avg 48 ms)
66 ms: rclcpp::Node::create_client<std_srvs::srv::Trigger> (1 times, avg 66 ms)
66 ms: rclcpp::Client<std_srvs::srv::Trigger>::make_shared<rclcpp::node_int... (1 times, avg 66 ms)
66 ms: std::make_shared<rclcpp::Client<std_srvs::srv::Trigger>, rclcpp::nod... (1 times, avg 66 ms)
66 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::Trigger>, std::al... (1 times, avg 66 ms)
64 ms: std::__shared_ptr_emplace<rclcpp::Client<std_srvs::srv::Trigger>, st... (1 times, avg 64 ms)
64 ms: rclcpp::Client<std_srvs::srv::Trigger>::Client (1 times, avg 64 ms)
57 ms: rclcpp::Node::create_service<diagnostic_msgs::srv::AddDiagnostics, s... (1 times, avg 57 ms)
57 ms: rclcpp::Node::create_service<lifecycle_msgs::srv::ChangeState, std::... (1 times, avg 57 ms)
56 ms: rclcpp::Node::create_client<lifecycle_msgs::srv::GetState> (1 times, avg 56 ms)
56 ms: rclcpp::Client<lifecycle_msgs::srv::GetState>::make_shared<rclcpp::n... (1 times, avg 56 ms)
56 ms: std::make_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, rclc... (1 times, avg 56 ms)
56 ms: std::allocate_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, ... (1 times, avg 56 ms)
55 ms: rclcpp::Node::create_client<std_srvs::srv::SetBool> (1 times, avg 55 ms)
55 ms: rclcpp::Client<std_srvs::srv::SetBool>::make_shared<rclcpp::node_int... (1 times, avg 55 ms)
54 ms: std::make_shared<rclcpp::Client<std_srvs::srv::SetBool>, rclcpp::nod... (1 times, avg 54 ms)
54 ms: rclcpp::Node::create_service<std_srvs::srv::SetBool, std::__bind<voi... (1 times, avg 54 ms)
54 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::SetBool>, std::al... (1 times, avg 54 ms)
54 ms: std::__shared_ptr_emplace<rclcpp::Client<lifecycle_msgs::srv::GetSta... (1 times, avg 54 ms)

**** Template sets that took longest to instantiate:
451 ms: std::make_shared<$> (27 times, avg 16 ms)
447 ms: std::allocate_shared<$> (27 times, avg 16 ms)
401 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (12 times, avg 33 ms)
331 ms: rclcpp::Node::create_client<$> (6 times, avg 55 ms)
330 ms: rclcpp::create_client<$> (6 times, avg 55 ms)
329 ms: rclcpp::Node::create_service<$> (6 times, avg 54 ms)
328 ms: rclcpp::create_service<$> (6 times, avg 54 ms)
328 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 54 ms)
314 ms: rclcpp::Client<$>::Client (6 times, avg 52 ms)
289 ms: std::function<$>::function<$> (15 times, avg 19 ms)
288 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 19 ms)
239 ms: std::__function::__func<$>::__func (15 times, avg 15 ms)
186 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 31 ms)
178 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
168 ms: std::unordered_map<$> (26 times, avg 6 ms)
161 ms: std::variant<$> (19 times, avg 8 ms)
153 ms: std::forward_as_tuple<$> (69 times, avg 2 ms)
152 ms: std::unordered_map<$>::unordered_map (6 times, avg 25 ms)
147 ms: std::__variant_detail::__impl<$>::__assign<$> (6 times, avg 24 ms)
147 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (19 times, avg 7 ms)
146 ms: std::__variant_detail::__assignment<$>::__assign_alt<$> (6 times, avg 24 ms)
146 ms: std::tuple<$> (95 times, avg 1 ms)
136 ms: std::__hash_table<$> (26 times, avg 5 ms)
133 ms: rclcpp::Client<$>::handle_response (6 times, avg 22 ms)
129 ms: std::__hash_table<$>::~__hash_table (6 times, avg 21 ms)
128 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 21 ms)
116 ms: std::__function::__func<$>::__clone (30 times, avg 3 ms)
104 ms: rclcpp::Client<$> (12 times, avg 8 ms)
100 ms: std::unique_ptr<$> (94 times, avg 1 ms)
100 ms: std::pair<$> (21 times, avg 4 ms)

**** Functions that took longest to compile:
1 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: TriggerClientNode::TriggerClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: ChangeStateClientNode::ChangeStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: GetStateClientNode::GetStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: SetBoolClientNode::SetBoolClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: AddDiagnosticsClientNode::AddDiagnosticsClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: EmptyClientNode::EmptyClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)

**** Function sets that took longest to compile / optimize:
2 ms: std::__1::pair<$> std::__1::__hash_table<$>::__emplace_unique_key_ar... (5 times, avg 0 ms)

**** Expensive headers:
817 ms: /Users/cursedrock17/ros2_rolling/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 817 ms), included via:
1x:

143 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 143 ms), included via:
1x:

31 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 31 ms), included via:
1x:

29 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 29 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 28 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 28 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 28 ms), included via:
1x:

26 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 26 ms), included via:
1x:

done in 0.0s.

service_type_adapt branch server side no adapters

> **** Time summary: Compilation (2 times): Parsing (frontend): 2.5 s Codegen & opts (backend): 0.2 s

**** Files that took longest to parse (compiler frontend):
2409 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o
121 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
245 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Templates that took longest to instantiate:
143 ms: rclcpp::create_client<lifecycle_msgs::srv::ChangeState> (2 times, avg 71 ms)
143 ms: rclcpp::create_client<lifecycle_msgs::srv::GetState> (2 times, avg 71 ms)
142 ms: rclcpp::create_client<std_srvs::srv::SetBool> (2 times, avg 71 ms)
141 ms: rclcpp::create_client<diagnostic_msgs::srv::AddDiagnostics> (2 times, avg 70 ms)
136 ms: rclcpp::create_service<std_srvs::srv::Empty, std::__bind<void (Empty... (2 times, avg 68 ms)
128 ms: rclcpp::create_client<std_srvs::srv::Empty> (2 times, avg 64 ms)
127 ms: rclcpp::create_client<std_srvs::srv::Trigger> (2 times, avg 63 ms)
119 ms: rclcpp::create_service<lifecycle_msgs::srv::GetState, std::__bind<vo... (2 times, avg 59 ms)
118 ms: rclcpp::create_service<std_srvs::srv::SetBool, std::__bind<void (Set... (2 times, avg 59 ms)
106 ms: rclcpp::create_service<lifecycle_msgs::srv::ChangeState, std::__bind... (2 times, avg 53 ms)
105 ms: rclcpp::create_service<std_srvs::srv::Trigger, std::bind<void (Tri... (2 times, avg 52 ms)
105 ms: rclcpp::create_service<diagnostic_msgs::srv::AddDiagnostics, std::
... (2 times, avg 52 ms)
71 ms: rclcpp::Node::create_client<lifecycle_msgs::srv::ChangeState> (1 times, avg 71 ms)
71 ms: rclcpp::Node::create_client<lifecycle_msgs::srv::GetState> (1 times, avg 71 ms)
71 ms: rclcpp::Node::create_client<std_srvs::srv::SetBool> (1 times, avg 71 ms)
71 ms: rclcpp::Client<lifecycle_msgs::srv::GetState>::make_shared<rclcpp::n... (1 times, avg 71 ms)
71 ms: rclcpp::Client<lifecycle_msgs::srv::ChangeState>::make_shared<rclcpp... (1 times, avg 71 ms)
71 ms: std::make_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, rclc... (1 times, avg 71 ms)
71 ms: std::make_shared<rclcpp::Client<lifecycle_msgs::srv::ChangeState>, r... (1 times, avg 71 ms)
71 ms: rclcpp::Client<std_srvs::srv::SetBool>::make_shared<rclcpp::node_int... (1 times, avg 71 ms)
71 ms: std::make_shared<rclcpp::Client<std_srvs::srv::SetBool>, rclcpp::nod... (1 times, avg 71 ms)
70 ms: std::allocate_shared<rclcpp::Client<lifecycle_msgs::srv::GetState>, ... (1 times, avg 70 ms)
70 ms: std::allocate_shared<rclcpp::Client<lifecycle_msgs::srv::ChangeState... (1 times, avg 70 ms)
70 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::SetBool>, std::al... (1 times, avg 70 ms)
70 ms: rclcpp::Node::create_client<diagnostic_msgs::srv::AddDiagnostics> (1 times, avg 70 ms)
70 ms: rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics>::make_shared<rc... (1 times, avg 70 ms)
70 ms: std::make_shared<rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics... (1 times, avg 70 ms)
70 ms: std::allocate_shared<rclcpp::Client<diagnostic_msgs::srv::AddDiagnos... (1 times, avg 70 ms)
69 ms: std::__shared_ptr_emplace<rclcpp::Client<std_srvs::srv::SetBool>, st... (1 times, avg 69 ms)
69 ms: std::__shared_ptr_emplace<rclcpp::Client<lifecycle_msgs::srv::Change... (1 times, avg 69 ms)

**** Template sets that took longest to instantiate:
560 ms: std::make_shared<$> (27 times, avg 20 ms)
556 ms: std::allocate_shared<$> (27 times, avg 20 ms)
508 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (12 times, avg 42 ms)
413 ms: rclcpp::Node::create_client<$> (6 times, avg 68 ms)
413 ms: rclcpp::create_client<$> (6 times, avg 68 ms)
411 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 68 ms)
396 ms: rclcpp::Client<$>::Client (6 times, avg 66 ms)
347 ms: rclcpp::Node::create_service<$> (6 times, avg 57 ms)
346 ms: rclcpp::create_service<$> (6 times, avg 57 ms)
282 ms: std::function<$>::function<$> (15 times, avg 18 ms)
280 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 18 ms)
228 ms: std::__function::__func<$>::__func (15 times, avg 15 ms)
202 ms: std::unordered_map<$>::unordered_map (6 times, avg 33 ms)
196 ms: std::variant<$> (19 times, avg 10 ms)
179 ms: std::__hash_table<$>::~__hash_table (6 times, avg 29 ms)
178 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 29 ms)
178 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 29 ms)
171 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
170 ms: std::unordered_map<$> (26 times, avg 6 ms)
164 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (19 times, avg 8 ms)
164 ms: rclcpp::Client<$>::handle_response (6 times, avg 27 ms)
145 ms: std::__hash_table<$> (26 times, avg 5 ms)
143 ms: std::__variant_detail::__impl<$>::__assign<$> (6 times, avg 23 ms)
142 ms: std::__variant_detail::__assignment<$>::__assign_alt<$> (6 times, avg 23 ms)
129 ms: std::__hash_value_type<$> (11 times, avg 11 ms)
127 ms: std::tuple<$> (88 times, avg 1 ms)
126 ms: std::forward_as_tuple<$> (62 times, avg 2 ms)
126 ms: std::__hash_node<$> (6 times, avg 21 ms)
124 ms: rclcpp::Service<$>::make_shared<$> (6 times, avg 20 ms)
121 ms: std::pair<$> (10 times, avg 12 ms)

**** Functions that took longest to compile:
4 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<lifecycle_msgs::srv::GetState>::handle_request(std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<std_srvs::srv::SetBool>::handle_request(std::__1::sh... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<diagnostic_msgs::srv::AddDiagnostics>::handle_reques... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<std_srvs::srv::Trigger>::handle_request(std::__1::sh... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<lifecycle_msgs::srv::ChangeState>::handle_request(st... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<std_srvs::srv::Empty>::handle_request(std::__1::shar... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: std::__1::__shared_ptr_emplace<SetBoolServerNode, std::__1::allocato... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr rclcpp::create_se... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: std::__1::shared_ptr std::__1::shared_ptr<SetBool... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)

**** Function sets that took longest to compile / optimize:
5 ms: rclcpp::Service<$>::handle_request(std::__1::shared_ptr<$>, std::__1... (6 times, avg 0 ms)
0 ms: std::__1::__shared_ptr_emplace<$>::__on_zero_shared() (1 times, avg 0 ms)
0 ms: rclcpp::Service<$>::SharedPtr rclcpp::create_service<$>(std::__1::sh... (1 times, avg 0 ms)
0 ms: std::__1::shared_ptr<$> std::__1::shared_ptr<$>::__create_with_contr... (1 times, avg 0 ms)

**** Expensive headers:
825 ms: /Users/cursedrock17/documents/coding/cpp/ros2/rclcpp/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 825 ms), included via:
1x:

160 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 160 ms), included via:
1x:

35 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 35 ms), included via:
1x:

33 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 33 ms), included via:
1x:

33 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 33 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 28 ms), included via:
1x:

27 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 27 ms), included via:
1x:

26 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 26 ms), included via:
1x:

done in 0.0s

rolling branch server side no adapters

**** Time summary: Compilation (2 times): Parsing (frontend): 2.4 s Codegen & opts (backend): 0.2 s

**** Files that took longest to parse (compiler frontend):
2249 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o
120 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
226 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Templates that took longest to instantiate:
131 ms: rclcpp::create_client<std_srvs::srv::Trigger> (2 times, avg 65 ms)
115 ms: rclcpp::create_service<diagnostic_msgs::srv::AddDiagnostics, std::__... (2 times, avg 57 ms)
115 ms: rclcpp::create_service<lifecycle_msgs::srv::ChangeState, std::__bind... (2 times, avg 57 ms)
109 ms: rclcpp::create_client<std_srvs::srv::SetBool> (2 times, avg 54 ms)
109 ms: rclcpp::create_service<std_srvs::srv::SetBool, std::__bind<void (Set... (2 times, avg 54 ms)
106 ms: rclcpp::create_service<std_srvs::srv::Empty, std::__bind<void (Empty... (2 times, avg 53 ms)
105 ms: rclcpp::create_service<lifecycle_msgs::srv::GetState, std::__bind<vo... (2 times, avg 52 ms)
105 ms: rclcpp::create_client<diagnostic_msgs::srv::AddDiagnostics> (2 times, avg 52 ms)
103 ms: rclcpp::create_service<std_srvs::srv::Trigger, std::__bind<void (Tri... (2 times, avg 51 ms)
101 ms: rclcpp::create_client<lifecycle_msgs::srv::ChangeState> (2 times, avg 50 ms)
101 ms: rclcpp::create_client<lifecycle_msgs::srv::GetState> (2 times, avg 50 ms)
97 ms: rclcpp::create_client<std_srvs::srv::Empty> (2 times, avg 48 ms)
66 ms: rclcpp::Node::create_client<std_srvs::srv::Trigger> (1 times, avg 66 ms)
65 ms: rclcpp::Client<std_srvs::srv::Trigger>::make_shared<rclcpp::node_int... (1 times, avg 65 ms)
65 ms: std::make_shared<rclcpp::Client<std_srvs::srv::Trigger>, rclcpp::nod... (1 times, avg 65 ms)
65 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::Trigger>, std::al... (1 times, avg 65 ms)
63 ms: std::__shared_ptr_emplace<rclcpp::Client<std_srvs::srv::Trigger>, st... (1 times, avg 63 ms)
63 ms: rclcpp::Client<std_srvs::srv::Trigger>::Client (1 times, avg 63 ms)
57 ms: rclcpp::Node::create_service<diagnostic_msgs::srv::AddDiagnostics, s... (1 times, avg 57 ms)
57 ms: rclcpp::Node::create_service<lifecycle_msgs::srv::ChangeState, std::... (1 times, avg 57 ms)
55 ms: rclcpp::Node::create_client<std_srvs::srv::SetBool> (1 times, avg 55 ms)
54 ms: rclcpp::Node::create_service<std_srvs::srv::SetBool, std::__bind<voi... (1 times, avg 54 ms)
54 ms: rclcpp::Client<std_srvs::srv::SetBool>::make_shared<rclcpp::node_int... (1 times, avg 54 ms)
54 ms: std::make_shared<rclcpp::Client<std_srvs::srv::SetBool>, rclcpp::nod... (1 times, avg 54 ms)
54 ms: std::allocate_shared<rclcpp::Client<std_srvs::srv::SetBool>, std::al... (1 times, avg 54 ms)
53 ms: rclcpp::Node::create_service<std_srvs::srv::Empty, std::__bind<void ... (1 times, avg 53 ms)
53 ms: rclcpp::Node::create_service<lifecycle_msgs::srv::GetState, std::__b... (1 times, avg 53 ms)
52 ms: rclcpp::Node::create_client<diagnostic_msgs::srv::AddDiagnostics> (1 times, avg 52 ms)
52 ms: std::__shared_ptr_emplace<rclcpp::Client<std_srvs::srv::SetBool>, st... (1 times, avg 52 ms)
52 ms: rclcpp::Client<diagnostic_msgs::srv::AddDiagnostics>::make_shared<rc... (1 times, avg 52 ms)

**** Template sets that took longest to instantiate:
445 ms: std::make_shared<$> (27 times, avg 16 ms)
441 ms: std::allocate_shared<$> (27 times, avg 16 ms)
394 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (12 times, avg 32 ms)
328 ms: rclcpp::Node::create_service<$> (6 times, avg 54 ms)
328 ms: rclcpp::create_service<$> (6 times, avg 54 ms)
324 ms: rclcpp::Node::create_client<$> (6 times, avg 54 ms)
324 ms: rclcpp::create_client<$> (6 times, avg 54 ms)
322 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 53 ms)
308 ms: rclcpp::Client<$>::Client (6 times, avg 51 ms)
289 ms: std::function<$>::function<$> (15 times, avg 19 ms)
288 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 19 ms)
238 ms: std::__function::__func<$>::__func (15 times, avg 15 ms)
186 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 31 ms)
177 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
167 ms: std::unordered_map<$> (26 times, avg 6 ms)
162 ms: std::variant<$> (19 times, avg 8 ms)
147 ms: std::__variant_detail::__impl<$>::__assign<$> (6 times, avg 24 ms)
146 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (19 times, avg 7 ms)
146 ms: std::__variant_detail::__assignment<$>::__assign_alt<$> (6 times, avg 24 ms)
146 ms: std::unordered_map<$>::unordered_map (6 times, avg 24 ms)
136 ms: std::tuple<$> (88 times, avg 1 ms)
135 ms: std::__hash_table<$> (26 times, avg 5 ms)
132 ms: std::forward_as_tuple<$> (62 times, avg 2 ms)
132 ms: rclcpp::Client<$>::handle_response (6 times, avg 22 ms)
123 ms: std::__hash_table<$>::~__hash_table (6 times, avg 20 ms)
122 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 20 ms)
114 ms: std::__function::__func<$>::__clone (30 times, avg 3 ms)
104 ms: rclcpp::Client<$> (12 times, avg 8 ms)
100 ms: std::unique_ptr<$> (94 times, avg 1 ms)
98 ms: rclcpp::Service<$>::make_shared<$> (6 times, avg 16 ms)

**** Functions that took longest to compile:
1 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: std::__1::__function::__func<std::__1::__bind<void (EmptyServerNode:... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)

**** Function sets that took longest to compile / optimize:
0 ms: std::__1::__function::__func<$>::__func[abi:v15006](std::__1::__bind... (1 times, avg 0 ms)

**** Expensive headers:
817 ms: /Users/cursedrock17/ros2_rolling/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 817 ms), included via:
1x:

143 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 143 ms), included via:
1x:

31 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 31 ms), included via:
1x:

29 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 29 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 28 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 28 ms), included via:
1x:

28 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 28 ms), included via:
1x:

26 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 26 ms), included via:
1x:

done in 0.0s.

service_type_adapt branch client side adapters

**** Time summary: Compilation (2 times): Parsing (frontend): 3.2 s Codegen & opts (backend): 0.3 s

**** Files that took longest to parse (compiler frontend):
3014 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o
211 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
319 ms: build/type_adapt_example/CMakeFiles/client_node_process.dir/src/client_node_process.cpp.o

**** Templates that took longest to instantiate:
239 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomChangeState, lifecy... (2 times, avg 119 ms)
213 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomAddDiagnostics, dia... (2 times, avg 106 ms)
212 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomChangeState, lifecyc... (2 times, avg 106 ms)
210 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv:... (2 times, avg 105 ms)
208 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomGetState, lifecycle_... (2 times, avg 104 ms)
205 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomGetState, lifecycle... (2 times, avg 102 ms)
202 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomTrigger, std_srvs::... (2 times, avg 101 ms)
198 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomTrigger, std_srvs::s... (2 times, avg 99 ms)
192 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomAddDiagnostics, diag... (2 times, avg 96 ms)
192 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomBool, std_srvs::srv... (2 times, avg 96 ms)
191 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomEmpty, std_srvs::srv... (2 times, avg 95 ms)
189 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomEmpty, std_srvs::sr... (2 times, avg 94 ms)
120 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomChangeState, ... (1 times, avg 120 ms)
106 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomAddDiagnostic... (1 times, avg 106 ms)
106 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomChangeState, l... (1 times, avg 106 ms)
106 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomChangeState, lifecycle_msgs... (1 times, avg 106 ms)
105 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomChangeStat... (1 times, avg 105 ms)
105 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomChange... (1 times, avg 105 ms)
105 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomBool, std_srvs... (1 times, avg 105 ms)
104 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv::SetBoo... (1 times, avg 104 ms)
104 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_... (1 times, avg 104 ms)
104 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomGetState, life... (1 times, avg 104 ms)
104 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomBool, ... (1 times, avg 104 ms)
104 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomGetState, lifecycle_msgs::s... (1 times, avg 104 ms)
104 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomGetState, ... (1 times, avg 104 ms)
103 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomGetSta... (1 times, avg 103 ms)
103 ms: std::__shared_ptr_emplace<rclcpp::Client<rclcpp::TypeAdapter<CustomC... (1 times, avg 103 ms)
103 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomChangeState, lifecycle_msgs... (1 times, avg 103 ms)
102 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomGetState, lif... (1 times, avg 102 ms)
102 ms: std::__shared_ptr_emplace<rclcpp::Client<rclcpp::TypeAdapter<CustomB... (1 times, avg 102 ms)

**** Template sets that took longest to instantiate:
892 ms: std::make_shared<$> (27 times, avg 33 ms)
888 ms: std::allocate_shared<$> (27 times, avg 32 ms)
840 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (12 times, avg 70 ms)
622 ms: rclcpp::Node::create_service<$> (6 times, avg 103 ms)
621 ms: rclcpp::create_service<$> (6 times, avg 103 ms)
608 ms: rclcpp::Node::create_client<$> (6 times, avg 101 ms)
607 ms: rclcpp::create_client<$> (6 times, avg 101 ms)
605 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 100 ms)
591 ms: rclcpp::Client<$>::Client (6 times, avg 98 ms)
320 ms: std::variant<$> (19 times, avg 16 ms)
315 ms: std::unordered_map<$>::unordered_map (6 times, avg 52 ms)
297 ms: std::function<$>::function<$> (15 times, avg 19 ms)
296 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 19 ms)
285 ms: std::__hash_table<$>::__hash_table (6 times, avg 47 ms)
283 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 47 ms)
261 ms: rclcpp::Service<$>::make_shared<$> (6 times, avg 43 ms)
248 ms: std::__function::__func<$>::__func (15 times, avg 16 ms)
245 ms: rclcpp::Client<$>::handle_response (6 times, avg 40 ms)
224 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 37 ms)
210 ms: std::pair<$> (21 times, avg 10 ms)
210 ms: std::__hash_value_type<$> (11 times, avg 19 ms)
206 ms: std::__hash_node<$> (6 times, avg 34 ms)
203 ms: std::__variant_detail::__ctor<$>::__generic_construct<$> (12 times, avg 16 ms)
193 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (18 times, avg 10 ms)
188 ms: std::__variant_detail::__visitation::__base::__make_dispatch<$> (236 times, avg 0 ms)
181 ms: std::unordered_map<$> (26 times, avg 6 ms)
181 ms: std::tuple<$> (107 times, avg 1 ms)
179 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
177 ms: std::__variant_detail::__dtor<$>::
__dtor (12 times, avg 14 ms)
176 ms: std::__variant_detail::__dtor<$>::__destroy (12 times, avg 14 ms)

**** Functions that took longest to compile:
1 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: AddDiagnosticsClientNode::AddDiagnosticsClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: GetStateClientNode::GetStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: SetBoolClientNode::SetBoolClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: TriggerClientNode::TriggerClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: ChangeStateClientNode::ChangeStateClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: EmptyClientNode::EmptyClientNode() (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomGetState, lifecycle_msgs::s... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomChangeState, lifecycle_msgs... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomTrigger, std_srvs::srv::Tri... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv::SetBoo... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomAddDiagnostics, diagnostic_... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomEmpty, std_srvs::srv::Empty... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: rclcpp::FutureReturnCode rclcpp::Executor::spin_until_future_complet... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)
0 ms: std::__1::pair<std::__1::__hash_iterator<std::__1::__hash_node<std::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/client_node_process.cpp)

**** Function sets that took longest to compile / optimize:
4 ms: rclcpp::Client<$>::handle_response(std::__1::shared_ptr<$>, std::__1... (6 times, avg 0 ms)
3 ms: std::__1::pair<$> std::__1::__hash_table<$>::__emplace_unique_key_ar... (6 times, avg 0 ms)
0 ms: rclcpp::FutureReturnCode rclcpp::Executor::spin_until_future_complet... (1 times, avg 0 ms)

**** Expensive headers:
816 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/rclcpp/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 816 ms), included via:
1x:

151 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 151 ms), included via:
1x:

43 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 43 ms), included via:
1x:

42 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 42 ms), included via:
1x:

41 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 41 ms), included via:
1x:

40 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 40 ms), included via:
1x:

40 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 40 ms), included via:
1x:

36 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 36 ms), included via:
1x:

done in 0.0s.

service_type_adapt branch server side adapters

**** Time summary: Compilation (2 times): Parsing (frontend): 3.0 s Codegen & opts (backend): 0.3 s

**** Files that took longest to parse (compiler frontend):
2754 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o
196 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Files that took longest to codegen (compiler backend):
346 ms: build/type_adapt_example/CMakeFiles/server_node_process.dir/src/server_node_process.cpp.o

**** Templates that took longest to instantiate:
226 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomChangeState, lifecy... (2 times, avg 113 ms)
217 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomAddDiagnostics, dia... (2 times, avg 108 ms)
214 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv:... (2 times, avg 107 ms)
211 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomGetState, lifecycle... (2 times, avg 105 ms)
208 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomGetState, lifecycle_... (2 times, avg 104 ms)
207 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomChangeState, lifecyc... (2 times, avg 103 ms)
201 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomTrigger, std_srvs::... (2 times, avg 100 ms)
195 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomAddDiagnostics, diag... (2 times, avg 97 ms)
193 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomEmpty, std_srvs::sr... (2 times, avg 96 ms)
191 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomTrigger, std_srvs::s... (2 times, avg 95 ms)
188 ms: rclcpp::create_service<rclcpp::TypeAdapter<CustomBool, std_srvs::srv... (2 times, avg 94 ms)
183 ms: rclcpp::create_client<rclcpp::TypeAdapter<CustomEmpty, std_srvs::srv... (2 times, avg 91 ms)
113 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomChangeState, ... (1 times, avg 113 ms)
108 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomAddDiagnostic... (1 times, avg 108 ms)
107 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomBool, std_srvs... (1 times, avg 107 ms)
107 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv::SetBoo... (1 times, avg 107 ms)
107 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_... (1 times, avg 107 ms)
106 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomBool, ... (1 times, avg 106 ms)
105 ms: rclcpp::Node::create_service<rclcpp::TypeAdapter<CustomGetState, lif... (1 times, avg 105 ms)
105 ms: std::__shared_ptr_emplace<rclcpp::Client<rclcpp::TypeAdapter<CustomB... (1 times, avg 105 ms)
104 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomBool, std_srvs::srv::SetBoo... (1 times, avg 104 ms)
104 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomGetState, life... (1 times, avg 104 ms)
104 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomGetState, lifecycle_msgs::s... (1 times, avg 104 ms)
103 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomGetState, ... (1 times, avg 103 ms)
103 ms: rclcpp::Node::create_client<rclcpp::TypeAdapter<CustomChangeState, l... (1 times, avg 103 ms)
103 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomGetSta... (1 times, avg 103 ms)
103 ms: rclcpp::Client<rclcpp::TypeAdapter<CustomChangeState, lifecycle_msgs... (1 times, avg 103 ms)
103 ms: std::make_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomChangeStat... (1 times, avg 103 ms)
103 ms: std::allocate_shared<rclcpp::Client<rclcpp::TypeAdapter<CustomChange... (1 times, avg 103 ms)
101 ms: std::__shared_ptr_emplace<rclcpp::Client<rclcpp::TypeAdapter<CustomG... (1 times, avg 101 ms)

**** Template sets that took longest to instantiate:
891 ms: std::make_shared<$> (27 times, avg 33 ms)
887 ms: std::allocate_shared<$> (27 times, avg 32 ms)
840 ms: std::__shared_ptr_emplace<$>::__shared_ptr_emplace<$> (12 times, avg 70 ms)
620 ms: rclcpp::Node::create_service<$> (6 times, avg 103 ms)
619 ms: rclcpp::create_service<$> (6 times, avg 103 ms)
601 ms: rclcpp::Node::create_client<$> (6 times, avg 100 ms)
600 ms: rclcpp::create_client<$> (6 times, avg 100 ms)
598 ms: rclcpp::Client<$>::make_shared<$> (6 times, avg 99 ms)
584 ms: rclcpp::Client<$>::Client (6 times, avg 97 ms)
315 ms: std::variant<$> (19 times, avg 16 ms)
307 ms: std::unordered_map<$>::unordered_map (6 times, avg 51 ms)
294 ms: std::function<$>::function<$> (15 times, avg 19 ms)
293 ms: std::__function::__value_func<$>::__value_func<$> (15 times, avg 19 ms)
278 ms: std::__hash_table<$>::__hash_table (6 times, avg 46 ms)
277 ms: std::__hash_table<$>::__deallocate_node (6 times, avg 46 ms)
268 ms: rclcpp::Service<$>::make_shared<$> (6 times, avg 44 ms)
246 ms: rclcpp::Client<$>::handle_response (6 times, avg 41 ms)
240 ms: std::__function::__func<$>::__func (15 times, avg 16 ms)
216 ms: rclcpp::AnyServiceCallback<$>::set<$> (6 times, avg 36 ms)
206 ms: std::__variant_detail::__ctor<$>::__generic_construct<$> (12 times, avg 17 ms)
205 ms: std::__hash_value_type<$> (11 times, avg 18 ms)
202 ms: std::__hash_node<$> (6 times, avg 33 ms)
198 ms: std::pair<$> (10 times, avg 19 ms)
194 ms: std::__variant_detail::__ctor<$>::__construct_alt<$> (18 times, avg 10 ms)
188 ms: std::__variant_detail::__visitation::__base::__make_dispatch<$> (234 times, avg 0 ms)
182 ms: std::unordered_map<$> (26 times, avg 7 ms)
175 ms: std::__variant_detail::__dtor<$>::
__dtor (12 times, avg 14 ms)
175 ms: std::__variant_detail::__dtor<$>::__destroy (12 times, avg 14 ms)
173 ms: std::__function::__alloc_func<$>::__alloc_func (45 times, avg 3 ms)
168 ms: std::tuple<$> (100 times, avg 1 ms)

**** Functions that took longest to compile:
1 ms: main (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomAddDiagnostics, diagnostic... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomGetState, lifecycle_msgs::... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomTrigger, std_srvs::srv::Tr... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomChangeState, lifecycle_msg... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomBool, std_srvs::srv::SetBo... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)
0 ms: rclcpp::Service<rclcpp::TypeAdapter<CustomEmpty, std_srvs::srv::Empt... (/Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/src/server_node_process.cpp)

**** Function sets that took longest to compile / optimize:
5 ms: rclcpp::Service<$>::handle_request(std::__1::shared_ptr<$>, std::__1... (6 times, avg 0 ms)

**** Expensive headers:
717 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/rclcpp/install/rclcpp/include/rclcpp/rclcpp/rclcpp.hpp (included 1 times, avg 717 ms), included via:
1x:

105 ms: /Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX13.3.sdk/usr/include/c++/v1/memory (included 1 times, avg 105 ms), included via:
1x:

43 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/trigger_node.hpp (included 1 times, avg 43 ms), included via:
1x:

42 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/set_bool_node.hpp (included 1 times, avg 42 ms), included via:
1x:

39 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/change_state_node.hpp (included 1 times, avg 39 ms), included via:
1x:

38 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/get_state_node.hpp (included 1 times, avg 38 ms), included via:
1x:

36 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/add_diagnostics_node.hpp (included 1 times, avg 36 ms), included via:
1x:

35 ms: /Users/cursedrock17/Documents/Coding/CPP/ros2/type_adapt_example/include/type_adapt_example/empty_node.hpp (included 1 times, avg 35 ms), included via:
1x:

done in 0.0s.

Roughly, it seems that this new branch is 12-20% more expensive than the previous branch, with size of the service not necessarily causing massive growth in build time (though there were no services that were large and extremly over the top). All of that comes with the making of so many types, not being able to just do a request and response, means that there are four types instead of two, where in rolling only one stood.

So, technically if we wanted a decrease in both the instantiation of the Client/Service we could limit users to only being able to make a Client/Service as entirely ROS_Service based or entirely Custom_Service based, instead of mix-matching. Though, I feel this isn't the correct way to go.

@fujitatomoya
Copy link
Collaborator

@CursedRock17 i am not sure if you are still working on this. Just FYI, service type support part has been already implemented by #2358 during rosbag2 service record/reply feature development.

@CursedRock17
Copy link
Contributor Author

Yeah I'm still working on this pull request, it just adds quite of bit of an increase to compile time, so I'm looking to bolster my template metaprogramming skills to increase efficiency, without sacrifing features in order to get the time to compile down. As for the service type support I did see that #2209 resolved type support issues so I should be able to remove get_type_support_handle.hpp

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

5 participants