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);
diagnostic_updater::DiagnosedPublisher< sensor_msgs::PointCloud2 > * diagnosticPub_
SickLDMRS(Manager *manager, boost::shared_ptr< diagnostic_updater::Updater > diagnostics)
dynamic_reconfigure::Server< SickLDMRSDriverConfig > dynamic_reconfigure_server_
void setData(BasicData &data)
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void validate_flexres_resolution(int &res)
void validate_config(SickLDMRSDriverConfig &conf)
boost::shared_ptr< diagnostic_updater::Updater > diagnostics_
std::string flexres_err_to_string(const UINT32 code) const
double expected_frequency_
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
void validate_flexres_start_angle(double &angle1, double &angle2)
void pubObjects(datatypes::ObjectList &objects)
ros::Publisher object_pub_
pcl::PointCloud< sick_ldmrs_msgs::SICK_LDMRS_Point > PointCloud
SickLDMRSDriverConfig config_