diff --git a/bebop_driver/CHANGELOG.rst b/bebop_driver/CHANGELOG.rst index 0dd8cca..de5aac7 100644 --- a/bebop_driver/CHANGELOG.rst +++ b/bebop_driver/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package bebop_driver ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.7.1 (2018-05-31) +------------------ +* Fixed the bug appearing when you run the catkin build command +* Contributors: Giuseppe Silano + 0.7.0 (2017-07-29) ------------------ * SDK 3.12.6 support (except 64bit Ubuntu Xenial, working on fix) diff --git a/bebop_driver/package.xml b/bebop_driver/package.xml index 1c0a3cb..63bf4dd 100644 --- a/bebop_driver/package.xml +++ b/bebop_driver/package.xml @@ -1,7 +1,7 @@ bebop_driver - 0.7.0 + 0.7.1 ROS driver for Parrot Bebop drone, based on Parrot’s official ARDroneSDK3 Mani Monajjemi diff --git a/bebop_driver/src/bebop_video_decoder.cpp b/bebop_driver/src/bebop_video_decoder.cpp index 63f0a82..9e2e500 100644 --- a/bebop_driver/src/bebop_video_decoder.cpp +++ b/bebop_driver/src/bebop_video_decoder.cpp @@ -133,7 +133,7 @@ bool VideoDecoder::ReallocateBuffers() boost::lexical_cast(codec_ctx_ptr_->width) + " x " + boost::lexical_cast(codec_ctx_ptr_->width)); - const uint32_t num_bytes = avpicture_get_size(PIX_FMT_RGB24, codec_ctx_ptr_->width, codec_ctx_ptr_->width); + const uint32_t num_bytes = avpicture_get_size(AV_PIX_FMT_RGB24, codec_ctx_ptr_->width, codec_ctx_ptr_->width); frame_rgb_ptr_ = av_frame_alloc(); ThrowOnCondition(!frame_rgb_ptr_, "Can not allocate memory for frames!"); @@ -143,12 +143,12 @@ bool VideoDecoder::ReallocateBuffers() std::string("Can not allocate memory for the buffer: ") + boost::lexical_cast(num_bytes)); ThrowOnCondition(0 == avpicture_fill( - reinterpret_cast(frame_rgb_ptr_), frame_rgb_raw_ptr_, PIX_FMT_RGB24, + reinterpret_cast(frame_rgb_ptr_), frame_rgb_raw_ptr_, AV_PIX_FMT_RGB24, codec_ctx_ptr_->width, codec_ctx_ptr_->height), "Failed to initialize the picture data structure."); img_convert_ctx_ptr_ = sws_getContext(codec_ctx_ptr_->width, codec_ctx_ptr_->height, codec_ctx_ptr_->pix_fmt, - codec_ctx_ptr_->width, codec_ctx_ptr_->height, PIX_FMT_RGB24, + codec_ctx_ptr_->width, codec_ctx_ptr_->height, AV_PIX_FMT_RGB24, SWS_FAST_BILINEAR, NULL, NULL, NULL); } catch (const std::runtime_error& e)