node.cpp
Go to the documentation of this file.
00001 /*
00002  * node.cpp
00003  *
00004  *  Created on: Aug 1, 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 perturbation based extremum seeking control
00010  */
00011 
00012 
00013 #include <esc_perturb/perturb_esc_nd.h>
00014 #include "esc_ros/esc_ros.h"
00015 
00016 int main(int argc, char **argv) {
00017 
00018         ros::init(argc, argv, "perturb_esc_nd");
00019         ros::NodeHandle n("~");
00020 
00021         double sin_amp,sin_freq,corr_gain,high_pass_pole,low_pass_pole,comp_pole,comp_zero,period;
00022 
00023         if (!n.getParam("sin_amp", sin_amp)){
00024                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter sin_amp from the parameter server. Using the default value.");
00025                 sin_amp = 0;
00026         }
00027         if (!n.getParam("sin_freq", sin_freq)){
00028                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter sin_freq from the parameter server. Using the default value.");
00029                 sin_freq = 0;
00030         }
00031         if (!n.getParam("corr_gain", corr_gain)){
00032                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter corr_gain from the parameter server. Using the default value.");
00033                 corr_gain = 0;
00034         }
00035         if (!n.getParam("high_pass_pole", high_pass_pole)){
00036                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter high_pass_pole from the parameter server. Using the default value.");
00037                 high_pass_pole = 0;
00038         }
00039         if (!n.getParam("low_pass_pole", low_pass_pole)){
00040                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter low_pass_pole from the parameter server. Using the default value.");
00041                 low_pass_pole = 0;
00042         }
00043         if (!n.getParam("comp_pole", comp_pole)){
00044                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter comp_pole from the parameter server. Using the default value.");
00045                 comp_pole = 0;
00046         }
00047         if (!n.getParam("comp_zero", comp_zero)){
00048                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter comp_zero from the parameter server. Using the default value.");
00049                 comp_zero = 0;
00050         }
00051         if (!n.getParam("period", period)){
00052                 ROS_WARN("[perturb_esc_nd]: Failed to get the parameter period from the parameter server. Using the default value.");
00053                 period = 0;
00054         }
00055 
00056         ESCROS esc_ros(&n);
00057         PerturbESCND* perturb_esc_nd = new PerturbESCND(sin_amp,sin_freq,corr_gain,high_pass_pole,low_pass_pole,comp_zero,comp_pole,period);
00058         esc_ros.init(perturb_esc_nd);
00059         esc_ros.spin();
00060 
00061         return 0;
00062 }


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