depth_sensor_pose_node.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <mutex>
4 
5 #include <ros/ros.h>
7 #include <dynamic_reconfigure/server.h>
8 #include <std_msgs/Float64.h>
9 #include <sensor_msgs/Image.h>
11 
12 #include <opencv2/highgui/highgui.hpp>
13 #include <opencv2/imgproc/imgproc.hpp>
14 #include <cv_bridge/cv_bridge.h>
15 
16 #include <depth_sensor_pose/DepthSensorPoseConfig.h>
18 
19 namespace depth_sensor_pose {
20 
22 {
23 public:
25 
27 
28  DepthSensorPoseNode (const DepthSensorPoseNode &) = delete;
30 
36  void setNodeRate(const float rate);
42  float getNodeRate();
43 
44  protected:
54  void depthCallback(const sensor_msgs::ImageConstPtr& depth_msg,
55  const sensor_msgs::CameraInfoConstPtr& info_msg);
64  void connectCallback();
72  void disconnectCallback();
81  void reconfigureCallback(depth_sensor_pose::DepthSensorPoseConfig& config, uint32_t level);
82 
83  private:
84 
85  float node_rate_hz_{1};
87 
90 
94 
96  dynamic_reconfigure::Server<depth_sensor_pose::DepthSensorPoseConfig> dyn_rec_srv_;
97 
100 
102  std::mutex connection_mutex_;
103 };
104 
105 } // namespace depth_sensor_pose
void depthCallback(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
depthCb is callback which is called when new depth image appear
void disconnectCallback()
disconnectCb is called when a subscriber stop subscribing
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
std::mutex connection_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
void reconfigureCallback(depth_sensor_pose::DepthSensorPoseConfig &config, uint32_t level)
reconfigureCb is dynamic reconfigure callback
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
image_transport::Publisher pub_
Publisher for image_transport.
float getNodeRate()
getNodeRate gets rate of data processing loop in node.
depth_sensor_pose::DepthSensorPose estimator_
Object which contain estimation methods.
DepthSensorPoseNode & operator=(const DepthSensorPoseNode &)=delete
void connectCallback()
connectCb is callback which is called when new subscriber connected.
void setNodeRate(const float rate)
setNodeRate sets rate of processing data loop in node.
ros::NodeHandle pnh_
Private node handler.
ros::Publisher pub_height_
Publisher for estimated sensor height.
ros::Publisher pub_angle_
Publisher for estimated sensor tilt angle.
dynamic_reconfigure::Server< depth_sensor_pose::DepthSensorPoseConfig > dyn_rec_srv_
Dynamic reconfigure server.
float node_rate_hz_
Node loop frequency in Hz.


depth_sensor_pose
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:10