node_2d.cpp
Go to the documentation of this file.
00001 /*
00002  * node.cpp
00003  *
00004  *  Created on: Jul 31, 2012
00005  *      Author: Berk Calli
00006  *      Organization: Delft Biorobotics Lab., Delft University of Technology
00007  *              Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl
00008  *
00009  *      Node for two dimensional neural network extremum seeking control
00010  */
00011 
00012 #include <esc_nn/nn_esc_2d.h>
00013 #include "esc_ros/esc_ros.h"
00014 
00015 int main(int argc, char **argv) {
00016 
00017         ros::init(argc, argv, "nn_esc_2d");
00018         ros::NodeHandle n("~");
00019 
00020         double A, B, M, ddelta1, ddelta2, ddelta3, delta, period,stoping_min_val;
00021         int stopping_cycle_number;
00022         if (!n.getParam("A", A)){
00023                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter A from the parameter server. Using the default value.");
00024                 A = 0;
00025         }
00026         if (!n.getParam("B", B)){
00027                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter B from the parameter server. Using the default value.");
00028                 B = 0;
00029         }
00030         if (!n.getParam("M", M)){
00031                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter M from the parameter server. Using the default value.");
00032                 M = 0;
00033         }
00034         if (!n.getParam("ddelta1", ddelta1)){
00035                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta1 from the parameter server. Using the default value.");
00036                 ddelta1 = 0;
00037         }
00038         if (!n.getParam("ddelta2", ddelta2)){
00039                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta2 from the parameter server. Using the default value.");
00040                 ddelta2 = 0;
00041         }
00042         if (!n.getParam("ddelta3", ddelta3)){
00043                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter ddelta3 from the parameter server. Using the default value.");
00044                 ddelta3 = 0;
00045         }
00046         if (!n.getParam("delta", delta)){
00047                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter delta from the parameter server. Using the default value.");
00048                 delta = 0;
00049         }
00050         if (!n.getParam("period", period)){
00051                 ROS_WARN("[nn_esc_2d]: Failed to get the parameter period from the parameter server. Using the default value.");
00052                 period = 0;
00053         }
00054 
00055         if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){
00056                 ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value.");
00057                 stopping_cycle_number = 0;
00058         }
00059 
00060         if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){
00061                 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.");
00062                 stoping_min_val = 0;
00063         }
00064 
00065         ESCROS esc_ros(&n);
00066         NNESC2D* nn_esc_2d = new NNESC2D(A,M,B,ddelta1,ddelta2,ddelta3,delta,period,stopping_cycle_number,stoping_min_val);
00067         esc_ros.init(nn_esc_2d);
00068         esc_ros.spin();
00069 
00070         return 0;
00071 }
00072 
00073 


esc_nn
Author(s): Berk Calli
autogenerated on Sun Jan 5 2014 11:07:07