evarobot_infrared.h
Go to the documentation of this file.
00001 #ifndef INCLUDE_EVAROBOT_INFRARED_H_
00002 #define INCLUDE_EVAROBOT_INFRARED_H_
00003 
00004 #include "ros/ros.h"
00005 #include "sensor_msgs/Range.h"
00006 
00007 #include <diagnostic_updater/diagnostic_updater.h>
00008 #include <diagnostic_updater/publisher.h>
00009 
00010 #include <dynamic_reconfigure/server.h>
00011 #include <evarobot_infrared/ParamsConfig.h>
00012 
00013 #include <vector>
00014 #include <sstream>
00015 
00016 #include <boost/shared_ptr.hpp>
00017 
00018 #include "IMADC.h"
00019 
00020 #include <ros/console.h>
00021 #include "ErrorCodes.h"
00022 
00023 //#ifndef DEBUG
00024 //#define DEBUG
00025 //#endif
00026 
00027 #define MAX_IR 8
00028 
00029 using namespace std;
00030 
00031 class IMDynamicReconfig
00032 {
00033         public:
00034         IMDynamicReconfig();
00035         
00036         void CallbackReconfigure(evarobot_infrared::ParamsConfig &config, uint32_t level);
00037         
00038         ros::NodeHandle n_private;
00039         
00040         double d_min_range, d_max_range, d_fov;
00041         double d_max_freq, d_min_freq;
00042         double d_par_k, d_par_a, d_par_b;
00043         
00044         bool b_always_on;
00045                 
00046         dynamic_reconfigure::Server<evarobot_infrared::ParamsConfig> srv;
00047         dynamic_reconfigure::Server<evarobot_infrared::ParamsConfig>::CallbackType f;
00048 };
00049 
00050 class IMInfrared
00051 {
00052         public:
00053         
00054         IMInfrared(int id,
00055                                         boost::shared_ptr<IMADC> _adc,
00056                                   boost::shared_ptr<IMDynamicReconfig> _dynamic_params);
00057         ~IMInfrared();
00058         bool ReadRange();
00059         void Publish();
00060         void ProduceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
00061         
00062         ros::NodeHandle n;
00063   ros::Publisher pub_inf;
00064   diagnostic_updater::Updater updater;
00065         
00066         private:
00067         
00068         int i_id;
00069         bool b_is_alive;
00070         
00071         sensor_msgs::Range inf_msg;
00072         
00073         boost::shared_ptr<IMADC> adc;
00074         boost::shared_ptr<IMDynamicReconfig> dynamic_params;
00075         
00076         double min_freq;
00077         double max_freq;
00078         diagnostic_updater::HeaderlessTopicDiagnostic * pub_inf_freq;
00079 
00080 };
00081 
00082 #endif


evarobot_infrared
Author(s): Mehmet Akcakoca
autogenerated on Fri Feb 12 2016 01:15:23