Skip to content

Commit

Permalink
Refactor dynamic type support structs to use allocators and refs
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Apr 10, 2023
1 parent 8447d36 commit c52f250
Show file tree
Hide file tree
Showing 13 changed files with 480 additions and 658 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
{ \
ValueT out; \
rosidl_dynamic_typesupport_dynamic_data_get_ ## FunctionT ## _value( \
rosidl_dynamic_data_.get(), id, &out); \
&rosidl_dynamic_data_, id, &out); \
return out; \
}

Expand All @@ -55,7 +55,7 @@
DynamicMessage::set_value<ValueT>(rosidl_dynamic_typesupport_member_id_t id, ValueT value) \
{ \
rosidl_dynamic_typesupport_dynamic_data_set_ ## FunctionT ## _value( \
rosidl_dynamic_data_.get(), id, value); \
&rosidl_dynamic_data_, id, value); \
}

#define __DYNAMIC_MESSAGE_SET_VALUE_BY_NAME_FN(ValueT, FunctionT) \
Expand All @@ -73,7 +73,7 @@
{ \
rosidl_dynamic_typesupport_member_id_t out; \
rosidl_dynamic_typesupport_dynamic_data_insert_ ## FunctionT ## _value( \
rosidl_dynamic_data_.get(), value, &out); \
&rosidl_dynamic_data_, value, &out); \
return out; \
}

Expand Down Expand Up @@ -127,7 +127,7 @@ std::byte
DynamicMessage::get_value<std::byte>(rosidl_dynamic_typesupport_member_id_t id)
{
unsigned char out;
rosidl_dynamic_typesupport_dynamic_data_get_byte_value(get_rosidl_dynamic_data(), id, &out);
rosidl_dynamic_typesupport_dynamic_data_get_byte_value(&get_rosidl_dynamic_data(), id, &out);
return static_cast<std::byte>(out);
}

Expand All @@ -146,7 +146,7 @@ DynamicMessage::set_value<std::byte>(
rosidl_dynamic_typesupport_member_id_t id, const std::byte value)
{
rosidl_dynamic_typesupport_dynamic_data_set_byte_value(
rosidl_dynamic_data_.get(), id, static_cast<unsigned char>(value));
&rosidl_dynamic_data_, id, static_cast<unsigned char>(value));
}


Expand All @@ -164,7 +164,7 @@ DynamicMessage::insert_value<std::byte>(const std::byte value)
{
rosidl_dynamic_typesupport_member_id_t out;
rosidl_dynamic_typesupport_dynamic_data_insert_byte_value(
rosidl_dynamic_data_.get(), static_cast<unsigned char>(value), &out);
&rosidl_dynamic_data_, static_cast<unsigned char>(value), &out);
return out;
}

Expand All @@ -177,7 +177,7 @@ DynamicMessage::get_value<std::string>(rosidl_dynamic_typesupport_member_id_t id
size_t buf_length;
char * buf = nullptr;
rosidl_dynamic_typesupport_dynamic_data_get_string_value(
get_rosidl_dynamic_data(), id, &buf, &buf_length);
&get_rosidl_dynamic_data(), id, &buf, &buf_length);
auto out = std::string(buf, buf_length);
delete buf;
return out;
Expand All @@ -191,7 +191,7 @@ DynamicMessage::get_value<std::u16string>(rosidl_dynamic_typesupport_member_id_t
size_t buf_length;
char16_t * buf = nullptr;
rosidl_dynamic_typesupport_dynamic_data_get_wstring_value(
get_rosidl_dynamic_data(), id, &buf, &buf_length);
&get_rosidl_dynamic_data(), id, &buf, &buf_length);
auto out = std::u16string(buf, buf_length);
delete buf;
return out;
Expand Down Expand Up @@ -220,7 +220,7 @@ DynamicMessage::set_value<std::string>(
rosidl_dynamic_typesupport_member_id_t id, const std::string value)
{
rosidl_dynamic_typesupport_dynamic_data_set_string_value(
rosidl_dynamic_data_.get(), id, value.c_str(), value.size());
&rosidl_dynamic_data_, id, value.c_str(), value.size());
}


Expand All @@ -230,7 +230,7 @@ DynamicMessage::set_value<std::u16string>(
rosidl_dynamic_typesupport_member_id_t id, const std::u16string value)
{
rosidl_dynamic_typesupport_dynamic_data_set_wstring_value(
rosidl_dynamic_data_.get(), id, value.c_str(), value.size());
&rosidl_dynamic_data_, id, value.c_str(), value.size());
}


Expand All @@ -256,7 +256,7 @@ DynamicMessage::insert_value<std::string>(const std::string value)
{
rosidl_dynamic_typesupport_member_id_t out;
rosidl_dynamic_typesupport_dynamic_data_insert_string_value(
rosidl_dynamic_data_.get(), value.c_str(), value.size(), &out);
&rosidl_dynamic_data_, value.c_str(), value.size(), &out);
return out;
}

Expand All @@ -267,7 +267,7 @@ DynamicMessage::insert_value<std::u16string>(const std::u16string value)
{
rosidl_dynamic_typesupport_member_id_t out;
rosidl_dynamic_typesupport_dynamic_data_insert_wstring_value(
rosidl_dynamic_data_.get(), value.c_str(), value.size(), &out);
&rosidl_dynamic_data_, value.c_str(), value.size(), &out);
return out;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
const std::string & default_value) \
{ \
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _member( \
rosidl_dynamic_type_builder_.get(), \
&rosidl_dynamic_type_builder_, \
id, name.c_str(), name.size(), default_value.c_str(), default_value.size()); \
}

Expand All @@ -52,7 +52,7 @@
const std::string & default_value) \
{ \
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _array_member( \
rosidl_dynamic_type_builder_.get(), \
&rosidl_dynamic_type_builder_, \
id, name.c_str(), name.size(), default_value.c_str(), default_value.size(), \
array_length); \
}
Expand All @@ -67,7 +67,7 @@
{ \
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## \
_unbounded_sequence_member( \
rosidl_dynamic_type_builder_.get(), \
&rosidl_dynamic_type_builder_, \
id, name.c_str(), name.size(), default_value.c_str(), default_value.size()); \
}

Expand All @@ -81,7 +81,7 @@
const std::string & default_value) \
{ \
rosidl_dynamic_typesupport_dynamic_type_builder_add_ ## FunctionT ## _bounded_sequence_member( \
rosidl_dynamic_type_builder_.get(), \
&rosidl_dynamic_type_builder_, \
id, name.c_str(), name.size(), default_value.c_str(), default_value.size(), \
sequence_bound); \
}
Expand Down
96 changes: 49 additions & 47 deletions rclcpp/include/rclcpp/dynamic_typesupport/dynamic_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_HPP_
#define RCLCPP__DYNAMIC_TYPESUPPORT__DYNAMIC_MESSAGE_HPP_

#include <rcl/allocator.h>
#include <rcl/types.h>
#include <rosidl_dynamic_typesupport/types.h>

Expand All @@ -26,21 +27,18 @@
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"


namespace rclcpp
{
namespace dynamic_typesupport
{


class DynamicMessageType;
class DynamicMessageTypeBuilder;

/// Utility wrapper class for rosidl_dynamic_typesupport_dynamic_data_t *
/// Utility wrapper class for rosidl_dynamic_typesupport_dynamic_data_t
/**
* This class:
* - Manages the lifetime of the raw pointer.
* - Exposes getter methods to get the raw pointer and shared pointers
* - Exposes getter methods for the struct
* - Exposes the underlying serialization support API
*
* Ownership:
Expand All @@ -67,50 +65,48 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
// the data should be the exact same object managed by the DynamicSerializationSupport,
// otherwise the lifetime management will not work properly.

/// Construct a new DynamicMessage with the provided dynamic type builder
/// Construct a new DynamicMessage with the provided dynamic type builder, using its allocator
RCLCPP_PUBLIC
explicit DynamicMessage(std::shared_ptr<DynamicMessageTypeBuilder> dynamic_type_builder);

/// Construct a new DynamicMessage with the provided dynamic type
/// Construct a new DynamicMessage with the provided dynamic type builder and allocator
RCLCPP_PUBLIC
DynamicMessage(
std::shared_ptr<DynamicMessageTypeBuilder> dynamic_type_builder,
rcl_allocator_t allocator);

/// Construct a new DynamicMessage with the provided dynamic type, using its allocator
RCLCPP_PUBLIC
explicit DynamicMessage(std::shared_ptr<DynamicMessageType> dynamic_type);

/// Assume ownership of raw pointer
/// Construct a new DynamicMessage with the provided dynamic type and allocator
RCLCPP_PUBLIC
DynamicMessage(
DynamicSerializationSupport::SharedPtr serialization_support,
rosidl_dynamic_typesupport_dynamic_data_t * rosidl_dynamic_data);
std::shared_ptr<DynamicMessageType> dynamic_type,
rcl_allocator_t allocator);

/// Copy shared pointer
/// Assume ownership of struct
RCLCPP_PUBLIC
DynamicMessage(
DynamicSerializationSupport::SharedPtr serialization_support,
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> rosidl_dynamic_data);
rosidl_dynamic_typesupport_dynamic_data_t && rosidl_dynamic_data);

/// Loaning constructor
/// Must only be called with raw ptr obtained from loaning!
/// Must only be called with a rosidl dynaimc data object obtained from loaning!
// NOTE(methylDragon): I'd put this in protected, but I need this exposed to
// enable_shared_from_this...
RCLCPP_PUBLIC
DynamicMessage(
DynamicMessage::SharedPtr parent_data,
rosidl_dynamic_typesupport_dynamic_data_t * rosidl_loaned_data);
rosidl_dynamic_typesupport_dynamic_data_t && rosidl_loaned_data);

// NOTE(methylDragon): Deliberately no constructor from description to nudge users towards using
// construction from dynamic type/builder, which is more efficient

/// Copy constructor
RCLCPP_PUBLIC
DynamicMessage(const DynamicMessage & other);

/// Move constructor
RCLCPP_PUBLIC
DynamicMessage(DynamicMessage && other) noexcept;

/// Copy assignment
RCLCPP_PUBLIC
DynamicMessage & operator=(const DynamicMessage & other);

/// Move assignment
RCLCPP_PUBLIC
DynamicMessage & operator=(DynamicMessage && other) noexcept;
Expand All @@ -129,21 +125,13 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
get_name() const;

RCLCPP_PUBLIC
rosidl_dynamic_typesupport_dynamic_data_t *
rosidl_dynamic_typesupport_dynamic_data_t &
get_rosidl_dynamic_data();

RCLCPP_PUBLIC
const rosidl_dynamic_typesupport_dynamic_data_t *
const rosidl_dynamic_typesupport_dynamic_data_t &
get_rosidl_dynamic_data() const;

RCLCPP_PUBLIC
std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t>
get_shared_rosidl_dynamic_data();

RCLCPP_PUBLIC
std::shared_ptr<const rosidl_dynamic_typesupport_dynamic_data_t>
get_shared_rosidl_dynamic_data() const;

RCLCPP_PUBLIC
DynamicSerializationSupport::SharedPtr
get_shared_dynamic_serialization_support();
Expand Down Expand Up @@ -176,31 +164,37 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
// METHODS =======================================================================================
RCLCPP_PUBLIC
DynamicMessage
clone() const;
clone(rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
clone_shared() const;
clone_shared(rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage
init_from_type(DynamicMessageType & type) const;
init_from_type(
DynamicMessageType & type, rcl_allocator_t allocator = rcl_get_default_allocator()) const;

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
init_from_type_shared(DynamicMessageType & type) const;
init_from_type_shared(
DynamicMessageType & type, rcl_allocator_t allocator = rcl_get_default_allocator()) const;

RCLCPP_PUBLIC
bool
equals(const DynamicMessage & other) const;

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
loan_value(rosidl_dynamic_typesupport_member_id_t id);
loan_value(
rosidl_dynamic_typesupport_member_id_t id,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
loan_value(const std::string & name);
loan_value(
const std::string & name,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
void
Expand Down Expand Up @@ -232,11 +226,11 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>

RCLCPP_PUBLIC
bool
serialize(rcl_serialized_message_t * buffer);
serialize(rcl_serialized_message_t & buffer);

RCLCPP_PUBLIC
bool
deserialize(rcl_serialized_message_t * buffer);
deserialize(rcl_serialized_message_t & buffer);


// MEMBER ACCESS TEMPLATES =======================================================================
Expand Down Expand Up @@ -366,19 +360,27 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
// NESTED MEMBER ACCESS ==========================================================================
RCLCPP_PUBLIC
DynamicMessage
get_complex_value(rosidl_dynamic_typesupport_member_id_t id);
get_complex_value(
rosidl_dynamic_typesupport_member_id_t id,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage
get_complex_value(const std::string & name);
get_complex_value(
const std::string & name,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
get_complex_value_shared(rosidl_dynamic_typesupport_member_id_t id);
get_complex_value_shared(
rosidl_dynamic_typesupport_member_id_t id,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
DynamicMessage::SharedPtr
get_complex_value_shared(const std::string & name);
get_complex_value_shared(
const std::string & name,
rcl_allocator_t allocator = rcl_get_default_allocator());

RCLCPP_PUBLIC
void
Expand All @@ -405,14 +407,15 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
// DynamicSerializationSupport
DynamicSerializationSupport::SharedPtr serialization_support_;

std::shared_ptr<rosidl_dynamic_typesupport_dynamic_data_t> rosidl_dynamic_data_;

rosidl_dynamic_typesupport_dynamic_data_t rosidl_dynamic_data_;
bool is_loaned_;

// Used for returning the loaned value, and lifetime management
DynamicMessage::SharedPtr parent_data_;

private:
RCLCPP_DISABLE_COPY(DynamicMessage)

RCLCPP_PUBLIC
DynamicMessage();

Expand All @@ -423,7 +426,6 @@ class DynamicMessage : public std::enable_shared_from_this<DynamicMessage>
const rosidl_dynamic_typesupport_dynamic_data_t & dynamic_data);
};


} // namespace dynamic_typesupport
} // namespace rclcpp

Expand Down
Loading

0 comments on commit c52f250

Please sign in to comment.