Skip to content

Commit

Permalink
[style] cpplint/uncrustify
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed Nov 6, 2015
1 parent cb39709 commit f0988b6
Show file tree
Hide file tree
Showing 28 changed files with 254 additions and 235 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/allocator/allocator_deleter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
#define RCLCPP__ALLOCATOR__ALLOCATOR_DELETER_HPP_

#include <memory>
#include <stdexcept>

namespace rclcpp
{

namespace allocator
{

Expand Down
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -44,7 +44,7 @@ struct AnyExecutable
rclcpp::node::Node::SharedPtr node;
};

} /* executor */
} /* rclcpp */
} // namespace executor
} // namespace rclcpp

#endif
#endif // RCLCPP__ANY_EXECUTABLE_HPP_
15 changes: 7 additions & 8 deletions rclcpp/include/rclcpp/any_service_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -99,7 +98,7 @@ class AnyServiceCallback
}
};

} /* 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_
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <functional>
#include <memory>
#include <stdexcept>
#include <type_traits>

#include "rclcpp/allocator/allocator_common.hpp"
Expand Down
21 changes: 10 additions & 11 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -32,7 +32,7 @@ namespace rclcpp
namespace node
{
class Node;
} // namespace node
} // namespace node

namespace callback_group
{
Expand Down Expand Up @@ -102,10 +102,9 @@ class CallbackGroup
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_
28 changes: 13 additions & 15 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down Expand Up @@ -70,7 +68,6 @@ class ClientBase

rmw_client_t * client_handle_;
std::string service_name_;

};

template<typename ServiceT>
Expand Down Expand Up @@ -109,7 +106,8 @@ class Client : public ClientBase
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);
Expand Down Expand Up @@ -149,7 +147,7 @@ class Client : public ClientBase
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_
18 changes: 7 additions & 11 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -73,10 +70,9 @@ class Context

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_
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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_
15 changes: 8 additions & 7 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -108,4 +109,4 @@ spin_until_future_complete(

} // namespace rclcpp

#endif /* RCLCPP_RCLCPP_EXECUTORS_HPP_ */
#endif // RCLCPP__EXECUTORS_HPP_
10 changes: 2 additions & 8 deletions rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down
13 changes: 9 additions & 4 deletions rclcpp/include/rclcpp/function_traits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -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_
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/intra_process_manager_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
7 changes: 4 additions & 3 deletions rclcpp/include/rclcpp/macros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*
Expand Down Expand Up @@ -76,11 +76,12 @@
{ \
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__) \
__RCLCPP_MAKE_UNIQUE_DEFINITION(__VA_ARGS__)

#define RCLCPP_INFO(Args) std::cout << Args << std::endl;

#endif /* RCLCPP_RCLCPP_MACROS_HPP_ */
#endif // RCLCPP__MACROS_HPP_
Loading

0 comments on commit f0988b6

Please sign in to comment.