/* * node.cpp * * Created on: Jul 31, 2012 * Author: Berk Calli * Organization: Delft Biorobotics Lab., Delft University of Technology * Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl * * Node for two dimensional approximation based network extremum seeking control */ #include #include "esc_ros/esc_ros.h" int main(int argc, char **argv) { ros::init(argc, argv, "approx_esc_2d"); ros::NodeHandle n("~"); int data_size, sampling; double k_grad, init_vel; if (!n.getParam("data_size", data_size)){ ROS_WARN("[approx_esc_2d]: Failed to get the parameter data_size from the parameter server. Using the default value."); data_size = 0; } if (!n.getParam("sampling", sampling)){ ROS_WARN("[approx_esc_2d]: Failed to get the parameter sampling from the parameter server. Using the default value."); sampling = 0; } if (!n.getParam("k_grad", k_grad)){ ROS_WARN("[approx_esc_2d]: Failed to get the parameter k_grad from the parameter server. Using the default value."); k_grad = 0; } if (!n.getParam("init_vel", init_vel)){ ROS_WARN("[approx_esc_2d]: Failed to get the parameter init_vel from the parameter server. Using the default value."); init_vel = 0; } ESCROS esc_ros(&n); ApproxESC2D* approx_esc_2d = new ApproxESC2D(data_size,k_grad,init_vel,sampling); esc_ros.init(approx_esc_2d); esc_ros.spin(); return 0; }