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

Windows support #14

Merged
merged 7 commits into from
Mar 21, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
9 changes: 5 additions & 4 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,7 +270,7 @@ class Executor
}));
}
// Use the number of subscriptions to allocate memory in the handles
size_t number_of_subscriptions = subs.size();
unsigned long number_of_subscriptions = subs.size();
Copy link
Member

Choose a reason for hiding this comment

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

std::size_t (not plain size_t) is part of C++11, doesn't Windows support it via cstdlib?

http://en.cppreference.com/w/cpp/types/size_t

Copy link
Member Author

Choose a reason for hiding this comment

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

This is not about the availability of size_t. This fixes a warning that we are later assigned this variable, number_of_subscriptions, on line 275 to subscriber_count which is an unsigned long and that results in a possible loss of precision. Rather than changing the size of the later storage, I changed the size of this temporary data field. Maybe we should use size_t everywhere, but I couldn't remember if there was a reason we did not use it in the structures.

Copy link
Member Author

Choose a reason for hiding this comment

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

Anyone think we should do something different right now?

Copy link
Member

Choose a reason for hiding this comment

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

I'd rather subscriber_count be changed to a size_t instead.

Copy link
Member

Choose a reason for hiding this comment

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

I am agnostic, but using size_t sounds reasonable and will likely be more consistent throughout the code.

rmw_subscriptions_t subscriber_handles;
subscriber_handles.subscriber_count = number_of_subscriptions;
// TODO(wjwwood): Avoid redundant malloc's
Expand All @@ -291,7 +291,7 @@ class Executor
}

// Use the number of services to allocate memory in the handles
size_t number_of_services = services.size();
unsigned long number_of_services = services.size();
rmw_services_t service_handles;
service_handles.service_count = number_of_services;
// TODO(esteve): Avoid redundant malloc's
Expand All @@ -312,7 +312,7 @@ class Executor
}

// Use the number of clients to allocate memory in the handles
size_t number_of_clients = clients.size();
unsigned long number_of_clients = clients.size();
rmw_clients_t client_handles;
client_handles.client_count = number_of_clients;
// TODO: Avoid redundant malloc's
Expand All @@ -335,7 +335,8 @@ class Executor
// Use the number of guard conditions to allocate memory in the handles
// Add 2 to the number for the ctrl-c guard cond and the executor's
size_t start_of_timer_guard_conds = 2;
size_t number_of_guard_conds = timers.size() + start_of_timer_guard_conds;
unsigned long number_of_guard_conds =
timers.size() + start_of_timer_guard_conds;
rmw_guard_conditions_t guard_condition_handles;
guard_condition_handles.guard_condition_count = number_of_guard_conds;
// TODO(wjwwood): Avoid redundant malloc's
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,11 +58,11 @@ class MultiThreadedExecutor : public executor::Executor
std::vector<std::thread> threads;
{
std::lock_guard<std::mutex> wait_lock(wait_mutex_);
size_t thread_id = 1;
size_t thread_id_ = 1; // Use a _ suffix to avoid shadowing `rclcpp::thread_id`
for (size_t i = number_of_threads_; i > 0; --i)
{
std::this_thread::sleep_for(std::chrono::milliseconds(100));
auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id++);
auto func = std::bind(&MultiThreadedExecutor::run, this, thread_id_++);
threads.emplace_back(func);
}
}
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,8 @@ class Node
} /* namespace node */
} /* namespace rclcpp */

#define RCLCPP_REGISTER_NODE(Class) rclcpp::node::Node::SharedPtr \
#define RCLCPP_REGISTER_NODE(Class) RMW_EXPORT \
rclcpp::node::Node::SharedPtr \
create_node() \
{ \
return rclcpp::node::Node::SharedPtr(new Class(rclcpp::contexts::default_context::DefaultContext::make_shared())); \
Expand Down
14 changes: 8 additions & 6 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,24 +27,26 @@
namespace rclcpp
{

constexpr std::chrono::seconds operator "" _s(unsigned long long s)
const std::chrono::seconds operator "" _s(unsigned long long s)
{
return std::chrono::seconds(s);
}
constexpr std::chrono::duration<long double> operator "" _s(long double s)
const std::chrono::nanoseconds operator "" _s(long double s)
{
return std::chrono::duration<long double>(s);
return std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<long double>(s));
}

constexpr std::chrono::nanoseconds
const std::chrono::nanoseconds
operator "" _ns(unsigned long long ns)
{
return std::chrono::nanoseconds(ns);
}
constexpr std::chrono::duration<long double, std::nano>
const std::chrono::nanoseconds
operator "" _ns(long double ns)
{
return std::chrono::duration<long double, std::nano>(ns);
return std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<long double, std::nano>(ns));
}

using rclcpp::node::Node;
Expand Down
9 changes: 5 additions & 4 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <mutex>
#include <thread>

#include <rmw/macros.h>
#include <rmw/rmw.h>

// Determine if sigaction is available
Expand Down Expand Up @@ -89,7 +90,7 @@ namespace
namespace rclcpp
{

__thread size_t thread_id = 0;
RMW_THREAD_LOCAL size_t thread_id = 0;

namespace utilities
{
Expand All @@ -115,6 +116,7 @@ init(int argc, char *argv[])
throw std::runtime_error(
std::string("Failed to set SIGINT signal handler: (" +
std::to_string(errno) + ")") +
// TODO(wjwwood): use strerror_r on POSIX and strerror_s on Windows.
std::strerror(errno));
}
}
Expand All @@ -131,13 +133,12 @@ get_global_sigint_guard_condition()
return ::g_sigint_guard_cond_handle;
}

template<class Rep, class Period>
bool
sleep_for(const std::chrono::duration<Rep, Period>& sleep_duration)
sleep_for(const std::chrono::nanoseconds& nanoseconds)
{
// TODO: determine if posix's nanosleep(2) is more efficient here
std::unique_lock<std::mutex> lock(::g_interrupt_mutex);
auto cvs = ::g_interrupt_condition_variable.wait_for(lock, sleep_duration);
auto cvs = ::g_interrupt_condition_variable.wait_for(lock, nanoseconds);
return cvs == std::cv_status::no_timeout;
}

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/node_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <rclcpp/rclcpp.hpp>

// This forward declaration is implemented by the RCLCPP_REGISTER_NODE macro
rclcpp::Node::SharedPtr create_node();
RMW_IMPORT rclcpp::Node::SharedPtr create_node();

int main(int argc, char **argv)
{
Expand Down