diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp index b92a2f6b03e25618946e417e53020e35e3dcd753..7fee4545668ab6b7cf4824f9ca9b7004a29e9f82 100644 --- a/libuvc_camera/src/camera_driver.cpp +++ b/libuvc_camera/src/camera_driver.cpp @@ -35,6 +35,7 @@ #include <ros/ros.h> #include <sensor_msgs/Image.h> +#include <std_msgs/Header.h> #include <image_transport/camera_publisher.h> #include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/SensorLevels.h> @@ -169,7 +170,7 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) { image->data.resize(image->step * image->height); memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes); - sensor_msgs::CameraInfo::ConstPtr cinfo( + sensor_msgs::CameraInfo::Ptr cinfo( new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo())); image->header.frame_id = config_.frame_id;