diff --git a/src/converter.hh b/src/converter.hh
index 772890340c58eaa2076114c72810d80275065ba1..4a57f252447eb2fc2622afbe05148041438aa2bd 100644
--- a/src/converter.hh
+++ b/src/converter.hh
@@ -52,6 +52,11 @@ SOT_TO_ROS_IMPL(int) { dst.data = src; }
 
 ROS_TO_SOT_IMPL(int) { dst = src.data; }
 
+// Int64
+SOT_TO_ROS_IMPL(int64_t) { dst.data = src; }
+
+ROS_TO_SOT_IMPL(int64_t) { dst = src.data; }
+
 // Unsigned
 SOT_TO_ROS_IMPL(unsigned int) { dst.data = src; }
 
@@ -190,6 +195,7 @@ DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Twist, twist, ;);
 DG_BRIDGE_MAKE_SHPTR_IMPL(bool);
 DG_BRIDGE_MAKE_SHPTR_IMPL(double);
 DG_BRIDGE_MAKE_SHPTR_IMPL(int);
+DG_BRIDGE_MAKE_SHPTR_IMPL(int64_t);
 DG_BRIDGE_MAKE_SHPTR_IMPL(unsigned int);
 DG_BRIDGE_MAKE_SHPTR_IMPL(std::string);
 DG_BRIDGE_MAKE_SHPTR_IMPL(Vector);
diff --git a/src/ros_publish.cpp b/src/ros_publish.cpp
index 41c66addd018119b79517730785e562899b35103..1052af2068c0307e690752daf25e3e34491f364a 100644
--- a/src/ros_publish.cpp
+++ b/src/ros_publish.cpp
@@ -50,6 +50,8 @@ Value Add::doExecute() {
     entity.add<unsigned int>(signal, topic);
   else if (type == "int")
     entity.add<int>(signal, topic);
+  else if (type == "int64")
+    entity.add<int64_t>(signal, topic);
   else if (type == "matrix")
     entity.add<Matrix>(signal, topic);
   else if (type == "vector")
@@ -162,7 +164,7 @@ void RosPublish::clear() {
   }
 }
 
-int& RosPublish::trigger(int& dummy, int t) {
+int& RosPublish::trigger(int& dummy, sigtime_t t) {
   typedef std::map<std::string, bindedSignal_t>::iterator iterator_t;
   ros::Time aTime;
   if (ros::Time::isSimTime()) {
diff --git a/src/ros_publish.hh b/src/ros_publish.hh
index 106ec9ec79135df1ba8757b2486cbaa58ad377fc..ceea1106a73c3f0fe090c9ac0e2b7baae2135707 100644
--- a/src/ros_publish.hh
+++ b/src/ros_publish.hh
@@ -42,9 +42,9 @@ class RosPublish : public dynamicgraph::Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
  public:
-  typedef boost::function<void(int)> callback_t;
+  typedef boost::function<void(sigtime_t)> callback_t;
 
-  typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
+  typedef boost::tuple<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
                        callback_t>
       bindedSignal_t;
 
@@ -61,14 +61,15 @@ class RosPublish : public dynamicgraph::Entity {
   std::vector<std::string> list() const;
   void clear();
 
-  int& trigger(int&, int);
+  int& trigger(int&, sigtime_t);
 
   template <typename T>
   void sendData(
       boost::shared_ptr<
           realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
           publisher,
-      boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time);
+      boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
+      sigtime_t time);
 
   template <typename T>
   void add(const std::string& signal, const std::string& topic);
@@ -77,7 +78,7 @@ class RosPublish : public dynamicgraph::Entity {
   static const std::string docstring_;
   ros::NodeHandle& nh_;
   std::map<std::string, bindedSignal_t> bindedSignal_;
-  dynamicgraph::SignalTimeDependent<int, int> trigger_;
+  dynamicgraph::SignalTimeDependent<int, sigtime_t> trigger_;
   ros::Duration rate_;
   ros::Time nextPublication_;
   boost::mutex mutex_;
diff --git a/src/ros_publish.hxx b/src/ros_publish.hxx
index 6534003242134eafae3ba3e1ad6a834d62bdbe3f..5f8c6bff9df1b5a71eafaffc42d1902839929540 100644
--- a/src/ros_publish.hxx
+++ b/src/ros_publish.hxx
@@ -16,8 +16,7 @@ inline void RosPublish::sendData<std::pair<sot::MatrixHomogeneous, Vector> >(
         publisher,
     boost::shared_ptr<
         SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::signalIn_t>
-        signal,
-    int time) {
+        signal, sigtime_t time) {
   SotToRos<std::pair<sot::MatrixHomogeneous, Vector> >::ros_t result;
   if (publisher->trylock()) {
     publisher->msg_.child_frame_id = "/dynamic_graph/world";
@@ -31,7 +30,8 @@ void RosPublish::sendData(
     boost::shared_ptr<
         realtime_tools::RealtimePublisher<typename SotToRos<T>::ros_t> >
         publisher,
-    boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal, int time) {
+    boost::shared_ptr<typename SotToRos<T>::signalIn_t> signal,
+    sigtime_t time) {
   typename SotToRos<T>::ros_t result;
   if (publisher->trylock()) {
     converter(publisher->msg_, signal->access(time));
diff --git a/src/ros_queued_subscribe.cpp b/src/ros_queued_subscribe.cpp
index 3217318a8c46a5dd03fa647966782f9eb3d9263c..14fc0b682b26762c3278f8ebe6ad338ac6500941 100644
--- a/src/ros_queued_subscribe.cpp
+++ b/src/ros_queued_subscribe.cpp
@@ -137,7 +137,7 @@ std::size_t RosQueuedSubscribe::queueSize(const std::string& signal) const {
   return -1;
 }
 
-void RosQueuedSubscribe::readQueue(int beginReadingAt) {
+void RosQueuedSubscribe::readQueue(int64_t beginReadingAt) {
   // Prints signal queues sizes
   /*for (std::map<std::string, bindedSignal_t>::const_iterator it =
          bindedSignal_.begin (); it != bindedSignal_.end (); it++) {
diff --git a/src/ros_queued_subscribe.hh b/src/ros_queued_subscribe.hh
index abfa6e1556a56b5057c7b5627ee5352fceb606f7..6a674f98a94ab1c27539888185a9827b7082d9d1 100644
--- a/src/ros_queued_subscribe.hh
+++ b/src/ros_queued_subscribe.hh
@@ -66,7 +66,7 @@ struct BindedSignalBase {
 
 template <typename T, int BufferSize>
 struct BindedSignal : BindedSignalBase {
-  typedef dynamicgraph::Signal<T, int> Signal_t;
+  typedef dynamicgraph::Signal<T, sigtime_t> Signal_t;
   typedef boost::shared_ptr<Signal_t> SignalPtr_t;
   typedef std::vector<T> buffer_t;
   typedef typename buffer_t::size_type size_type;
@@ -132,7 +132,7 @@ struct BindedSignal : BindedSignalBase {
 
   template <typename R>
   void writer(const R& data);
-  T& reader(T& val, int time);
+  T& reader(T& val, sigtime_t time);
 
  private:
   /// Indicates whether the signal has received atleast one data point
@@ -159,7 +159,7 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
   std::vector<std::string> listTopics();
   void clear();
   void clearQueue(const std::string& signal);
-  void readQueue(int beginReadingAt);
+  void readQueue(int64_t beginReadingAt);
   std::size_t queueSize(const std::string& signal) const;
   bool queueReceivedData(const std::string& signal) const;
   void setQueueReceivedData(const std::string& signal, bool status);
@@ -176,12 +176,12 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
   ros::NodeHandle& nh() { return nh_; }
 
   template <typename R, typename S>
-  void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
-                const R& data);
+  void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
+                signal, const R& data);
 
   template <typename R>
   void callbackTimestamp(
-      boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
+      boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
       const R& data);
 
   template <typename T>
@@ -193,8 +193,7 @@ class RosQueuedSubscribe : public dynamicgraph::Entity {
   std::map<std::string, bindedSignal_t> bindedSignal_;
   std::map<std::string, std::string> topics_;
 
-  int readQueue_;
-  // Signal<bool, int> readQueue_;
+  int64_t readQueue_;
 
   template <typename T>
   friend class internal::BindedSignal;
diff --git a/src/ros_queued_subscribe.hxx b/src/ros_queued_subscribe.hxx
index b398f7151456bdf6e06e8166d07b3cd2afb0a6a8..26481100b4c067c2942190f70e0ef3087c3bcf76 100644
--- a/src/ros_queued_subscribe.hxx
+++ b/src/ros_queued_subscribe.hxx
@@ -92,7 +92,7 @@ void BindedSignal<T, N>::writer(const R& data) {
 }
 
 template <typename T, int N>
-T& BindedSignal<T, N>::reader(T& data, int time) {
+T& BindedSignal<T, N>::reader(T& data, sigtime_t time) {
   // synchronize with method clear:
   // If reading from the list cannot be done, then return last value.
   boost::mutex::scoped_lock lock(rmutex, boost::try_to_lock);
diff --git a/src/ros_subscribe.cpp b/src/ros_subscribe.cpp
index 0c9374e62c60957734dd887d097ef9969943eb3c..c5c190638d120a39eec113e5db6e786c952fed42 100644
--- a/src/ros_subscribe.cpp
+++ b/src/ros_subscribe.cpp
@@ -36,6 +36,10 @@ Value Add::doExecute() {
     entity.add<double>(signal, topic);
   else if (type == "unsigned")
     entity.add<unsigned int>(signal, topic);
+  else if (type == "int")
+    entity.add<int>(signal, topic);
+  else if (type == "int64")
+    entity.add<int64_t>(signal, topic);
   else if (type == "matrix")
     entity.add<dg::Matrix>(signal, topic);
   else if (type == "vector")
diff --git a/src/ros_subscribe.hh b/src/ros_subscribe.hh
index 3b3bb88e9b0a3d401e14f52461f7ca56ec15d756..21a8a09722b07a5f8598aed153f6802f85637a91 100644
--- a/src/ros_subscribe.hh
+++ b/src/ros_subscribe.hh
@@ -46,7 +46,7 @@ class RosSubscribe : public dynamicgraph::Entity {
   typedef boost::posix_time::ptime ptime;
 
  public:
-  typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<int> >,
+  typedef std::pair<boost::shared_ptr<dynamicgraph::SignalBase<sigtime_t> >,
                     boost::shared_ptr<ros::Subscriber> >
       bindedSignal_t;
 
@@ -71,12 +71,12 @@ class RosSubscribe : public dynamicgraph::Entity {
   ros::NodeHandle& nh() { return nh_; }
 
   template <typename R, typename S>
-  void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal,
-                const R& data);
+  void callback(boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> >
+                signal, const R& data);
 
   template <typename R>
   void callbackTimestamp(
-      boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
+      boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
       const R& data);
 
   template <typename T>
diff --git a/src/ros_subscribe.hxx b/src/ros_subscribe.hxx
index 6e322615909259a23e2d5094a22e6e2e4a3264a1..ff98e9e671ff680223343117059e34df6d1f2479 100644
--- a/src/ros_subscribe.hxx
+++ b/src/ros_subscribe.hxx
@@ -18,7 +18,7 @@ namespace dg = dynamicgraph;
 namespace dynamicgraph {
 template <typename R, typename S>
 void RosSubscribe::callback(
-    boost::shared_ptr<dynamicgraph::SignalPtr<S, int> > signal, const R& data) {
+    boost::shared_ptr<dynamicgraph::SignalPtr<S, sigtime_t> > signal, const R& data) {
   typedef S sot_t;
   sot_t value;
   converter(value, data);
@@ -27,7 +27,7 @@ void RosSubscribe::callback(
 
 template <typename R>
 void RosSubscribe::callbackTimestamp(
-    boost::shared_ptr<dynamicgraph::SignalPtr<ptime, int> > signal,
+    boost::shared_ptr<dynamicgraph::SignalPtr<ptime, sigtime_t> > signal,
     const R& data) {
   ptime time = rosTimeToPtime(data->header.stamp);
   signal->setConstant(time);
@@ -101,7 +101,7 @@ struct Add<std::pair<T, dg::Vector> > {
     RosSubscribe.bindedSignal()[signal] = bindedSignal;
 
     // Timestamp.
-    typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, int> signalTimestamp_t;
+    typedef dynamicgraph::SignalPtr<RosSubscribe::ptime, sigtime_t> signalTimestamp_t;
     std::string signalTimestamp =
         (boost::format("%1%%2%") % signal % "Timestamp").str();
 
diff --git a/src/ros_tf_listener.cpp b/src/ros_tf_listener.cpp
index 68e94c924b20099ed6d137d61fc54e888b631f44..045aa60b955bec591201da7378ab7f2135c4ae60 100644
--- a/src/ros_tf_listener.cpp
+++ b/src/ros_tf_listener.cpp
@@ -9,7 +9,7 @@
 namespace dynamicgraph {
 namespace internal {
 sot::MatrixHomogeneous& TransformListenerData::getTransform(
-    sot::MatrixHomogeneous& res, int time) {
+    sot::MatrixHomogeneous& res, sigtime_t time) {
   availableSig.recompute(time);
 
   bool available = availableSig.accessCopy();
@@ -29,7 +29,7 @@ sot::MatrixHomogeneous& TransformListenerData::getTransform(
   return res;
 }
 
-bool& TransformListenerData::isAvailable(bool& available, int time) {
+bool& TransformListenerData::isAvailable(bool& available, sigtime_t time) {
   static const ros::Time origin(0);
   available = false;
   ros::Duration elapsed;
diff --git a/src/ros_tf_listener.hh b/src/ros_tf_listener.hh
index d753aa4f8daec3ac8feaff9145446958408815be..df3958bd86ee5d4409c3c70689a822392b84e103 100644
--- a/src/ros_tf_listener.hh
+++ b/src/ros_tf_listener.hh
@@ -17,9 +17,9 @@ class RosTfListener;
 
 namespace internal {
 struct TransformListenerData {
-  typedef SignalTimeDependent<bool, int> AvailableSignal_t;
-  typedef SignalTimeDependent<sot::MatrixHomogeneous, int> MatrixSignal_t;
-  typedef SignalPtr<sot::MatrixHomogeneous, int> DefaultSignal_t;
+  typedef SignalTimeDependent<bool, sigtime_t> AvailableSignal_t;
+  typedef SignalTimeDependent<sot::MatrixHomogeneous, sigtime_t> MatrixSignal_t;
+  typedef SignalPtr<sot::MatrixHomogeneous, sigtime_t> DefaultSignal_t;
 
   RosTfListener* entity;
   tf2_ros::Buffer& buffer;
@@ -52,9 +52,10 @@ struct TransformListenerData {
     signal.addDependencies(failbackSig << availableSig);
   }
 
-  sot::MatrixHomogeneous& getTransform(sot::MatrixHomogeneous& res, int time);
+  sot::MatrixHomogeneous& getTransform(sot::MatrixHomogeneous& res,
+                                       sigtime_t time);
 
-  bool& isAvailable(bool& isAvailable, int time);
+  bool& isAvailable(bool& isAvailable, sigtime_t time);
 };
 }  // namespace internal
 
diff --git a/src/ros_time.cpp b/src/ros_time.cpp
index 79519ca7fb35eda4a3559fc977bcd21de7cb9f73..8e7690b9225b0bc929ac4fa98b3e160aa4d0ec88 100644
--- a/src/ros_time.cpp
+++ b/src/ros_time.cpp
@@ -31,7 +31,7 @@ RosTime::RosTime(const std::string& _name)
   now_.setFunction(boost::bind(&RosTime::update, this, _1, _2));
 }
 
-ptime& RosTime::update(ptime& time, const int&) {
+ptime& RosTime::update(ptime& time, const sigtime_t&) {
   time = rosTimeToPtime(ros::Time::now());
   return time;
 }
diff --git a/src/ros_time.hh b/src/ros_time.hh
index 1601d88d680c05b20e286c510a58fdb894050c16..ce98aaefabefef39f82a70a932a03172d8895cec 100644
--- a/src/ros_time.hh
+++ b/src/ros_time.hh
@@ -18,13 +18,13 @@ class RosTime : public dynamicgraph::Entity {
   DYNAMIC_GRAPH_ENTITY_DECL();
 
  public:
-  Signal<boost::posix_time::ptime, int> now_;
+  Signal<boost::posix_time::ptime, sigtime_t> now_;
   RosTime(const std::string& name);
   virtual std::string getDocString() const;
 
  protected:
   boost::posix_time::ptime& update(boost::posix_time::ptime& time,
-                                   const int& t);
+                                   const sigtime_t& t);
 
  private:
   static const std::string docstring_;
diff --git a/src/sot_to_ros.cpp b/src/sot_to_ros.cpp
index 8b03235588c3110377d78caa64903994c579b919..af3f171f82f4dde30a8effa2392f4ef1e1f23238 100644
--- a/src/sot_to_ros.cpp
+++ b/src/sot_to_ros.cpp
@@ -5,6 +5,7 @@ namespace dynamicgraph {
 const char* SotToRos<bool>::signalTypeName = "bool";
 const char* SotToRos<double>::signalTypeName = "Double";
 const char* SotToRos<int>::signalTypeName = "int";
+const char* SotToRos<int64_t>::signalTypeName = "int64";
 const char* SotToRos<std::string>::signalTypeName = "string";
 const char* SotToRos<unsigned int>::signalTypeName = "Unsigned";
 const char* SotToRos<Matrix>::signalTypeName = "Matrix";
diff --git a/src/sot_to_ros.hh b/src/sot_to_ros.hh
index d16d7076579de2cc73ba3e3793f2b0dd542adab1..4e0ba44d2829f7ad351a7dd302c06296ca53036b 100644
--- a/src/sot_to_ros.hh
+++ b/src/sot_to_ros.hh
@@ -6,6 +6,7 @@
 #include <std_msgs/Bool.h>
 #include <std_msgs/Float64.h>
 #include <std_msgs/Int32.h>
+#include <std_msgs/Int64.h>
 #include <std_msgs/String.h>
 #include <std_msgs/UInt32.h>
 
@@ -52,9 +53,9 @@ struct SotToRos<bool> {
   typedef bool sot_t;
   typedef std_msgs::Bool ros_t;
   typedef std_msgs::BoolConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::Signal<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -71,9 +72,9 @@ struct SotToRos<double> {
   typedef double sot_t;
   typedef std_msgs::Float64 ros_t;
   typedef std_msgs::Float64ConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::Signal<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -90,9 +91,9 @@ struct SotToRos<unsigned int> {
   typedef unsigned int sot_t;
   typedef std_msgs::UInt32 ros_t;
   typedef std_msgs::UInt32ConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::Signal<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -109,9 +110,28 @@ struct SotToRos<int> {
   typedef int sot_t;
   typedef std_msgs::Int32 ros_t;
   typedef std_msgs::Int32ConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::Signal<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
+
+  static const char* signalTypeName;
+
+  template <typename S>
+  static void setDefault(S& s) {
+    s.setConstant(0);
+  }
+
+  static void setDefault(sot_t& s) { s = 0; }
+};
+
+template <>
+struct SotToRos<int64_t> {
+  typedef int64_t sot_t;
+  typedef std_msgs::Int64 ros_t;
+  typedef std_msgs::Int64ConstPtr ros_const_ptr_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -128,9 +148,9 @@ struct SotToRos<std::string> {
   typedef std::string sot_t;
   typedef std_msgs::String ros_t;
   typedef std_msgs::StringConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::Signal<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::Signal<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -147,9 +167,9 @@ struct SotToRos<Matrix> {
   typedef Matrix sot_t;
   typedef dynamic_graph_bridge_msgs::Matrix ros_t;
   typedef dynamic_graph_bridge_msgs::MatrixConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -168,9 +188,9 @@ struct SotToRos<Vector> {
   typedef Vector sot_t;
   typedef dynamic_graph_bridge_msgs::Vector ros_t;
   typedef dynamic_graph_bridge_msgs::VectorConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -189,9 +209,9 @@ struct SotToRos<specific::Vector3> {
   typedef Vector sot_t;
   typedef geometry_msgs::Vector3 ros_t;
   typedef geometry_msgs::Vector3ConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -209,9 +229,9 @@ struct SotToRos<sot::MatrixHomogeneous> {
   typedef sot::MatrixHomogeneous sot_t;
   typedef geometry_msgs::Transform ros_t;
   typedef geometry_msgs::TransformConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -229,9 +249,9 @@ struct SotToRos<specific::Twist> {
   typedef Vector sot_t;
   typedef geometry_msgs::Twist ros_t;
   typedef geometry_msgs::TwistConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -251,9 +271,9 @@ struct SotToRos<std::pair<specific::Vector3, Vector> > {
   typedef Vector sot_t;
   typedef geometry_msgs::Vector3Stamped ros_t;
   typedef geometry_msgs::Vector3StampedConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -269,9 +289,9 @@ struct SotToRos<std::pair<sot::MatrixHomogeneous, Vector> > {
   typedef sot::MatrixHomogeneous sot_t;
   typedef geometry_msgs::TransformStamped ros_t;
   typedef geometry_msgs::TransformStampedConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;
 
@@ -287,9 +307,9 @@ struct SotToRos<std::pair<specific::Twist, Vector> > {
   typedef Vector sot_t;
   typedef geometry_msgs::TwistStamped ros_t;
   typedef geometry_msgs::TwistStampedConstPtr ros_const_ptr_t;
-  typedef dynamicgraph::SignalTimeDependent<sot_t, int> signal_t;
-  typedef dynamicgraph::SignalPtr<sot_t, int> signalIn_t;
-  typedef boost::function<sot_t&(sot_t&, int)> callback_t;
+  typedef dynamicgraph::SignalTimeDependent<sot_t, sigtime_t> signal_t;
+  typedef dynamicgraph::SignalPtr<sot_t, sigtime_t> signalIn_t;
+  typedef boost::function<sot_t&(sot_t&, sigtime_t)> callback_t;
 
   static const char* signalTypeName;