v4lctl_node.cpp
Go to the documentation of this file.
00001 /*
00002   File: v4lctl_node.cpp
00003   Date: 10.04.2016
00004   Author: Patrick Feuser
00005   Copyrights: 2016 UAV-Concept http://uav-concept.com
00006   License: GNU GPLv3
00007 
00008   This ROS node is a wrapper for the v4lctl command line tool.
00009   It provides two services to set or get particular bttv parameter.
00010   If a yaml file will be provided a save and restore capability will be enabled.
00011   Parameter are then loaded and set automatically in the capture card when starting the node.
00012   Changed parameter are stored to a yaml file when the program ends.
00013   Additionally a dynamic reconfigure rqt gui is available to manipulate bttv parameter.
00014 
00015   The below v4lctl list output is based on an Osprey 440 capture card.
00016   This node is optimized for this card.
00017   Your card may output other options then change this file and v4lctlNodeDyn.cfg to your needs.
00018 
00019   $ v4lctl list
00020   attribute  | type   | current | default | comment
00021   -----------+--------+---------+---------+-------------------------------------
00022   norm       | choice | PAL-I   | NTSC    | NTSC NTSC-M NTSC-M-JP NTSC-M-KR PAL PAL-BG PAL-H PAL-I PAL-DK PAL-M PAL-N PAL-Nc PAL-60 SECAM SECAM-B SECAM-G SECAM-H SECAM-DK SECAM-L SECAM-Lc
00023   input      | choice | Composi | Composi | Composite0 Composite1 Composite2 Composite3
00024   bright     | int    |   32768 |   32768 | range is 0 => 65280
00025   contrast   | int    |   32768 |   27648 | range is 0 => 65408
00026   color      | int    |   32768 |   32768 | range is 0 => 65408
00027   hue        | int    |   32768 |   32768 | range is 0 => 65280
00028   mute       | bool   | on      | off     |
00029   Chroma AGC | bool   | off     | off     |
00030   Color Kill | bool   | off     | off     |
00031   Comb Filte | bool   | off     | off     |
00032   Auto Mute  | bool   | on      | on      |
00033   Luma Decim | bool   | off     | off     |
00034   AGC Crush  | bool   | on      | on      |
00035   VCR Hack   | bool   | off     | off     |
00036   Whitecrush | int    |     127 |     127 | range is 0 => 255
00037   Whitecrush | int    |     207 |     207 | range is 0 => 255
00038   UV Ratio   | int    |      51 |      50 | range is 0 => 100
00039   Full Luma  | bool   | off     | off     |
00040   Coring     | int    |       0 |       0 | range is 0 => 3
00041 
00042   See also http://linux.die.net/man/1/v4lctl
00043 
00044   setnorm <norm>
00045     Set the TV norm (NTSC/PAL/SECAM).
00046   setinput [ <input> | next ]
00047     Set the video input (Television/Composite1/...)
00048   capture [ on | off | overlay | grabdisplay ]
00049     Set capture mode.
00050   volume mute on | off
00051     mute / unmute audio.
00052   volume <arg>
00053   color <arg>
00054   hue <arg>
00055   bright <arg>
00056   contrast <arg>
00057     Set the parameter to the specified value. <arg> can be one of the following: A percent value ("70%" for example). Some absolute value ("32768"), the valid range is hardware specific. Relative values can be specified too by prefixing with "+=" or "-=" ("+=10%" or "-=2000"). The keywords "inc" and "dec" are accepted to and will increase and decrease the given value in small steps.
00058   setattr <name> <value>
00059     Set set the value of some attribute (color, contrast, ... can be set this way too).
00060   show [ <name> ]
00061     Show the value current of some attribute.
00062 
00063   Samples:
00064   $ v4lctl -c /dev/video0 bright 70%
00065   $ v4lctl -c /dev/video0 contrast "60%"
00066   $ v4lctl -c /dev/video0 color 27648
00067   $ v4lctl -c /dev/video0 setattr "Auto Mute" off
00068 */
00069 #include <ros/ros.h>
00070 #include <dynamic_reconfigure/server.h>
00071 #include <uavc_v4lctl/v4lctlNodeDynConfig.h>
00072 #include <uavc_v4lctl/v4lctlSet.h>
00073 #include <uavc_v4lctl/v4lctlGet.h>
00074 #include <opencv2/opencv.hpp>
00075 #include <boost/algorithm/string/replace.hpp>
00076 #include <boost/regex.hpp>
00077 #include <sstream>
00078 #include <map>
00079 
00080 #define YAML_OPT_TO_NAME(s) boost::replace_all_copy(boost::replace_all_copy(s,"\"","-")," ","_")
00081 #define YAML_NAME_TO_OPT(s) boost::replace_all_copy(boost::replace_all_copy(s,"-","\""),"_"," ")
00082 
00083 namespace uavc_v4lctl {
00084 
00085 class v4lctlNode
00086 {
00087   ros::NodeHandle nh_;
00088 
00089   ros::ServiceServer srv_v4lctl_get_;
00090   ros::ServiceServer srv_v4lctl_set_;
00091 
00092   v4lctlNodeDynConfig cfg_;
00093   dynamic_reconfigure::Server<v4lctlNodeDynConfig> cfg_server_;
00094 
00095   std::map<std::string, std::string> fs_map_;
00096 
00097   std::string device_;
00098   std::string yaml_;
00099 
00100 public:
00101 
00102   v4lctlNode()
00103   {
00104     ros::NodeHandle pnh("~");
00105 
00106     pnh.param<std::string>("device", device_, "/dev/video0");
00107     pnh.param<std::string>("yaml", yaml_, "");
00108 
00109     if (!yaml_.empty())
00110       restoreFromYaml();
00111 
00112     cfg_server_.setCallback(boost::bind(&v4lctlNode::configCb, this, _1, _2));
00113 
00114     srv_v4lctl_set_ = nh_.advertiseService("v4lctlSet", &v4lctlNode::v4lctlSetCb, this);
00115     srv_v4lctl_get_ = nh_.advertiseService("v4lctlGet", &v4lctlNode::v4lctlGetCb, this);
00116   }
00117 
00118   ~v4lctlNode()
00119   {
00120     cv::FileStorage fs;
00121 
00122     if (!yaml_.empty() && fs.open(yaml_, cv::FileStorage::WRITE))
00123     {
00124       std::map<std::string, std::string>::iterator it = fs_map_.begin();
00125 
00126       while (it != fs_map_.end())
00127       {
00128         std::string key = (*it).first;
00129 
00130         fs << key << fs_map_[key];
00131         it++;
00132       }
00133     }
00134   }
00135 
00136   std::string v4lctlGet(std::string name)
00137   {
00138     FILE *pipe;
00139     char stdout[128];
00140     std::string result;
00141     std::stringstream ss;
00142 
00143     ss << "v4lctl -c " << device_ << " show \"" << name << "\"";
00144 
00145     if ((pipe=popen(ss.str().c_str(), "r")))
00146     {
00147       if (fgets(stdout, sizeof(stdout), pipe))
00148         result = boost::regex_replace(std::string(stdout), boost::regex("^" + name + ": ([a-zA-Z0-9\\-]+).*"), "$1");
00149 
00150       ROS_INFO_STREAM("Call '" << ss.str() << "' Result: " << result);
00151 
00152       pclose(pipe);
00153     }
00154     else
00155       ROS_ERROR_STREAM("Call failed '" << ss.str() << "'");
00156 
00157     return result;
00158   }
00159 
00160   bool v4lctlSet(std::string name, std::string value)
00161   {
00162     std::stringstream ss;
00163     bool result = false;
00164 
00165     ss << "v4lctl -c " << device_ << " " << name << " " << value;
00166 
00167     ROS_INFO_STREAM("Call '" << ss.str() << "'");
00168 
00169     if ((result=std::system(ss.str().c_str()) > -1))
00170       fs_map_[YAML_OPT_TO_NAME(name)] = value;
00171 
00172     return result;
00173   }
00174 
00175   void restoreFromYaml()
00176   {
00177     cv::FileStorage fs;
00178 
00179     if (fs.open(yaml_, cv::FileStorage::READ))
00180     {
00181       cv::FileNode fn = fs.root();
00182 
00183       for (cv::FileNodeIterator fit = fn.begin(); fit != fn.end(); fit++)
00184       {
00185         cv::FileNode item = *fit;
00186 
00187         v4lctlSet(YAML_NAME_TO_OPT(item.name()), (std::string)item);
00188       }
00189     }
00190   }
00191 
00192   void initConfig(v4lctlNodeDynConfig &config, bool defaults = false)
00193   {
00194     std::string s;
00195 
00196 #define V4LCTL_GET_PERCENT(name,default,max) (defaults || (s=v4lctlGet(name)).empty() ? default : (atoi(s.c_str()) * 100 / max))
00197 #define V4LCTL_GET_BOOL(name,default)        (defaults || (s=v4lctlGet(name)).empty() ? default : boost::regex_match(s, boost::regex("^on\$")))
00198 #define V4LCTL_GET_INT(name,default)         (defaults || (s=v4lctlGet(name)).empty() ? default : atoi(s.c_str()))
00199 #define V4LCTL_GET_STRING(name,default)      (defaults || (s=v4lctlGet(name)).empty() ? default : s)
00200 
00201     config.input            = V4LCTL_GET_STRING ("input",           "Composite0");
00202     config.norm             = V4LCTL_GET_STRING ("norm",                 "PAL-I");
00203     config.bright           = V4LCTL_GET_PERCENT("bright",             50, 65280);
00204     config.contrast         = V4LCTL_GET_PERCENT("contrast",           40, 65280);
00205     config.color            = V4LCTL_GET_PERCENT("color",              50, 65280);
00206     config.hue              = V4LCTL_GET_PERCENT("hue",                50, 65280);
00207     config.UV_Ratio         = V4LCTL_GET_INT    ("UV Ratio",                  50);
00208     config.Coring           = V4LCTL_GET_INT    ("Coring",                     0);
00209     config.Whitecrush_Lower = V4LCTL_GET_PERCENT("Whitecrush Lower",     50, 255);
00210     config.Whitecrush_Upper = V4LCTL_GET_PERCENT("Whitecrush Upper",     80, 255);
00211     config.mute             = V4LCTL_GET_BOOL   ("mute",                   false);
00212     config.Chroma_AGC       = V4LCTL_GET_BOOL   ("Chroma AGC",             false);
00213     config.Color_Killer     = V4LCTL_GET_BOOL   ("Color Killer",           false);
00214     config.Comb_Filter      = V4LCTL_GET_BOOL   ("Comb Filter",            false);
00215     config.Auto_Mute        = V4LCTL_GET_BOOL   ("Auto Mute",               true);
00216     config.Luma_Decim       = V4LCTL_GET_BOOL   ("Luma Decimation Filter", false);
00217     config.AGC_Crush        = V4LCTL_GET_BOOL   ("AGC Crush",               true);
00218     config.VCR_Hack         = V4LCTL_GET_BOOL   ("VCR Hack",               false);
00219     config.Full_Luma        = V4LCTL_GET_BOOL   ("Full Luma Range",        false);
00220   }
00221 
00222   void configCb(v4lctlNodeDynConfig &config, int level)
00223   {
00224     if (level < 0)
00225     {
00226       initConfig(config);
00227       cfg_ = config;
00228 
00229       ROS_INFO("Reconfigure server initialized");
00230 
00231       return;
00232     }
00233 
00234     if (config.Set_Defaults)
00235     {
00236       initConfig(config, true);
00237       config.Set_Defaults = false;
00238     }
00239 
00240     if (config.input != cfg_.input)
00241       v4lctlSet("setattr input", config.input);
00242 
00243     if (config.norm != cfg_.norm)
00244       v4lctlSet("setnorm", config.norm);
00245 
00246     if (config.bright != cfg_.bright)
00247       v4lctlSet("bright", std::to_string(config.bright)+'%');
00248 
00249     if (config.contrast != cfg_.contrast)
00250       v4lctlSet("contrast", std::to_string(config.contrast)+'%');
00251 
00252     if (config.color != cfg_.color)
00253       v4lctlSet("color", std::to_string(config.color)+'%');
00254 
00255     if (config.hue != cfg_.hue)
00256       v4lctlSet("hue", std::to_string(config.hue)+'%');
00257 
00258     if (config.UV_Ratio != cfg_.UV_Ratio)
00259       v4lctlSet("setattr \"UV Ratio\"", std::to_string(config.UV_Ratio)+'%');
00260 
00261     if (config.Coring != cfg_.Coring)
00262       v4lctlSet("setattr Coring", std::to_string(config.Coring));
00263 
00264     if (config.Whitecrush_Lower != cfg_.Whitecrush_Lower)
00265       v4lctlSet("setattr \"Whitecrush Lower\"", std::to_string(config.Whitecrush_Lower)+'%');
00266 
00267     if (config.Whitecrush_Upper != cfg_.Whitecrush_Upper)
00268       v4lctlSet("setattr \"Whitecrush Upper\"", std::to_string(config.Whitecrush_Upper)+'%');
00269 
00270     if (config.mute != cfg_.mute)
00271       v4lctlSet("setattr mute", config.mute ? "on" : "off");
00272 
00273     if (config.Chroma_AGC != cfg_.Chroma_AGC)
00274       v4lctlSet("setattr \"Chroma AGC\"", config.Chroma_AGC ? "on" : "off");
00275 
00276     if (config.Color_Killer != cfg_.Color_Killer)
00277       v4lctlSet("setattr \"Color Killer\"", config.Color_Killer ? "on" : "off");
00278 
00279     if (config.Comb_Filter != cfg_.Comb_Filter)
00280       v4lctlSet("setattr \"Comb Filter\"", config.Comb_Filter ? "on" : "off");
00281 
00282     if (config.Auto_Mute != cfg_.Auto_Mute)
00283       v4lctlSet("setattr \"Auto Mute\"", config.Auto_Mute ? "on" : "off");
00284 
00285     if (config.Luma_Decim != cfg_.Luma_Decim)
00286       v4lctlSet("setattr \"Luma Decimation Filter\"", config.Luma_Decim ? "on" : "off");
00287 
00288     if (config.AGC_Crush != cfg_.AGC_Crush)
00289       v4lctlSet("setattr \"AGC Crush\"", config.AGC_Crush ? "on" : "off");
00290 
00291     if (config.VCR_Hack != cfg_.VCR_Hack)
00292       v4lctlSet("setattr \"VCR Hack\"", config.VCR_Hack ? "on" : "off");
00293 
00294     if (config.Full_Luma != cfg_.Full_Luma)
00295       v4lctlSet("setattr \"Full Luma Range\"", config.Full_Luma ? "on" : "off");
00296 
00297     cfg_ = config;
00298   }
00299 
00300   bool v4lctlGetCb(v4lctlGet::Request  &req, v4lctlGet::Response &res)
00301   {
00302     res.result = v4lctlGet(req.name);
00303 
00304     return true;
00305   }
00306 
00307   bool v4lctlSetCb(v4lctlSet::Request  &req, v4lctlSet::Response &res)
00308   {
00309     return v4lctlSet(req.name, req.value);
00310   }
00311 };
00312 
00313 }
00314 
00315 int main(int argc, char **argv)
00316 {
00317   ros::init(argc, argv, "v4lctl");
00318 
00319   uavc_v4lctl::v4lctlNode n;
00320 
00321   ros::spin();
00322 
00323   return 0;
00324 }


uavc_v4lctl
Author(s):
autogenerated on Sat Jun 8 2019 20:39:09