2121#include < ffmpeg_encoder_decoder/types.hpp>
2222#include < functional>
2323#include < memory>
24+ #include < mutex>
2425#include < rclcpp/rclcpp.hpp>
2526#include < string>
27+ #include < thread>
2628#include < unordered_map>
2729
2830extern " C" {
@@ -92,15 +94,19 @@ class Decoder
9294 Decoder ();
9395
9496 /* *
95- * \brief Destructor. Calls reset();
97+ * \brief Destructor.
9698 */
9799 ~Decoder ();
98100
99101 /* *
100102 * Test if decoder is initialized.
101103 * \return true if the decoder is initialized.
102104 */
103- bool isInitialized () const { return (codecContext_ != NULL ); }
105+ bool isInitialized () const
106+ {
107+ Lock lock (mutex_);
108+ return (codecContext_ != NULL );
109+ }
104110
105111 /* *
106112 * \brief Initializes the decoder for a given codec and libav decoder.
@@ -160,36 +166,21 @@ class Decoder
160166 * \brief Overrides the default ("Decoder") logger.
161167 * \param logger the logger to override the default ("Decoder") with.
162168 */
163- void setLogger (rclcpp::Logger logger) { logger_ = logger; }
164-
165- /* *
166- * \brief Finds all hardware and software decoders for a given codec.
167- *
168- * Finds the name of all hardware and software decoders that match
169- * a certain codec (or encoder).
170- * \param codec name of the codec, i.e. h264, hevc etc
171- * \param hw_decoders non-null pointer for returning list of hardware decoders
172- * \param sw_decoders non-null pointer for returning list of software decoders
173- */
174- static void findDecoders (
175- const std::string & codec, std::vector<std::string> * hw_decoders,
176- std::vector<std::string> * sw_decoders);
177-
178- /* *
179- * \brief Finds all decoders that can decode a given codec.
180- *
181- * Finds the name of all hardware and software decoders (combined)
182- * that match a certain codec (or encoder).
183- * \param codec name of the codec, i.e. h264, hevc etc
184- * \return string with comma-separated list of libav decoders
185- */
186- static std::string findDecoders (const std::string & codec);
169+ void setLogger (rclcpp::Logger logger)
170+ {
171+ Lock lock (mutex_);
172+ logger_ = logger;
173+ }
187174
188175 /* *
189176 * \brief Enables or disables performance measurements. Poorly tested, may be broken.
190177 * \param p set to true to enable performance debugging.
191178 */
192- void setMeasurePerformance (bool p) { measurePerformance_ = p; }
179+ void setMeasurePerformance (bool p)
180+ {
181+ Lock lock (mutex_);
182+ measurePerformance_ = p;
183+ }
193184
194185 /* *
195186 * \brief Prints performance timers. Poorly tested, may be broken.
@@ -201,16 +192,41 @@ class Decoder
201192 * \brief resets performance debugging timers. Poorly tested, may be broken.
202193 */
203194 void resetTimers ();
195+
204196 /* *
205197 * \brief adds AVOption setting to list of options to be applied before opening the encoder
206198 * \param key name of AVOption to set, e.g. "preset"
207199 * \param value value of AVOption e.g. "slow"
208200 */
209201 void addAVOption (const std::string & key, const std::string & value)
210202 {
203+ Lock lock (mutex_);
211204 avOptions_.push_back ({key, value});
212205 }
213206
207+ /* *
208+ * \brief Finds all hardware and software decoders for a given codec.
209+ *
210+ * Finds the name of all hardware and software decoders that match
211+ * a certain codec (or encoder).
212+ * \param codec name of the codec, i.e. h264, hevc etc
213+ * \param hw_decoders non-null pointer for returning list of hardware decoders
214+ * \param sw_decoders non-null pointer for returning list of software decoders
215+ */
216+ static void findDecoders (
217+ const std::string & codec, std::vector<std::string> * hw_decoders,
218+ std::vector<std::string> * sw_decoders);
219+
220+ /* *
221+ * \brief Finds all decoders that can decode a given codec.
222+ *
223+ * Finds the name of all hardware and software decoders (combined)
224+ * that match a certain codec (or encoder).
225+ * \param codec name of the codec, i.e. h264, hevc etc
226+ * \return string with comma-separated list of libav decoders
227+ */
228+ static std::string findDecoders (const std::string & codec);
229+
214230 // ------------------- deprecated functions ---------------
215231 /* *
216232 * \deprecated Use findDecoders(codec) instead.
@@ -220,17 +236,20 @@ class Decoder
220236 getDefaultEncoderToDecoderMap ();
221237
222238private:
239+ using Lock = std::unique_lock<std::mutex>;
223240 bool doInitDecoder (const std::string & encoding, const std::string & decoder);
224241 bool initDecoder (const std::string & encoding, const std::string & decoders);
225242 int receiveFrame ();
226243 int convertFrameToMessage (const AVFrame * frame, const ImagePtr & image);
227244 void setAVOption (const std::string & field, const std::string & value);
228245 void setEncoding (const std::string & encoding);
246+ void resetNoLock ();
229247 // --------------- variables
230248 rclcpp::Logger logger_;
231249 Callback callback_;
232250 PTSMap ptsToStamp_;
233251 std::vector<std::pair<std::string, std::string>> avOptions_;
252+ mutable std::mutex mutex_;
234253 // --- performance analysis
235254 bool measurePerformance_{false };
236255 TDiff tdiffTotal_;
0 commit comments