Skip to content

Commit

Permalink
GstCameraPlugin: correct cast and nullptr usage
Browse files Browse the repository at this point in the history
  • Loading branch information
khancyr committed Aug 5, 2024
1 parent a52f356 commit 7cd6bfa
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions src/GstCameraPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ void GstCameraPlugin::Impl::StartStreaming()

void *GstCameraPlugin::Impl::StartThread(void *param)
{
GstCameraPlugin::Impl *impl = (GstCameraPlugin::Impl *)param;
GstCameraPlugin::Impl *impl = static_cast<GstCameraPlugin::Impl *>(param);
impl->StartGstThread();
return nullptr;
}
Expand Down Expand Up @@ -351,7 +351,7 @@ void GstCameraPlugin::Impl::StartGstThread()
if (ret != GST_STATE_CHANGE_SUCCESS)
{
gzmsg << "GstCameraPlugin: GStreamer element set state returned: "
<< ret << std::endl;
<< static_cast<int>(ret) << std::endl;
}

// this call blocks until the main_loop is killed
Expand Down Expand Up @@ -501,8 +501,8 @@ void GstCameraPlugin::Impl::OnImage(const msgs::Image &msg)
if (!isGstMainLoopActive) return;

// Alloc buffer
const guint size = width * height * 1.5;
GstBuffer *buffer = gst_buffer_new_allocate(NULL, size, NULL);
const auto size = static_cast<guint>(width * height * 1.5);
GstBuffer *buffer = gst_buffer_new_allocate(nullptr, size, nullptr);

if (!buffer)
{
Expand All @@ -520,8 +520,8 @@ void GstCameraPlugin::Impl::OnImage(const msgs::Image &msg)
}

// Color Conversion from RGB to YUV
cv::Mat frame = cv::Mat(height, width, CV_8UC3);
cv::Mat frameYUV = cv::Mat(height, width, CV_8UC3);
cv::Mat frame = cv::Mat(static_cast<int>(height), static_cast<int>(width), CV_8UC3);
cv::Mat frameYUV = cv::Mat(static_cast<int>(height), static_cast<int>(width), CV_8UC3);
frame.data = reinterpret_cast<unsigned char *>(
const_cast<char *>(msg.data().c_str()));

Expand Down Expand Up @@ -568,7 +568,7 @@ void GstCameraPlugin::Impl::StopStreaming()
{
StopGstThread();

pthread_join(threadId, NULL);
pthread_join(threadId, nullptr);
isGstMainLoopActive = false;
}
}
Expand Down

0 comments on commit 7cd6bfa

Please sign in to comment.