File tree Expand file tree Collapse file tree 4 files changed +289
-112
lines changed
ign_ros2_control_demos/urdf Expand file tree Collapse file tree 4 files changed +289
-112
lines changed Original file line number Diff line number Diff line change 27
27
28
28
#include " ign_ros2_control_parameters.hpp"
29
29
30
+ #include " rclcpp/executors/single_threaded_executor.hpp"
31
+
30
32
namespace ign_ros2_control
31
33
{
32
34
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
@@ -97,6 +99,8 @@ class IgnitionSystem : public IgnitionSystemInterface
97
99
98
100
rclcpp::Node::SharedPtr param_node_;
99
101
std::thread spin_thread_;
102
+ std::atomic<bool > stop_spin_ = false ;
103
+ rclcpp::executors::SingleThreadedExecutor::SharedPtr exec_;
100
104
};
101
105
102
106
} // namespace ign_ros2_control
Original file line number Diff line number Diff line change @@ -9,42 +9,82 @@ ign_ros2_control:
9
9
}
10
10
gains :
11
11
__map_joints :
12
- p : {
12
+ p_pos : {
13
13
type : double,
14
14
default_value : 0.0,
15
15
description : " Proportional gain for PID"
16
16
}
17
- i : {
17
+ i_pos : {
18
18
type : double,
19
19
default_value : 0.0,
20
20
description : " Integral gain for PID"
21
21
}
22
- d : {
22
+ d_pos : {
23
23
type : double,
24
24
default_value : 0.0,
25
25
description : " Derivative gain for PID"
26
26
}
27
- iMax : {
27
+ iMax_pos : {
28
28
type : double,
29
29
default_value : 0.0,
30
30
description : " Integral positive clamp."
31
31
}
32
- iMin : {
32
+ iMin_pos : {
33
33
type : double,
34
34
default_value : 0.0,
35
35
description : " Integral negative clamp."
36
36
}
37
- cmdMax : {
37
+ cmdMax_pos : {
38
38
type : double,
39
39
default_value : 0.0,
40
40
description : " Maximum value for the PID command."
41
41
}
42
- cmdMin : {
42
+ cmdMin_pos : {
43
43
type : double,
44
44
default_value : 0.0,
45
45
description : " Maximum value for the PID command."
46
46
}
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 : {
48
88
type : double,
49
89
default_value : 0.0,
50
90
description : " Offset value for the command which is added to the result of the PID controller."
You can’t perform that action at this time.
0 commit comments