Go to the documentation of this file.
35 #ifndef SICK_MRS1000_PARSER_H_
36 #define SICK_MRS1000_PARSER_H_
50 virtual int parse_datagram(
char* datagram,
size_t datagram_length, SickTimConfig &config,
51 sensor_msgs::LaserScan &scan, sensor_msgs::PointCloud2& cloud);
float override_time_increment_
sensor_msgs::PointCloud2Iterator< float > y_iter
sensor_msgs::PointCloud2Iterator< float > z_iter
virtual ~SickMRS1000Parser()
void set_time_increment(float time)
float override_range_max_
sensor_msgs::PointCloud2Iterator< float > x_iter
void set_range_max(float max)
sensor_msgs::PointCloud2Modifier modifier_
virtual int parse_datagram(char *datagram, size_t datagram_length, SickTimConfig &config, sensor_msgs::LaserScan &scan, sensor_msgs::PointCloud2 &cloud)
sensor_msgs::PointCloud2 cloud_
sick_tim::SickTimConfig current_config_
float override_range_min_
void set_range_min(float min)
sick_tim
Author(s): Jochen Sprickerhof
, Martin Günther , Sebastian Pütz
autogenerated on Thu Nov 28 2024 03:03:33