/* * node.cpp * * Created on: Jul 30, 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 sliding mode extremum seeking control algorithm with perodic driving signal. */ #include "esc_sm/sm_esc_1d.h" #include "ros/ros.h" #include "esc_ros/esc_ros.h" int main(int argc, char **argv) { ros::init(argc, argv, "sm_esc_1d"); ros::NodeHandle n("~"); double rho,alpha,k; if (!n.getParam("rho", rho)){ ROS_WARN("[sm_esc_1d]: Failed to get the parameter rho from the parameter server. Using the default value."); rho = 0; } if (!n.getParam("alpha", alpha)){ ROS_WARN("[sm_esc_1d]: Failed to get the parameter alpha from the parameter server. Using the default value."); alpha = 0; } if (!n.getParam("k", k)){ ROS_WARN("[sm_esc_1d]: Failed to get the parameter k from the parameter server. Using the default value."); k = 0; } ESCROS esc_ros(&n); SMESC1D* sm_esc_1d = new SMESC1D(rho,k,alpha); esc_ros.init(sm_esc_1d); esc_ros.spin(); return 0; }