node_1d.cpp
Go to the documentation of this file.
00001 /*
00002  * node.cpp
00003  *
00004  *  Created on: Jul 30, 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 approximation based extremum seeking control
00010  */
00011 
00012 #include <esc_approx/approx_esc_1d.h>
00013 #include "esc_ros/esc_ros.h"
00014 
00015 int main(int argc, char **argv) {
00016 
00017         ros::init(argc, argv, "approx_esc_1d");
00018         ros::NodeHandle n("~");
00019 
00020         double k_grad,init_vel;
00021         int data_size, poly_degree,sampling;
00022         if (!n.getParam("data_size", data_size)){
00023                 ROS_WARN("[approx_esc_1d]: Failed to get the parameter data_size from the parameter server. Using the default value.");
00024                 data_size = 0;
00025         }
00026         if (!n.getParam("poly_degree", poly_degree)){
00027                 ROS_WARN("[approx_esc_1d]: Failed to get the parameter poly_degree from the parameter server. Using the default value.");
00028                 poly_degree = 0;
00029         }
00030         if (!n.getParam("k_grad", k_grad)){
00031                 ROS_WARN("[approx_esc_1d]: Failed to get the parameter k_grad from the parameter server. Using the default value.");
00032                 k_grad = 0;
00033         }
00034         if (!n.getParam("init_vel", init_vel)){
00035                 ROS_WARN("[approx_esc_1d]: Failed to get the parameter init_vel from the parameter server. Using the default value.");
00036                 init_vel = 0;
00037         }
00038         if (!n.getParam("sampling", sampling)){
00039                 ROS_WARN("[approx_esc_1d]: Failed to get the parameter sampling from the parameter server. Using the default value.");
00040                 sampling = 0;
00041         }
00042 
00043         ESCROS esc_ros(&n);
00044         ApproxESC1D* approx_esc_1d = new ApproxESC1D(data_size,poly_degree,k_grad,init_vel,sampling);
00045         esc_ros.init(approx_esc_1d);
00046         esc_ros.spin();
00047 
00048         return 0;
00049 }


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