Skip to content

Commit

Permalink
Implement first cut
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Jan 30, 2023
1 parent ab71df3 commit 0ee1cee
Show file tree
Hide file tree
Showing 11 changed files with 531 additions and 5 deletions.
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/qos.cpp
src/rclcpp/qos_event.cpp
src/rclcpp/qos_overriding_options.cpp
src/rclcpp/runtime_type_subscription.cpp
src/rclcpp/serialization.cpp
src/rclcpp/serialized_message.cpp
src/rclcpp/service.cpp
Expand Down
18 changes: 18 additions & 0 deletions rclcpp/include/rclcpp/generic_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,24 @@ class GenericSubscription : public rclcpp::SubscriptionBase
RCLCPP_PUBLIC
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;


// RUNTIME TYPE ==================================================================================
// TODO(methylDragon): Reorder later
RCLCPP_PUBLIC
std::shared_ptr<ser_dynamic_type_t> get_dynamic_type() override;

RCLCPP_PUBLIC
std::shared_ptr<ser_dynamic_data_t> get_dynamic_data() override;

RCLCPP_PUBLIC
std::shared_ptr<serialization_support_t> get_serialization_support() override;

RCLCPP_PUBLIC
void handle_runtime_type_message(
const std::shared_ptr<serialization_support_t> & ser,
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
const rclcpp::MessageInfo & message_info) override;

private:
RCLCPP_DISABLE_COPY(GenericSubscription)

Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,4 +167,6 @@
#include "rclcpp/waitable.hpp"
#include "rclcpp/wait_set.hpp"

#include "rclcpp/runtime_type_subscription.hpp"

#endif // RCLCPP__RCLCPP_HPP_
182 changes: 182 additions & 0 deletions rclcpp/include/rclcpp/runtime_type_subscription.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,182 @@
// Copyright 2022 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_
#define RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_

#include <functional>
#include <memory>
#include <string>

#include "rcpputils/shared_library.hpp"

#include "rclcpp/callback_group.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rclcpp/subscription_base.hpp"
#include "rclcpp/typesupport_helpers.hpp"
#include "rclcpp/visibility_control.hpp"

namespace rclcpp
{

/// %Subscription for messages whose type descriptions are obtained at runtime.
/**
* Since the type is not known at compile time, this is not a template, and the dynamic library
* containing type support information has to be identified and loaded based on the type name.
*
* NOTE(methylDragon): No considerations for intra-process handling are made.
*/
class RuntimeTypeSubscription : public rclcpp::SubscriptionBase
{
public:
// cppcheck-suppress unknownMacro
RCLCPP_SMART_PTR_DEFINITIONS(RuntimeTypeSubscription)

template<typename AllocatorT = std::allocator<void>>
RuntimeTypeSubscription(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
rosidl_message_type_support_t & type_support_handle,
const std::string & topic_name,
const rclcpp::QoS & qos,
// TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser
// support and DynamicData, and pass that to the callback
std::function<void(
std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
)> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
bool use_take_runtime_type_message = false)
: SubscriptionBase(
node_base,
type_support_handle,
topic_name,
options.to_rcl_subscription_options(qos),
options.event_callbacks,
options.use_default_callbacks,
false,
true,
use_take_runtime_type_message),
ts_(type_support_handle),
callback_(callback)
{
if(type_support_handle.typesupport_identifier
!= rmw_typesupport_runtime_type_introspection_c__identifier)
{
throw std::runtime_error(
"RuntimeTypeSubscription must use runtime type introspection type support!");
}
}

// TODO(methylDragon):
/// Deferred type description constructor, only usable if the middleware implementation supports
/// type discovery
// template<typename AllocatorT = std::allocator<void>>
// RuntimeTypeSubscription(
// rclcpp::node_interfaces::NodeBaseInterface * node_base,
// const std::string & topic_name,
// const rclcpp::QoS & qos,
// // TODO(methylDragons): Eventually roll out an rclcpp::DynamicData that encompasses the ser
// // support and DynamicData, and pass that to the callback
// std::function<void(
// std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
// )> callback,
// const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
// const char * serialization_lib_name = nullptr)
// : SubscriptionBase(
// node_base,
// // NOTE(methylDragon): Since the typesupport is deferred, it needs to be modified post-hoc
// // which means it technically isn't const correct...
// *rmw_get_runtime_type_message_typesupport_handle(serialization_lib_name),
// topic_name,
// options.to_rcl_subscription_options(qos),
// options.event_callbacks,
// options.use_default_callbacks,
// false,
// true),
// callback_(callback)
// {}

RCLCPP_PUBLIC
virtual ~RuntimeTypeSubscription() = default;

// Same as create_serialized_message() as the subscription is to serialized_messages only
RCLCPP_PUBLIC
std::shared_ptr<void> create_message() override;

RCLCPP_PUBLIC
std::shared_ptr<rclcpp::SerializedMessage> create_serialized_message() override;

/// Cast the message to a rclcpp::SerializedMessage and call the callback.
RCLCPP_PUBLIC
void handle_message(
std::shared_ptr<void> & message, const rclcpp::MessageInfo & message_info) override;

/// Handle dispatching rclcpp::SerializedMessage to user callback.
RCLCPP_PUBLIC
void
handle_serialized_message(
const std::shared_ptr<rclcpp::SerializedMessage> & serialized_message,
const rclcpp::MessageInfo & message_info) override;

/// This function is currently not implemented.
RCLCPP_PUBLIC
void handle_loaned_message(
void * loaned_message, const rclcpp::MessageInfo & message_info) override;

// Same as return_serialized_message() as the subscription is to serialized_messages only
RCLCPP_PUBLIC
void return_message(std::shared_ptr<void> & message) override;

RCLCPP_PUBLIC
void return_serialized_message(std::shared_ptr<rclcpp::SerializedMessage> & message) override;


// RUNTIME TYPE ==================================================================================
// TODO(methylDragon): Reorder later
RCLCPP_PUBLIC
std::shared_ptr<ser_dynamic_type_t>
get_dynamic_type() override;

RCLCPP_PUBLIC
std::shared_ptr<ser_dynamic_data_t>
get_dynamic_data() override;

RCLCPP_PUBLIC
std::shared_ptr<serialization_support_t>
get_serialization_support() override;

RCLCPP_PUBLIC
void handle_runtime_type_message(
const std::shared_ptr<serialization_support_t> & ser,
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
const rclcpp::MessageInfo & message_info
) override;


private:
RCLCPP_DISABLE_COPY(RuntimeTypeSubscription)

rosidl_message_type_support_t & ts_;

std::function<void(
std::shared_ptr<serialization_support_t>, std::shared_ptr<ser_dynamic_data_t>
)> callback_;
};

} // namespace rclcpp

#endif // RCLCPP__RUNTIME_TYPE_SUBSCRIPTION_HPP_
37 changes: 37 additions & 0 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,6 +388,43 @@ class Subscription : public SubscriptionBase
return any_callback_.use_take_shared_method();
}

// RUNTIME TYPE ==================================================================================
// TODO(methylDragon): Reorder later
// TODO(methylDragon): Implement later...
std::shared_ptr<ser_dynamic_type_t>
get_dynamic_type() override
{
throw rclcpp::exceptions::UnimplementedError(
"get_dynamic_type is not implemented for Subscription");
}

std::shared_ptr<ser_dynamic_data_t>
get_dynamic_data() override
{
throw rclcpp::exceptions::UnimplementedError(
"get_dynamic_data is not implemented for Subscription");
}

std::shared_ptr<serialization_support_t>
get_serialization_support() override
{
throw rclcpp::exceptions::UnimplementedError(
"get_serialization_support is not implemented for Subscription");
}

void
handle_runtime_type_message(
const std::shared_ptr<serialization_support_t> & ser,
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
const rclcpp::MessageInfo & message_info) override
{
(void) ser;
(void) dyn_data;
(void) message_info;
throw rclcpp::exceptions::UnimplementedError(
"handle_runtime_type_message is not implemented for Subscription");
}

private:
RCLCPP_DISABLE_COPY(Subscription)

Expand Down
63 changes: 62 additions & 1 deletion rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,8 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
* \param[in] topic_name Name of the topic to subscribe to.
* \param[in] subscription_options Options for the subscription.
* \param[in] is_serialized is true if the message will be delivered still serialized
* \param[in] use_runtime_type_cb is true if the message will be taken serialized and then handled
* using dynamic type and dynamic data (type constructed at runtime)
*/
RCLCPP_PUBLIC
SubscriptionBase(
Expand All @@ -86,7 +88,12 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
const rcl_subscription_options_t & subscription_options,
const SubscriptionEventCallbacks & event_callbacks,
bool use_default_callbacks,
bool is_serialized = false);
bool is_serialized = false,
bool use_runtime_type_cb = false,
bool use_take_runtime_type_message = false);
// TODO(methylDragon): If we don't need this, remove it,
// rclcpp::node_interfaces::NodeGraphInterface * node_graph = 0,
// rclcpp::node_interfaces::NodeServicesInterface * node_services = 0);

/// Destructor.
RCLCPP_PUBLIC
Expand Down Expand Up @@ -535,6 +542,54 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
rclcpp::ContentFilterOptions
get_content_filter() const;

// RUNTIME TYPE ==================================================================================
// TODO(methylDragon): Reorder later
RCLCPP_PUBLIC
virtual
std::shared_ptr<ser_dynamic_type_t>
get_dynamic_type() = 0;

RCLCPP_PUBLIC
virtual
std::shared_ptr<ser_dynamic_data_t>
get_dynamic_data() = 0;

RCLCPP_PUBLIC
virtual
std::shared_ptr<serialization_support_t>
get_serialization_support() = 0;

RCLCPP_PUBLIC
virtual
void
handle_runtime_type_message(
const std::shared_ptr<serialization_support_t> & ser,
const std::shared_ptr<ser_dynamic_data_t> & dyn_data,
const rclcpp::MessageInfo & message_info
) = 0;

// TODO(methylDragon):
// RCLCPP_PUBLIC
// bool
// take_runtime_type_message(ser_dynamic_data_t * message_out, rclcpp::MessageInfo & message_info_out);

/// Return if the subscription should use runtime type
/**
* This will cause the subscription to use the handle_runtime_type_message methods, which must be
* used with take_serialized or take_runtime_type.
*
* \return `true` if the subscription should use a runtime type callback, `false` otherwise
*/
RCLCPP_PUBLIC
bool
use_runtime_type_cb() const;

RCLCPP_PUBLIC
bool
use_take_runtime_type_message() const;
// ===============================================================================================


protected:
template<typename EventCallbackT>
void
Expand Down Expand Up @@ -565,6 +620,10 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>

rclcpp::node_interfaces::NodeBaseInterface * const node_base_;

// TODO(methylDragon): Remove if we don't need this
// rclcpp::node_interfaces::NodeGraphInterface * const node_graph_;
// rclcpp::node_interfaces::NodeServicesInterface * const node_services_;

std::shared_ptr<rcl_node_t> node_handle_;
std::shared_ptr<rcl_subscription_t> subscription_handle_;
std::shared_ptr<rcl_subscription_t> intra_process_subscription_handle_;
Expand All @@ -585,6 +644,8 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>

rosidl_message_type_support_t type_support_;
bool is_serialized_;
bool use_runtime_type_cb_;
bool use_take_runtime_type_message_;

std::atomic<bool> subscription_in_use_by_wait_set_{false};
std::atomic<bool> intra_process_subscription_waitable_in_use_by_wait_set_{false};
Expand Down
Loading

0 comments on commit 0ee1cee

Please sign in to comment.