Skip to content

Commit c3bd601

Browse files
committed
Change pid params. Cascade control. Comment mimic stuff for now.
1 parent c11b195 commit c3bd601

File tree

4 files changed

+289
-112
lines changed

4 files changed

+289
-112
lines changed

ign_ros2_control/include/ign_ros2_control/ign_system.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727

2828
#include "ign_ros2_control_parameters.hpp"
2929

30+
#include "rclcpp/executors/single_threaded_executor.hpp"
31+
3032
namespace ign_ros2_control
3133
{
3234
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
@@ -97,6 +99,8 @@ class IgnitionSystem : public IgnitionSystemInterface
9799

98100
rclcpp::Node::SharedPtr param_node_;
99101
std::thread spin_thread_;
102+
std::atomic<bool> stop_spin_ = false;
103+
rclcpp::executors::SingleThreadedExecutor::SharedPtr exec_;
100104
};
101105

102106
} // namespace ign_ros2_control

ign_ros2_control/src/ign_ros2_control_parameters.yaml

Lines changed: 48 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -9,42 +9,82 @@ ign_ros2_control:
99
}
1010
gains:
1111
__map_joints:
12-
p: {
12+
p_pos: {
1313
type: double,
1414
default_value: 0.0,
1515
description: "Proportional gain for PID"
1616
}
17-
i: {
17+
i_pos: {
1818
type: double,
1919
default_value: 0.0,
2020
description: "Integral gain for PID"
2121
}
22-
d: {
22+
d_pos: {
2323
type: double,
2424
default_value: 0.0,
2525
description: "Derivative gain for PID"
2626
}
27-
iMax: {
27+
iMax_pos: {
2828
type: double,
2929
default_value: 0.0,
3030
description: "Integral positive clamp."
3131
}
32-
iMin: {
32+
iMin_pos: {
3333
type: double,
3434
default_value: 0.0,
3535
description: "Integral negative clamp."
3636
}
37-
cmdMax: {
37+
cmdMax_pos: {
3838
type: double,
3939
default_value: 0.0,
4040
description: "Maximum value for the PID command."
4141
}
42-
cmdMin: {
42+
cmdMin_pos: {
4343
type: double,
4444
default_value: 0.0,
4545
description: "Maximum value for the PID command."
4646
}
47-
cmdOffset: {
47+
cmdOffset_pos: {
48+
type: double,
49+
default_value: 0.0,
50+
description: "Offset value for the command which is added to the result of the PID controller."
51+
}
52+
p_vel: {
53+
type: double,
54+
default_value: 0.0,
55+
description: "Proportional gain for PID"
56+
}
57+
i_vel: {
58+
type: double,
59+
default_value: 0.0,
60+
description: "Integral gain for PID"
61+
}
62+
d_vel: {
63+
type: double,
64+
default_value: 0.0,
65+
description: "Derivative gain for PID"
66+
}
67+
iMax_vel: {
68+
type: double,
69+
default_value: 0.0,
70+
description: "Integral positive clamp."
71+
}
72+
iMin_vel: {
73+
type: double,
74+
default_value: 0.0,
75+
description: "Integral negative clamp."
76+
}
77+
cmdMax_vel: {
78+
type: double,
79+
default_value: 0.0,
80+
description: "Maximum value for the PID command."
81+
}
82+
cmdMin_vel: {
83+
type: double,
84+
default_value: 0.0,
85+
description: "Maximum value for the PID command."
86+
}
87+
cmdOffset_vel: {
4888
type: double,
4989
default_value: 0.0,
5090
description: "Offset value for the command which is added to the result of the PID controller."

0 commit comments

Comments
 (0)