Skip to content

Commit abf107f

Browse files
author
Jackie Kay
committed
Minimal implementation of pendulum control demo
1 parent 005bc4c commit abf107f

File tree

11 files changed

+813
-0
lines changed

11 files changed

+813
-0
lines changed

pendulum_control/CMakeLists.txt

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
3+
project(pendulum_control)
4+
5+
if(APPLE OR WIN32)
6+
message(STATUS "The pendulum_control demo is only supported on Linux. Package will not be built.")
7+
return()
8+
endif()
9+
10+
find_package(ament_cmake REQUIRED)
11+
12+
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall -Wextra")
13+
14+
find_package(rclcpp REQUIRED)
15+
find_package(rmw_implementation REQUIRED)
16+
find_package(pendulum_msgs REQUIRED)
17+
find_package(rttest)
18+
19+
if(NOT rttest_FOUND)
20+
message(STATUS "rttest not found. pendulum_control package will not be built.")
21+
return()
22+
endif()
23+
24+
add_executable_for_each_rmw_implementations(pendulum_demo
25+
src/pendulum_demo.cpp
26+
TARGET_DEPENDENCIES
27+
"rclcpp"
28+
"pendulum_msgs"
29+
"rttest"
30+
INSTALL
31+
)
32+
33+
if(AMENT_ENABLE_TESTING)
34+
find_package(ament_lint_auto REQUIRED)
35+
ament_lint_auto_find_test_dependencies()
36+
endif()
37+
38+
ament_package()

pendulum_control/README.md

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
## Build instructions
2+
3+
If you haven't already, clone [rttest](https://github.com/jacquelinekay/rttest) into your ament workspace.
4+
5+
Build:
6+
7+
```
8+
./src/ament/ament_tools/scripts/ament.py build --build-tests --symlink-install --only pendulum_control
9+
```
10+
11+
Run:
12+
13+
```
14+
. install/setup.bash
15+
./build/pendulum_control/pendulum_demo[__rmw_opensplice/__rmw_connext]
16+
```
17+
The demo should work with both middleware implementations.
18+
19+
A few command line arguments related to real-time performance profiling are provided by rttest.
20+
See https://github.com/ros2/rttest/blob/master/README.md for more information.
21+
22+
## Running with real-time performance
23+
24+
The demo will print out its performance statistics continuously and at the end of the program.
25+
26+
Example final output:
27+
```
28+
rttest statistics:
29+
- Minor pagefaults: 0
30+
- Major pagefaults: 0
31+
Latency (time after deadline was missed):
32+
- Min: 2414 ns
33+
- Max: 45949 ns
34+
- Mean: 8712.12 ns
35+
- Standard deviation: 1438.74
36+
```
37+
38+
Ideally you want to see 0 minor or major pagefaults and an average latency of less than 30,000 nanosceonds
39+
(3% of the 1 millisecond update period).
40+
41+
If you see pagefaults, you may not have permission to lock memory via `mlockall`.
42+
You can run the program as sudo, or you can adjust the system limits for memory locking.
43+
44+
Add to `/etc/security/limits.conf`:
45+
```
46+
<user> - memlock <limit in kB>
47+
```
48+
49+
A limit of `-1` is unlimited.
50+
If you choose this, you may need to accompany it with `ulimit -l unlimited` after editing the file.
51+
52+
After saving the file, log out and log back in.
53+
54+
If you see a high mean latency in the results, you may need to adjust the maximum priority for processes.
55+
56+
Add to `/etc/security/limits.conf`:
57+
```
58+
<user> - rtprio <maximum priority>
59+
```
60+
61+
The range of the priority is 0-99.
62+
However, do NOT set the limit to 99 because then your processes could interfere with important system processes that run at the top priority (e.g. watchdog).
63+
This demo will attempt to run the control loop at priority 98.
64+
65+
With these settings you can get decent performance even if you don't have the RT_PREEMPT kernel installed, but you will likely see an unacceptably large maximum latency and periodic latency spikes.

pendulum_control/package.xml

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
<?xml version="1.0"?>
2+
<package format="2">
3+
<name>pendulum_control</name>
4+
<version>0.0.0</version>
5+
<description>Demonstrates ROS 2's realtime capabilities with a simulated inverted pendulum.</description>
6+
<maintainer email="[email protected]">Jackie Kay</maintainer>
7+
<license>Apache License 2.0</license>
8+
9+
<buildtool_depend>ament_cmake</buildtool_depend>
10+
11+
<build_depend>rclcpp</build_depend>
12+
<build_depend>rmw_implementation</build_depend>
13+
<build_depend>pendulum_msgs</build_depend>
14+
<build_depend>rttest</build_depend>
15+
16+
<exec_depend>rclcpp</exec_depend>
17+
<exec_depend>rmw_implementation</exec_depend>
18+
<exec_depend>pendulum_msgs</exec_depend>
19+
<exec_depend>rttest</exec_depend>
20+
21+
<test_depend>ament_lint_auto</test_depend>
22+
<test_depend>ament_lint_common</test_depend>
23+
24+
<export>
25+
<build_type>ament_cmake</build_type>
26+
</export>
27+
</package>
Lines changed: 136 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,136 @@
1+
// Copyright 2015 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_
16+
#define PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_
17+
18+
#include <chrono>
19+
20+
#include <pendulum_msgs/msg/joint_command.hpp>
21+
#include <pendulum_msgs/msg/joint_state.hpp>
22+
23+
#ifndef PI
24+
#define PI 3.14159265359
25+
#endif
26+
27+
namespace pendulum_control
28+
{
29+
30+
struct PIDProperties
31+
{
32+
// Properties of a PID controller
33+
double p = 1;
34+
double i = 0;
35+
double d = 0;
36+
double command = PI / 2;
37+
};
38+
39+
class PendulumController
40+
{
41+
public:
42+
PendulumController(std::chrono::nanoseconds period, PIDProperties pid)
43+
: publish_period_(period), pid_(pid),
44+
command_message_(std::make_shared<pendulum_msgs::msg::JointCommand>()),
45+
message_ready_(false)
46+
{
47+
command_message_->position = pid_.command;
48+
dt_ = publish_period_.count() / (1000.0 * 1000.0 * 1000.0);
49+
if (isnan(dt_) || dt_ == 0) {
50+
throw std::runtime_error("Invalid dt_ calculated in PendulumController constructor");
51+
}
52+
}
53+
54+
// Calculate new command based on new sensor state and PID controller properties
55+
void on_sensor_message(const pendulum_msgs::msg::JointState::SharedPtr msg)
56+
{
57+
++messages_received;
58+
59+
if (isnan(msg->position)) {
60+
throw std::runtime_error("Sensor value was NaN in on_sensor_message callback");
61+
}
62+
double error = pid_.command - msg->position;
63+
double p_gain = pid_.p * error;
64+
i_gain_ = pid_.i * (i_gain_ + error * dt_);
65+
double d_gain = pid_.d * (error - last_error_) / dt_;
66+
last_error_ = error;
67+
68+
// TODO consider filtering the PID output
69+
command_message_->position = msg->position + p_gain + i_gain_ + d_gain;
70+
// limits
71+
if (command_message_->position > PI) {
72+
command_message_->position = PI;
73+
} else if (command_message_->position < 0) {
74+
command_message_->position = 0;
75+
}
76+
77+
if (isnan(command_message_->position)) {
78+
throw std::runtime_error("Resulting command was NaN in on_sensor_message callback");
79+
}
80+
message_ready_ = true;
81+
}
82+
83+
const pendulum_msgs::msg::JointCommand::SharedPtr get_next_command_message()
84+
{
85+
return command_message_;
86+
}
87+
88+
bool next_message_ready() const
89+
{
90+
return message_ready_;
91+
}
92+
93+
std::chrono::nanoseconds get_publish_period() const
94+
{
95+
return publish_period_;
96+
}
97+
98+
void set_pid_properties(const PIDProperties & properties)
99+
{
100+
pid_ = properties;
101+
}
102+
103+
const PIDProperties & get_pid_properties() const
104+
{
105+
return pid_;
106+
}
107+
108+
void set_command(double command)
109+
{
110+
pid_.command = command;
111+
}
112+
113+
double get_command() const
114+
{
115+
return pid_.command;
116+
}
117+
118+
// gather statistics
119+
size_t messages_received = 0;
120+
121+
private:
122+
// controller should publish less frequently than the motor
123+
std::chrono::nanoseconds publish_period_;
124+
PIDProperties pid_;
125+
pendulum_msgs::msg::JointCommand::SharedPtr command_message_;
126+
bool message_ready_;
127+
128+
// state for PID controller
129+
double last_error_ = 0;
130+
double i_gain_ = 0;
131+
double dt_;
132+
};
133+
134+
} /* namespace pendulum_demo */
135+
136+
#endif /* PENDULUM_DEMO_PENDULUM_CONTROLLER_HPP_ */

0 commit comments

Comments
 (0)