35 #ifndef _STEREO_NODE_H_ 36 #define _STEREO_NODE_H_ 40 #include <ueye/stereoConfig.h> 43 #include <boost/thread/mutex.hpp> 44 #include <boost/thread/lock_guard.hpp> 57 void reconfig(stereoConfig &config, uint32_t level);
61 bool setCameraInfoL(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
62 bool setCameraInfoR(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
63 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp,
Camera& cam,
64 sensor_msgs::CameraInfo &msg_info);
68 sensor_msgs::CameraInfoPtr &info, sensor_msgs::CameraInfo &msg_info);
76 dynamic_reconfigure::Server<stereoConfig>
srv_;
103 #endif // _STEREO_NODE_H_
void handlePath(std::string &path)
dynamic_reconfigure::Server< stereoConfig > srv_
void loadIntrinsics(Camera &cam, sensor_msgs::CameraInfo &msg_info)
ros::ServiceServer r_srv_cam_info_
sensor_msgs::CameraInfo r_msg_camera_info_
image_transport::CameraPublisher l_pub_stream_
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp, Camera &cam, sensor_msgs::CameraInfo &msg_info)
image_transport::CameraPublisher r_pub_stream_
ros::ServiceServer l_srv_cam_info_
ros::Timer timer_force_trigger_
void timerCallback(const ros::TimerEvent &event)
void reconfig(stereoConfig &config, uint32_t level)
sensor_msgs::ImagePtr processFrame(const char *frame, size_t size, const Camera &cam, sensor_msgs::CameraInfoPtr &info, sensor_msgs::CameraInfo &msg_info)
void publishImageR(const char *frame, size_t size)
StereoNode(ros::NodeHandle node, ros::NodeHandle private_nh)
sensor_msgs::CameraInfo l_msg_camera_info_
void timerForceTrigger(const ros::TimerEvent &event)
void reconfigCam(stereoConfig &config, uint32_t level, Camera &cam)
image_transport::ImageTransport it_
bool setCameraInfoL(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
void publishImageL(const char *frame, size_t size)
bool setCameraInfoR(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)