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

Create MessageMemoryStrategy for subscribers #64

Merged
merged 1 commit into from
Jul 24, 2015

Conversation

jacquelinekay
Copy link
Contributor

To avoid new whenever a message is received by the subscriber, abstract out the memory strategy for subscribers. MessageMemoryStrategy is templated on the message type and gets passed to the subscriber constructor.

Example usage in ros2/examples#39

@jacquelinekay jacquelinekay added the in progress Actively being worked on (Kanban column) label Jul 22, 2015
@jacquelinekay jacquelinekay self-assigned this Jul 22, 2015
@jacquelinekay jacquelinekay added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Jul 22, 2015

std::shared_ptr<void> borrow_message()
{
return message_;
Copy link
Member

Choose a reason for hiding this comment

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

What happens when this is called from multiple threads, i.e. when queue_size is greater than 1 and a multithreaded executor is used?

@jacquelinekay jacquelinekay added in progress Actively being worked on (Kanban column) and removed in review Waiting for review (Kanban column) labels Jul 23, 2015
std::shared_ptr<MessageT> message_;

};

Copy link
Member

Choose a reason for hiding this comment

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

I agree, it should be possible to make a solid reset function using the generated code. Though it probably needs to be a free function that takes the message as an argument, to avoid collisions with a message field called reset. Either that or the reset function would need to contain __ somewhere.

@jacquelinekay
Copy link
Contributor Author

summary of changes:

Generalized SingleMsgStrategy to MessagePoolMemoryStrategy.
Implemented placement new for messages to ensure resetting of state.
Keep track of usage state and throw an error if calling code attempts to borrow a message that is currently in use.
Use enable_if to disallow specialization of MessagePoolMemoryStrategy for non-fixed size messages.

@jacquelinekay jacquelinekay added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Jul 23, 2015
protected:
std::array<MessageT, size> msg_pool_;
std::array<bool, size> msg_used_;
std::array<std::shared_ptr<MessageT>, size> msg_ptrs_;
Copy link
Member

Choose a reason for hiding this comment

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

Since all three arrays use the same index wouldn't it make sense to only have one array which contains a struct with three members?

throw std::runtime_error("Tried to access message that was still in use! Abort.");
}
pool[current_index].msg_ptr_->~MessageT();
new (pool[current_index].msg_ptr_.get())MessageT;
Copy link
Member

Choose a reason for hiding this comment

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

Does this compile? I've always called the constructor explicitly, it would be like this:

new (pool[current_index].msg_ptr_.get()) MessageT();

(note the trailing ()) If this compiles, then no worries, I just didn't know you could do that.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yep, it does compile. actually, what bothers me is that uncrustify always removes the space between the memory location and the name of the class, regardless of trailing parentheses:

new (pool[current_index].msg_ptr_.get()) MessageT; -> new (pool[current_index].msg_ptr_.get())MessageT;

I'm not going to mess with that though.

Copy link
Member

Choose a reason for hiding this comment

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

Yeah, that does bother me too; it makes it look like a c-style cast or something.

@wjwwood
Copy link
Member

wjwwood commented Jul 24, 2015

This is looking great! +1

@esteve
Copy link
Member

esteve commented Jul 24, 2015

+1

@jacquelinekay
Copy link
Contributor Author

jenkins: http://ci.ros2.org/job/ros2_batch_ci_linux/79/

@dirk-thomas, any more comments? Otherwise I will merge this by the end of the day.

@dirk-thomas
Copy link
Member

+1 to squash and merge.

jacquelinekay added a commit that referenced this pull request Jul 24, 2015
Create MessageMemoryStrategy for subscribers
@jacquelinekay jacquelinekay merged commit e16cef5 into master Jul 24, 2015
@jacquelinekay jacquelinekay removed the in review Waiting for review (Kanban column) label Jul 24, 2015
@jacquelinekay jacquelinekay deleted the msg_memory_strategy branch July 24, 2015 22:06
mauropasse pushed a commit to mauropasse/rclcpp that referenced this pull request Apr 28, 2021
Complete support for rmw listener APIs
nnmm pushed a commit to ApexAI/rclcpp that referenced this pull request Jul 9, 2022
DensoADAS pushed a commit to DensoADAS/rclcpp that referenced this pull request Aug 5, 2022
* ros2GH-64 Rearrange default plugins build to use public headers

Also already links write integration test against the default plugins.

* ros2GH-64 Remove after_write_action

Query the underlying db directly in tests to determine the amount of
recorded messages.

* ros2GH-64 Add convenience getter for single line SQL result

* ros2GH-64 Add visibility macros to enable linking on Windows

* ros2GH-64 Remove second sqlite exception class (it is not needed)

* ros2GH-64 Fix hanging rosbag2_read_integration_test

* ros2GH-64 Always log sqlite return code

* ros2GH-64 Improve opening of sqlite database

- Always open db with threading mode multi-thread. This forbids
  sharing database connections across threads. Db access from multiple
  threads is possible when each thread uses its own connection.
- Open sqlite db accordingly to given io flags. Readonly open works
  only with already existing database.
- Set journal mode pragma to WAL (write ahead log) and synchronous
  pragma to NORMAL. This should yield good write performance.
- Small fix: use *.db3 as db name in tests.

* ros2GH-64 Fix package test dependencies

* ros2GH-64 Fix cppcheck error

* ros2GH-64 Fix asserting typesupport in test (varies on architectures)

* Cleanup

- consistently use const ref of string instead of string for function
  arguments
- simplify package dependencies
- minor formatting

* Make play integration test compile on Mac

* Fix sqlite_wrapper_integration_test
DensoADAS pushed a commit to DensoADAS/rclcpp that referenced this pull request Aug 5, 2022
* ros2GH-118 Rename rosbag2_storage::TopicMetadata to TopicInformation and rosbag2_storage::TopicwithType to TopicMetadata

- The former TopicWithTye struct will be enlarged to contain also the rmw serialization format relative to the topic. This is why the name 'TopicMetadata' is now better suited for it.

* ros2GH-17 Rename timestamp to time_stamp for consistency in types

* Fix renaming of TopicWithType to TopicMetadata

* formatting

* pass by const ref
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.

4 participants