8 _imager.init(¶ms, dev->getFrequency(), dev->getWidth(), dev->getHeight(), dev->controlledViaHID());
11 _bufferRaw =
new unsigned char[dev->getRawBufferSize()];
25 if(
_imager.hasBispectralTechnology())
62 _dev->startStreaming();
68 _dev->stopStreaming();
74 if(retval==evo::IRIMAGER_SUCCESS)
78 if(retval==evo::IRIMAGER_DISCONNECTED)
113 memcpy(&
_visible_image.data[0], image, 2 * w * h *
sizeof(*image));
122 optris_drivers::Flag flag;
123 flag.flag_state = flagstate;
136 _imager.setAutoFlag(req.autoFlag);
137 res.isAutoFlagActive =
_imager.getAutoFlag();
149 bool validParam =
_imager.setTempRange(req.temperatureRangeMin, req.temperatureRangeMax);
156 res.success = validParam;
image_transport::Publisher _visible_pub
sensor_msgs::Image _thermal_image
bool onForceFlag(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer _sTemp
void publish(const boost::shared_ptr< M > &message) const
bool onSetTemperatureRange(TemperatureRange::Request &req, TemperatureRange::Response &res)
virtual void onProcessExit(void *arg)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::Publisher _timer_pub
unsigned char * _bufferRaw
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual void onVisibleFrame(unsigned char *image, unsigned int w, unsigned int h, evo::IRFrameMetadata meta, void *arg)
sensor_msgs::TimeReference _device_timer
uint32_t getNumSubscribers() const
ros::ServiceServer _sAuto
ROSCPP_DECL void spin(Spinner &spinner)
void onTimer(const ros::TimerEvent &event)
bool onAutoFlag(AutoFlag::Request &req, AutoFlag::Response &res)
void publish(const sensor_msgs::Image &message) const
OptrisImager(evo::IRDevice *dev, evo::IRDeviceParams params)
virtual void onThermalFrame(unsigned short *image, unsigned int w, unsigned int h, evo::IRFrameMetadata meta, void *arg)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer _sForce
sensor_msgs::Image _visible_image
image_transport::Publisher _thermal_pub
optris_drivers::Temperature _internal_temperature
virtual void onFlagStateChange(evo::EnumFlagState flagstate, void *arg)
ROSCPP_DECL void shutdown()