node_1d.cpp
Go to the documentation of this file.
00001 /*
00002  * node.cpp
00003  *
00004  *  Created on: July 24, 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 neural network extremum seeking control
00010  */
00011 
00012 #include <esc_nn/nn_esc_1d.h>
00013 #include "esc_ros/esc_ros.h"
00014 
00015 int main(int argc, char **argv) {
00016 
00017         ros::init(argc, argv, "nn_esc_1d");
00018         ros::NodeHandle n("~");
00019 
00020         double A, B, M, ddelta, delta, period,stoping_min_val;
00021         int stopping_cycle_number;
00022         if (!n.getParam("A", A)){
00023                 ROS_WARN("[nn_esc_1D]: 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_1D]: 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_1D]: Failed to get the parameter M from the parameter server. Using the default value.");
00032                 M = 0;
00033         }
00034         if (!n.getParam("ddelta", ddelta)){
00035                 ROS_WARN("[nn_esc_1D]: Failed to get the parameter ddelta from the parameter server. Using the default value.");
00036                 ddelta = 0;
00037         }
00038         if (!n.getParam("delta", delta)){
00039                 ROS_WARN("[nn_esc_1D]: Failed to get the parameter delta from the parameter server. Using the default value.");
00040                 delta = 0;
00041         }
00042 
00043         if (!n.getParam("period", period)){
00044                 ROS_WARN("[nn_esc_1D]: Failed to get the parameter period from the parameter server. Using the default value.");
00045                 period = 0;
00046         }
00047 
00048         if (!n.getParam("stopping_condition/cycle_number", stopping_cycle_number)){
00049                 ROS_WARN("[nn_esc_1D]: Failed to get the parameter stopping_condition/cycle_number from the parameter server. Using the default value.");
00050                 stopping_cycle_number = 0;
00051         }
00052 
00053         if (!n.getParam("stopping_condition/min_val_change_per_cycle", stoping_min_val)){
00054                 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.");
00055                 stoping_min_val = 0;
00056         }
00057 
00058         ESCROS esc_ros(&n);
00059         NNESC1D* nn_esc_1d = new NNESC1D(A,M,B,ddelta,delta,period,stopping_cycle_number,stoping_min_val);
00060         esc_ros.init(nn_esc_1d);
00061         esc_ros.spin();
00062 
00063         return 0;
00064 }


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