DroneCam.cpp
Go to the documentation of this file.
1 /*
2 BSD 2-Clause License
3 
4 Copyright (c) 2019, Simranjeet Singh
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without
8 modification, are permitted provided that the following conditions are met:
9 
10 1. Redistributions of source code must retain the above copyright notice, this
11  list of conditions and the following disclaimer.
12 
13 2. Redistributions in binary form must reproduce the above copyright notice,
14  this list of conditions and the following disclaimer in the documentation
15  and/or other materials provided with the distribution.
16 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
21 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 
28 Created by vedanshi on 26/4/19.
29 Edited by badrobot15 on 20/5/19.
30 
31 */
32 
33 
34 extern "C" {
35 #include <libavcodec/avcodec.h>
36 #include <libswscale/swscale.h>
37 #include <libavutil/pixfmt.h>
38 }
39 
40 #include <iostream>
41 
42 #include <ros/ros.h>
44 #include <cv_bridge/cv_bridge.h>
45 
46 #include <eyantra_drone/liblewei.h>
47 #include <std_msgs/String.h>
48 
49 #include <opencv2/opencv.hpp>
50 
51 using namespace cv;
52 using namespace std;
53 
56 sensor_msgs::ImagePtr msg;
57 
58 uint8_t *pframe_pixel;
60 AVCodecContext *pCodecCtxc;
61 AVCodec *pdecode;
62 SwsContext *pSwsCtx;
63 
64 
65 static void read_buffer(void* lpParam, lewei_video_frame *pFrame);
66 
67 
68 int main(int argc, char **argv)
69 {
70 
71  ros::init(argc, argv, "droneCam");
72 
74 
76 
77  cam_pub = it.advertise("/drone_cam", 1);
78 
80 
81  long ret = lewei_start_stream(nullptr, read_buffer);
82 
83  pthread_join(ret, NULL);
84 
85  return 0;
86 }
87 
88 static void read_buffer(void* lpParam, lewei_video_frame *pFrame)
89 {
90 
91  int ret = 0;
92  int got_picture = 0;
93 
94  if (pFrame->size <= 0)
95  {
96  video_free_frame_ram(pFrame);
97  return;
98  }
99 
100  if (!pdecode) {
101  avcodec_register_all();
102 
103  pdecode = avcodec_find_decoder(AV_CODEC_ID_H264);
104 
105  pCodecCtxc = avcodec_alloc_context3(pdecode);
106  pCodecCtxc->bit_rate = 125000;
107  pCodecCtxc->width = 1280;
108  pCodecCtxc->height = 720;
109 
110  if(!pdecode) {
111  cout <<"no h264 decoder found"<< endl;
112  }
113 
114  if (avcodec_open2(pCodecCtxc, pdecode, nullptr) < 0) {
115  cout << "could not open codec" << endl;
116  return;
117  }
118  }
119 
120  if (!pVideoFrameIn)
121  pVideoFrameIn = av_frame_alloc();
122 
123  if (!pVideoFrameOut)
124  pVideoFrameOut = av_frame_alloc();//avcodec_alloc_frame();
125 
126  AVPacket pkt;
127  av_init_packet(&pkt);
128  pkt.data = pFrame->buf;
129  pkt.size = pFrame->size;
130  pkt.flags = pFrame->iFrame;
131 
132  uint8_t *buffer;
133  int numBytes;
134 
135  AVPixelFormat pFormat = AV_PIX_FMT_BGR24;
136 
137  numBytes = avpicture_get_size(pFormat,pCodecCtxc->width,pCodecCtxc->height);
138 
139  buffer = (uint8_t *) av_malloc(numBytes*sizeof(uint8_t));
140 
141  avpicture_fill((AVPicture *) pVideoFrameOut,buffer,pFormat,pCodecCtxc->width,pCodecCtxc->height);
142 
143  ret = avcodec_decode_video2(pCodecCtxc, pVideoFrameIn, &got_picture, &pkt);
144 
145  if (ret < 0)
146  {
147  cout << "decode error" << endl;
148  return;
149  }
150 
151  struct SwsContext * img_convert_ctx;
152 
153  img_convert_ctx = sws_getCachedContext(NULL,pCodecCtxc->width, pCodecCtxc->height, pCodecCtxc->pix_fmt, pCodecCtxc->width,
154  pCodecCtxc->height, AV_PIX_FMT_BGR24, SWS_BICUBIC, NULL, NULL,NULL);
155 
156  sws_scale(img_convert_ctx, ((AVPicture*)pVideoFrameIn)->data, ((AVPicture*)pVideoFrameIn)->linesize, 0, pCodecCtxc->height,
157  ((AVPicture *)pVideoFrameOut)->data, ((AVPicture *)pVideoFrameOut)->linesize);
158 
159  Mat img(pVideoFrameIn->height,pVideoFrameIn->width,CV_8UC3,pVideoFrameOut->data[0]);
160 
161  try{
162  msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", img).toImageMsg();
163  }catch(cv_bridge::Exception& e){
164  ROS_ERROR("CV Bridge error: %s", e.what());
165  return;
166  }
167 
168  ros::Rate loop_rate(5);
169  // imshow("display",img);
170  cvWaitKey(1);
171 
172  cam_pub.publish(msg);
173 
174  ros::spinOnce();
175 
176  video_free_frame_ram(pFrame);
177  av_free_packet(&pkt);
178  av_free(buffer);
179  sws_freeContext(img_convert_ctx);
180 }
AVCodecContext * pCodecCtxc
Definition: DroneCam.cpp:60
ros::Publisher chatter_pub
Definition: DroneCam.cpp:54
AVCodec * pdecode
Definition: DroneCam.cpp:61
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
AVFrame * pVideoFrameIn
Definition: DroneCam.cpp:59
int lewei_initialize_stream()
SwsContext * pSwsCtx
Definition: DroneCam.cpp:62
long lewei_start_stream(void *mydata, P_LEWEI_CALLBACK pcallback)
uint8_t * pframe_pixel
Definition: DroneCam.cpp:58
void publish(const sensor_msgs::Image &message) const
AVFrame * pVideoFrameOut
Definition: DroneCam.cpp:59
void video_free_frame_ram(void *pFrame)
image_transport::Publisher cam_pub
Definition: DroneCam.cpp:55
int main(int argc, char **argv)
Definition: DroneCam.cpp:68
sensor_msgs::ImagePtr msg
Definition: DroneCam.cpp:56
ROSCPP_DECL void spinOnce()
static void read_buffer(void *lpParam, lewei_video_frame *pFrame)
Definition: DroneCam.cpp:88
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const


edrone_client
Author(s): Simranjeet Singh
autogenerated on Sun Dec 1 2019 03:30:51