35 #ifndef _CAMERA_NODE_H_ 36 #define _CAMERA_NODE_H_ 41 #include <sensor_msgs/Image.h> 42 #include <sensor_msgs/CameraInfo.h> 43 #include <sensor_msgs/SetCameraInfo.h> 48 #include <dynamic_reconfigure/server.h> 49 #include <ueye/monoConfig.h> 75 void reconfig(monoConfig &config, uint32_t level);
77 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
80 sensor_msgs::ImagePtr
processFrame(
const char *frame,
size_t size, sensor_msgs::CameraInfoPtr &info);
87 dynamic_reconfigure::Server<monoConfig>
srv_;
109 #endif // _CAMERA_NODE_H_
image_transport::ImageTransport it_
sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, sensor_msgs::CameraInfoPtr &info)
unsigned int getCameraSerialNo() const
void timerCallback(const ros::TimerEvent &event)
const char * getCameraName() const
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
dynamic_reconfigure::Server< monoConfig > srv_
image_transport::CameraPublisher pub_stream_
void handlePath(std::string &path)
void publishImage(const char *frame, size_t size)
CameraNode(ros::NodeHandle node, ros::NodeHandle private_nh)
sensor_msgs::CameraInfo msg_camera_info_
void reconfig(monoConfig &config, uint32_t level)
static std::string configFileName(const Camera &cam)
ros::ServiceServer srv_cam_info_