Skip to content
Snippets Groups Projects
Commit 0ab494b9 authored by Michael Stypa's avatar Michael Stypa Committed by v4hn
Browse files

fixed setting frame_id

parent 928a5c3e
No related branches found
No related tags found
No related merge requests found
...@@ -35,6 +35,7 @@ ...@@ -35,6 +35,7 @@
#include <ros/ros.h> #include <ros/ros.h>
#include <sensor_msgs/Image.h> #include <sensor_msgs/Image.h>
#include <std_msgs/Header.h>
#include <image_transport/camera_publisher.h> #include <image_transport/camera_publisher.h>
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include <dynamic_reconfigure/SensorLevels.h> #include <dynamic_reconfigure/SensorLevels.h>
...@@ -166,9 +167,16 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) { ...@@ -166,9 +167,16 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
image->data.resize(image->step * image->height); image->data.resize(image->step * image->height);
memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes); 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())); new sensor_msgs::CameraInfo(cinfo_manager_.getCameraInfo()));
std_msgs::Header::Ptr imageheader(new std_msgs::Header());
std_msgs::Header::Ptr cinfoheader(new std_msgs::Header());
imageheader->frame_id = config_.frame_id;
cinfoheader->frame_id = config_.frame_id;
image->header = *imageheader;
cinfo->header = *cinfoheader;
cam_pub_.publish(image, cinfo); cam_pub_.publish(image, cinfo);
if (config_changed_) { if (config_changed_) {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment