From 04f931dd03b3da751825fc9b7f73c3d9781c25de Mon Sep 17 00:00:00 2001
From: Florent Lamiraux <florent@laas.fr>
Date: Sat, 28 Mar 2020 17:50:41 +0100
Subject: [PATCH] [Edge] Rename configConstraint into targetConstraint

  Make previous methods deprecated
  Rename Graph::configConstraint(EdgePtr_t) into targetConstraint.
---
 include/hpp/manipulation/graph/edge.hh  | 24 +++++++++++++++----
 include/hpp/manipulation/graph/graph.hh | 16 +++++++++----
 src/graph/edge.cc                       | 32 ++++++++++++++++++-------
 src/graph/graph.cc                      |  9 +++++--
 4 files changed, 63 insertions(+), 18 deletions(-)

diff --git a/include/hpp/manipulation/graph/edge.hh b/include/hpp/manipulation/graph/edge.hh
index 5eff0b52..40403654 100644
--- a/include/hpp/manipulation/graph/edge.hh
+++ b/include/hpp/manipulation/graph/edge.hh
@@ -191,7 +191,12 @@ namespace hpp {
           virtual std::ostream& dotPrint (std::ostream& os, dot::DrawingAttributes da = dot::DrawingAttributes ()) const;
 
           /// Constraint of the destination state and of the path
-          ConstraintSetPtr_t configConstraint() const;
+          /// \deprecated Use targetConstraint instead
+          ConstraintSetPtr_t configConstraint() const
+            HPP_MANIPULATION_DEPRECATED;
+
+          /// Constraint of the destination state and of the path
+          ConstraintSetPtr_t targetConstraint() const;
 
           void setShort (bool isShort) {
             isShort_ = isShort;
@@ -212,8 +217,13 @@ namespace hpp {
           /// Constructor
           Edge (const std::string& name);
 
-          virtual ConstraintSetPtr_t buildConfigConstraint();
+          virtual ConstraintSetPtr_t buildConfigConstraint()
+            HPP_MANIPULATION_DEPRECATED;
+
+          /// Build path and target state constraint set.
+          virtual ConstraintSetPtr_t buildTargetConstraint();
 
+          /// Build path constraints
           virtual ConstraintSetPtr_t buildPathConstraint();
 
           virtual void initialize ();
@@ -229,7 +239,7 @@ namespace hpp {
 
           /// Constraint ensuring that a q_proj will be in to_ and in the
           /// same leaf of to_ as the configuration used for initialization.
-          ConstraintSetPtr_t configConstraints_;
+          ConstraintSetPtr_t targetConstraints_;
 
           /// The two ends of the transition.
           StateWkPtr_t from_, to_;
@@ -425,7 +435,13 @@ namespace hpp {
           ///                from nnear.
           virtual bool generateTargetConfig (ConfigurationIn_t qStart,
                                              ConfigurationOut_t q) const;
-          virtual ConstraintSetPtr_t buildConfigConstraint();
+
+          /// \deprecated Use buildTargetConstraint instead
+          virtual ConstraintSetPtr_t buildConfigConstraint()
+            HPP_MANIPULATION_DEPRECATED;
+
+          /// Build path and target state constraints
+          virtual ConstraintSetPtr_t buildTargetConstraint();
 
           void buildHistogram ();
 
diff --git a/include/hpp/manipulation/graph/graph.hh b/include/hpp/manipulation/graph/graph.hh
index ff072019..af584067 100644
--- a/include/hpp/manipulation/graph/graph.hh
+++ b/include/hpp/manipulation/graph/graph.hh
@@ -122,10 +122,18 @@ namespace hpp {
           /// \return The initialized projector.
           ConstraintSetPtr_t configConstraint (const StatePtr_t& state) const;
 
-          /// Constraint to project onto the same leaf as config.
-          /// \param edges a list of edges defining the foliation.
-          /// \return The constraint.
-          ConstraintSetPtr_t configConstraint (const EdgePtr_t& edge) const;
+          /// Constraints of path and target state of an edge
+          /// \deprecated Use tagetConstraint instead.
+          ConstraintSetPtr_t configConstraint (const EdgePtr_t& edge) const
+            HPP_MANIPULATION_DEPRECATED;
+
+          /// Constraints a configuration in target state should satisfy
+          /// \param edge a transition
+          /// \return The set of constraints a configuration lying in the
+          ///         target state of the edge should satisfy. This set
+          ///         includes the paths constraints of the edge.
+          /// \sa Edge::targetConstraint.
+          ConstraintSetPtr_t targetConstraint (const EdgePtr_t& edge) const;
 
 	  /// Get error of a config with respect to a state constraint
 	  ///
diff --git a/src/graph/edge.cc b/src/graph/edge.cc
index f5fce065..6545f994 100644
--- a/src/graph/edge.cc
+++ b/src/graph/edge.cc
@@ -41,7 +41,7 @@ namespace hpp {
       Edge::Edge (const std::string& name) :
 	GraphComponent (name), isShort_ (false),
         pathConstraints_ (),
-	configConstraints_ (),
+	targetConstraints_ (),
         steeringMethod_ (),
         securityMargins_ (),
         pathValidation_ ()
@@ -165,7 +165,7 @@ namespace hpp {
 
       void Edge::initialize ()
       {
-        configConstraints_ = buildConfigConstraint ();
+        targetConstraints_ = buildTargetConstraint ();
         pathConstraints_ = buildPathConstraint ();
         isInit_ = true;
       }
@@ -191,10 +191,16 @@ namespace hpp {
         return os;
       }
 
+      ConstraintSetPtr_t Edge::targetConstraint() const
+      {
+        throwIfNotInitialized ();
+        return targetConstraints_;
+      }
+
       ConstraintSetPtr_t Edge::configConstraint() const
       {
         throwIfNotInitialized ();
-        return configConstraints_;
+        return targetConstraints_;
       }
 
       // Merge constraints of several graph components into a config projectors
@@ -264,6 +270,11 @@ namespace hpp {
       }
 
       ConstraintSetPtr_t Edge::buildConfigConstraint()
+      {
+        return buildTargetConstraint();
+      }
+
+      ConstraintSetPtr_t Edge::buildTargetConstraint()
       {
         std::string n = "(" + name () + ")";
         GraphPtr_t g = graph_.lock ();
@@ -392,7 +403,7 @@ namespace hpp {
       bool Edge::generateTargetConfig (ConfigurationIn_t qStart,
                                        ConfigurationOut_t q) const
       {
-        ConstraintSetPtr_t c = configConstraint ();
+        ConstraintSetPtr_t c = targetConstraint();
         ConfigProjectorPtr_t proj = c->configProjector ();
         proj->rightHandSideFromConfig (qStart);
         if (isShort_) q = qStart;
@@ -463,10 +474,10 @@ namespace hpp {
             lastSucceeded_ = false;
             return false;
           }
-          assert (configConstraint ());
-          assert (configConstraint ()->configProjector ());
+          assert (targetConstraint());
+          assert (targetConstraint()->configProjector ());
           value_type eps
-            (configConstraint ()->configProjector ()->errorThreshold ());
+            (targetConstraint()->configProjector ()->errorThreshold ());
           if ((configs_.col(i) - configs_.col (i+1)).squaredNorm () > eps*eps) {
             if (!edges_[i]->build (p, configs_.col(i), configs_.col (i+1))) {
               hppDout (info, "Waypoint edge " << name()
@@ -639,7 +650,7 @@ namespace hpp {
           ConfigurationIn_t qlevelset, ConfigurationOut_t q) const
       {
         // First, set the offset.
-        ConstraintSetPtr_t cs = configConstraint ();
+        ConstraintSetPtr_t cs = targetConstraint();
         const ConfigProjectorPtr_t cp = cs->configProjector ();
         assert (cp);
 
@@ -754,6 +765,11 @@ namespace hpp {
       }
 
       ConstraintSetPtr_t LevelSetEdge::buildConfigConstraint()
+      {
+        return buildTargetConstraint();
+      }
+
+      ConstraintSetPtr_t LevelSetEdge::buildTargetConstraint()
       {
         std::string n = "(" + name () + ")";
         GraphPtr_t g = graph_.lock ();
diff --git a/src/graph/graph.cc b/src/graph/graph.cc
index 14a441ca..3725672c 100644
--- a/src/graph/graph.cc
+++ b/src/graph/graph.cc
@@ -205,7 +205,7 @@ namespace hpp {
       (ConfigurationIn_t leafConfig, ConfigurationIn_t config,
        const EdgePtr_t& edge, vector_t& error) const
       {
-	ConstraintSetPtr_t cs (configConstraint (edge));
+	ConstraintSetPtr_t cs (targetConstraint (edge));
 	ConfigProjectorPtr_t cp (cs->configProjector ());
 	if (cp) cp->rightHandSideFromConfig (leafConfig);
 	return cs->isSatisfied (config, error);
@@ -223,7 +223,12 @@ namespace hpp {
 
       ConstraintSetPtr_t Graph::configConstraint (const EdgePtr_t& edge) const
       {
-        return edge->configConstraint ();
+        return edge->targetConstraint ();
+      }
+
+      ConstraintSetPtr_t Graph::targetConstraint (const EdgePtr_t& edge) const
+      {
+        return edge->targetConstraint ();
       }
 
       ConstraintSetPtr_t Graph::pathConstraint (const EdgePtr_t& edge) const
-- 
GitLab