6 #include "rclcpp/rclcpp.hpp"
8 #include <experimental/optional>
15 using ::std::function;
16 using ::std::make_shared;
18 using ::std::experimental::optional;
24 using Publisher = typename ::rclcpp::Publisher<T>::SharedPtr;
27 using Subscription = typename ::rclcpp::Subscription<T>::SharedPtr;
33 return nh->node()->create_publisher<T>(topic_name, queue_size);
36 template <
typename T,
typename C,
typename M>
38 int queue_size,
void (C::*callback)(M), C*
object)
40 return nh->node()->create_subscription<T>(topic_name, queue_size,
41 ::std::bind(callback,
object, ::std::placeholders::_1));
46 return ::std::string(nh->get_base_interface()->get_name());
54 return nh->node()->get_parameter(name, parameter);
75 #include <rcpputils/asserts.hpp>
76 #define ENSENSO_ASSERT(cond) rcpputils::assert_true(cond)
79 #include <boost/optional.hpp>
80 #include <boost/bind.hpp>
81 #include <boost/function.hpp>
82 #include <boost/make_shared.hpp>
91 using boost::function;
92 using boost::make_shared;
93 using boost::optional;
98 template <
typename T,
typename... Args>
101 return ::std::unique_ptr<T>(
new T(::std::forward<Args>(
args)...));
107 template <
typename T>
112 template <
typename T>
121 template <
typename T>
124 template <
typename T>
127 template <
typename T>
131 return ensenso::std::make_unique< ::ros::Publisher>(nh.advertise<T>(topic_name, queue_size));
134 template <
typename T,
typename C,
typename M>
136 int queue_size,
void (C::*callback)(M), C*
object)
138 return nh.subscribe(topic_name, queue_size, callback,
object);
144 return ::ros::this_node::getName();
147 template <
typename T>
150 return nh.getParam(name, parameter);
153 template <
typename T>
156 return nh.getParam(name, parameter);
166 #define ENSENSO_ASSERT(cond) ROS_ASSERT(cond)