Skip to content

Commit 51444ed

Browse files
committed
Implement first cut
Signed-off-by: methylDragon <[email protected]>
1 parent cbd48c0 commit 51444ed

File tree

11 files changed

+531
-5
lines changed

11 files changed

+531
-5
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ set(${PROJECT_NAME}_SRCS
9595
src/rclcpp/qos.cpp
9696
src/rclcpp/event_handler.cpp
9797
src/rclcpp/qos_overriding_options.cpp
98+
src/rclcpp/runtime_type_subscription.cpp
9899
src/rclcpp/serialization.cpp
99100
src/rclcpp/serialized_message.cpp
100101
src/rclcpp/service.cpp

rclcpp/include/rclcpp/generic_subscription.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,24 @@ class GenericSubscription : public rclcpp::SubscriptionBase
123123
RCLCPP_PUBLIC
124124
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;
125125

126+
127+
// RUNTIME TYPE ==================================================================================
128+
// TODO(methylDragon): Reorder later
129+
RCLCPP_PUBLIC
130+
std::shared_ptr<ser_dynamic_type_t> get_dynamic_type() override;
131+
132+
RCLCPP_PUBLIC
133+
std::shared_ptr<ser_dynamic_data_t> get_dynamic_data() override;
134+
135+
RCLCPP_PUBLIC
136+
std::shared_ptr<serialization_support_t> get_serialization_support() override;
137+
138+
RCLCPP_PUBLIC
139+
void handle_runtime_type_message(
140+
const std::shared_ptr<serialization_support_t> & ser,
141+
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
142+
const rclcpp::MessageInfo & message_info) override;
143+
126144
private:
127145
RCLCPP_DISABLE_COPY(GenericSubscription)
128146

rclcpp/include/rclcpp/rclcpp.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,4 +167,6 @@
167167
#include "rclcpp/waitable.hpp"
168168
#include "rclcpp/wait_set.hpp"
169169

170+
#include "rclcpp/runtime_type_subscription.hpp"
171+
170172
#endif // RCLCPP__RCLCPP_HPP_
Lines changed: 182 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,182 @@
1+
// Copyright 2022 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_
16+
#define RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_
17+
18+
#include <functional>
19+
#include <memory>
20+
#include <string>
21+
22+
#include "rcpputils/shared_library.hpp"
23+
24+
#include "rclcpp/callback_group.hpp"
25+
#include "rclcpp/macros.hpp"
26+
#include "rclcpp/node_interfaces/node_base_interface.hpp"
27+
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
28+
#include "rclcpp/qos.hpp"
29+
#include "rclcpp/serialized_message.hpp"
30+
#include "rclcpp/subscription_base.hpp"
31+
#include "rclcpp/typesupport_helpers.hpp"
32+
#include "rclcpp/visibility_control.hpp"
33+
34+
namespace rclcpp
35+
{
36+
37+
/// %Subscription for messages whose type descriptions are obtained at runtime.
38+
/**
39+
* Since the type is not known at compile time, this is not a template, and the dynamic library
40+
* containing type support information has to be identified and loaded based on the type name.
41+
*
42+
* NOTE(methylDragon): No considerations for intra-process handling are made.
43+
*/
44+
class RuntimeTypeSubscription : public rclcpp::SubscriptionBase
45+
{
46+
public:
47+
// cppcheck-suppress unknownMacro
48+
RCLCPP_SMART_PTR_DEFINITIONS(RuntimeTypeSubscription)
49+
50+
template<typename AllocatorT = std::allocator<void>>
51+
RuntimeTypeSubscription(
52+
rclcpp::node_interfaces::NodeBaseInterface * node_base,
53+
rosidl_message_type_support_t & type_support_handle,
54+
const std::string & topic_name,
55+
const rclcpp::QoS & qos,
56+
// TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser
57+
// support and DynamicData, and pass that to the callback
58+
std::function<void(
59+
std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
60+
)> callback,
61+
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
62+
bool use_take_runtime_type_message = false)
63+
: SubscriptionBase(
64+
node_base,
65+
type_support_handle,
66+
topic_name,
67+
options.to_rcl_subscription_options(qos),
68+
options.event_callbacks,
69+
options.use_default_callbacks,
70+
false,
71+
true,
72+
use_take_runtime_type_message),
73+
ts_(type_support_handle),
74+
callback_(callback)
75+
{
76+
if(type_support_handle.typesupport_identifier
77+
!= rmw_typesupport_runtime_type_introspection_c__identifier)
78+
{
79+
throw std::runtime_error(
80+
"RuntimeTypeSubscription must use runtime type introspection type support!");
81+
}
82+
}
83+
84+
// TODO(methylDragon):
85+
/// Deferred type description constructor, only usable if the middleware implementation supports
86+
/// type discovery
87+
// template<typename AllocatorT = std::allocator<void>>
88+
// RuntimeTypeSubscription(
89+
// rclcpp::node_interfaces::NodeBaseInterface * node_base,
90+
// const std::string & topic_name,
91+
// const rclcpp::QoS & qos,
92+
// // TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser
93+
// // support and DynamicData, and pass that to the callback
94+
// std::function<void(
95+
// std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
96+
// )> callback,
97+
// const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
98+
// const char * serialization_lib_name = nullptr)
99+
// : SubscriptionBase(
100+
// node_base,
101+
// // NOTE(methylDragon): Since the typesupport is deferred, it needs to be modified post-hoc
102+
// // which means it technically isn't const correct...
103+
// *rmw_get_runtime_type_message_typesupport_handle(serialization_lib_name),
104+
// topic_name,
105+
// options.to_rcl_subscription_options(qos),
106+
// options.event_callbacks,
107+
// options.use_default_callbacks,
108+
// false,
109+
// true),
110+
// callback_(callback)
111+
// {}
112+
113+
RCLCPP_PUBLIC
114+
virtual ~RuntimeTypeSubscription() = default;
115+
116+
// Same as create_serialized_message() as the subscription is to serialized_messages only
117+
RCLCPP_PUBLIC
118+
std::shared_ptr<void> create_message() override;
119+
120+
RCLCPP_PUBLIC
121+
std::shared_ptr<rclcpp::SerializedMessage> create_serialized_message() override;
122+
123+
/// Cast the message to a rclcpp::SerializedMessage and call the callback.
124+
RCLCPP_PUBLIC
125+
void handle_message(
126+
std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) override;
127+
128+
/// Handle dispatching rclcpp::SerializedMessage to user callback.
129+
RCLCPP_PUBLIC
130+
void
131+
handle_serialized_message(
132+
const std::shared_ptr<rclcpp::SerializedMessage> & serialized_message,
133+
const rclcpp::MessageInfo & message_info) override;
134+
135+
/// This function is currently not implemented.
136+
RCLCPP_PUBLIC
137+
void handle_loaned_message(
138+
void * loaned_message, const rclcpp::MessageInfo & message_info) override;
139+
140+
// Same as return_serialized_message() as the subscription is to serialized_messages only
141+
RCLCPP_PUBLIC
142+
void return_message(std::shared_ptr<void> & message) override;
143+
144+
RCLCPP_PUBLIC
145+
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;
146+
147+
148+
// RUNTIME TYPE ==================================================================================
149+
// TODO(methylDragon): Reorder later
150+
RCLCPP_PUBLIC
151+
std::shared_ptr<ser_dynamic_type_t>
152+
get_dynamic_type() override;
153+
154+
RCLCPP_PUBLIC
155+
std::shared_ptr<ser_dynamic_data_t>
156+
get_dynamic_data() override;
157+
158+
RCLCPP_PUBLIC
159+
std::shared_ptr<serialization_support_t>
160+
get_serialization_support() override;
161+
162+
RCLCPP_PUBLIC
163+
void handle_runtime_type_message(
164+
const std::shared_ptr<serialization_support_t> & ser,
165+
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
166+
const rclcpp::MessageInfo & message_info
167+
) override;
168+
169+
170+
private:
171+
RCLCPP_DISABLE_COPY(RuntimeTypeSubscription)
172+
173+
rosidl_message_type_support_t & ts_;
174+
175+
std::function<void(
176+
std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
177+
)> callback_;
178+
};
179+
180+
} // namespace rclcpp
181+
182+
#endif // RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_

rclcpp/include/rclcpp/subscription.hpp

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -388,6 +388,43 @@ class Subscription : public SubscriptionBase
388388
return any_callback_.use_take_shared_method();
389389
}
390390

391+
// RUNTIME TYPE ==================================================================================
392+
// TODO(methylDragon): Reorder later
393+
// TODO(methylDragon): Implement later...
394+
std::shared_ptr<ser_dynamic_type_t>
395+
get_dynamic_type() override
396+
{
397+
throw rclcpp::exceptions::UnimplementedError(
398+
"get_dynamic_type is not implemented for Subscription");
399+
}
400+
401+
std::shared_ptr<ser_dynamic_data_t>
402+
get_dynamic_data() override
403+
{
404+
throw rclcpp::exceptions::UnimplementedError(
405+
"get_dynamic_data is not implemented for Subscription");
406+
}
407+
408+
std::shared_ptr<serialization_support_t>
409+
get_serialization_support() override
410+
{
411+
throw rclcpp::exceptions::UnimplementedError(
412+
"get_serialization_support is not implemented for Subscription");
413+
}
414+
415+
void
416+
handle_runtime_type_message(
417+
const std::shared_ptr<serialization_support_t> & ser,
418+
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
419+
const rclcpp::MessageInfo & message_info) override
420+
{
421+
(void) ser;
422+
(void) dyn_data;
423+
(void) message_info;
424+
throw rclcpp::exceptions::UnimplementedError(
425+
"handle_runtime_type_message is not implemented for Subscription");
426+
}
427+
391428
private:
392429
RCLCPP_DISABLE_COPY(Subscription)
393430

rclcpp/include/rclcpp/subscription_base.hpp

Lines changed: 62 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,8 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
7777
* \param[in] topic_name Name of the topic to subscribe to.
7878
* \param[in] subscription_options Options for the subscription.
7979
* \param[in] is_serialized is true if the message will be delivered still serialized
80+
* \param[in] use_runtime_type_cb is true if the message will be taken serialized and then handled
81+
* using dynamic type and dynamic data (type constructed at runtime)
8082
*/
8183
RCLCPP_PUBLIC
8284
SubscriptionBase(
@@ -86,7 +88,12 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
8688
const rcl_subscription_options_t & subscription_options,
8789
const SubscriptionEventCallbacks & event_callbacks,
8890
bool use_default_callbacks,
89-
bool is_serialized = false);
91+
bool is_serialized = false,
92+
bool use_runtime_type_cb = false,
93+
bool use_take_runtime_type_message = false);
94+
// TODO(methylDragon): If we don't need this, remove it,
95+
// rclcpp::node_interfaces::NodeGraphInterface * node_graph = 0,
96+
// rclcpp::node_interfaces::NodeServicesInterface * node_services = 0);
9097

9198
/// Destructor.
9299
RCLCPP_PUBLIC
@@ -535,6 +542,54 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
535542
rclcpp::ContentFilterOptions
536543
get_content_filter() const;
537544

545+
// RUNTIME TYPE ==================================================================================
546+
// TODO(methylDragon): Reorder later
547+
RCLCPP_PUBLIC
548+
virtual
549+
std::shared_ptr<ser_dynamic_type_t>
550+
get_dynamic_type() = 0;
551+
552+
RCLCPP_PUBLIC
553+
virtual
554+
std::shared_ptr<ser_dynamic_data_t>
555+
get_dynamic_data() = 0;
556+
557+
RCLCPP_PUBLIC
558+
virtual
559+
std::shared_ptr<serialization_support_t>
560+
get_serialization_support() = 0;
561+
562+
RCLCPP_PUBLIC
563+
virtual
564+
void
565+
handle_runtime_type_message(
566+
const std::shared_ptr<serialization_support_t> & ser,
567+
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
568+
const rclcpp::MessageInfo & message_info
569+
) = 0;
570+
571+
// TODO(methylDragon):
572+
// RCLCPP_PUBLIC
573+
// bool
574+
// take_runtime_type_message(ser_dynamic_data_t * message_out, rclcpp::MessageInfo & message_info_out);
575+
576+
/// Return if the subscription should use runtime type
577+
/**
578+
* This will cause the subscription to use the handle_runtime_type_message methods, which must be
579+
* used with take_serialized or take_runtime_type.
580+
*
581+
* \return `true` if the subscription should use a runtime type callback, `false` otherwise
582+
*/
583+
RCLCPP_PUBLIC
584+
bool
585+
use_runtime_type_cb() const;
586+
587+
RCLCPP_PUBLIC
588+
bool
589+
use_take_runtime_type_message() const;
590+
// ===============================================================================================
591+
592+
538593
protected:
539594
template<typename EventCallbackT>
540595
void
@@ -568,6 +623,10 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
568623

569624
rclcpp::node_interfaces::NodeBaseInterface * const node_base_;
570625

626+
// TODO(methylDragon): Remove if we don't need this
627+
// rclcpp::node_interfaces::NodeGraphInterface * const node_graph_;
628+
// rclcpp::node_interfaces::NodeServicesInterface * const node_services_;
629+
571630
std::shared_ptr<rcl_node_t> node_handle_;
572631
std::shared_ptr<rcl_subscription_t> subscription_handle_;
573632
std::shared_ptr<rcl_subscription_t> intra_process_subscription_handle_;
@@ -588,6 +647,8 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
588647

589648
rosidl_message_type_support_t type_support_;
590649
bool is_serialized_;
650+
bool use_runtime_type_cb_;
651+
bool use_take_runtime_type_message_;
591652

592653
std::atomic<bool> subscription_in_use_by_wait_set_{false};
593654
std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};

0 commit comments

Comments
 (0)