SMACC2
cp_lidar_data.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
21#include <smacc2/smacc.hpp>
22
24{
25namespace cl_lidar
26{
27using namespace std::chrono_literals;
28
30{
31public:
32 sensor_msgs::msg::LaserScan lastMessage_;
34
35 const float SECURITY_DISTANCE = 1; // meters
36
37 void onInitialize() override
38 {
39 auto client_ =
41 owner_);
43 }
44
45 void MessageCallbackStoreDistanceToWall(const sensor_msgs::msg::LaserScan & scanmsg)
46 {
47 this->lastMessage_ = scanmsg;
48 //auto fwdist = scanmsg.ranges[scanmsg.ranges.size() / 2] /*meter*/;
49 auto fwdist = scanmsg.ranges[0] /*meter*/;
50
51 /*if the distance is infinity or nan, use max range distance*/
52 if (fwdist == std::numeric_limits<float>::infinity() || fwdist != fwdist)
53 {
54 this->forwardObstacleDistance = scanmsg.range_max - SECURITY_DISTANCE /*meters*/;
55 RCLCPP_INFO_THROTTLE(
56 getLogger(), *(getNode()->get_clock()), 1000,
57 "[CpLidarSensorData] Distance to forward obstacle is not a number, setting default value "
58 "to: %lf",
59 scanmsg.range_max);
60 }
61 else
62 {
63 this->forwardObstacleDistance = std::max(fwdist - SECURITY_DISTANCE, 0.0F);
64 }
65 }
66};
67} // namespace cl_lidar
68} // namespace sm_dance_bot_strikes_back
void MessageCallbackStoreDistanceToWall(const sensor_msgs::msg::LaserScan &scanmsg)
ISmaccClient * owner_
Definition: component.hpp:77
rclcpp::Logger getLogger()
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)