25 #include <sensor_msgs/Image.h> 26 #include <sensor_msgs/PointCloud2.h> 27 #include <stereo_msgs/DisparityImage.h> 29 #include <cob_perception_msgs/Float64ArrayStamped.h> 36 #include <opencv2/opencv.hpp> 41 #include <pcl/point_types.h> 101 void imageCallback(
const sensor_msgs::ImageConstPtr& color_image_msg);
108 void pcCallback(
const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg);
115 void disparityCallback(
const stereo_msgs::DisparityImage::ConstPtr& disparity_image_msg);
ros::Publisher point_cloud_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
unsigned int pc_sub_counter_
void imageCallback(const sensor_msgs::ImageConstPtr &color_image_msg)
ros::Subscriber point_cloud_sub_
point cloud input topic
ImageFlip(ros::NodeHandle nh)
image_transport::Publisher color_camera_image_pub_
color camera image output topic
ros::Publisher disparity_image_pub_
disparity image output topic
void disparityConnectCB(const ros::SingleSubscriberPublisher &pub)
image_transport::ImageTransport * it_
ros::NodeHandle node_handle_
ROS node handle.
unsigned int img_sub_counter_
ros::Publisher color_camera_image_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
ros::Publisher point_cloud_pub_
point cloud output topic
void imgDisconnectCB(const image_transport::SingleSubscriberPublisher &pub)
void pcConnectCB(const ros::SingleSubscriberPublisher &pub)
double last_rotation_angle_
void pcDisconnectCB(const ros::SingleSubscriberPublisher &pub)
void imgConnectCB(const image_transport::SingleSubscriberPublisher &pub)
bool flip_disparity_image_
image_transport::SubscriberFilter color_camera_image_sub_
color camera image input topic
double last_rotation_factor_
void disparityCallback(const stereo_msgs::DisparityImage::ConstPtr &disparity_image_msg)
void pcCallback(const sensor_msgs::PointCloud2::ConstPtr &point_cloud_msg)
unsigned int disparity_sub_counter_
ros::Subscriber disparity_image_sub_
disparity image input topic
void disparityDisconnectCB(const ros::SingleSubscriberPublisher &pub)
std::string reference_frame_
tf::TransformListener transform_listener_
ros::Publisher disparity_image_2d_transform_pub_
publisher for the transformation matrix for the in plane rotation and translation in the image plane...
double determineRotationAngle(const std::string &camera_frame_id, const ros::Time &time)
bool convertImageMessageToMat(const sensor_msgs::Image::ConstPtr &color_image_msg, cv_bridge::CvImageConstPtr &color_image_ptr, cv::Mat &color_image)