Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00036 
00037 #ifndef CAMERA_OFFSETTER_GENERIC_OFFSETTER_H_
00038 #define CAMERA_OFFSETTER_GENERIC_OFFSETTER_H_
00039 
00040 #include <ros/ros.h>
00041 
00042 #include <tf/transform_broadcaster.h>
00043 #include <tf/transform_datatypes.h>
00044 
00045 #include <geometry_msgs/Pose.h>
00046 #include <geometry_msgs/Twist.h>
00047 
00048 #include <boost/thread.hpp>
00049 #include <boost/thread/mutex.hpp>
00050 
00051 #include <fstream>
00052 
00053 namespace camera_offsetter
00054 {
00055 
00056 class GenericOffsetter
00057 {
00058 public:
00059   GenericOffsetter() : virtual_offset_( btQuaternion(0,0,0,1))
00060   {
00061     pose_sub_ = nh_.subscribe("virtual_pose", 1, &GenericOffsetter::poseCb, this);
00062     twist_sub_ = nh_.subscribe("virtual_twist", 1, &GenericOffsetter::twistCb, this);
00063 
00064     ros::NodeHandle private_nh_("~");
00065 
00066     private_nh_.param("config_file", config_file_, std::string("N/A"));
00067 
00068     
00069     frame_suffix_ = "_offset";
00070 
00071     readConfig();
00072   }
00073 
00074   void readConfig()
00075   {
00076     if(config_file_==std::string("N/A"))
00077     {
00078       ROS_WARN("No config file is set");
00079       return;
00080     }
00081 
00082     geometry_msgs::PosePtr p(new geometry_msgs::Pose());
00083     std::fstream f (config_file_.c_str(), std::fstream::in);
00084     if(!f.is_open())
00085     {
00086       ROS_WARN("Couldn't open config file");
00087       return;
00088     }
00089     f >> p->position.x;
00090     f >> p->position.y;
00091     f >> p->position.z;
00092     f >> p->orientation.x;
00093     f >> p->orientation.y;
00094     f >> p->orientation.z;
00095     f >> p->orientation.w;
00096     f >> baseline_factor_;
00097     ROS_INFO_STREAM(p->orientation.x);
00098     ROS_INFO_STREAM(p);
00099     poseCb(p);
00100   }
00101   void saveConfig()
00102   {
00103     if(config_file_==std::string("N/A"))
00104     {
00105       ROS_WARN("No config file is set");
00106       return;
00107     }
00108     printf("saveConfig (%s)\n", config_file_.c_str());
00109     std::fstream f (config_file_.c_str(), std::fstream::out);
00110     f << virtual_offset_.getOrigin().x() << " ";
00111     f << virtual_offset_.getOrigin().y() << " ";
00112     f << virtual_offset_.getOrigin().z() << std::endl;
00113     f << virtual_offset_.getRotation().x()<< " ";
00114     f << virtual_offset_.getRotation().y()<< " ";
00115     f << virtual_offset_.getRotation().z()<< " ";
00116     f << virtual_offset_.getRotation().w() << std::endl;
00117     f << baseline_factor_;
00118   }
00119 
00120   void poseCb(const geometry_msgs::PoseConstPtr& msg)
00121   {
00122     boost::mutex::scoped_lock lock(offset_mutex_);
00123     tf::poseMsgToTF(*msg, virtual_offset_);
00124   }
00125 
00126   void twistCb(const geometry_msgs::TwistConstPtr& msg)
00127   {
00128     boost::mutex::scoped_lock lock(offset_mutex_);
00129 
00130     btVector3 rot_vector(msg->angular.x, msg->angular.y, msg->angular.z);
00131     double angle = rot_vector.length();
00132 
00133     btQuaternion rot;
00134     if (angle < 1e-6)
00135     {
00136       rot = btQuaternion(0,0,0,1);
00137     }
00138     else
00139       rot = btQuaternion( rot_vector, angle);
00140 
00141     btVector3 trans( msg->linear.x, msg->linear.y, msg->linear.z);
00142 
00143     btTransform incrementalT(rot, trans);
00144 
00145     virtual_offset_ = virtual_offset_ * incrementalT;
00146 
00147     saveConfig();
00148   }
00149 
00150   void publishTransform(const ros::Time& time, const std::string frame_id, const std::string parent_id)
00151   {
00152     boost::mutex::scoped_lock lock(offset_mutex_);
00153                 
00154                 
00155                 
00156                 
00157                 
00158                 
00159                 
00160                 
00161     tf_.sendTransform(tf::StampedTransform(virtual_offset_, time, parent_id, frame_id));
00162   }
00163 
00164 protected:
00165   std::string frame_suffix_;
00166   double baseline_factor_;
00167 
00168 private:
00169   ros::NodeHandle nh_;
00170 
00171   ros::Subscriber pose_sub_;
00172   ros::Subscriber twist_sub_;
00173 
00174   tf::TransformBroadcaster tf_;
00175 
00176   std::string config_file_;
00177 
00178   boost::mutex offset_mutex_;
00179   btTransform virtual_offset_;
00180 };
00181 
00182 
00183 }
00184 
00185 #endif