[style] cpplint/uncrustify

This commit is contained in:
William Woodall 2015-11-05 12:59:57 -08:00
parent 0bbe9b2099
commit 51695d1b24
28 changed files with 254 additions and 235 deletions

View file

@ -16,10 +16,10 @@
#define RCLCPP__ALLOCATOR__ALLOCATOR_DELETER_HPP_
#include <memory>
#include <stdexcept>
namespace rclcpp
{
namespace allocator
{

View file

@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_ANY_EXECUTABLE_HPP_
#define RCLCPP_RCLCPP_ANY_EXECUTABLE_HPP_
#ifndef RCLCPP__ANY_EXECUTABLE_HPP_
#define RCLCPP__ANY_EXECUTABLE_HPP_
#include <memory>
#include <rclcpp/macros.hpp>
#include <rclcpp/node.hpp>
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -44,7 +44,7 @@ struct AnyExecutable
rclcpp::node::Node::SharedPtr node;
};
} /* executor */
} /* rclcpp */
} // namespace executor
} // namespace rclcpp
#endif
#endif // RCLCPP__ANY_EXECUTABLE_HPP_

View file

@ -12,18 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_ANY_SERVICE_CALLBACK_HPP_
#define RCLCPP_RCLCPP_ANY_SERVICE_CALLBACK_HPP_
#include <rclcpp/function_traits.hpp>
#ifndef RCLCPP__ANY_SERVICE_CALLBACK_HPP_
#define RCLCPP__ANY_SERVICE_CALLBACK_HPP_
#include <functional>
#include <memory>
#include <stdexcept>
#include <type_traits>
#include <rmw/types.h>
#include "rclcpp/function_traits.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/types.h"
namespace rclcpp
{
@ -99,7 +98,7 @@ public:
}
};
} /* namespace any_service_callback */
} /* namespace rclcpp */
} // namespace any_service_callback
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_ANY_SERVICE_CALLBACK_HPP_ */
#endif // RCLCPP__ANY_SERVICE_CALLBACK_HPP_

View file

@ -19,6 +19,7 @@
#include <functional>
#include <memory>
#include <stdexcept>
#include <type_traits>
#include "rclcpp/allocator/allocator_common.hpp"

View file

@ -12,17 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_CALLBACK_GROUP_HPP_
#define RCLCPP_RCLCPP_CALLBACK_GROUP_HPP_
#ifndef RCLCPP__CALLBACK_GROUP_HPP_
#define RCLCPP__CALLBACK_GROUP_HPP_
#include <atomic>
#include <string>
#include <vector>
#include <rclcpp/subscription.hpp>
#include <rclcpp/timer.hpp>
#include <rclcpp/service.hpp>
#include <rclcpp/client.hpp>
#include "rclcpp/client.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/timer.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -32,7 +32,7 @@ namespace rclcpp
namespace node
{
class Node;
} // namespace node
} // namespace node
namespace callback_group
{
@ -102,10 +102,9 @@ private:
std::vector<rclcpp::service::ServiceBase::SharedPtr> service_ptrs_;
std::vector<rclcpp::client::ClientBase::SharedPtr> client_ptrs_;
std::atomic_bool can_be_taken_from_;
};
} /* namespace callback_group */
} /* namespace rclcpp */
} // namespace callback_group
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_CALLBACK_GROUP_HPP_ */
#endif // RCLCPP__CALLBACK_GROUP_HPP_

View file

@ -12,32 +12,30 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_CLIENT_HPP_
#define RCLCPP_RCLCPP_CLIENT_HPP_
#ifndef RCLCPP__CLIENT_HPP_
#define RCLCPP__CLIENT_HPP_
#include <future>
#include <iostream>
#include <map>
#include <memory>
#include <sstream>
#include <string>
#include <tuple>
#include <utility>
#include <rmw/error_handling.h>
#include <rmw/rmw.h>
#include <rclcpp/macros.hpp>
#include <rclcpp/utilities.hpp>
#include "rclcpp/macros.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
namespace rclcpp
{
namespace client
{
class ClientBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase);
@ -70,7 +68,6 @@ private:
rmw_client_t * client_handle_;
std::string service_name_;
};
template<typename ServiceT>
@ -109,7 +106,8 @@ public:
auto typed_request_header = std::static_pointer_cast<rmw_request_id_t>(request_header);
auto typed_response = std::static_pointer_cast<typename ServiceT::Response>(response);
int64_t sequence_number = typed_request_header->sequence_number;
// TODO this must check if the sequence_number is valid otherwise the call_promise will be null
// TODO(esteve) this must check if the sequence_number is valid otherwise the
// call_promise will be null
auto tuple = this->pending_requests_[sequence_number];
auto call_promise = std::get<0>(tuple);
auto callback = std::get<1>(tuple);
@ -149,7 +147,7 @@ private:
std::map<int64_t, std::tuple<SharedPromise, CallbackType, SharedFuture>> pending_requests_;
};
} /* namespace client */
} /* namespace rclcpp */
} // namespace client
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_CLIENT_HPP_ */
#endif // RCLCPP__CLIENT_HPP_

View file

@ -12,22 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_CONTEXT_HPP_
#define RCLCPP_RCLCPP_CONTEXT_HPP_
#include <rclcpp/macros.hpp>
#ifndef RCLCPP__CONTEXT_HPP_
#define RCLCPP__CONTEXT_HPP_
#include <iostream>
#include <memory>
#include <mutex>
#include <typeinfo>
#include <typeindex>
#include <typeinfo>
#include <unordered_map>
#include <rmw/rmw.h>
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"
namespace rclcpp
{
@ -73,10 +70,9 @@ private:
std::unordered_map<std::type_index, std::shared_ptr<void>> sub_contexts_;
std::mutex mutex_;
};
} /* namespace context */
} /* namespace rclcpp */
} // namespace context
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_CONTEXT_HPP_ */
#endif // RCLCPP__CONTEXT_HPP_

View file

@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_CONTEXTS_DEFAULT_CONTEXT_HPP_
#define RCLCPP_RCLCPP_CONTEXTS_DEFAULT_CONTEXT_HPP_
#ifndef RCLCPP__CONTEXTS__DEFAULT_CONTEXT_HPP_
#define RCLCPP__CONTEXTS__DEFAULT_CONTEXT_HPP_
#include <rclcpp/context.hpp>
#include "rclcpp/context.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -38,8 +38,8 @@ RCLCPP_PUBLIC
DefaultContext::SharedPtr
get_global_default_context();
} // namespace default_context
} // namespace contexts
} // namespace rclcpp
} // namespace default_context
} // namespace contexts
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_CONTEXTS_DEFAULT_CONTEXT_HPP_ */
#endif // RCLCPP__CONTEXTS__DEFAULT_CONTEXT_HPP_

View file

@ -12,14 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_EXECUTORS_HPP_
#define RCLCPP_RCLCPP_EXECUTORS_HPP_
#ifndef RCLCPP__EXECUTORS_HPP_
#define RCLCPP__EXECUTORS_HPP_
#include <future>
#include <rclcpp/executors/multi_threaded_executor.hpp>
#include <rclcpp/executors/single_threaded_executor.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/utilities.hpp>
#include "rclcpp/executors/multi_threaded_executor.hpp"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -108,4 +109,4 @@ spin_until_future_complete(
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_EXECUTORS_HPP_ */
#endif // RCLCPP__EXECUTORS_HPP_

View file

@ -15,18 +15,12 @@
#ifndef RCLCPP__EXECUTORS__MULTI_THREADED_EXECUTOR_HPP_
#define RCLCPP__EXECUTORS__MULTI_THREADED_EXECUTOR_HPP_
#include <rmw/rmw.h>
#include <cassert>
#include <cstdlib>
#include <memory>
#include <mutex>
#include <vector>
#include <thread>
#include <unordered_map>
#include "rclcpp/executor.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/memory_strategies.hpp"
#include "rclcpp/visibility_control.hpp"

View file

@ -12,9 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_FUNCTION_TRAITS_HPP_
#define RCLCPP_RCLCPP_FUNCTION_TRAITS_HPP_
#ifndef RCLCPP__FUNCTION_TRAITS_HPP_
#define RCLCPP__FUNCTION_TRAITS_HPP_
#include <memory>
#include <tuple>
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
{
@ -95,6 +99,7 @@ struct same_arguments : std::is_same<
typename function_traits<FunctorBT>::arguments
>
{};
} /* namespace rclcpp */
#endif /* RCLCPP_RCLCPP_FUNCTION_TRAITS_HPP_ */
} // namespace rclcpp
#endif // RCLCPP__FUNCTION_TRAITS_HPP_

View file

@ -15,21 +15,21 @@
#ifndef RCLCPP__INTRA_PROCESS_MANAGER_STATE_HPP_
#define RCLCPP__INTRA_PROCESS_MANAGER_STATE_HPP_
#include <rclcpp/mapped_ring_buffer.hpp>
#include <rclcpp/publisher.hpp>
#include <rclcpp/subscription.hpp>
#include <algorithm>
#include <atomic>
#include <functional>
#include <limits>
#include <memory>
#include <map>
#include <unordered_map>
#include <memory>
#include <set>
#include <string>
#include <unordered_map>
#include <utility>
#include "rclcpp/macros.hpp"
#include "rclcpp/mapped_ring_buffer.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_MACROS_HPP_
#define RCLCPP_RCLCPP_MACROS_HPP_
#ifndef RCLCPP__MACROS_HPP_
#define RCLCPP__MACROS_HPP_
/* Disables the copy constructor and operator= for the given class.
*
@ -76,6 +76,7 @@
{ \
return std::unique_ptr<__VA_ARGS__>(new __VA_ARGS__(std::forward<Args>(args) ...)); \
}
/// Defines aliases and static functions for using the Class with unique_ptrs.
#define RCLCPP_UNIQUE_PTR_DEFINITIONS(...) \
__RCLCPP_UNIQUE_PTR_ALIAS(__VA_ARGS__) \
@ -83,4 +84,4 @@
#define RCLCPP_INFO(Args) std::cout << Args << std::endl;
#endif /* RCLCPP_RCLCPP_MACROS_HPP_ */
#endif // RCLCPP__MACROS_HPP_

View file

@ -15,8 +15,7 @@
#ifndef RCLCPP__MEMORY_STRATEGIES_HPP_
#define RCLCPP__MEMORY_STRATEGIES_HPP_
#include <rclcpp/memory_strategy.hpp>
#include <rclcpp/strategies/allocator_memory_strategy.hpp>
#include "rclcpp/memory_strategy.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp

View file

@ -16,6 +16,7 @@
#define RCLCPP__MESSAGE_MEMORY_STRATEGY_HPP_
#include <memory>
#include <stdexcept>
#include "rclcpp/allocator/allocator_common.hpp"
#include "rclcpp/macros.hpp"

View file

@ -12,35 +12,33 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_PARAMETER_HPP_
#define RCLCPP_RCLCPP_PARAMETER_HPP_
#ifndef RCLCPP__PARAMETER_HPP_
#define RCLCPP__PARAMETER_HPP_
#include <ostream>
#include <sstream>
#include <string>
#include <vector>
#include <rmw/rmw.h>
#include <rcl_interfaces/msg/parameter.hpp>
#include <rcl_interfaces/msg/parameter_type.hpp>
#include <rcl_interfaces/msg/parameter_value.hpp>
#include "rcl_interfaces/msg/parameter.hpp"
#include "rcl_interfaces/msg/parameter_type.hpp"
#include "rcl_interfaces/msg/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"
namespace rclcpp
{
namespace parameter
{
enum ParameterType
{
PARAMETER_NOT_SET=rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
PARAMETER_BOOL=rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
PARAMETER_INTEGER=rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER,
PARAMETER_DOUBLE=rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
PARAMETER_STRING=rcl_interfaces::msg::ParameterType::PARAMETER_STRING,
PARAMETER_BYTES=rcl_interfaces::msg::ParameterType::PARAMETER_BYTES,
PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER,
PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING,
PARAMETER_BYTES = rcl_interfaces::msg::ParameterType::PARAMETER_BYTES,
};
// Structure to store an arbitrary parameter with templated get/set methods
@ -87,48 +85,52 @@ public:
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
// TODO: use custom exception
// TODO(wjwwood): use custom exception
throw std::runtime_error("Invalid type");
}
return value_.integer_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::type
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
// TODO: use custom exception
// TODO(wjwwood): use custom exception
throw std::runtime_error("Invalid type");
}
return value_.double_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) {
// TODO: use custom exception
// TODO(wjwwood): use custom exception
throw std::runtime_error("Invalid type");
}
return value_.string_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
// TODO: use custom exception
// TODO(wjwwood): use custom exception
throw std::runtime_error("Invalid type");
}
return value_.bool_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BYTES,
const std::vector<uint8_t> &>::type
get_value() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTES) {
// TODO: use custom exception
// TODO(wjwwood): use custom exception
throw std::runtime_error("Invalid type");
}
return value_.bytes_value;
@ -203,4 +205,4 @@ to_string(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
} // namespace std
#endif /* RCLCPP_RCLCPP_PARAMETER_HPP_ */
#endif // RCLCPP__PARAMETER_HPP_

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_PARAMETER_CLIENT_HPP_
#define RCLCPP_RCLCPP_PARAMETER_CLIENT_HPP_
#ifndef RCLCPP__PARAMETER_CLIENT_HPP_
#define RCLCPP__PARAMETER_CLIENT_HPP_
#include <string>
#include <vector>
@ -162,8 +162,7 @@ private:
AsyncParametersClient::SharedPtr async_parameters_client_;
};
} /* namespace parameter_client */
} // namespace parameter_client
} // namespace rclcpp
} /* namespace rclcpp */
#endif /* RCLCPP_RCLCPP_PARAMETER_CLIENT_HPP_ */
#endif // RCLCPP__PARAMETER_CLIENT_HPP_

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_
#define RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_
#ifndef RCLCPP__PARAMETER_SERVICE_HPP_
#define RCLCPP__PARAMETER_SERVICE_HPP_
#include <string>
@ -32,13 +32,11 @@
namespace rclcpp
{
namespace parameter_service
{
class ParameterService
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService);
@ -58,8 +56,7 @@ private:
rclcpp::service::Service<rcl_interfaces::srv::ListParameters>::SharedPtr list_parameters_service_;
};
} /* namespace parameter_service */
} // namespace parameter_service
} // namespace rclcpp
} /* namespace rclcpp */
#endif /* RCLCPP_RCLCPP_PARAMETER_SERVICE_HPP_ */
#endif // RCLCPP__PARAMETER_SERVICE_HPP_

View file

@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_RATE_HPP_
#define RCLCPP_RCLCPP_RATE_HPP_
#ifndef RCLCPP__RATE_HPP_
#define RCLCPP__RATE_HPP_
#include <chrono>
#include <memory>
#include <thread>
#include <rclcpp/macros.hpp>
#include <rclcpp/utilities.hpp>
#include "rclcpp/macros.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -110,13 +110,12 @@ private:
std::chrono::nanoseconds period_;
std::chrono::time_point<Clock> last_interval_;
};
using Rate = GenericRate<std::chrono::system_clock>;
using WallRate = GenericRate<std::chrono::steady_clock>;
} // namespace rate
} // namespace rclcpp
} // namespace rate
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_RATE_HPP_ */
#endif // RCLCPP__RATE_HPP_

View file

@ -12,19 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_RCLCPP_HPP_
#define RCLCPP_RCLCPP_RCLCPP_HPP_
#ifndef RCLCPP__RCLCPP_HPP_
#define RCLCPP__RCLCPP_HPP_
#include <csignal>
#include <memory>
#include <rclcpp/node.hpp>
#include <rclcpp/parameter.hpp>
#include <rclcpp/parameter_client.hpp>
#include <rclcpp/parameter_service.hpp>
#include <rclcpp/executors.hpp>
#include <rclcpp/rate.hpp>
#include <rclcpp/utilities.hpp>
#include "rclcpp/executors.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_client.hpp"
#include "rclcpp/parameter_service.hpp"
#include "rclcpp/rate.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
// NOLINTNEXTLINE(runtime/int)
@ -80,6 +80,6 @@ using rclcpp::utilities::shutdown;
using rclcpp::utilities::init;
using rclcpp::utilities::sleep_for;
} /* namespace rclcpp */
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_RCLCPP_HPP_ */
#endif // RCLCPP__RCLCPP_HPP_

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_SERVICE_HPP_
#define RCLCPP_RCLCPP_SERVICE_HPP_
#ifndef RCLCPP__SERVICE_HPP_
#define RCLCPP__SERVICE_HPP_
#include <functional>
#include <iostream>
@ -21,22 +21,19 @@
#include <sstream>
#include <string>
#include <rmw/error_handling.h>
#include <rmw/rmw.h>
#include <rclcpp/macros.hpp>
#include <rclcpp/any_service_callback.hpp>
#include "rclcpp/any_service_callback.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
namespace rclcpp
{
namespace service
{
class ServiceBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase);
@ -70,10 +67,9 @@ private:
rmw_service_t * service_handle_;
std::string service_name_;
};
using namespace any_service_callback;
using any_service_callback::AnyServiceCallback;
template<typename ServiceT>
class Service : public ServiceBase
@ -141,7 +137,7 @@ private:
AnyServiceCallback<ServiceT> any_callback_;
};
} /* namespace service */
} /* namespace rclcpp */
} // namespace service
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_SERVICE_HPP_ */
#endif // RCLCPP__SERVICE_HPP_

View file

@ -25,10 +25,8 @@
namespace rclcpp
{
namespace memory_strategies
{
namespace allocator_memory_strategy
{
@ -313,7 +311,6 @@ private:
} // namespace allocator_memory_strategy
} // namespace memory_strategies
} // namespace rclcpp
#endif // RCLCPP__STRATEGIES__ALLOCATOR_MEMORY_STRATEGY_HPP_

View file

@ -15,8 +15,8 @@
#ifndef RCLCPP__STRATEGIES__MESSAGE_POOL_MEMORY_STRATEGY_HPP_
#define RCLCPP__STRATEGIES__MESSAGE_POOL_MEMORY_STRATEGY_HPP_
#include <rclcpp/macros.hpp>
#include <rclcpp/message_memory_strategy.hpp>
#include "rclcpp/macros.hpp"
#include "rclcpp/message_memory_strategy.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
@ -106,4 +106,5 @@ protected:
} // namespace message_pool_memory_strategy
} // namespace strategies
} // namespace rclcpp
#endif // RCLCPP__STRATEGIES__MESSAGE_POOL_MEMORY_STRATEGY_HPP_

View file

@ -147,7 +147,7 @@ public:
bool ignore_local_publications,
AnySubscriptionCallback<MessageT, Alloc> callback,
typename message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
memory_strategy = message_memory_strategy::MessageMemoryStrategy<MessageT,
memory_strategy = message_memory_strategy::MessageMemoryStrategy<MessageT,
Alloc>::create_default())
: SubscriptionBase(node_handle, subscription_handle, topic_name, ignore_local_publications),
any_callback_(callback),

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_TIMER_HPP_
#define RCLCPP_RCLCPP_TIMER_HPP_
#ifndef RCLCPP__TIMER_HPP_
#define RCLCPP__TIMER_HPP_
#include <chrono>
#include <functional>
@ -21,17 +21,15 @@
#include <sstream>
#include <thread>
#include <rmw/error_handling.h>
#include <rmw/rmw.h>
#include <rclcpp/macros.hpp>
#include <rclcpp/rate.hpp>
#include <rclcpp/utilities.hpp>
#include "rclcpp/macros.hpp"
#include "rclcpp/rate.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/error_handling.h"
#include "rmw/rmw.h"
namespace rclcpp
{
namespace timer
{
@ -39,7 +37,6 @@ using CallbackType = std::function<void()>;
class TimerBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase);
@ -83,14 +80,12 @@ protected:
CallbackType callback_;
bool canceled_;
};
/// Generic timer templated on the clock type. Periodically executes a user-specified callback.
template<class Clock = std::chrono::high_resolution_clock>
class GenericTimer : public TimerBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(GenericTimer);
@ -158,7 +153,6 @@ private:
rclcpp::rate::GenericRate<Clock> loop_rate_;
std::chrono::time_point<Clock> last_triggered_time_;
};
using WallTimer = GenericTimer<std::chrono::steady_clock>;
@ -166,4 +160,4 @@ using WallTimer = GenericTimer<std::chrono::steady_clock>;
} /* namespace timer */
} /* namespace rclcpp */
#endif /* RCLCPP_RCLCPP_TIMER_HPP_ */
#endif // RCLCPP__TIMER_HPP_

View file

@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP_RCLCPP_UTILITIES_HPP_
#define RCLCPP_RCLCPP_UTILITIES_HPP_
#ifndef RCLCPP__UTILITIES_HPP_
#define RCLCPP__UTILITIES_HPP_
#include <chrono>
@ -64,4 +64,4 @@ sleep_for(const std::chrono::nanoseconds & nanoseconds);
} // namespace utilities
} // namespace rclcpp
#endif /* RCLCPP_RCLCPP_UTILITIES_HPP_ */
#endif // RCLCPP__UTILITIES_HPP_

View file

@ -21,6 +21,7 @@ int func_no_args()
return 0;
}
// NOLINTNEXTLINE(readability/casting)
int func_one_int(int)
{
return 1;
@ -142,15 +143,20 @@ TEST(TestFunctionTraits, arity) {
return 0;
};
auto lambda_one_int = [](int) {
auto lambda_one_int = [](int one) {
(void)one;
return 1;
};
auto lambda_two_ints = [](int, int) {
auto lambda_two_ints = [](int one, int two) {
(void)one;
(void)two;
return 2;
};
auto lambda_one_int_one_char = [](int, char) {
auto lambda_one_int_one_char = [](int one, char two) {
(void)one;
(void)two;
return 3;
};
@ -224,15 +230,20 @@ TEST(TestFunctionTraits, argument_types) {
>::value, "Functor accepts a char as second argument");
// Test lambdas
auto lambda_one_int = [](int) {
auto lambda_one_int = [](int one) {
(void)one;
return 1;
};
auto lambda_two_ints = [](int, int) {
auto lambda_two_ints = [](int one, int two) {
(void)one;
(void)two;
return 2;
};
auto lambda_one_int_one_char = [](int, char) {
auto lambda_one_int_one_char = [](int one, char two) {
(void)one;
(void)two;
return 3;
};
@ -336,15 +347,20 @@ TEST(TestFunctionTraits, check_arguments) {
"Functor accepts an int and a char as arguments");
// Test lambdas
auto lambda_one_int = [](int) {
auto lambda_one_int = [](int one) {
(void)one;
return 1;
};
auto lambda_two_ints = [](int, int) {
auto lambda_two_ints = [](int one, int two) {
(void)one;
(void)two;
return 2;
};
auto lambda_one_int_one_char = [](int, char) {
auto lambda_one_int_one_char = [](int one, char two) {
(void)one;
(void)two;
return 3;
};
@ -378,11 +394,14 @@ TEST(TestFunctionTraits, check_arguments) {
Tests that same_arguments work.
*/
TEST(TestFunctionTraits, same_arguments) {
auto lambda_one_int = [](int) {
auto lambda_one_int = [](int one) {
(void)one;
return 1;
};
auto lambda_two_ints = [](int, int) {
auto lambda_two_ints = [](int one, int two) {
(void)one;
(void)two;
return 1;
};
@ -427,15 +446,20 @@ TEST(TestFunctionTraits, sfinae_match) {
return 0;
};
auto lambda_one_int = [](int) {
auto lambda_one_int = [](int one) {
(void)one;
return 1;
};
auto lambda_two_ints = [](int, int) {
auto lambda_two_ints = [](int one, int two) {
(void)one;
(void)two;
return 2;
};
auto lambda_one_int_one_char = [](int, char) {
auto lambda_one_int_one_char = [](int one, char two) {
(void)one;
(void)two;
return 3;
};

View file

@ -13,12 +13,12 @@
// limitations under the License.
#include <memory>
#include <string>
#include <gtest/gtest.h>
#include <rclcpp/allocator/allocator_common.hpp>
#include <rclcpp/macros.hpp>
#include <rmw/types.h>
#include "gtest/gtest.h"
#include "rclcpp/allocator/allocator_common.hpp"
#include "rclcpp/macros.hpp"
#include "rmw/types.h"
// Mock up publisher and subscription base to avoid needing an rmw impl.
namespace rclcpp
@ -79,9 +79,9 @@ public:
}
};
}
}
}
} // namespace mock
} // namespace publisher
} // namespace rclcpp
namespace rclcpp
{
@ -111,9 +111,9 @@ public:
size_t mock_queue_size;
};
}
}
}
} // namespace mock
} // namespace subscription
} // namespace rclcpp
// Prevent rclcpp/publisher.hpp and rclcpp/subscription.hpp from being imported.
#define RCLCPP__PUBLISHER_HPP_
@ -129,6 +129,7 @@ public:
#undef Publisher
#undef PublisherBase
// NOLINTNEXTLINE(build/include_order)
#include <rcl_interfaces/msg/intra_process_message.hpp>
/*
@ -144,13 +145,15 @@ public:
TEST(TestIntraProcessManager, nominal) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 2;
auto p2 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p2 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p2->mock_topic_name = "nominal2";
p2->mock_queue_size = 10;
@ -233,8 +236,9 @@ TEST(TestIntraProcessManager, nominal) {
TEST(TestIntraProcessManager, remove_publisher_before_trying_to_take) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 10;
@ -274,8 +278,9 @@ TEST(TestIntraProcessManager, remove_publisher_before_trying_to_take) {
TEST(TestIntraProcessManager, removed_subscription_affects_take) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 10;
@ -344,8 +349,9 @@ TEST(TestIntraProcessManager, removed_subscription_affects_take) {
TEST(TestIntraProcessManager, multiple_subscriptions_one_publisher) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 10;
@ -415,18 +421,21 @@ TEST(TestIntraProcessManager, multiple_subscriptions_one_publisher) {
TEST(TestIntraProcessManager, multiple_publishers_one_subscription) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 10;
auto p2 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p2 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p2->mock_topic_name = "nominal1";
p2->mock_queue_size = 10;
auto p3 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p3 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p3->mock_topic_name = "nominal1";
p3->mock_queue_size = 10;
@ -512,18 +521,21 @@ TEST(TestIntraProcessManager, multiple_publishers_one_subscription) {
TEST(TestIntraProcessManager, multiple_publishers_multiple_subscription) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 10;
auto p2 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p2 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p2->mock_topic_name = "nominal1";
p2->mock_queue_size = 10;
auto p3 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p3 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p3->mock_topic_name = "nominal1";
p3->mock_queue_size = 10;
@ -676,8 +688,9 @@ TEST(TestIntraProcessManager, multiple_publishers_multiple_subscription) {
TEST(TestIntraProcessManager, ring_buffer_displacement) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 2;
@ -746,8 +759,9 @@ TEST(TestIntraProcessManager, ring_buffer_displacement) {
TEST(TestIntraProcessManager, subscription_creation_race_condition) {
rclcpp::intra_process_manager::IntraProcessManager ipm;
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 2;
@ -794,8 +808,9 @@ TEST(TestIntraProcessManager, publisher_out_of_scope_take) {
uint64_t p1_id;
uint64_t p1_m1_id;
{
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 2;
@ -832,8 +847,9 @@ TEST(TestIntraProcessManager, publisher_out_of_scope_store) {
uint64_t p1_id;
{
auto p1 =
std::make_shared<rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>>();
auto p1 = std::make_shared<
rclcpp::publisher::mock::Publisher<rcl_interfaces::msg::IntraProcessMessage>
>();
p1->mock_topic_name = "nominal1";
p1->mock_queue_size = 2;