SMACC2
cp_forward_obstacle_detector.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI 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/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
22#include <smacc2/smacc.hpp>
23
25{
26namespace cl_lidar
27{
28using namespace std::chrono_literals;
29
31{
32public:
33 sensor_msgs::msg::LaserScan lastScanMessage_;
34
35 const float SECURITY_DISTANCE = 0.4; // meters
36
37 void onInitialize() override
38 {
39 auto client_ =
41 owner_);
43 }
44
45 int modulo_Euclidean(int a, int b)
46 {
47 int m = a % b;
48 if (m < 0)
49 {
50 // m += (b < 0) ? -b : b; // avoid this form: -b is UB when b == INT_MIN
51 m = (b < 0) ? m - b : m + b;
52 }
53 return m;
54 }
55
56 float getForwardDistance(int raysWidthCount = 0)
57 {
58 //auto fwdist = scanmsg.ranges[scanmsg.ranges.size() / 2] /*meter*/;
59 auto fwdist = lastScanMessage_.ranges[0] /*meter*/;
60
61 std::stringstream ss;
62 //check rays around main ray
63 for (int i = 0; i < raysWidthCount; i++)
64 {
65 // int baseindex = 0;
66 int scanindex = (- raysWidthCount / 2 + i) % raysWidthCount;
67
68 if(scanindex < 0)
69 {
70 scanindex = lastScanMessage_.ranges.size() + scanindex;
71 }
72
73 float fwdist2 = lastScanMessage_.ranges[scanindex];
74
75 RCLCPP_INFO_STREAM(
76 getLogger(), "[" << getName() << "]"
77 << "range[" << scanindex << "] = " << fwdist2);
78
79 if (fwdist2 > 0.01 && fwdist2 < fwdist)
80 {
81 RCLCPP_INFO_STREAM(
82 getLogger(), "[" << getName() << "]"
83 << "updated range[0] = " << fwdist2);
84
85 fwdist = fwdist2;
86 }
87 }
88
89 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "]" << ss.str());
90
91 /*if the distance is infinity or nan, use max range distance*/
92 if (fwdist == std::numeric_limits<float>::infinity() || fwdist != fwdist)
93 {
94 fwdist = lastScanMessage_.range_max - SECURITY_DISTANCE /*meters*/;
95 RCLCPP_INFO_THROTTLE(
96 getLogger(), *(getNode()->get_clock()), 1000,
97 "[CpForwardObstacleDetector] Distance to forward obstacle is not a number, setting default value "
98 "to: %lf",
99 lastScanMessage_.range_max);
100 }
101 else
102 {
103 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] fwdist: " << fwdist);
104 fwdist = std::max(fwdist - SECURITY_DISTANCE, 0.0F);
105 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] fwdist: " << fwdist);
106 }
107
108 return fwdist;
109 }
110
111 void MessageCallbackStoreDistanceToWall(const sensor_msgs::msg::LaserScan & scanmsg)
112 {
113 this->lastScanMessage_ = scanmsg;
114 }
115};
116} // namespace cl_lidar
117} // namespace sm_dance_bot_warehouse_3
void MessageCallbackStoreDistanceToWall(const sensor_msgs::msg::LaserScan &scanmsg)
ISmaccClient * owner_
Definition: component.hpp:77
rclcpp::Logger getLogger()
virtual std::string getName() const
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)