1 |
|
|
#ifndef DYNAMIC_GRAPH_ROS_PUBLISH_HXX |
2 |
|
|
#define DYNAMIC_GRAPH_ROS_PUBLISH_HXX |
3 |
|
|
#include <std_msgs/Float64.h> |
4 |
|
|
|
5 |
|
|
#include <vector> |
6 |
|
|
|
7 |
|
|
#include "dynamic_graph_bridge_msgs/Matrix.h" |
8 |
|
|
#include "dynamic_graph_bridge_msgs/Vector.h" |
9 |
|
|
#include "sot_to_ros.hh" |
10 |
|
|
|
11 |
|
|
namespace dynamicgraph { |
12 |
|
|
template <> |
13 |
|
|
inline void RosPublish::sendData<std::pair<sot::MatrixHomogeneous, Vector> >( |
14 |
|
|
boost::shared_ptr<realtime_tools::RealtimePublisher< |
15 |
|
|
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t> > |
16 |
|
|
publisher, |
17 |
|
|
boost::shared_ptr< |
18 |
|
|
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalIn_t> |
19 |
|
|
signal, |
20 |
|
|
int time) { |
21 |
|
|
SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t result; |
22 |
|
|
if (publisher->trylock()) { |
23 |
|
|
publisher->msg_.child_frame_id = "/dynamic_graph/world"; |
24 |
|
|
converter(publisher->msg_, signal->access(time)); |
25 |
|
|
publisher->unlockAndPublish(); |
26 |
|
|
} |
27 |
|
|
} |
28 |
|
|
|
29 |
|
|
template <typename T> |
30 |
|
|
void RosPublish::sendData( |
31 |
|
|
boost::shared_ptr< |
32 |
|
|
realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> > |
33 |
|
|
publisher, |
34 |
|
|
boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time) { |
35 |
|
|
typename SotToRos<T>::ros_t result; |
36 |
|
|
if (publisher->trylock()) { |
37 |
|
|
converter(publisher->msg_, signal->access(time)); |
38 |
|
|
publisher->unlockAndPublish(); |
39 |
|
|
} |
40 |
|
|
} |
41 |
|
|
|
42 |
|
|
template <typename T> |
43 |
|
|
void RosPublish::add(const std::string& signal, const std::string& topic) { |
44 |
|
|
typedef typename SotToRos<T>::ros_t ros_t; |
45 |
|
|
typedef typename SotToRos<T>::signalIn_t signal_t; |
46 |
|
|
|
47 |
|
|
// Initialize the bindedSignal object. |
48 |
|
|
bindedSignal_t bindedSignal; |
49 |
|
|
|
50 |
|
|
// Initialize the publisher. |
51 |
|
|
boost::shared_ptr<realtime_tools::RealtimePublisher<ros_t> > pubPtr = |
52 |
|
|
boost::make_shared<realtime_tools::RealtimePublisher<ros_t> >(nh_, topic, |
53 |
|
|
1); |
54 |
|
|
|
55 |
|
|
// Initialize the signal. |
56 |
|
|
boost::shared_ptr<signal_t> signalPtr(new signal_t( |
57 |
|
|
0, MAKE_SIGNAL_STRING(name, true, SotToRos<T>::signalTypeName, signal))); |
58 |
|
|
boost::get<0>(bindedSignal) = signalPtr; |
59 |
|
|
SotToRos<T>::setDefault(*signalPtr); |
60 |
|
|
signalRegistration(*boost::get<0>(bindedSignal)); |
61 |
|
|
|
62 |
|
|
// Initialize the callback. |
63 |
|
|
callback_t callback = |
64 |
|
|
boost::bind(&RosPublish::sendData<T>, this, pubPtr, signalPtr, _1); |
65 |
|
|
boost::get<1>(bindedSignal) = callback; |
66 |
|
|
|
67 |
|
|
bindedSignal_[signal] = bindedSignal; |
68 |
|
|
} |
69 |
|
|
|
70 |
|
|
} // end of namespace dynamicgraph. |
71 |
|
|
|
72 |
|
|
#endif //! DYNAMIC_GRAPH_ROS_PUBLISH_HXX |