9
9
#include " depthai-shared/common/CameraBoardSocket.hpp"
10
10
#include " depthai-shared/common/Point2f.hpp"
11
11
#include " depthai/device/CalibrationHandler.hpp"
12
+ #include " depthai/pipeline/datatype/EncodedFrame.hpp"
12
13
#include " depthai/pipeline/datatype/ImgFrame.hpp"
14
+ #include " depthai_ros_msgs/FFMPEGPacket.h"
13
15
#include " ros/time.h"
14
16
#include " sensor_msgs/CameraInfo.h"
17
+ #include " sensor_msgs/CompressedImage.h"
15
18
#include " sensor_msgs/Image.h"
16
19
#include " std_msgs/Header.h"
17
20
@@ -21,8 +24,11 @@ namespace ros {
21
24
22
25
namespace StdMsgs = std_msgs;
23
26
namespace ImageMsgs = sensor_msgs;
27
+ namespace DepthAiRosMsgs = depthai_ros_msgs;
24
28
using ImagePtr = ImageMsgs::ImagePtr;
25
29
using TimePoint = std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration>;
30
+ using FFMPegImagePtr = DepthAiRosMsgs::FFMPEGPacketPtr;
31
+ using CompImagePtr = ImageMsgs::CompressedImagePtr;
26
32
27
33
class ImageConverter {
28
34
public:
@@ -44,7 +50,7 @@ class ImageConverter {
44
50
* @param update: bool whether to automatically update the ROS base time on message conversion
45
51
*/
46
52
void setUpdateRosBaseTimeOnToRosMsg (bool update = true ) {
47
- _updateRosBaseTimeOnToRosMsg = update;
53
+ updateRosBaseTimeOnToRosMsg = update;
48
54
}
49
55
50
56
/* *
@@ -77,10 +83,20 @@ class ImageConverter {
77
83
*/
78
84
void setAlphaScaling (double alphaScalingFactor = 0.0 );
79
85
86
+ /* *
87
+ * @brief Sets the encoding of the image when converting to FFMPEG message. Default is libx264.
88
+ * @param encoding: The encoding to be used.
89
+ */
90
+ void setFFMPEGEncoding (const std::string& encoding);
91
+
80
92
ImageMsgs::Image toRosMsgRawPtr (std::shared_ptr<dai::ImgFrame> inData, const sensor_msgs::CameraInfo& info = sensor_msgs::CameraInfo());
81
93
void toRosMsg (std::shared_ptr<dai::ImgFrame> inData, std::deque<ImageMsgs::Image>& outImageMsgs);
82
94
ImagePtr toRosMsgPtr (std::shared_ptr<dai::ImgFrame> inData);
83
95
96
+ DepthAiRosMsgs::FFMPEGPacket toRosFFMPEGPacket (std::shared_ptr<dai::EncodedFrame> inData);
97
+
98
+ ImageMsgs::CompressedImage toRosCompressedMsg (std::shared_ptr<dai::ImgFrame> inData);
99
+
84
100
void toDaiMsg (const ImageMsgs::Image& inMsg, dai::ImgFrame& outData);
85
101
86
102
/* * TODO(sachin): Add support for ros msg to cv mat since we have some
@@ -99,29 +115,31 @@ class ImageConverter {
99
115
static std::unordered_map<dai::RawImgFrame::Type, std::string> encodingEnumMap;
100
116
static std::unordered_map<dai::RawImgFrame::Type, std::string> planarEncodingEnumMap;
101
117
102
- // dai::RawImgFrame::Type _srcType;
103
- bool _daiInterleaved;
118
+ bool daiInterleaved;
104
119
// bool c
105
- const std::string _frameName = " " ;
120
+ const std::string frameName = " " ;
106
121
void planarToInterleaved (const std::vector<uint8_t >& srcData, std::vector<uint8_t >& destData, int w, int h, int numPlanes, int bpp);
107
122
void interleavedToPlanar (const std::vector<uint8_t >& srcData, std::vector<uint8_t >& destData, int w, int h, int numPlanes, int bpp);
108
- std::chrono::time_point<std::chrono::steady_clock> _steadyBaseTime ;
123
+ std::chrono::time_point<std::chrono::steady_clock> steadyBaseTime ;
109
124
110
- ::ros::Time _rosBaseTime ;
111
- bool _getBaseDeviceTimestamp ;
125
+ ::ros::Time rosBaseTime ;
126
+ bool getBaseDeviceTimestamp ;
112
127
// For handling ROS time shifts and debugging
113
- int64_t _totalNsChange {0 };
128
+ int64_t totalNsChange {0 };
114
129
// Whether to update the ROS base time on each message conversion
115
- bool _updateRosBaseTimeOnToRosMsg{false };
116
- dai::RawImgFrame::Type _srcType;
117
- bool _fromBitstream = false ;
118
- bool _convertDispToDepth = false ;
119
- bool _addExpOffset = false ;
120
- dai::CameraExposureOffset _expOffset;
121
- bool _reverseStereoSocketOrder = false ;
122
- double _baseline;
123
- bool _alphaScalingEnabled = false ;
124
- double _alphaScalingFactor = 0.0 ;
130
+ bool updateRosBaseTimeOnToRosMsg{false };
131
+ dai::RawImgFrame::Type srcType;
132
+ bool fromBitstream = false ;
133
+ bool dispToDepth = false ;
134
+ bool addExpOffset = false ;
135
+ dai::CameraExposureOffset expOffset;
136
+ bool reversedStereoSocketOrder = false ;
137
+ double baseline;
138
+ bool alphaScalingEnabled = false ;
139
+ double alphaScalingFactor = 0.0 ;
140
+ int camHeight = -1 ;
141
+ int camWidth = -1 ;
142
+ std::string ffmpegEncoding = " libx264" ;
125
143
};
126
144
127
145
} // namespace ros
0 commit comments