fixes for Windows
This commit is contained in:
parent
ef89f5a5ab
commit
3dd193efbb
5 changed files with 14 additions and 8 deletions
|
@ -19,7 +19,7 @@
|
||||||
using rclcpp::executor::AnyExecutable;
|
using rclcpp::executor::AnyExecutable;
|
||||||
using rclcpp::executor::Executor;
|
using rclcpp::executor::Executor;
|
||||||
|
|
||||||
Executor::Executor(memory_strategy::MemoryStrategy::SharedPtr ms)
|
Executor::Executor(rclcpp::memory_strategy::MemoryStrategy::SharedPtr ms)
|
||||||
: interrupt_guard_condition_(rmw_create_guard_condition()),
|
: interrupt_guard_condition_(rmw_create_guard_condition()),
|
||||||
memory_strategy_(ms)
|
memory_strategy_(ms)
|
||||||
{
|
{
|
||||||
|
@ -119,7 +119,7 @@ Executor::spin_some()
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Executor::set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy)
|
Executor::set_memory_strategy(rclcpp::memory_strategy::MemoryStrategy::SharedPtr memory_strategy)
|
||||||
{
|
{
|
||||||
if (memory_strategy == nullptr) {
|
if (memory_strategy == nullptr) {
|
||||||
throw std::runtime_error("Received NULL memory strategy in executor.");
|
throw std::runtime_error("Received NULL memory strategy in executor.");
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
|
using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
|
||||||
|
|
||||||
MultiThreadedExecutor::MultiThreadedExecutor(memory_strategy::MemoryStrategy::SharedPtr ms)
|
MultiThreadedExecutor::MultiThreadedExecutor(rclcpp::memory_strategy::MemoryStrategy::SharedPtr ms)
|
||||||
: executor::Executor(ms)
|
: executor::Executor(ms)
|
||||||
{
|
{
|
||||||
number_of_threads_ = std::thread::hardware_concurrency();
|
number_of_threads_ = std::thread::hardware_concurrency();
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
|
|
||||||
using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
|
using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
|
||||||
|
|
||||||
SingleThreadedExecutor::SingleThreadedExecutor(memory_strategy::MemoryStrategy::SharedPtr ms)
|
SingleThreadedExecutor::SingleThreadedExecutor(rclcpp::memory_strategy::MemoryStrategy::SharedPtr ms)
|
||||||
: executor::Executor(ms) {}
|
: executor::Executor(ms) {}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -14,11 +14,14 @@
|
||||||
|
|
||||||
#include "rclcpp/intra_process_manager.hpp"
|
#include "rclcpp/intra_process_manager.hpp"
|
||||||
|
|
||||||
using rclcpp::intra_process_manager::IntraProcessManager;
|
namespace rclcpp
|
||||||
|
{
|
||||||
|
namespace intra_process_manager
|
||||||
|
{
|
||||||
|
|
||||||
static std::atomic<uint64_t> _next_unique_id {1};
|
static std::atomic<uint64_t> _next_unique_id {1};
|
||||||
|
|
||||||
IntraProcessManager::IntraProcessManager(IntraProcessManagerStateBase::SharedPtr state)
|
IntraProcessManager::IntraProcessManager(rclcpp::intra_process_manager::IntraProcessManagerStateBase::SharedPtr state)
|
||||||
: state_(state)
|
: state_(state)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
@ -73,3 +76,6 @@ IntraProcessManager::get_next_unique_id()
|
||||||
}
|
}
|
||||||
return next_id;
|
return next_id;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
} // namespace intra_process_manager
|
||||||
|
} // namespace rclcpp
|
|
@ -69,7 +69,7 @@ Node::Node(const std::string & node_name, bool use_intra_process_comms)
|
||||||
|
|
||||||
Node::Node(
|
Node::Node(
|
||||||
const std::string & node_name,
|
const std::string & node_name,
|
||||||
context::Context::SharedPtr context,
|
rclcpp::context::Context::SharedPtr context,
|
||||||
bool use_intra_process_comms)
|
bool use_intra_process_comms)
|
||||||
: name_(node_name), context_(context),
|
: name_(node_name), context_(context),
|
||||||
number_of_subscriptions_(0), number_of_timers_(0), number_of_services_(0),
|
number_of_subscriptions_(0), number_of_timers_(0), number_of_services_(0),
|
||||||
|
@ -139,7 +139,7 @@ Node::create_callback_group(
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
Node::group_in_node(callback_group::CallbackGroup::SharedPtr group)
|
Node::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group)
|
||||||
{
|
{
|
||||||
bool group_belongs_to_this_node = false;
|
bool group_belongs_to_this_node = false;
|
||||||
for (auto & weak_group : this->callback_groups_) {
|
for (auto & weak_group : this->callback_groups_) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue