diff --git a/include/hpp/manipulation/steering-method/end-effector-trajectory.hh b/include/hpp/manipulation/steering-method/end-effector-trajectory.hh
index 65bcaba6d26613ab8d7d8c797558caccac9e7a37..7c8feee3c521b363160f2eacf33502318201ae47 100644
--- a/include/hpp/manipulation/steering-method/end-effector-trajectory.hh
+++ b/include/hpp/manipulation/steering-method/end-effector-trajectory.hh
@@ -49,6 +49,11 @@ namespace hpp {
           /// Set the constraint whose right hand side will vary.
           void trajectoryConstraint (const constraints::ImplicitPtr_t& ic);
 
+          const constraints::ImplicitPtr_t& trajectoryConstraint ()
+          {
+            return constraint_;
+          }
+
           /// Set the right hand side of the function from a path
           /// \param se3Output set to True if the output of path must be
           ///                  understood as SE3.
@@ -64,6 +69,11 @@ namespace hpp {
             return eeTraj_;
           }
 
+          const interval_t& timeRange () const
+          {
+            return timeRange_;
+          }
+
           core::SteeringMethodPtr_t copy () const
           {
             EndEffectorTrajectoryPtr_t ptr (new EndEffectorTrajectory (*this));