Go to the documentation of this file.00001 #include "ros/ros.h"
00002 #include "video_player/PlayVideoSrv.h"
00003 #include "stdlib.h"
00004 #include <gscam/gscam.h>
00005
00006 int METHOD;
00007
00008
00009 bool playVideo(video_player::PlayVideoSrv::Request &req, video_player::PlayVideoSrv::Response &res){
00010
00017 if(METHOD == 1){
00018
00019 std::string gsconfig_param = "";
00020 gsconfig_param = req.videoPath + "/openVideo.sh";
00021 system(gsconfig_param.c_str());
00022
00023 } else if(METHOD == 2) {
00024 ros::NodeHandle n, nh_private("~");
00025 gscam::GSCam gscam_driver(n, nh_private);
00026
00027 ROS_INFO("Setting Param\n");
00028
00029
00030 std::string gsconfig_param = "";
00031 gsconfig_param = "filesrc location=" + req.videoPath + "/Video.avi ! avidemux name=demux demux.video_00 ! decodebin ! ffmpegcolorspace ! video/x-raw-rgb ! identity name=ros ! fakesin";
00032
00033
00034 nh_private.setParam("gscam_config", gsconfig_param);
00035 if(!gscam_driver.configure()) {
00036 ROS_FATAL("Failed to configure gscam!");
00037 } else if(!gscam_driver.init_stream()) {
00038 ROS_FATAL("Failed to initialize gscam stream!");
00039 } else {
00040 gscam_driver.publish_stream();
00041 }
00042
00043
00044 ROS_INFO("Cleaning up stream and exiting...");
00045 gscam_driver.cleanup_stream();
00046 ROS_INFO("GStreamer stream stopped!");
00047
00048 } else {
00049 ROS_INFO("METHOD variable false");
00050 }
00051
00052 return true;
00053 }
00054
00055 int main(int argc, char **argv){
00056
00057 ros::init(argc, argv, "play_video_server");
00058
00059 ros::NodeHandle n, nh_private("~");
00060
00065 std::string mode_;
00066 nh_private.param<std::string>("mode", mode_, "mode_II");
00067 if(mode_.compare("mode_I") == 0){
00068 METHOD = 1;
00069 } else {
00070 METHOD = 2;
00071 }
00072
00073 ros::ServiceServer service = n.advertiseService("/wheeled_robin/application/play_video", playVideo);
00074
00075 ROS_INFO("Ready to play video");
00076
00077 ros::spin();
00078
00079 return 0;
00080 }