@@ -30,18 +30,19 @@ yaets::TraceSession session("strategy_3.log");
3030void 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
3737class SensorDriverNode : public rclcpp ::Node
3838{
3939public:
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
7879class ObstacleDetectorNode : public rclcpp ::Node
7980{
8081public:
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
116118private:
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
124126class LoggerNode : public rclcpp ::Node
125127{
126128public:
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
152155class BrakeActuatorNode : public rclcpp ::Node
153156{
154157public:
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