ScitosServer.cpp
Go to the documentation of this file.
00001 
00002 #include <string>
00003 
00004 #include <ros/ros.h>
00005 
00006 #include "ScitosBase.h"
00007 
00008 #define SCHUNK_NOT_AMTEC 0
00009 #include "SchunkServer.h"
00010 
00011 
00012 
00013 void robotArmThread(ScitosBase& scitos_base, ros::NodeHandle nh_schunk) {
00014         ROS_INFO("Starting ros schunk connector...");
00015         SchunkServer schunk_server(nh_schunk);
00016 
00017         try {
00018                 while (nh_schunk.ok())
00019                         boost::this_thread::sleep(boost::posix_time::minutes(42));
00020         }
00021         catch(const boost::thread_interrupted&) {
00022                 ROS_INFO("Robot arm thread was interrupted and returns, stopping the arm interface.");
00023         }
00024 }
00025 
00026 
00027 int main(int argc, char **argv) {
00028         ros::init(argc, argv, "metralabs_ros");
00029 
00030         ros::NodeHandle nh_private("~");
00031         ros::NodeHandle nh_scitos("scitos");
00032         ros::NodeHandle nh_schunk("schunk");
00033 
00034 
00036 
00037         std::string scitos_config_file;
00038         nh_private.param<std::string>("scitos_config_file", scitos_config_file,
00039                         "/opt/MetraLabs/MLRobotic/etc/config/SCITOS-G5_without_Head_config.xml");
00040 
00041 
00043 
00044         ROS_INFO("Starting robot base...");
00045         ScitosBase base(scitos_config_file.c_str(), argc, argv, nh_scitos);
00046 
00047 
00049 
00050         boost::thread robot_arm_thread_;
00051         std::string robot_arm_class;
00052         if(nh_private.getParam("robot_arm_class", robot_arm_class) && robot_arm_class != "None") {
00053                 // if the parameter exists and does not match "None"
00054                 robot_arm_thread_ = boost::thread(robotArmThread, boost::ref(base), boost::ref(nh_schunk));
00055         }
00056 
00057 
00059 
00060         ROS_INFO("Initializing done, starting ROS spinner");
00061         ros::spin();
00062 
00063 
00064         // clean up
00065 
00066         if(robot_arm_thread_.joinable()) {
00067                 robot_arm_thread_.interrupt();
00068                 robot_arm_thread_.join();
00069         }
00070         else
00071                 ROS_WARN("robot arm thread not joinable, should this happen?");
00072 
00073         return 0;
00074 }


metralabs_ros
Author(s): Yianni Gatsoulis and Chris Burbridge and Lorenzo Riano and Felix Kolbe
autogenerated on Tue Jan 7 2014 11:38:56