|
| 1 | +#ifndef DYNAMIC_GRAPH_ROS_TF_LISTENER_HH |
| 2 | +# define DYNAMIC_GRAPH_ROS_TF_LISTENER_HH |
| 3 | + |
| 4 | +# include <boost/bind.hpp> |
| 5 | + |
| 6 | +# include <tf/transform_listener.h> |
| 7 | + |
| 8 | +# include <dynamic-graph/entity.h> |
| 9 | +# include <dynamic-graph/signal.h> |
| 10 | +# include <dynamic-graph/command-bind.h> |
| 11 | + |
| 12 | +# include <sot/core/matrix-geometry.hh> |
| 13 | + |
| 14 | +namespace dynamicgraph { |
| 15 | + class RosTfListener; |
| 16 | + |
| 17 | + namespace internal |
| 18 | + { |
| 19 | + struct TransformListenerData { |
| 20 | + typedef Signal<sot::MatrixHomogeneous, int> signal_t; |
| 21 | + |
| 22 | + tf::TransformListener& listener; |
| 23 | + const std::string toFrame, fromFrame; |
| 24 | + tf::StampedTransform transform; |
| 25 | + signal_t signal; |
| 26 | + |
| 27 | + TransformListenerData (tf::TransformListener& l, |
| 28 | + const std::string& to, const std::string& from, |
| 29 | + const std::string& signame) |
| 30 | + : listener (l) |
| 31 | + , toFrame (to) |
| 32 | + , fromFrame (from) |
| 33 | + , signal (signame) |
| 34 | + { |
| 35 | + signal.setFunction (boost::bind(&TransformListenerData::getTransform, this, _1, _2)); |
| 36 | + } |
| 37 | + |
| 38 | + sot::MatrixHomogeneous& getTransform (sot::MatrixHomogeneous& res, int time) |
| 39 | + { |
| 40 | + static const ros::Time rosTime(0); |
| 41 | + try { |
| 42 | + listener.lookupTransform (toFrame, fromFrame, rosTime, transform); |
| 43 | + } catch (const tf::TransformException& ex) { |
| 44 | + res.setIdentity(); |
| 45 | + ROS_ERROR("Enable to get transform at time %i: %s",time,ex.what()); |
| 46 | + } |
| 47 | + for (sot::MatrixHomogeneous::Index r = 0; r < 3; ++r) { |
| 48 | + for (sot::MatrixHomogeneous::Index c = 0; c < 3; ++c) |
| 49 | + res.linear ()(r,c) = transform.getBasis().getRow(r)[c]; |
| 50 | + res.translation()[r] = transform.getOrigin()[r]; |
| 51 | + } |
| 52 | + return res; |
| 53 | + } |
| 54 | + }; |
| 55 | + } // end of internal namespace. |
| 56 | + |
| 57 | + class RosTfListener : public Entity |
| 58 | + { |
| 59 | + DYNAMIC_GRAPH_ENTITY_DECL(); |
| 60 | + |
| 61 | + public: |
| 62 | + typedef internal::TransformListenerData TransformListenerData; |
| 63 | + |
| 64 | + RosTfListener (const std::string& name) : Entity (name) |
| 65 | + { |
| 66 | + std::string docstring = |
| 67 | + "\n" |
| 68 | + " Add a signal containing the transform between two frames.\n" |
| 69 | + "\n" |
| 70 | + " Input:\n" |
| 71 | + " - to : frame name\n" |
| 72 | + " - from: frame name,\n" |
| 73 | + " - signalName: the signal name in dynamic-graph" |
| 74 | + "\n"; |
| 75 | + addCommand ("add", |
| 76 | + command::makeCommandVoid3(*this, &RosTfListener::add, docstring)); |
| 77 | + } |
| 78 | + |
| 79 | + ~RosTfListener () |
| 80 | + { |
| 81 | + for (Map_t::const_iterator _it = listenerDatas.begin(); _it != listenerDatas.end(); ++_it) |
| 82 | + delete _it->second; |
| 83 | + } |
| 84 | + |
| 85 | + void add (const std::string& to, const std::string& from, const std::string& signame) |
| 86 | + { |
| 87 | + if (listenerDatas.find(signame) != listenerDatas.end()) |
| 88 | + throw std::invalid_argument ("A signal " + signame |
| 89 | + + " already exists in RosTfListener " + getName()); |
| 90 | + |
| 91 | + boost::format signalName ("RosTfListener(%1%)::output(MatrixHomo)::%2%"); |
| 92 | + signalName % getName () % signame; |
| 93 | + |
| 94 | + TransformListenerData* tld = new TransformListenerData ( |
| 95 | + listener, to, from, signalName.str()); |
| 96 | + signalRegistration (tld->signal); |
| 97 | + listenerDatas[signame] = tld; |
| 98 | + } |
| 99 | + |
| 100 | + private: |
| 101 | + typedef std::map<std::string, TransformListenerData*> Map_t; |
| 102 | + Map_t listenerDatas; |
| 103 | + tf::TransformListener listener; |
| 104 | + }; |
| 105 | +} // end of namespace dynamicgraph. |
| 106 | + |
| 107 | +#endif // DYNAMIC_GRAPH_ROS_TF_LISTENER_HH |
0 commit comments