Index: trunk/extremum_seeking/esc_common/include/esc_common/esc.h
===================================================================
--- trunk/extremum_seeking/esc_common/include/esc_common/esc.h	(revision 13)
+++ trunk/extremum_seeking/esc_common/include/esc_common/esc.h	(revision 18)
@@ -63,4 +63,9 @@
     /// Reset control algorithm to initial conditions.
     virtual void reset() = 0;
+
+    /// Reset control algorithm to initial conditions.
+    virtual bool isStoppingConditionsMet(){
+    	return false;
+    }
 };
 
Index: trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_1d.h
===================================================================
--- trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_1d.h	(revision 13)
+++ trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_1d.h	(revision 18)
@@ -27,6 +27,8 @@
 
 protected:
-	double A_,M_,ddelta_,A,delta_,B_, mpd_init_, w_switch_old_, a_switch_old_,yr_,period_;
-	double min_peak_,vel_ref_,w_switch_;
+	double A_,M_,ddelta_,delta_,B_, mpd_init_, w_switch_old_, a_switch_old_,yr_,period_;
+	double min_peak_,vel_ref_,w_switch_,obj_val_cycle_init_;
+	double stoping_min_val_,vel_ref_old_;
+	int stopping_cycle_number_,nn_cycle_count_;
 	bool initialized_,min_peak_detect_init_;
 
@@ -34,7 +36,7 @@
 	NNESC1D();
 
-	NNESC1D(double A,double M, double B, double ddelta, double delta, double period);
+	NNESC1D(double A,double M, double B, double ddelta, double delta, double period, int stopping_cycle_number, double stoping_min_val);
 
-	void init(double A, double M, double B, double ddelta, double delta, double period);
+	void init(double A, double M, double B, double ddelta, double delta, double period, int stopping_cycle_number, double stoping_min_val);
 
 	std::vector<double> step(double obj_val);
@@ -48,4 +50,5 @@
 	double aSwitch(double e);
 	void reset();
+	bool isStoppingConditionsMet();
 
 };
Index: trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_2d.h
===================================================================
--- trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_2d.h	(revision 13)
+++ trunk/extremum_seeking/esc_nn/include/esc_nn/nn_esc_2d.h	(revision 18)
@@ -26,14 +26,14 @@
 protected:
 	double A_,M_,ddelta1_,ddelta2_,ddelta3_,delta_,B_, mpd_init_, w_switch_old_, a_switch1_old_, a_switch2_old_, a_switch3_old_,yr_,period_;
-	double min_peak_,w_switch_;
-	std::vector<double> vel_ref_;
+	double min_peak_,w_switch_, stoping_min_val_, obj_val_cycle_init_;
+	int stopping_cycle_number_, nn_cycle_count_;
+	std::vector<double> vel_ref_,vel_ref_old_;
 	bool initialized_,min_peak_detect_init_;
+
 
 public:
 	NNESC2D();
-
-	NNESC2D(double A,double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period);
-
-	void init(double A, double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period);
+	NNESC2D(double A,double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val);
+	void init(double A, double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val);
 
 	std::vector<double> step(double obj_val);
@@ -43,4 +43,5 @@
 	std::vector<std::string> monitorNames();
 	void reset();
+	bool isStoppingConditionsMet();
 protected:
 	double wSwitch(double e);
Index: trunk/extremum_seeking/esc_nn/launch/nn_esc_1d.launch
===================================================================
--- trunk/extremum_seeking/esc_nn/launch/nn_esc_1d.launch	(revision 13)
+++ trunk/extremum_seeking/esc_nn/launch/nn_esc_1d.launch	(revision 18)
@@ -9,4 +9,6 @@
 		<param name="period" type="double" value="0.01" />
 		<param name="monitor" type="bool" value="true" />
+		<param name="stopping_condition/cycle_number" type="int" value="0" />
+		<param name="stopping_condition/min_val_change_per_cycle" type="double" value="0" />
 	</node> 
 </launch>
Index: trunk/extremum_seeking/esc_nn/src/nn_esc_1d.cpp
===================================================================
--- trunk/extremum_seeking/esc_nn/src/nn_esc_1d.cpp	(revision 13)
+++ trunk/extremum_seeking/esc_nn/src/nn_esc_1d.cpp	(revision 18)
@@ -30,4 +30,5 @@
 	min_peak_detect_init_ = false;
 	initialized_ = false;
+
 }
 
@@ -59,9 +60,9 @@
 }
 
-NNESC1D::NNESC1D(double A,double M, double B, double ddelta, double delta, double period){
-	init(A, M, B, ddelta, delta, period);
+NNESC1D::NNESC1D(double A,double M, double B, double ddelta, double delta, double period, int stopping_cycle_number, double stoping_min_val){
+	init(A, M, B, ddelta, delta, period,stopping_cycle_number,stoping_min_val);
 }
 
-void NNESC1D::init(double A, double M, double B, double ddelta, double delta, double period){
+void NNESC1D::init(double A, double M, double B, double ddelta, double delta, double period, int stopping_cycle_number, double stoping_min_val){
 	A_ = A;
 	M_ = M;
@@ -70,12 +71,8 @@
 	delta_ = delta;
 	period_ = period;
-	w_switch_old_ = 0;
-	a_switch_old_ = A;
-	yr_ = 0;
-	min_peak_ = 0;
-	vel_ref_ = 0;
-	w_switch_ = 0;
-	min_peak_detect_init_ = false;
+	reset();
 	initialized_ = true;
+	stopping_cycle_number_ = stopping_cycle_number;
+	stoping_min_val_ = stoping_min_val;
 }
 
@@ -89,4 +86,5 @@
 		yr_ = obj_val;
 		min_peak_detect_init_ = true;
+		obj_val_cycle_init_ = obj_val;
 	}
 
@@ -96,4 +94,15 @@
 	w_switch_ = wSwitch(-e);
 	yr_ = yr_ + (w_switch_+min_peak_)*period_;
+
+	if(vel_ref_old_ != vel_ref_ && vel_ref_ == -A_){
+		if(obj_val_cycle_init_ - obj_val < stoping_min_val_)
+			nn_cycle_count_++;
+		else
+			nn_cycle_count_ = 0;
+		obj_val_cycle_init_ = obj_val;
+	}
+
+	vel_ref_old_ = vel_ref_;
+
 	std::vector<double> output;
 	output.push_back(vel_ref_);
@@ -137,9 +146,23 @@
 void NNESC1D::reset(){
 	w_switch_old_ = 0;
-	a_switch_old_ = A;
+	a_switch_old_ = A_;
 	yr_ = 0;
 	min_peak_ = 0;
 	vel_ref_ = 0;
 	w_switch_ = 0;
+	nn_cycle_count_ = 0;
+	vel_ref_old_ = 0;
 	min_peak_detect_init_ = false;
+
 }
+
+
+bool NNESC1D::isStoppingConditionsMet(){
+	if(stopping_cycle_number_ <= 0)
+		return false;
+	else if(nn_cycle_count_ >= stopping_cycle_number_){
+		return true;
+	}
+	else
+		return false;
+}
Index: trunk/extremum_seeking/esc_nn/src/nn_esc_2d.cpp
===================================================================
--- trunk/extremum_seeking/esc_nn/src/nn_esc_2d.cpp	(revision 13)
+++ trunk/extremum_seeking/esc_nn/src/nn_esc_2d.cpp	(revision 18)
@@ -31,4 +31,5 @@
 	min_peak_ = 0;
 	vel_ref_.resize(2);
+	vel_ref_old_.resize(2);
 	vel_ref_[0] = 0;
 	vel_ref_[1] = 0;
@@ -73,9 +74,9 @@
 }
 
-NNESC2D::NNESC2D(double A,double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period){
-	init(A, M, B, ddelta1, ddelta2, ddelta3, delta, period);
-}
-
-void NNESC2D::init(double A, double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period){
+NNESC2D::NNESC2D(double A,double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val){
+	init(A, M, B, ddelta1, ddelta2, ddelta3, delta, period, stopping_cycle_number, stoping_min_val);
+}
+
+void NNESC2D::init(double A, double M, double B, double ddelta1, double ddelta2, double ddelta3, double delta, double period, int stopping_cycle_number, double stoping_min_val){
 	A_ = A;
 	M_ = M;
@@ -86,16 +87,8 @@
 	delta_ = delta;
 	period_ = period;
-	w_switch_old_ = 0;
-	a_switch1_old_ = A_;
-	a_switch2_old_ = 0;
-	a_switch3_old_ = 0;
-	vel_ref_.resize(2);
-	vel_ref_[0] = 0;
-	vel_ref_[1] = 0;
-	yr_ = 0;
-	min_peak_ = 0;
-	w_switch_ = 0;
-	min_peak_detect_init_ = false;
+	reset();
 	initialized_ = true;
+	stopping_cycle_number_ = stopping_cycle_number;
+	stoping_min_val_ = stoping_min_val;
 }
 
@@ -110,4 +103,7 @@
 		yr_ = min_peak_;
 		min_peak_detect_init_ = true;
+		obj_val_cycle_init_ = obj_val;
+		vel_ref_old_[0] = vel_ref_[0];
+		vel_ref_old_[1] = vel_ref_[1];
 	}
 
@@ -124,4 +120,16 @@
 	w_switch_ = wSwitch(e);
 	yr_ = yr_ + (w_switch_+min_peak_)*period_;
+
+	if((vel_ref_old_[0] != vel_ref_[0] || vel_ref_old_[1] != vel_ref_[1]) && vel_ref_[1] == A_ && vel_ref_[0] == 0){
+		if(obj_val_cycle_init_ - obj_val < stoping_min_val_){
+			nn_cycle_count_++;
+		}
+		else
+			nn_cycle_count_ = 0;
+		obj_val_cycle_init_ = obj_val;
+	}
+	//printf("[nn_esc_2d]: nn_cycle_count = %d \n",nn_cycle_count_);
+	vel_ref_old_[0] = vel_ref_[0];
+	vel_ref_old_[1] = vel_ref_[1];
 
 	return vel_ref_;
@@ -197,8 +205,21 @@
 	vel_ref_[0] = 0;
 	vel_ref_[1] = 0;
+	vel_ref_old_.resize(2);
+	vel_ref_old_[0] = 0;
+	vel_ref_old_[1] = 0;
 	yr_ = 0;
 	min_peak_ = 0;
 	w_switch_ = 0;
+	nn_cycle_count_ = 0;
 	min_peak_detect_init_ = false;
-	initialized_ = true;
-}
+}
+
+bool NNESC2D::isStoppingConditionsMet(){
+	if(stopping_cycle_number_ <= 0)
+		return false;
+	else if(nn_cycle_count_ > stopping_cycle_number_){
+		return true;
+	}
+	else
+		return false;
+}
Index: trunk/extremum_seeking/esc_nn/src/node_1d.cpp
===================================================================
--- trunk/extremum_seeking/esc_nn/src/node_1d.cpp	(revision 13)
+++ trunk/extremum_seeking/esc_nn/src/node_1d.cpp	(revision 18)
@@ -18,5 +18,6 @@
 	ros::NodeHandle n("~");
 
-	double A, B, M, ddelta, delta, period;
+	double A, B, M, ddelta, delta, period,stoping_min_val;
+	int stopping_cycle_number;
 	if (!n.getParam("A", A)){
 		ROS_WARN("[nn_esc_1D]: Failed to get the parameter A from the parameter server. Using the default value.");
@@ -39,4 +40,5 @@
 		delta = 0;
 	}
+
 	if (!n.getParam("period", period)){
 		ROS_WARN("[nn_esc_1D]: Failed to get the parameter period from the parameter server. Using the default value.");
@@ -44,6 +46,16 @@
 	}
 
+	if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){
+		ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value.");
+		stopping_cycle_number = 0;
+	}
+
+	if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){
+		ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/min_val_change_per_cycle from the parameter server. Using the default value.");
+		stoping_min_val = 0;
+	}
+
 	ESCROS esc_ros(&n);
-	NNESC1D* nn_esc_1d = new NNESC1D(A,M,B,ddelta,delta,period);
+	NNESC1D* nn_esc_1d = new NNESC1D(A,M,B,ddelta,delta,period,stopping_cycle_number,stoping_min_val);
 	esc_ros.init(nn_esc_1d);
 	esc_ros.spin();
Index: trunk/extremum_seeking/esc_nn/src/node_2d.cpp
===================================================================
--- trunk/extremum_seeking/esc_nn/src/node_2d.cpp	(revision 13)
+++ trunk/extremum_seeking/esc_nn/src/node_2d.cpp	(revision 18)
@@ -18,5 +18,6 @@
 	ros::NodeHandle n("~");
 
-	double A, B, M, ddelta1, ddelta2, ddelta3, delta, period;
+	double A, B, M, ddelta1, ddelta2, ddelta3, delta, period,stoping_min_val;
+	int stopping_cycle_number;
 	if (!n.getParam("A", A)){
 		ROS_WARN("[nn_esc_2d]: Failed to get the parameter A from the parameter server. Using the default value.");
@@ -52,6 +53,16 @@
 	}
 
+	if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){
+		ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value.");
+		stopping_cycle_number = 0;
+	}
+
+	if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){
+		ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/min_val_change_per_cycle from the parameter server. Using the default value.");
+		stoping_min_val = 0;
+	}
+
 	ESCROS esc_ros(&n);
-	NNESC2D* nn_esc_2d = new NNESC2D(A,M,B,ddelta1,ddelta2,ddelta3,delta,period);
+	NNESC2D* nn_esc_2d = new NNESC2D(A,M,B,ddelta1,ddelta2,ddelta3,delta,period,stopping_cycle_number,stoping_min_val);
 	esc_ros.init(nn_esc_2d);
 	esc_ros.spin();
Index: trunk/extremum_seeking/esc_test/launch/nn_esc_1d.launch
===================================================================
--- trunk/extremum_seeking/esc_test/launch/nn_esc_1d.launch	(revision 13)
+++ trunk/extremum_seeking/esc_test/launch/nn_esc_1d.launch	(revision 18)
@@ -9,4 +9,6 @@
 		<param name="period" type="double" value="0.01" />
 		<param name="monitor" type="bool" value="true" />
+		<param name="stopping_condition/cycle_number" type="int" value="3" />
+		<param name="stopping_condition/min_val_change_per_cycle" type="double" value="0.3" />
 
 		<remap from="/nn_esc_1d/obj_val" to="/esc_test/obj_val"/>
Index: trunk/extremum_seeking/stack.xml
===================================================================
--- trunk/extremum_seeking/stack.xml	(revision 13)
+++ trunk/extremum_seeking/stack.xml	(revision 18)
@@ -5,4 +5,6 @@
   <review status="unreviewed" notes=""/>
   <url>http://ros.org/wiki/extremum_seeking</url>
-  <depend stack="ros" />
+  <depend stack="ros"/>
+  <depend stack="ros_comm"/>
+  <version>0.1.0</version>
 </stack>
