Skip to content

Commit 25f0122

Browse files
committed
Added LeadLag controller
1 parent dcdaa98 commit 25f0122

File tree

10 files changed

+1027
-3
lines changed

10 files changed

+1027
-3
lines changed

CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,14 @@ find_package(TinyXML REQUIRED)
1818
# Dynamics reconfigure
1919
generate_dynamic_reconfigure_options(
2020
cfg/Parameters.cfg
21+
cfg/LeadLag.cfg
2122
)
2223

2324
# Add services and generate them
2425
add_service_files(
2526
FILES
2627
SetPidGains.srv
28+
SetLeadLagGains.srv
2729
)
2830

2931
generate_messages(
@@ -52,6 +54,8 @@ include_directories(
5254
)
5355

5456
add_library(${PROJECT_NAME}
57+
src/lead_lag.cpp
58+
src/lead_lag_gains_setter.cpp
5559
src/pid.cpp
5660
src/pid_gains_setter.cpp
5761
src/sine_sweep.cpp
@@ -68,6 +72,9 @@ if(CATKIN_ENABLE_TESTING)
6872
catkin_add_gtest(pid_tests test/pid_tests.cpp)
6973
target_link_libraries(pid_tests ${catkin_LIBRARIES} ${PROJECT_NAME})
7074

75+
catkin_add_gtest(lead_lag_tests test/lead_lag_tests.cpp)
76+
target_link_libraries(lead_lag_tests ${catkin_LIBRARIES} ${PROJECT_NAME})
77+
7178
# add_executable(test_linear test/linear.cpp)
7279
endif()
7380

cfg/LeadLag.cfg

Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
#! /usr/bin/env python
2+
#*********************************************************************
3+
#* Software License Agreement (BSD License)
4+
#*
5+
#* Copyright (c) 2017, Open Source Robotics Foundation
6+
#* All rights reserved.
7+
#*
8+
#* Redistribution and use in source and binary forms, with or without
9+
#* modification, are permitted provided that the following conditions
10+
#* are met:
11+
#*
12+
#* * Redistributions of source code must retain the above copyright
13+
#* notice, this list of conditions and the following disclaimer.
14+
#* * Redistributions in binary form must reproduce the above
15+
#* copyright notice, this list of conditions and the following
16+
#* disclaimer in the documentation and/or other materials provided
17+
#* with the distribution.
18+
#* * Neither the name of the Open Source Robotics Foundation
19+
#* nor the names of its contributors may be
20+
#* used to endorse or promote products derived
21+
#* from this software without specific prior written permission.
22+
#*
23+
#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24+
#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25+
#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26+
#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27+
#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28+
#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29+
#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30+
#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31+
#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32+
#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33+
#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34+
#* POSSIBILITY OF SUCH DAMAGE.
35+
#*********************************************************************/
36+
37+
# Author: Aris Synodinos
38+
# Desc: Allows Lead Lag parameters, etc to be tuned in realtime using dynamic reconfigure
39+
40+
PACKAGE='control_toolbox'
41+
42+
def generate(gen):
43+
# Name Type Level Description Default Min Max
44+
gen.add( "k" , double_t, 1,"Gain.", 10.0 , -100000 , 100000)
45+
gen.add( "a" , double_t, 1,"Lead gain.", 0.1 , -1000 , 1000)
46+
gen.add( "b" , double_t, 1,"Lag gain.", 1.0 , -1000 , 1000)
47+
# PkgName #NodeName #Prefix for generated .h include file, e.g. ParametersConfig.py
48+
exit(gen.generate(PACKAGE, "control_toolbox", "LeadLag"))
49+
50+
# try catkin generator first
51+
try:
52+
from dynamic_reconfigure.parameter_generator_catkin import *
53+
gen = ParameterGenerator()
54+
generate(gen)
55+
# reason for catching IndexError
56+
# parameter_generator_catkin expects 4 arguments while rosbuild only passes in 2
57+
# not thrilled with this solution
58+
except IndexError:
59+
print 'ERROR', PACKAGE, 'Parameters.cfg failed using parameter_generator_catkin, using rosbuild instead'
60+
from dynamic_reconfigure.parameter_generator import *
61+
gen = ParameterGenerator()
62+
generate(gen)

doc.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,11 @@
44
55
The control_toolbox package contains the following C++ classes which may be useful when implementing controllers.
66
\li \ref control_toolbox::Pid "Pid" for implementing position/integral/derivative control loops.
7+
\li \ref control_toolbox::LeadLag "Lead Lag" for implementing lead or lag compensator control loops.
78
\li \ref control_toolbox::Ramp "Ramp Output"
89
\li \ref control_toolbox::SineSweep "Sine Sweep"
910
\li \ref control_toolbox::Dither "Dither" for giving white noise at specified amplitude
1011
\li \ref control_toolbox::PidGainsSetter "Pid gains setter" for advertising a service for automatically changing PID gains.
12+
\li \ref control_toolbox::LeadLagGainsSetter "Lead Lag gains setter" for advertising a service for automatically changing LeadLag gains.
1113
1214
**/

0 commit comments

Comments
 (0)