radiometry.hpp
Go to the documentation of this file.
00001 
00005 #ifndef _THERMALVIS_RADIOMETRY_H_
00006 #define _THERMALVIS_RADIOMETRY_H_
00007         
00008 #include "time.h"
00009 
00010 #include <signal.h>
00011 
00012 #include "ros_resources.hpp"
00013 #include "tools.hpp"
00014 #include "improc.hpp"
00015 
00016 #include <dynamic_reconfigure/server.h>
00017 #include "radiometryConfig.h"
00018 
00019 // MODBUS STUFF
00020 #include <inttypes.h>
00021 #include <stdint.h>
00022 #include <stdio.h>
00023 #include <unistd.h>
00024 #include <string.h>
00025 #include <stdlib.h>
00026 #include <errno.h>
00027 #include <modbus.h>
00028 
00029 const uint16_t UT_BITS_NB = 0x25;
00030 const uint16_t UT_INPUT_BITS_NB = 0x16;
00031 const uint16_t UT_REGISTERS_NB = 0x3;
00032 const uint16_t UT_INPUT_REGISTERS_NB = 0x1;
00033 
00034 const uint16_t ISOTECH_SETPOINT_ADDR = 0x18; // Address 24
00035 const uint16_t ISOTECH_TEMP_ADDR = 0x01; // Address 1
00036 const uint16_t ISOTECH_SP_ADDR = 0x02; // Address 1
00037 
00038 // ---END MODBUS STUFF
00039 
00040 const char __PROGRAM__[] = "RADIOMETRY";
00041 
00042 #define DEFAULT_MIN_STABLE_TIME                 60.0    // in seconds
00043 #define DEFAULT_MAX_STABLE_VARIATION    0.01    // in seconds
00044 #define DEFAULT_SERIAL_POLLING_RATE     0.1     // in cycles per second
00045 #define DEFAULT_PORT_ADDRESS                    "/dev/ttyUSB0"
00046 #define DEFAULT_BAUD_RATE                               9600
00047 #define MAXIMUM_BLACKBODY_TEMPERATURE   80.0
00048 #define TEMP_ERROR_HACK                                 0.001
00049 
00050 typedef dynamic_reconfigure::Server < thermalvis::radiometryConfig > Server;
00051 
00052 bool wantsToShutdown = false;
00053 void mySigintHandler(int sig);
00054 
00056 struct radiometryData {
00057         
00058         string read_addr;
00059         
00060         string thermal_topic;
00061         
00062         string outputFolder;
00063 
00064         bool verboseMode;
00065         
00066         bool communicateWithBlackbody;
00067         double serialPollingRate;
00068         double minStableTime;
00069         double maxStableVariation;
00070         double targetTemperature;
00071         
00072         double completionTimeout;
00073         
00074         string portAddress;
00075         int baudRate;
00076         
00077         radiometryData();
00078         
00079         bool obtainStartingData(ros::NodeHandle& nh);   
00080         
00081 };
00082 
00084 class radiometryNode {
00085 private:
00086 
00087         char nodeName[256];
00088         
00089         bool targetTemperatureChanged;
00090         
00091         bool nodeStillValid;
00092         
00093         bool blackbodyIsSetup;
00094         
00095         char subdirectoryName[256];
00096         
00097         bool temperatureIsStable;
00098         bool stabilityOnceOffFlag;
00099         double stabilityTimer;
00100         double elapsedTime;
00101         ros::Time previousTime;
00102         
00103         int imageIndex;
00104         
00105         double currentTemp;
00106         
00107         cv::Mat lastFrame, frame;
00108         bool matEquality;
00109         
00110         string thermistorLogFile, imageLogFile, serialCommsFile;
00111         ofstream ofs_thermistor_log, ofs_image_log; //, ofs_serial_log;
00112         
00113         radiometryData configData;
00114         
00115         cv_bridge::CvImagePtr cv_ptr;
00116         
00117         image_transport::ImageTransport *it;
00118         image_transport::CameraSubscriber camera_sub;
00119         
00120         ros::Timer serial_timer;
00121 
00122         bool firstCall;
00123         
00124         // MODBUS STUFF
00125         modbus_t *ctx;
00126         uint8_t *tab_rp_bits;
00127         int nb_points;
00128         uint16_t *tab_rp_registers;
00129         
00130         
00131         // ---END MODBUS STUFF
00132         
00133         dynamic_reconfigure::Server<thermalvis::radiometryConfig> server;
00134         dynamic_reconfigure::Server<thermalvis::radiometryConfig>::CallbackType f;
00135         
00136         
00137 public:
00138         
00139         radiometryNode(ros::NodeHandle& nh, radiometryData startupData);
00140         
00141         void handle_camera(const sensor_msgs::ImageConstPtr& msg_ptr, const sensor_msgs::CameraInfoConstPtr& info_msg);
00142         
00143         bool setupBlackbodyComms();
00144         bool setupBlackbody();
00145         
00146         bool changeSetPoint(double newVal);
00147         bool readTemperature(double& actualTemp);
00148         bool readSetpoint(double& setPoint);
00149         bool closeBlackbodyComms();
00150         
00151         void serialCallback(const ros::TimerEvent& e);
00152         
00153         void serverCallback(thermalvis::radiometryConfig &config, uint32_t level);
00154         
00155         void prepareForTermination();
00156         
00157         bool setupFilesAndDirectories();
00158         
00159         bool dataStillStreaming();
00160         
00161         bool isNodeValid();
00162         
00163         
00164         
00165 };
00166 
00167 boost::shared_ptr < radiometryNode > *globalNodePtr;
00168 
00169 #endif


thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45