SMACC2
Public Member Functions | Public Attributes | List of all members
sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData Class Reference

#include <cp_lidar_data.hpp>

Inheritance diagram for sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData:
Inheritance graph
Collaboration diagram for sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData:
Collaboration graph

Public Member Functions

void onInitialize () override
 
void MessageCallbackStoreDistanceToWall (const sensor_msgs::msg::LaserScan &scanmsg)
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

sensor_msgs::msg::LaserScan lastMessage_
 
float forwardObstacleDistance
 
const float SECURITY_DISTANCE = 1
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
virtual void onInitialize ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 29 of file cp_lidar_data.hpp.

Member Function Documentation

◆ MessageCallbackStoreDistanceToWall()

void sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData::MessageCallbackStoreDistanceToWall ( const sensor_msgs::msg::LaserScan &  scanmsg)
inline

Definition at line 45 of file cp_lidar_data.hpp.

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 }
rclcpp::Logger getLogger()
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), and SECURITY_DISTANCE.

Referenced by onInitialize().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData::onInitialize ( )
inlineoverridevirtual

Member Data Documentation

◆ forwardObstacleDistance

float sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData::forwardObstacleDistance

Definition at line 33 of file cp_lidar_data.hpp.

◆ lastMessage_

sensor_msgs::msg::LaserScan sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData::lastMessage_

Definition at line 32 of file cp_lidar_data.hpp.

◆ SECURITY_DISTANCE

const float sm_dance_bot_strikes_back::cl_lidar::CpLidarSensorData::SECURITY_DISTANCE = 1

Definition at line 35 of file cp_lidar_data.hpp.

Referenced by MessageCallbackStoreDistanceToWall().


The documentation for this class was generated from the following files: