Skip to content

Commit 1252158

Browse files
committed
Kilted version
Signed-off-by: Francisco Martín Rico <[email protected]>
1 parent ceadd83 commit 1252158

File tree

8 files changed

+103
-46
lines changed

8 files changed

+103
-46
lines changed
Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
name: kilted-devel
2+
3+
on:
4+
pull_request:
5+
branches:
6+
- kilted-devel
7+
push:
8+
branches:
9+
- kilted-devel
10+
11+
12+
jobs:
13+
build-and-test:
14+
runs-on: ${{ matrix.os }}
15+
strategy:
16+
matrix:
17+
os: [ubuntu-24.04]
18+
fail-fast: false
19+
steps:
20+
- name: Install popf deps
21+
run: sudo apt-get install libfl-dev
22+
- uses: actions/checkout@v2
23+
- name: Setup ROS 2
24+
uses: ros-tooling/[email protected]
25+
with:
26+
required-ros-distributions: kilted
27+
- name: build and test
28+
uses: ros-tooling/[email protected]
29+
with:
30+
package-name: br2_basics br2_bt_bumpgo br2_bt_patrolling br2_fsm_bumpgo_cpp br2_fsm_bumpgo_py br2_navigation br2_tf2_detector br2_tiago br2_tracking br2_tracking_msgs br2_vff_avoidance br2_deep_ros
31+
target-ros2-distro: kilted
32+
vcs-repo-file-url: ${GITHUB_WORKSPACE}/third_parties.repos
33+
colcon-defaults: |
34+
{
35+
"test": {
36+
"parallel-workers" : 1
37+
}
38+
}

br2_deep_ros/src/executors.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,8 @@ yaets::TraceSession session("session1.log");
2828
class ProducerNode : public rclcpp::Node
2929
{
3030
public:
31-
ProducerNode() : Node("producer_node")
31+
ProducerNode()
32+
: Node("producer_node")
3233
{
3334
pub_1_ = create_publisher<std_msgs::msg::Int32>("topic_1", 100);
3435
pub_2_ = create_publisher<std_msgs::msg::Int32>("topic_2", 100);
@@ -52,13 +53,14 @@ class ProducerNode : public rclcpp::Node
5253
class ConsumerNode : public rclcpp::Node
5354
{
5455
public:
55-
ConsumerNode() : Node("consumer_node")
56+
ConsumerNode()
57+
: Node("consumer_node")
5658
{
5759
sub_2_ = create_subscription<std_msgs::msg::Int32>(
5860
"topic_2", 100, std::bind(&ConsumerNode::cb_2, this, _1));
5961
sub_1_ = create_subscription<std_msgs::msg::Int32>(
6062
"topic_1", 100, std::bind(&ConsumerNode::cb_1, this, _1));
61-
63+
6264
timer_ = create_wall_timer(10ms, std::bind(&ConsumerNode::timer_cb, this));
6365
}
6466

@@ -86,7 +88,7 @@ class ConsumerNode : public rclcpp::Node
8688
void waste_time(const rclcpp::Duration & duration)
8789
{
8890
auto start = now();
89-
while (now() - start < duration);
91+
while (now() - start < duration) {}
9092
}
9193

9294
private:

br2_deep_ros/src/executors_cbg.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,8 @@ yaets::TraceSession session("session1.log");
2828
class ProducerNode : public rclcpp::Node
2929
{
3030
public:
31-
ProducerNode() : Node("producer_node")
31+
ProducerNode()
32+
: Node("producer_node")
3233
{
3334
pub_1_ = create_publisher<std_msgs::msg::Int32>("topic_1", 100);
3435
pub_2_ = create_publisher<std_msgs::msg::Int32>("topic_2", 100);
@@ -52,7 +53,8 @@ class ProducerNode : public rclcpp::Node
5253
class ConsumerNode : public rclcpp::Node
5354
{
5455
public:
55-
ConsumerNode() : Node("consumer_node")
56+
ConsumerNode()
57+
: Node("consumer_node")
5658
{
5759
custom_cb_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
5860

@@ -63,7 +65,7 @@ class ConsumerNode : public rclcpp::Node
6365
"topic_2", 100, std::bind(&ConsumerNode::cb_2, this, _1), options);
6466
sub_1_ = create_subscription<std_msgs::msg::Int32>(
6567
"topic_1", 100, std::bind(&ConsumerNode::cb_1, this, _1), options);
66-
68+
6769
timer_ = create_wall_timer(10ms, std::bind(&ConsumerNode::timer_cb, this));
6870
}
6971

@@ -91,7 +93,7 @@ class ConsumerNode : public rclcpp::Node
9193
void waste_time(const rclcpp::Duration & duration)
9294
{
9395
auto start = now();
94-
while (now() - start < duration);
96+
while (now() - start < duration) {}
9597
}
9698

9799
private:
@@ -108,7 +110,7 @@ int main(int argc, char * argv[])
108110
auto node_pub = std::make_shared<ProducerNode>();
109111
auto node_sub1 = std::make_shared<ConsumerNode>();
110112

111-
//rclcpp::executors::SingleThreadedExecutor executor;
113+
// rclcpp::executors::SingleThreadedExecutor executor;
112114
rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(), 8);
113115

114116
executor.add_node(node_pub);

br2_deep_ros/src/executors_cbg_reentrant.cpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,8 @@ yaets::TraceSession session("session1.log");
2828
class ProducerNode : public rclcpp::Node
2929
{
3030
public:
31-
ProducerNode() : Node("producer_node")
31+
ProducerNode()
32+
: Node("producer_node")
3233
{
3334
pub_1_ = create_publisher<std_msgs::msg::Int32>("topic_1", 100);
3435
pub_2_ = create_publisher<std_msgs::msg::Int32>("topic_2", 100);
@@ -52,16 +53,19 @@ class ProducerNode : public rclcpp::Node
5253
class ConsumerNode : public rclcpp::Node
5354
{
5455
public:
55-
ConsumerNode() : Node("consumer_node")
56+
ConsumerNode()
57+
: Node("consumer_node")
5658
{
5759
custom_cb_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant);
5860

5961
rclcpp::SubscriptionOptions options;
6062
options.callback_group = custom_cb_;
6163

62-
sub_2_ = create_subscription<std_msgs::msg::Int32>("topic_2", 100, std::bind(&ConsumerNode::cb_2, this, _1), options);
63-
sub_1_ = create_subscription<std_msgs::msg::Int32>("topic_1", 100, std::bind(&ConsumerNode::cb_1, this, _1), options);
64-
64+
sub_2_ = create_subscription<std_msgs::msg::Int32>("topic_2", 100,
65+
std::bind(&ConsumerNode::cb_2, this, _1), options);
66+
sub_1_ = create_subscription<std_msgs::msg::Int32>("topic_1", 100,
67+
std::bind(&ConsumerNode::cb_1, this, _1), options);
68+
6569
timer_ = create_wall_timer(10ms, std::bind(&ConsumerNode::timer_cb, this), custom_cb_);
6670
}
6771

@@ -91,7 +95,7 @@ class ConsumerNode : public rclcpp::Node
9195
void waste_time(const rclcpp::Duration & duration)
9296
{
9397
auto start = now();
94-
while (now() - start < duration);
98+
while (now() - start < duration) {}
9599
}
96100

97101
private:
@@ -109,7 +113,7 @@ int main(int argc, char * argv[])
109113
auto node_pub = std::make_shared<ProducerNode>();
110114
auto node_sub1 = std::make_shared<ConsumerNode>();
111115

112-
//rclcpp::executors::SingleThreadedExecutor executor;
116+
// rclcpp::executors::SingleThreadedExecutor executor;
113117
rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(), 8);
114118

115119
executor.add_node(node_pub);

br2_deep_ros/src/strategy_1.cpp

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,14 @@ yaets::TraceSession session("strategy_1.log");
2929
void waste_time(rclcpp::Node::SharedPtr node, const rclcpp::Duration & duration)
3030
{
3131
auto start = node->now();
32-
while (node->now() - start < duration);
32+
while (node->now() - start < duration) {}
3333
}
3434

3535
class ProducerNode : public rclcpp::Node
3636
{
3737
public:
38-
ProducerNode() : Node("producer_node")
38+
ProducerNode()
39+
: Node("producer_node")
3940
{
4041
pub_ = create_publisher<std_msgs::msg::Int32>("int_topic", 100);
4142
timer_ = create_wall_timer(10ms, std::bind(&ProducerNode::timer_callback, this));
@@ -60,11 +61,12 @@ class ProducerNode : public rclcpp::Node
6061
class ConsumerNode : public rclcpp::Node
6162
{
6263
public:
63-
ConsumerNode() : Node("consumer_node")
64+
ConsumerNode()
65+
: Node("consumer_node")
6466
{
6567
sub_ = create_subscription<std_msgs::msg::Int32>(
6668
"int_topic", 100, std::bind(&ConsumerNode::cb, this, _1));
67-
69+
6870
timer_ = create_wall_timer(10ms, std::bind(&ConsumerNode::timer_cb, this));
6971
}
7072

@@ -91,11 +93,12 @@ class ConsumerNode : public rclcpp::Node
9193
class LoggerNode : public rclcpp::Node
9294
{
9395
public:
94-
LoggerNode() : Node("logger_node")
96+
LoggerNode()
97+
: Node("logger_node")
9598
{
9699
sub_ = create_subscription<std_msgs::msg::Int32>(
97100
"int_topic", 100, std::bind(&LoggerNode::cb, this, _1));
98-
101+
99102
timer_ = create_wall_timer(10ms, std::bind(&LoggerNode::timer_cb, this));
100103
}
101104

@@ -139,11 +142,11 @@ int main(int argc, char * argv[])
139142
[&]() {
140143
sched_param sch;
141144
sch.sched_priority = 90;
142-
145+
143146
if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
144147
throw std::runtime_error{std::string("failed to set scheduler: ") + std::strerror(errno)};
145148
}
146-
149+
147150
rt_executor.spin();
148151
});
149152

br2_deep_ros/src/strategy_2.cpp

Lines changed: 10 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,14 @@ yaets::TraceSession session("strategy_2.log");
2929
void waste_time(rclcpp::Node::SharedPtr node, const rclcpp::Duration & duration)
3030
{
3131
auto start = node->now();
32-
while (node->now() - start < duration);
32+
while (node->now() - start < duration) {}
3333
}
3434

3535
class ProducerNode : public rclcpp::Node
3636
{
3737
public:
38-
ProducerNode() : Node("producer_node")
38+
ProducerNode()
39+
: Node("producer_node")
3940
{
4041
pub_ = create_publisher<std_msgs::msg::Int32>("int_topic", 100);
4142
timer_ = create_wall_timer(10ms, std::bind(&ProducerNode::timer_callback, this));
@@ -60,7 +61,8 @@ class ProducerNode : public rclcpp::Node
6061
class ConsumerNode : public rclcpp::Node
6162
{
6263
public:
63-
ConsumerNode() : Node("consumer_node")
64+
ConsumerNode()
65+
: Node("consumer_node")
6466
{
6567
rt_callback_group_ = this->create_callback_group(
6668
rclcpp::CallbackGroupType::MutuallyExclusive, false);
@@ -102,11 +104,12 @@ class ConsumerNode : public rclcpp::Node
102104
class LoggerNode : public rclcpp::Node
103105
{
104106
public:
105-
LoggerNode() : Node("logger_node")
107+
LoggerNode()
108+
: Node("logger_node")
106109
{
107110
sub_ = create_subscription<std_msgs::msg::Int32>(
108111
"int_topic", 100, std::bind(&LoggerNode::cb, this, _1));
109-
112+
110113
timer_ = create_wall_timer(10ms, std::bind(&LoggerNode::timer_cb, this));
111114
}
112115

@@ -154,11 +157,11 @@ int main(int argc, char * argv[])
154157
[&]() {
155158
sched_param sch;
156159
sch.sched_priority = 90;
157-
160+
158161
if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
159162
throw std::runtime_error{std::string("failed to set scheduler: ") + std::strerror(errno)};
160163
}
161-
164+
162165
rt_executor.spin();
163166
});
164167

br2_deep_ros/src/strategy_3.cpp

Lines changed: 19 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -30,18 +30,19 @@ yaets::TraceSession session("strategy_3.log");
3030
void waste_time(rclcpp::Node::SharedPtr node, const rclcpp::Duration & duration)
3131
{
3232
auto start = node->now();
33-
while (node->now() - start < duration);
33+
while (node->now() - start < duration) {}
3434
}
3535

3636

3737
class SensorDriverNode : public rclcpp::Node
3838
{
3939
public:
40-
SensorDriverNode() : Node("sensor_driver")
40+
SensorDriverNode()
41+
: Node("sensor_driver")
4142
{
4243
rt_callback_group_ = create_callback_group(
4344
rclcpp::CallbackGroupType::MutuallyExclusive, false);
44-
45+
4546
pub_ = create_publisher<sensor_msgs::msg::Image>("image", 100);
4647
timer_scan_ = create_wall_timer(
4748
10ms, std::bind(&SensorDriverNode::produce_data, this), rt_callback_group_);
@@ -78,14 +79,15 @@ class SensorDriverNode : public rclcpp::Node
7879
class ObstacleDetectorNode : public rclcpp::Node
7980
{
8081
public:
81-
ObstacleDetectorNode() : Node("obstacle_detector")
82+
ObstacleDetectorNode()
83+
: Node("obstacle_detector")
8284
{
8385
rt_callback_group_ = create_callback_group(
8486
rclcpp::CallbackGroupType::MutuallyExclusive, false);
8587

8688
rclcpp::SubscriptionOptions sub_options;
8789
sub_options.callback_group = rt_callback_group_;
88-
90+
8991
sub_ = create_subscription<sensor_msgs::msg::Image>(
9092
"image", 100,
9193
std::bind(&ObstacleDetectorNode::detect_obstacle, this, _1),
@@ -97,7 +99,7 @@ class ObstacleDetectorNode : public rclcpp::Node
9799
void detect_obstacle(const sensor_msgs::msg::Image::SharedPtr msg)
98100
{
99101
waste_time(shared_from_this(), 5ms);
100-
102+
101103
vision_msgs::msg::Detection3D detection_msg;
102104
pub_->publish(detection_msg);
103105
}
@@ -115,7 +117,7 @@ class ObstacleDetectorNode : public rclcpp::Node
115117

116118
private:
117119
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr sub_;
118-
rclcpp::Publisher< vision_msgs::msg::Detection3D>::SharedPtr pub_;
120+
rclcpp::Publisher<vision_msgs::msg::Detection3D>::SharedPtr pub_;
119121
rclcpp::TimerBase::SharedPtr timer_state_;
120122
rclcpp::CallbackGroup::SharedPtr rt_callback_group_;
121123
};
@@ -124,11 +126,12 @@ class ObstacleDetectorNode : public rclcpp::Node
124126
class LoggerNode : public rclcpp::Node
125127
{
126128
public:
127-
LoggerNode() : Node("logger_node")
129+
LoggerNode()
130+
: Node("logger_node")
128131
{
129132
sub_ = create_subscription<sensor_msgs::msg::Image>(
130133
"image", 100, std::bind(&LoggerNode::cb, this, _1));
131-
134+
132135
timer_state_ = create_wall_timer(10ms, std::bind(&LoggerNode::print_state, this));
133136
}
134137

@@ -152,14 +155,15 @@ class LoggerNode : public rclcpp::Node
152155
class BrakeActuatorNode : public rclcpp::Node
153156
{
154157
public:
155-
BrakeActuatorNode() : Node("brake_actuator")
158+
BrakeActuatorNode()
159+
: Node("brake_actuator")
156160
{
157161
rt_callback_group_ = create_callback_group(
158162
rclcpp::CallbackGroupType::MutuallyExclusive, false);
159163

160164
rclcpp::SubscriptionOptions sub_options;
161165
sub_options.callback_group = rt_callback_group_;
162-
166+
163167
sub_ = create_subscription<vision_msgs::msg::Detection3D>(
164168
"obstacles", 100,
165169
std::bind(&BrakeActuatorNode::react_obstacle, this, _1),
@@ -224,11 +228,12 @@ int main(int argc, char * argv[])
224228
[&]() {
225229
// sched_param sch;
226230
// sch.sched_priority = 90;
227-
//
231+
//
228232
// if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) {
229-
// throw std::runtime_error{std::string("failed to set scheduler: ") + std::strerror(errno)};
233+
// throw std::runtime_error{std::string("failed to set scheduler: ") +
234+
// std::strerror(errno)};
230235
// }
231-
236+
232237
rt_executor.spin();
233238
});
234239

0 commit comments

Comments
 (0)