00001 /* 00002 * Copyright (C) 2015, DFKI GmbH 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of DFKI GmbH nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 * Created on: 23.11.2015 00030 * 00031 * Authors: 00032 * Martin Günther <martin.guenther@dfki.de> 00033 * Jochen Sprickerhof <jochen@sprickerhof.de> 00034 * 00035 */ 00036 00037 #ifndef SICK_LDMRS800001S01_H_ 00038 #define SICK_LDMRS800001S01_H_ 00039 00040 #include <stdio.h> 00041 #include <stdlib.h> 00042 #include <string.h> 00043 #include <vector> 00044 00045 #include <ros/ros.h> 00046 #include <sensor_msgs/PointCloud2.h> 00047 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h> 00048 00049 #include <diagnostic_updater/diagnostic_updater.h> 00050 #include <diagnostic_updater/publisher.h> 00051 00052 #include <dynamic_reconfigure/server.h> 00053 #include <sick_ldmrs_driver/SickLDMRSDriverConfig.h> 00054 00055 #include <sick_ldmrs/manager.hpp> 00056 #include <sick_ldmrs/application/BasicApplication.hpp> 00057 #include <sick_ldmrs/datatypes/Object.hpp> 00058 00059 00060 namespace sick_ldmrs_driver 00061 { 00062 00063 typedef pcl::PointCloud<sick_ldmrs_msgs::SICK_LDMRS_Point> PointCloud; 00064 00065 class SickLDMRS : public application::BasicApplication 00066 { 00067 public: 00068 SickLDMRS(Manager* manager, boost::shared_ptr<diagnostic_updater::Updater> diagnostics); 00069 virtual ~SickLDMRS(); 00070 void init(); 00071 void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat); 00072 void validate_config(SickLDMRSDriverConfig &conf); 00073 void update_config(SickLDMRSDriverConfig &new_config, uint32_t level = 0); 00074 void pubObjects(datatypes::ObjectList &objects); 00075 00076 protected: 00077 boost::shared_ptr<diagnostic_updater::Updater> diagnostics_; 00078 void setData(BasicData& data); // Callback for new data from the manager (scans etc.) 00079 void validate_flexres_resolution(int &res); 00080 void validate_flexres_start_angle(double &angle1, double &angle2); 00081 bool isUpsideDown(); 00082 void printFlexResError(); 00083 std::string flexres_err_to_string(const UINT32 code) const; 00084 00085 private: 00086 // ROS 00087 ros::NodeHandle nh_; 00088 ros::Publisher pub_; 00089 ros::Publisher object_pub_; 00090 // Diagnostics 00091 diagnostic_updater::DiagnosedPublisher<sensor_msgs::PointCloud2>* diagnosticPub_; 00092 00093 // Dynamic Reconfigure 00094 SickLDMRSDriverConfig config_; 00095 dynamic_reconfigure::Server<SickLDMRSDriverConfig> dynamic_reconfigure_server_; 00096 00097 // sick_ldmrs library objects 00098 Manager* manager_; 00099 00100 // Expected scan frequency. Must be a member variable for access by diagnostics. 00101 double expected_frequency_; 00102 00103 bool initialized_; 00104 }; 00105 00106 } /* namespace sick_ldmrs_driver */ 00107 #endif /* SICK_LDMRS800001S01_H_ */