Go to the documentation of this file.
   37 #ifndef SICK_LDMRS800001S01_H_ 
   38 #define SICK_LDMRS800001S01_H_ 
   46 #include <sensor_msgs/PointCloud2.h> 
   52 #include <dynamic_reconfigure/server.h> 
   53 #include <sick_ldmrs_driver/SickLDMRSDriverConfig.h> 
   55 #include <sick_ldmrs/manager.hpp> 
   56 #include <sick_ldmrs/application/BasicApplication.hpp> 
   57 #include <sick_ldmrs/datatypes/Object.hpp> 
   63 typedef pcl::PointCloud<sick_ldmrs_msgs::SICK_LDMRS_Point> 
PointCloud;
 
   65 class SickLDMRS : 
public application::BasicApplication
 
   73   void update_config(SickLDMRSDriverConfig &new_config, uint32_t level = 0);
 
   74   void pubObjects(datatypes::ObjectList &objects);
 
  
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
diagnostic_updater::DiagnosedPublisher< sensor_msgs::PointCloud2 > * diagnosticPub_
void validate_flexres_resolution(int &res)
void pubObjects(datatypes::ObjectList &objects)
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
void setData(BasicData &data)
dynamic_reconfigure::Server< SickLDMRSDriverConfig > dynamic_reconfigure_server_
pcl::PointCloud< sick_ldmrs_msgs::SICK_LDMRS_Point > PointCloud
double expected_frequency_
void validate_config(SickLDMRSDriverConfig &conf)
SickLDMRS(Manager *manager, boost::shared_ptr< diagnostic_updater::Updater > diagnostics)
ros::Publisher object_pub_
boost::shared_ptr< diagnostic_updater::Updater > diagnostics_
SickLDMRSDriverConfig config_
std::string flexres_err_to_string(const UINT32 code) const
void validate_flexres_start_angle(double &angle1, double &angle2)
sick_ldmrs_driver
Author(s): Martin Günther 
, Jochen Sprickerhof 
autogenerated on Tue Oct 25 2022 02:14:18