00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016 #include <ros/ros.h>
00017 #include <ros/package.h>
00018 #include <actionlib/server/simple_action_server.h>
00019
00020 #include <cob_mimic/SetMimicAction.h>
00021 #include <cob_mimic/SetMimicGoal.h>
00022 #include <cob_mimic/SetMimicFeedback.h>
00023 #include <cob_mimic/SetMimicResult.h>
00024
00025 #include <cob_mimic/SetMimic.h>
00026 #include <cob_mimic/SetMimicRequest.h>
00027 #include <cob_mimic/SetMimicResponse.h>
00028
00029 #include <vlc/vlc.h>
00030 #include <unistd.h>
00031
00032 #include <boost/thread.hpp>
00033 #include <boost/filesystem.hpp>
00034 #include <boost/random/mersenne_twister.hpp>
00035 #include <boost/random/uniform_real_distribution.hpp>
00036 #include <boost/random/uniform_int_distribution.hpp>
00037
00038 class Mimic
00039 {
00040 public:
00041 Mimic():
00042 as_mimic_(nh_, ros::this_node::getName() + "/set_mimic", boost::bind(&Mimic::as_cb_mimic_, this, _1), false),
00043 new_mimic_request_(false), sim_enabled_(false), real_dist_(2,10), int_dist_(0,6)
00044 {
00045 nh_ = ros::NodeHandle("~");
00046 }
00047
00048 ~Mimic(void)
00049 {
00050 libvlc_media_player_stop(vlc_player_);
00051 libvlc_media_player_release(vlc_player_);
00052 libvlc_release(vlc_inst_);
00053 }
00054
00055 bool init()
00056 {
00057 if(!copy_mimic_files())
00058 return false;
00059
00060 sim_enabled_ = nh_.param<bool>("sim", false);
00061 srvServer_mimic_ = nh_.advertiseService("set_mimic", &Mimic::service_cb_mimic, this);
00062
00063 random_mimics_.push_back("blinking");
00064 random_mimics_.push_back("blinking");
00065 random_mimics_.push_back("blinking");
00066 random_mimics_.push_back("blinking_left");
00067 random_mimics_.push_back("blinking_right");
00068
00069 int_dist_ = boost::random::uniform_int_distribution<>(0,static_cast<int>(random_mimics_.size())-1);
00070
00071 char const *argv[] =
00072 {
00073 "--ignore-config",
00074 "--mouse-hide-timeout=0",
00075 "-q",
00076 "--no-osd",
00077 "-L",
00078 "--one-instance",
00079 "--playlist-enqueue",
00080 "--no-video-title-show",
00081 "--no-skip-frames",
00082 "--no-audio",
00083 "--vout=glx,none"
00084 };
00085 int argc = sizeof( argv ) / sizeof( *argv );
00086
00087 vlc_inst_ = libvlc_new(argc, argv);
00088 if(!vlc_inst_){ROS_ERROR("failed to create libvlc instance"); return false;}
00089 vlc_player_ = libvlc_media_player_new(vlc_inst_);
00090 if(!vlc_player_){ROS_ERROR("failed to create vlc media player object"); return false;}
00091
00092 if(!sim_enabled_){libvlc_set_fullscreen(vlc_player_, 1);}
00093 set_mimic("default", 1, 1.0, false);
00094 blinking_timer_ = nh_.createTimer(ros::Duration(real_dist_(gen_)), &Mimic::blinking_cb, this, true);
00095 as_mimic_.start();
00096 return true;
00097 }
00098
00099 private:
00100 ros::NodeHandle nh_;
00101 actionlib::SimpleActionServer<cob_mimic::SetMimicAction> as_mimic_;
00102 ros::ServiceServer srvServer_mimic_;
00103 ros::Timer blinking_timer_;
00104 std::string mimic_folder_;
00105
00106 libvlc_instance_t* vlc_inst_;
00107 libvlc_media_player_t* vlc_player_;
00108 libvlc_media_t* vlc_media_;
00109
00110 bool sim_enabled_;
00111 bool new_mimic_request_;
00112 boost::mutex mutex_;
00113
00114 boost::random::mt19937 gen_;
00115 boost::random::uniform_real_distribution<> real_dist_;
00116 boost::random::uniform_int_distribution<> int_dist_;
00117 std::vector<std::string> random_mimics_;
00118
00119 bool copy_mimic_files()
00120 {
00121 char *lgn;
00122 if((lgn = getlogin()) == NULL)
00123 {
00124 lgn = getenv("USER");
00125 if(lgn == NULL || std::string(lgn) == "")
00126 {
00127 ROS_ERROR("unable to get user name");
00128 return false;
00129 }
00130 }
00131 std::string username(lgn);
00132 mimic_folder_ = "/tmp/mimic_" + username;
00133 ROS_INFO("copying all mimic files to %s...", mimic_folder_.c_str());
00134 std::string pkg_path = ros::package::getPath("cob_mimic");
00135 std::string mimics_path = pkg_path + "/common";
00136
00137 try{
00138 if(boost::filesystem::exists(mimic_folder_))
00139 {
00140 boost::filesystem::remove_all(mimic_folder_);
00141 }
00142 }
00143 catch(boost::filesystem::filesystem_error const & e)
00144 {
00145 ROS_ERROR_STREAM(std::string(e.what()));
00146 return false;
00147 }
00148
00149 if(copy_dir(boost::filesystem::path(mimics_path), boost::filesystem::path(mimic_folder_)) )
00150 {
00151 ROS_INFO("...copied all mimic files to %s", mimic_folder_.c_str());
00152 return true;
00153 }
00154 else
00155 {
00156 ROS_ERROR("...could not copy mimic files to %s", mimic_folder_.c_str());
00157 return false;
00158 }
00159 }
00160
00161 void as_cb_mimic_(const cob_mimic::SetMimicGoalConstPtr &goal)
00162 {
00163 blinking_timer_.stop();
00164
00165 if(set_mimic(goal->mimic, goal->repeat, goal->speed))
00166 as_mimic_.setSucceeded();
00167 else
00168 as_mimic_.setAborted();
00169
00170 if(goal->mimic != "falling_asleep" && goal->mimic != "sleeping")
00171 blinking_timer_ = nh_.createTimer(ros::Duration(real_dist_(gen_)), &Mimic::blinking_cb, this, true);
00172 }
00173
00174 bool service_cb_mimic(cob_mimic::SetMimic::Request &req,
00175 cob_mimic::SetMimic::Response &res )
00176 {
00177 blinking_timer_.stop();
00178
00179 res.success = set_mimic(req.mimic, req.repeat, req.speed);
00180 res.message = "";
00181
00182 if(req.mimic != "falling_asleep" && req.mimic != "sleeping")
00183 blinking_timer_ = nh_.createTimer(ros::Duration(real_dist_(gen_)), &Mimic::blinking_cb, this, true);
00184 return true;
00185 }
00186
00187 bool set_mimic(std::string mimic, int repeat, float speed, bool blocking=true)
00188 {
00189 bool ret = false;
00190 new_mimic_request_=true;
00191 ROS_INFO("New mimic request with: %s", mimic.c_str());
00192 mutex_.lock();
00193 new_mimic_request_=false;
00194 ROS_INFO("Mimic: %s (speed: %f, repeat: %d)", mimic.c_str(), speed, repeat);
00195
00196 std::string filename = mimic_folder_ + "/" + mimic + ".mp4";
00197
00198
00199 if ( !boost::filesystem::exists(filename) )
00200 {
00201 if ( !boost::filesystem::exists(mimic) )
00202 {
00203 ROS_ERROR("File not found: %s", filename.c_str());
00204 mutex_.unlock();
00205 return false;
00206 }
00207 else
00208 {
00209 ROS_INFO("Playing mimic from non-default file: %s", mimic.c_str());
00210 filename = mimic;
00211 }
00212 }
00213
00214
00215 repeat = std::max(1, repeat);
00216
00217
00218 if(speed <= 0)
00219 {
00220 ROS_WARN("Mimic speed cannot be 0 or negative. Setting Speed to 1.0");
00221 speed = 1.0;
00222 }
00223
00224
00225 if(libvlc_media_player_set_rate(vlc_player_, speed)!=0){ROS_ERROR("failed to set movie play rate");}
00226
00227 while(repeat > 0)
00228 {
00229 vlc_media_ = libvlc_media_new_path(vlc_inst_, filename.c_str());
00230 if(!vlc_media_)
00231 {
00232 ROS_ERROR("failed to create media for filepath %s", filename.c_str());
00233 mutex_.unlock();
00234 return false;
00235 }
00236
00237 libvlc_media_player_set_media(vlc_player_, vlc_media_);
00238 libvlc_media_release(vlc_media_);
00239
00240
00241 if(libvlc_media_player_play(vlc_player_)!=0)
00242 {
00243 ROS_ERROR("failed to play");
00244 mutex_.unlock();
00245 return false;
00246 }
00247
00248 ros::Duration(0.1).sleep();
00249 while(blocking && (libvlc_media_player_is_playing(vlc_player_) == 1))
00250 {
00251 ros::Duration(0.1).sleep();
00252 ROS_DEBUG("still playing %s", mimic.c_str());
00253 if(new_mimic_request_)
00254 {
00255 ROS_WARN("mimic %s preempted", mimic.c_str());
00256 mutex_.unlock();
00257 return false;
00258 }
00259 }
00260 repeat --;
00261 }
00262 mutex_.unlock();
00263 return true;
00264 }
00265
00266 void blinking_cb(const ros::TimerEvent&)
00267 {
00268 int rand = int_dist_(gen_);
00269 set_mimic(random_mimics_[rand], 1, 1.5);
00270 blinking_timer_ = nh_.createTimer(ros::Duration(real_dist_(gen_)), &Mimic::blinking_cb, this, true);
00271 }
00272
00273 bool copy_dir( boost::filesystem::path const & source,
00274 boost::filesystem::path const & mimic_folder )
00275 {
00276 namespace fs = boost::filesystem;
00277 try
00278 {
00279
00280 if(!fs::exists(source) || !fs::is_directory(source))
00281 {
00282 ROS_ERROR_STREAM("Source directory " << source.string() << " does not exist or is not a directory.");
00283 return false;
00284 }
00285 if(fs::exists(mimic_folder))
00286 {
00287 ROS_INFO_STREAM("Destination directory " << mimic_folder.string() << " already exists.");
00288 return false;
00289 }
00290
00291 if(!fs::create_directory(mimic_folder))
00292 {
00293 ROS_ERROR_STREAM( "Unable to create mimic_folder directory" << mimic_folder.string());
00294 return false;
00295 }
00296 }
00297 catch(fs::filesystem_error const & e)
00298 {
00299 ROS_ERROR_STREAM(std::string(e.what()));
00300 return false;
00301 }
00302
00303 for(fs::directory_iterator file(source); file != fs::directory_iterator(); ++file)
00304 {
00305 try
00306 {
00307 fs::path current(file->path());
00308 if(fs::is_directory(current))
00309 {
00310
00311 if( !copy_dir(current, mimic_folder / current.filename()) )
00312 return false;
00313 }
00314 else
00315 {
00316
00317 fs::copy_file(current, mimic_folder / current.filename() );
00318 }
00319 }
00320 catch(fs::filesystem_error const & e)
00321 {
00322 ROS_ERROR_STREAM(std::string(e.what()));
00323 }
00324 }
00325 return true;
00326 }
00327 };
00328
00329
00330 int main(int argc, char** argv)
00331 {
00332 ros::init(argc, argv, "mimic");
00333
00334 Mimic mimic;
00335 if(!mimic.init())
00336 {
00337 ROS_ERROR("mimic init failed");
00338 return 1;
00339 }
00340 else
00341 {
00342 ROS_INFO("mimic node started");
00343 ros::spin();
00344 return 0;
00345 }
00346 }