35 #include <libavcodec/avcodec.h> 36 #include <libswscale/swscale.h> 37 #include <libavutil/pixfmt.h> 47 #include <std_msgs/String.h> 49 #include <opencv2/opencv.hpp> 56 sensor_msgs::ImagePtr
msg;
68 int main(
int argc,
char **argv)
83 pthread_join(ret, NULL);
94 if (pFrame->
size <= 0)
101 avcodec_register_all();
103 pdecode = avcodec_find_decoder(AV_CODEC_ID_H264);
111 cout <<
"no h264 decoder found"<< endl;
115 cout <<
"could not open codec" << endl;
127 av_init_packet(&pkt);
128 pkt.data = pFrame->
buf;
129 pkt.size = pFrame->
size;
130 pkt.flags = pFrame->
iFrame;
135 AVPixelFormat pFormat = AV_PIX_FMT_BGR24;
139 buffer = (uint8_t *) av_malloc(numBytes*
sizeof(uint8_t));
147 cout <<
"decode error" << endl;
151 struct SwsContext * img_convert_ctx;
154 pCodecCtxc->height, AV_PIX_FMT_BGR24, SWS_BICUBIC, NULL, NULL,NULL);
164 ROS_ERROR(
"CV Bridge error: %s", e.what());
177 av_free_packet(&pkt);
179 sws_freeContext(img_convert_ctx);
AVCodecContext * pCodecCtxc
ros::Publisher chatter_pub
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)
int lewei_initialize_stream()
long lewei_start_stream(void *mydata, P_LEWEI_CALLBACK pcallback)
void publish(const sensor_msgs::Image &message) const
void video_free_frame_ram(void *pFrame)
image_transport::Publisher cam_pub
int main(int argc, char **argv)
sensor_msgs::ImagePtr msg
ROSCPP_DECL void spinOnce()
static void read_buffer(void *lpParam, lewei_video_frame *pFrame)
sensor_msgs::ImagePtr toImageMsg() const