Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #include "esc_sm/sm_esc_1d.h"
00013 #include "ros/ros.h"
00014 #include "esc_ros/esc_ros.h"
00015
00016 int main(int argc, char **argv) {
00017
00018 ros::init(argc, argv, "sm_esc_1d");
00019 ros::NodeHandle n("~");
00020 double rho,alpha,k;
00021
00022 if (!n.getParam("rho", rho)){
00023 ROS_WARN("[sm_esc_1d]: Failed to get the parameter rho from the parameter server. Using the default value.");
00024 rho = 0;
00025 }
00026 if (!n.getParam("alpha", alpha)){
00027 ROS_WARN("[sm_esc_1d]: Failed to get the parameter alpha from the parameter server. Using the default value.");
00028 alpha = 0;
00029 }
00030 if (!n.getParam("k", k)){
00031 ROS_WARN("[sm_esc_1d]: Failed to get the parameter k from the parameter server. Using the default value.");
00032 k = 0;
00033 }
00034
00035 ESCROS esc_ros(&n);
00036 SMESC1D* sm_esc_1d = new SMESC1D(rho,k,alpha);
00037 esc_ros.init(sm_esc_1d);
00038 esc_ros.spin();
00039
00040 return 0;
00041 }