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