Skip to content

Commit

Permalink
Memory issues
Browse files Browse the repository at this point in the history
  • Loading branch information
Jackie Kay committed Mar 30, 2016
1 parent 99831d7 commit 1154d0d
Show file tree
Hide file tree
Showing 7 changed files with 18 additions and 17 deletions.
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,10 +306,10 @@ class Executor
std::atomic_bool spinning;

/// Guard condition for signaling the rmw layer to wake up for special events.
rcl_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.
rcl_wait_set_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
3 changes: 1 addition & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -271,7 +271,6 @@ class Node

std::string name_;

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

rclcpp::context::Context::SharedPtr context_;
Expand All @@ -289,7 +288,7 @@ class Node
mutable std::mutex mutex_;

/// Guard condition for notifying the Executor of changes to this node.
rcl_guard_condition_t notify_guard_condition_;
rcl_guard_condition_t notify_guard_condition_ = rcl_get_zero_initialized_guard_condition();

std::map<std::string, rclcpp::parameter::ParameterVariant> parameters_;

Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -341,7 +341,8 @@ Node::create_service(
service_options.qos = qos_profile;

auto serv = service::Service<ServiceT>::make_shared(
node_handle_, service_name, any_service_callback, service_options);
node_handle_,
service_name, any_service_callback, service_options);
auto serv_base_ptr = std::dynamic_pointer_cast<service::ServiceBase>(serv);
if (group) {
if (!group_in_node(group)) {
Expand Down
12 changes: 8 additions & 4 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,8 +126,8 @@ class PublisherBase

std::shared_ptr<rcl_node_t> node_handle_;

rcl_publisher_t publisher_handle_;
rcl_publisher_t intra_process_publisher_handle_;
rcl_publisher_t publisher_handle_ = rcl_get_zero_initialized_publisher();
rcl_publisher_t intra_process_publisher_handle_ = rcl_get_zero_initialized_publisher();
rcl_allocator_t rcl_allocator_;

std::string topic_;
Expand Down Expand Up @@ -175,8 +175,12 @@ class Publisher : public PublisherBase
rcl_get_error_string_safe());
}
// Life time of this object is tied to the publisher handle.
if (rmw_get_gid_for_publisher(
rcl_publisher_get_rmw_handle(&publisher_handle_), &rmw_gid_) != RMW_RET_OK)
rmw_publisher_t * publisher_rmw_handle = rcl_publisher_get_rmw_handle(&publisher_handle_);
if (!publisher_rmw_handle) {
throw std::runtime_error(
std::string("failed to get rmw handle: ") + rcl_get_error_string_safe());
}
if (rmw_get_gid_for_publisher(publisher_rmw_handle, &rmw_gid_) != RMW_RET_OK)
{
// *INDENT-OFF* (prevent uncrustify from making unecessary indents here)
throw std::runtime_error(
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,8 +103,8 @@ class SubscriptionBase
const rmw_message_info_t & message_info) = 0;

protected:
rcl_subscription_t intra_process_subscription_handle_;
rcl_subscription_t subscription_handle_;
rcl_subscription_t intra_process_subscription_handle_ = rcl_get_zero_initialized_subscription();
rcl_subscription_t subscription_handle_ = rcl_get_zero_initialized_subscription();
std::shared_ptr<rcl_node_t> node_handle_;

private:
Expand Down
6 changes: 2 additions & 4 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ Executor::Executor(const ExecutorArgs & args)
memory_strategy_->add_guard_condition(&interrupt_guard_condition_);

if (rcl_wait_set_init(
&waitset_, 0, 0, 0, 0, 0, rcl_get_default_allocator()) != RCL_RET_OK)
&waitset_, 0, 2, 0, 0, 0, rcl_get_default_allocator()) != RCL_RET_OK)
{
fprintf(stderr,
"[rclcpp::error] failed to create waitset: %s\n", rcl_get_error_string_safe());
Expand Down Expand Up @@ -378,10 +378,8 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)

rcl_ret_t status = rcl_wait(&waitset_, timeout.count());
if (status != RCL_RET_OK && status != RCL_RET_TIMEOUT && status != RCL_RET_WAIT_SET_EMPTY) {
throw std::runtime_error(rcl_get_error_string_safe());
throw std::runtime_error(std::string("rcl_wait() failed: ") + rcl_get_error_string_safe());
}


}

rclcpp::node::Node::SharedPtr
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,7 @@ Node::Node(
// Initialize node handle shared_ptr with custom deleter.
// *INDENT-OFF*
node_handle_.reset(&node, [](rcl_node_t * node) {
auto ret = rcl_node_fini(node);
if (ret != RMW_RET_OK) {
if (rcl_node_fini(node) != RMW_RET_OK) {
fprintf(
stderr, "Error in destruction of rmw node handle: %s\n", rcl_get_error_string_safe());
}
Expand Down

0 comments on commit 1154d0d

Please sign in to comment.