Skip to content

Commit 9cb8fc9

Browse files
feat(controller_node): controller timeout is now dynamic param
1 parent 0831935 commit 9cb8fc9

File tree

2 files changed

+3
-1
lines changed

2 files changed

+3
-1
lines changed

cfg/Pid.cfg

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,4 +31,6 @@ gen.add("coupling_ang_long", bool_t, 0, "Enable coupling between angular and
3131

3232
gen.add("controller_debug_enabled", bool_t, 0, "Debug controller intermediate gains", False)
3333

34+
gen.add("controller_timeout", double_t, 0, "Timeout on setpoint input signal", 0.2, 0, 10)
35+
3436
exit(gen.generate(PACKAGE, "tracking_pid", "Pid"))

src/controller_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,7 @@ void reconfigure_callback(const tracking_pid::PidConfig& config)
147147
{
148148
pid_controller.configure(config);
149149
controller_debug_enabled = config.controller_debug_enabled;
150+
controller_timeout = config.controller_timeout;
150151
}
151152

152153
int main(int argc, char** argv)
@@ -166,7 +167,6 @@ int main(int argc, char** argv)
166167
node_priv.param<bool>("enabled_on_boot", enabled_on_boot, true);
167168
controller_enabled = enabled_on_boot;
168169
waiting_for_setpoint = true;
169-
node_priv.param<double>("controller_timeout", controller_timeout, 0.1);
170170

171171
// instantiate publishers & subscribers
172172
control_effort_pub = node.advertise<geometry_msgs::Twist>("move_base/cmd_vel", 1);

0 commit comments

Comments
 (0)