Last change
on this file since 42 was
5,
checked in by wcaarls, 12 years ago
|
Imported extremum_seeking at revision 987
|
File size:
1.1 KB
|
Line | |
---|
1 | /* |
---|
2 | * node.cpp |
---|
3 | * |
---|
4 | * Created on: Jul 30, 2012 |
---|
5 | * Author: Berk Calli |
---|
6 | * Organization: Delft Biorobotics Lab., Delft University of Technology |
---|
7 | * Contact info: b.calli@tudelft.nl, web: www.dbl.tudelft.nl |
---|
8 | * |
---|
9 | * node for sliding mode extremum seeking control algorithm with perodic driving signal. |
---|
10 | */ |
---|
11 | |
---|
12 | #include "esc_sm/sm_esc_1d.h" |
---|
13 | #include "ros/ros.h" |
---|
14 | #include "esc_ros/esc_ros.h" |
---|
15 | |
---|
16 | int main(int argc, char **argv) { |
---|
17 | |
---|
18 | ros::init(argc, argv, "sm_esc_1d"); |
---|
19 | ros::NodeHandle n("~"); |
---|
20 | double rho,alpha,k; |
---|
21 | |
---|
22 | if (!n.getParam("rho", rho)){ |
---|
23 | ROS_WARN("[sm_esc_1d]: Failed to get the parameter rho from the parameter server. Using the default value."); |
---|
24 | rho = 0; |
---|
25 | } |
---|
26 | if (!n.getParam("alpha", alpha)){ |
---|
27 | ROS_WARN("[sm_esc_1d]: Failed to get the parameter alpha from the parameter server. Using the default value."); |
---|
28 | alpha = 0; |
---|
29 | } |
---|
30 | if (!n.getParam("k", k)){ |
---|
31 | ROS_WARN("[sm_esc_1d]: Failed to get the parameter k from the parameter server. Using the default value."); |
---|
32 | k = 0; |
---|
33 | } |
---|
34 | |
---|
35 | ESCROS esc_ros(&n); |
---|
36 | SMESC1D* sm_esc_1d = new SMESC1D(rho,k,alpha); |
---|
37 | esc_ros.init(sm_esc_1d); |
---|
38 | esc_ros.spin(); |
---|
39 | |
---|
40 | return 0; |
---|
41 | } |
---|
Note: See
TracBrowser
for help on using the repository browser.