1 #ifndef ORG_EEROS_CONTROL_ROSSUBSCRIBER_LASERSCAN_HPP 2 #define ORG_EEROS_CONTROL_ROSSUBSCRIBER_LASERSCAN_HPP 8 #include <sensor_msgs/LaserScan.h> 14 template <
typename TRangesOutput,
typename TIntensitiesOutput >
26 auto time = msg.header.stamp.toNSec();
45 std::vector<double> rangesTmp( msg.ranges.begin(), msg.ranges.end() );
51 std::vector<double> intensitiesTmp( msg.intensities.begin(), msg.intensities.end() );
87 #endif // ORG_EEROS_CONTROL_ROSSUBSCRIBER_LASERSCAN_HPP Output< double > range_minOutput
Definition: RosSubscriberLaserScan.hpp:76
Output< TIntensitiesOutput > & getIntensitiesOutput()
Definition: RosSubscriberLaserScan.hpp:66
Output< double > range_maxOutput
Definition: RosSubscriberLaserScan.hpp:77
Output< double > & getRange_maxOutput()
Definition: RosSubscriberLaserScan.hpp:63
virtual Signal< T > & getSignal()
Definition: Output.hpp:16
bool callNewest
Definition: RosSubscriber.hpp:52
Output< TRangesOutput > rangesOutput
Definition: RosSubscriberLaserScan.hpp:80
Output< double > angle_maxOutput
Definition: RosSubscriberLaserScan.hpp:72
Output< double > & getAngle_minOutput()
Definition: RosSubscriberLaserScan.hpp:57
Output< TRangesOutput > & getRangesOutput()
Definition: RosSubscriberLaserScan.hpp:65
Definition: Config.hpp:14
RosSubscriberLaserScan(const std::string &topic, const uint32_t queueSize=1000, const bool callNewest=false)
Definition: RosSubscriberLaserScan.hpp:20
Output< double > time_incrementOutput
Definition: RosSubscriberLaserScan.hpp:74
virtual void setValue(T newValue)
Definition: Signal.hpp:53
Type
Definition: HALFeatures.hpp:14
const std::string & topic
Definition: RosSubscriber.hpp:51
Output< double > & getAngle_maxOutput()
Definition: RosSubscriberLaserScan.hpp:58
TIntensitiesOutput intensitiesValue
Definition: RosSubscriberLaserScan.hpp:81
virtual void setTimestamp(timestamp_t newTimestamp)
Definition: Signal.hpp:66
Definition: RosSubscriber.hpp:14
Output< TIntensitiesOutput > intensitiesOutput
Definition: RosSubscriberLaserScan.hpp:82
Output< double > & getScan_timeOutput()
Definition: RosSubscriberLaserScan.hpp:61
void rosCallbackFct(const TRosMsg &msg)
Definition: RosSubscriberLaserScan.hpp:23
Output< double > angle_incrementOutput
Definition: RosSubscriberLaserScan.hpp:73
Definition: RosSubscriberLaserScan.hpp:16
Output< double > & getRange_minOutput()
Definition: RosSubscriberLaserScan.hpp:62
TRangesOutput rangesValue
Definition: RosSubscriberLaserScan.hpp:79
Output< double > scan_timeOutput
Definition: RosSubscriberLaserScan.hpp:75
Output< double > & getTime_incrementOutput()
Definition: RosSubscriberLaserScan.hpp:60
Output< double > angle_minOutput
Definition: RosSubscriberLaserScan.hpp:71
Output< double > & getAngle_incrementOutput()
Definition: RosSubscriberLaserScan.hpp:59