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

Refactor to use rcl #207

Merged
merged 49 commits into from
Apr 24, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
49 commits
Select commit Hold shift + click to select a range
ea81bde
notify guard condition cleanup
Mar 23, 2016
bf227d6
Warnings
Mar 25, 2016
73bc7dd
Clean up guard conditions properly
Mar 25, 2016
93ba85d
Temporary storage
Mar 25, 2016
0d16715
Working towards getting that tlsf test passing again
Mar 26, 2016
e0717f2
pub/sub mostly
Mar 10, 2016
87adf80
Starting client/service
Mar 10, 2016
ffb5da6
blocked by guard condition (obviously)
Mar 11, 2016
84cfe94
Begin replacing guard conditions
Mar 11, 2016
bb4cc98
memory strategy conversion
Mar 12, 2016
85bd43b
Compiles with warnings
jacquelinekay Mar 13, 2016
61f9f34
Services and clients in mem strat
jacquelinekay Mar 13, 2016
69bb176
hacking on timers
jacquelinekay Mar 14, 2016
9bfbb8e
Reduce Timer API
Mar 14, 2016
8473102
Make some pure virtual functions in Timer implemented in the base class
Mar 14, 2016
d65ae9b
Add rcl to get_rclcpp_information
Mar 15, 2016
cb8c54c
Change heap-allocated rcl handles to stack-allocated, add all timers …
Mar 15, 2016
486e187
Starting to use rcl allocators
Mar 15, 2016
ea54212
Finish allocator interface
Mar 15, 2016
06d66a4
Address some warnings due to allocators
Mar 16, 2016
b0fba6c
Rebase/compile/fix warnings, still need to convert notify guard condi…
Mar 25, 2016
6bd0477
Convert rmw to rcl guard conditions, still need to actually add them
Mar 25, 2016
f3b1cc8
Allocator is going out of scope
Mar 25, 2016
1965af9
Ownership of options
Mar 25, 2016
ac5161e
Compile again after rebase
Mar 30, 2016
da190eb
Fix allocator
Mar 30, 2016
6992ed8
Memory issues
Mar 30, 2016
a7dcef5
memory problems in initialization fixed
Mar 30, 2016
0af71eb
publisher working (?)
Mar 30, 2016
2572a32
talker/listener works
Mar 31, 2016
0a63018
Test tweaking
Mar 31, 2016
321a17f
Fix linking to rcl
Mar 31, 2016
1ac062f
zero init timer
Apr 1, 2016
ad0f2c2
don't use rcl callback path
Apr 1, 2016
11a33fc
Timers not working
Apr 1, 2016
d37e00e
Linting
Apr 2, 2016
153cf13
Fix intra process
Apr 2, 2016
355af64
Uncrustify and fix intra process for real now
Apr 2, 2016
88e2cd8
Add rcl as a general depend, not just a build depend
Apr 4, 2016
9d2661b
remove message
Apr 4, 2016
2472194
fix linking again
Apr 4, 2016
6c2296a
Trying to fix services
Apr 5, 2016
5fbd54b
destructor inheritance
Apr 16, 2016
ac1f22d
use allocator interface in waitset
jacquelinekay Apr 19, 2016
1c715fe
Fix reallocate
jacquelinekay Apr 19, 2016
7b9e270
Correct retcode enum from rmw to rcl
Apr 20, 2016
6739c79
initialize publisher (necessary?)
Apr 20, 2016
c1fc16e
Tweaks to fix timer on Windows
jacquelinekay Apr 21, 2016
a67fe80
Lint
jacquelinekay Apr 21, 2016
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 9 additions & 7 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ cmake_minimum_required(VERSION 2.8.3)
project(rclcpp)

find_package(ament_cmake REQUIRED)
find_package(rcl REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rmw REQUIRED)
find_package(rmw_implementation REQUIRED)
Expand Down Expand Up @@ -42,13 +43,14 @@ set(${PROJECT_NAME}_SRCS
)

macro(target)
if(NOT "${target_suffix} " STREQUAL " ")
get_rcl_information("${rmw_implementation}" "rcl${target_suffix}")
endif()
add_library(${PROJECT_NAME}${target_suffix} SHARED
${${PROJECT_NAME}_SRCS})
ament_target_dependencies(${PROJECT_NAME}${target_suffix}
"rcl_interfaces"
"rmw"
"rosidl_generator_cpp"
"${rmw_implementation}")
"rcl${target_suffix}"
"rosidl_generator_cpp")

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
Expand All @@ -66,9 +68,7 @@ endmacro()
call_for_each_rmw_implementation(target GENERATE_DEFAULT)

ament_export_dependencies(ament_cmake)
ament_export_dependencies(rcl_interfaces)
ament_export_dependencies(rmw)
ament_export_dependencies(rmw_implementation)
ament_export_dependencies(rcl)
ament_export_dependencies(rosidl_generator_cpp)

ament_export_include_directories(include)
Expand All @@ -90,6 +90,7 @@ if(AMENT_ENABLE_TESTING)
ament_add_gtest(test_mapped_ring_buffer test/test_mapped_ring_buffer.cpp)
if(TARGET test_mapped_ring_buffer)
target_include_directories(test_mapped_ring_buffer PUBLIC
${rcl_INCLUDE_DIRS}
${rcl_interfaces_INCLUDE_DIRS}
${rmw_INCLUDE_DIRS}
Copy link
Member

Choose a reason for hiding this comment

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

Is rclcpp still using rmw in places? Can/should references to rmw be removed from the rclcpp build files?

${rosidl_generator_cpp_INCLUDE_DIRS}
Expand All @@ -98,6 +99,7 @@ if(AMENT_ENABLE_TESTING)
ament_add_gtest(test_intra_process_manager test/test_intra_process_manager.cpp)
if(TARGET test_intra_process_manager)
target_include_directories(test_intra_process_manager PUBLIC
${rcl_INCLUDE_DIRS}
${rcl_interfaces_INCLUDE_DIRS}
${rmw_INCLUDE_DIRS}
${rosidl_generator_cpp_INCLUDE_DIRS}
Expand Down
8 changes: 6 additions & 2 deletions rclcpp/cmake/get_rclcpp_information.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,11 @@ macro(get_rclcpp_information rmw_implementation var_prefix)
# so that the variables can be used by various functions / macros
set(${var_prefix}_FOUND TRUE)

# Get rcl using the existing macro
if(NOT "${target_suffix} " STREQUAL " ")
get_rcl_information("${rmw_implementation}" "rcl${target_suffix}")
endif()

# include directories
normalize_path(${var_prefix}_INCLUDE_DIRS
"${rclcpp_DIR}/../../../include")
Expand Down Expand Up @@ -63,8 +68,7 @@ macro(get_rclcpp_information rmw_implementation var_prefix)
# dependencies
set(_exported_dependencies
"rcl_interfaces"
"rmw"
"${rmw_implementation}"
"rcl${target_suffix}"
Copy link
Member

Choose a reason for hiding this comment

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

Should rcl_interfaces be exported here? It was removed.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I can add it back in, not sure why I removed it.

"rosidl_generator_cpp")
set(${var_prefix}_DEFINITIONS)
foreach(_dep ${_exported_dependencies})
Expand Down
60 changes: 60 additions & 0 deletions rclcpp/include/rclcpp/allocator/allocator_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <memory>

#include "rcl/allocator.h"

#include "rclcpp/allocator/allocator_deleter.hpp"

namespace rclcpp
Expand All @@ -27,6 +29,64 @@ namespace allocator
template<typename T, typename Alloc>
using AllocRebind = typename std::allocator_traits<Alloc>::template rebind_traits<T>;

template<typename Alloc>
void * retyped_allocate(size_t size, void * untyped_allocator)
{
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
if (!typed_allocator) {
throw std::runtime_error("Received incorrect allocator type");
}
return std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
}

template<typename T, typename Alloc>
void retyped_deallocate(void * untyped_pointer, void * untyped_allocator)
{
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
if (!typed_allocator) {
throw std::runtime_error("Received incorrect allocator type");
}
auto typed_ptr = static_cast<T *>(untyped_pointer);
std::allocator_traits<Alloc>::deallocate(*typed_allocator, typed_ptr, 1);
}

template<typename T, typename Alloc>
void * retyped_reallocate(void * untyped_pointer, size_t size, void * untyped_allocator)
{
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
if (!typed_allocator) {
throw std::runtime_error("Received incorrect allocator type");
}
auto typed_ptr = static_cast<T *>(untyped_pointer);
std::allocator_traits<Alloc>::deallocate(*typed_allocator, typed_ptr, 1);
return std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
}


// Convert a std::allocator_traits-formatted Allocator into an rcl allocator
template<typename T, typename Alloc,
typename std::enable_if<!std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
rcl_allocator_t get_rcl_allocator(Alloc & allocator)
{
rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
#ifndef _WIN32
rcl_allocator.allocate = &retyped_allocate<Alloc>;
rcl_allocator.deallocate = &retyped_deallocate<T, Alloc>;
rcl_allocator.reallocate = &retyped_reallocate<T, Alloc>;
rcl_allocator.state = &allocator;
#endif
return rcl_allocator;
}

// TODO(jacquelinekay) Workaround for an incomplete implementation of std::allocator<void>
template<typename T, typename Alloc,
typename std::enable_if<std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
rcl_allocator_t get_rcl_allocator(Alloc & allocator)
{
(void)allocator;
return rcl_get_default_allocator();
}

} // namespace allocator
} // namespace rclcpp

Expand Down
53 changes: 39 additions & 14 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,15 @@
#include <tuple>
#include <utility>

#include "rcl/client.h"
Copy link
Member

Choose a reason for hiding this comment

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

nitpick: alpha-ordering

#include "rcl/error_handling.h"

#include "rclcpp/function_traits.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/type_support_decl.hpp"
Copy link
Member

Choose a reason for hiding this comment

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

alpha

#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"

#include "rmw/error_handling.h"
#include "rmw/rmw.h"

Expand All @@ -42,32 +47,31 @@ class ClientBase

RCLCPP_PUBLIC
ClientBase(
std::shared_ptr<rmw_node_t> node_handle,
rmw_client_t * client_handle,
std::shared_ptr<rcl_node_t> node_handle,
Copy link
Member

Choose a reason for hiding this comment

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

Why did you remove the destructor declaration? I think it might be important that it is declared virtual.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I'm not sure. Previously the child templated class Client did not implement a custom destructor, and I add one in this pull request. Maybe I needed to delete this declaration to make it work. I can put this back in and see.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

When I add it back I get:

librclcpp__rmw_opensplice_cpp.so: undefined reference to `rclcpp::client::ClientBase::~ClientBase()'
librclcpp__rmw_opensplice_cpp.so: undefined reference to `typeinfo for rclcpp::client::ClientBase'
librclcpp__rmw_opensplice_cpp.so: undefined reference to `vtable for rclcpp::client::ClientBase'

Copy link
Member

Choose a reason for hiding this comment

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

It needs to be implemented or made pure virtual. I'd say give it an empty implementation in the .cpp file.

const std::string & service_name);

RCLCPP_PUBLIC
virtual ~ClientBase();
~ClientBase();

RCLCPP_PUBLIC
const std::string &
get_service_name() const;

RCLCPP_PUBLIC
const rmw_client_t *
const rcl_client_t *
get_client_handle() const;

virtual std::shared_ptr<void> create_response() = 0;
virtual std::shared_ptr<rmw_request_id_t> create_request_header() = 0;
virtual void handle_response(
std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;

private:
protected:
Copy link
Member

Choose a reason for hiding this comment

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

Any rational here? making members protected is possibly the right thing to do, but it's not clear why you decided to do this.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I decided to push some member variables that are not templated but need to be accessible by the child class into the parent class.

RCLCPP_DISABLE_COPY(ClientBase);

std::shared_ptr<rmw_node_t> node_handle_;
std::shared_ptr<rcl_node_t> node_handle_;

rmw_client_t * client_handle_;
rcl_client_t client_handle_ = rcl_get_zero_initialized_client();
std::string service_name_;
};

Expand All @@ -93,11 +97,32 @@ class Client : public ClientBase
RCLCPP_SMART_PTR_DEFINITIONS(Client);

Client(
std::shared_ptr<rmw_node_t> node_handle,
rmw_client_t * client_handle,
const std::string & service_name)
: ClientBase(node_handle, client_handle, service_name)
{}
std::shared_ptr<rcl_node_t> node_handle,
const std::string & service_name,
rcl_client_options_t & client_options)
Copy link
Member

Choose a reason for hiding this comment

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

You changed the order of the arguments here, does this not need changes in the examples and stuff like that?

Copy link
Member

Choose a reason for hiding this comment

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

nvm, this is not used directly by the user.

: ClientBase(node_handle, service_name)
{
using rosidl_generator_cpp::get_service_type_support_handle;
auto service_type_support_handle =
get_service_type_support_handle<ServiceT>();
if (rcl_client_init(&client_handle_, this->node_handle_.get(),
service_type_support_handle, service_name.c_str(), &client_options) != RCL_RET_OK)
{
// *INDENT-OFF* (prevent uncrustify from making unecessary indents here)
throw std::runtime_error(
std::string("could not create client: ") +
rcl_get_error_string_safe());
// *INDENT-ON*
}
}

virtual ~Client()
{
if (rcl_client_fini(&client_handle_, node_handle_.get()) != RCL_RET_OK) {
fprintf(stderr,
"Error in destruction of rmw client handle: %s\n", rmw_get_error_string_safe());
}
}

std::shared_ptr<void> create_response()
{
Expand Down Expand Up @@ -149,10 +174,10 @@ class Client : public ClientBase
{
std::lock_guard<std::mutex> lock(pending_requests_mutex_);
int64_t sequence_number;
if (RMW_RET_OK != rmw_send_request(get_client_handle(), request.get(), &sequence_number)) {
if (RCL_RET_OK != rcl_send_request(get_client_handle(), request.get(), &sequence_number)) {
// *INDENT-OFF* (prevent uncrustify from making unecessary indents here)
throw std::runtime_error(
std::string("failed to send request: ") + rmw_get_error_string_safe());
std::string("failed to send request: ") + rcl_get_error_string_safe());
// *INDENT-ON*
}

Expand Down
24 changes: 12 additions & 12 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@
#include <string>
#include <vector>

#include "rcl/guard_condition.h"
#include "rcl/wait.h"

#include "rclcpp/any_executable.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/memory_strategies.hpp"
Expand Down Expand Up @@ -193,10 +196,12 @@ class Executor
}

auto end_time = std::chrono::steady_clock::now();
if (timeout > std::chrono::nanoseconds::zero()) {
end_time += timeout;
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
timeout);
if (timeout_ns > std::chrono::nanoseconds::zero()) {
end_time += timeout_ns;
}
auto timeout_left = timeout;
std::chrono::nanoseconds timeout_left = timeout_ns;

while (rclcpp::utilities::ok()) {
// Do one item of work.
Expand All @@ -207,7 +212,7 @@ class Executor
return FutureReturnCode::SUCCESS;
}
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
if (timeout < std::chrono::nanoseconds::zero()) {
if (timeout_ns < std::chrono::nanoseconds::zero()) {
continue;
}
// Otherwise check if we still have time to wait, return TIMEOUT if not.
Expand All @@ -216,8 +221,7 @@ class Executor
return FutureReturnCode::TIMEOUT;
}
// Subtract the elapsed time from the original timeout.
using duration_type = std::chrono::duration<int64_t, TimeT>;
timeout_left = std::chrono::duration_cast<duration_type>(end_time - now);
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
}

// The future did not complete before ok() returned false, return INTERRUPTED.
Expand Down Expand Up @@ -291,10 +295,6 @@ class Executor
void
get_next_timer(AnyExecutable::SharedPtr any_exec);
Copy link
Member

Choose a reason for hiding this comment

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

Why was this removed?

Copy link
Member

Choose a reason for hiding this comment

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

nvm, I guess it's probably handled by rcl_wait now. Sorry for the noise.


RCLCPP_PUBLIC
std::chrono::nanoseconds
get_earliest_timer();

RCLCPP_PUBLIC
AnyExecutable::SharedPtr
get_next_ready_executable();
Expand All @@ -307,10 +307,10 @@ class Executor
std::atomic_bool spinning;

/// Guard condition for signaling the rmw layer to wake up for special events.
rmw_guard_condition_t * interrupt_guard_condition_;
rcl_guard_condition_t interrupt_guard_condition_ = rcl_get_zero_initialized_guard_condition();

/// Waitset for managing entities that the rmw layer waits on.
rmw_waitset_t * waitset_;
rcl_wait_set_t waitset_ = rcl_get_zero_initialized_wait_set();

/// The memory strategy: an interface for handling user-defined memory allocation strategies.
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_;
Expand Down
38 changes: 19 additions & 19 deletions rclcpp/include/rclcpp/memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@
#include <memory>
#include <vector>

#include "rcl/allocator.h"
#include "rcl/wait.h"

#include "rclcpp/any_executable.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
Expand All @@ -40,31 +43,25 @@ class RCLCPP_PUBLIC MemoryStrategy
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(MemoryStrategy);
using WeakNodeVector = std::vector<std::weak_ptr<rclcpp::node::Node>>;

// return the new number of subscribers
virtual size_t fill_subscriber_handles(void ** & ptr) = 0;

// return the new number of services
virtual size_t fill_service_handles(void ** & ptr) = 0;

// return the new number of clients
virtual size_t fill_client_handles(void ** & ptr) = 0;

// return the new number of guard_conditions
virtual size_t fill_guard_condition_handles(void ** & ptr) = 0;
virtual bool collect_entities(const WeakNodeVector & weak_nodes) = 0;

virtual void clear_active_entities() = 0;
virtual size_t number_of_ready_subscriptions() const = 0;
virtual size_t number_of_ready_services() const = 0;
virtual size_t number_of_ready_clients() const = 0;
virtual size_t number_of_ready_timers() const = 0;
virtual size_t number_of_guard_conditions() const = 0;

virtual bool add_handles_to_waitset(rcl_wait_set_t * wait_set) = 0;
virtual void clear_handles() = 0;
virtual void remove_null_handles() = 0;
virtual bool collect_entities(const WeakNodeVector & weak_nodes) = 0;
virtual void remove_null_handles(rcl_wait_set_t * wait_set) = 0;

/// Provide a newly initialized AnyExecutable object.
// \return Shared pointer to the fresh executable.
virtual rclcpp::executor::AnyExecutable::SharedPtr instantiate_next_executable() = 0;

virtual void add_guard_condition(const rmw_guard_condition_t * guard_condition) = 0;
virtual void add_guard_condition(const rcl_guard_condition_t * guard_condition) = 0;

virtual void remove_guard_condition(const rmw_guard_condition_t * guard_condition) = 0;
virtual void remove_guard_condition(const rcl_guard_condition_t * guard_condition) = 0;

virtual void
get_next_subscription(rclcpp::executor::AnyExecutable::SharedPtr any_exec,
Expand All @@ -78,15 +75,18 @@ class RCLCPP_PUBLIC MemoryStrategy
get_next_client(rclcpp::executor::AnyExecutable::SharedPtr any_exec,
const WeakNodeVector & weak_nodes) = 0;

virtual rcl_allocator_t
get_allocator() = 0;

static rclcpp::subscription::SubscriptionBase::SharedPtr
get_subscription_by_handle(void * subscriber_handle,
get_subscription_by_handle(const rcl_subscription_t * subscriber_handle,
const WeakNodeVector & weak_nodes);

static rclcpp::service::ServiceBase::SharedPtr
get_service_by_handle(void * service_handle, const WeakNodeVector & weak_nodes);
get_service_by_handle(const rcl_service_t * service_handle, const WeakNodeVector & weak_nodes);

static rclcpp::client::ClientBase::SharedPtr
get_client_by_handle(void * client_handle, const WeakNodeVector & weak_nodes);
get_client_by_handle(const rcl_client_t * client_handle, const WeakNodeVector & weak_nodes);

static rclcpp::node::Node::SharedPtr
get_node_by_group(rclcpp::callback_group::CallbackGroup::SharedPtr group,
Expand Down
Loading