runtime_utils.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Southwest Research Institute
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 
00019 #ifndef RUNTIME_UTILS_H_
00020 #define RUNTIME_UTILS_H_
00021 
00022 #include <industrial_extrinsic_cal/basic_types.h>
00023 #include <industrial_extrinsic_cal/calibration_job_definition.h>
00024 
00025 //#include <ros/ros.h>
00026 #include <tf/transform_datatypes.h>
00027 #include <tf/transform_listener.h>
00028 #include <tf_conversions/tf_eigen.h>
00029 #include <tf/transform_broadcaster.h>
00030 #include <tf/transform_listener.h>
00031 
00032 #include <Eigen/Geometry>
00033 #include <Eigen/Core>
00034 
00035 namespace industrial_extrinsic_cal
00036 {
00037 class ROSRuntimeUtils
00038 {
00039 public:
00040 
00044   ROSRuntimeUtils()
00045   {  };
00046 
00050   ~ROSRuntimeUtils()
00051   {
00052 
00053   };
00054 
00060   tf::Transform pblockToPose(industrial_extrinsic_cal::P_BLOCK &optimized_input);
00061 
00068   bool store_tf_broadcasters(std::string &package_name, std::string &file_name);
00072   std::string camera_file_;
00076   std::string target_file_;
00080   std::string caljob_file_;
00084   std::string world_frame_;
00088   std::vector<std::string> target_frame_;
00092   std::vector<std::string> camera_optical_frame_;
00096   std::vector<std::string> camera_intermediate_frame_;
00097 
00098   //CalJob specific
00102   std::vector<industrial_extrinsic_cal::P_BLOCK> initial_extrinsics_;
00106   std::vector<industrial_extrinsic_cal::P_BLOCK> calibrated_extrinsics_;
00110   std::vector<industrial_extrinsic_cal::P_BLOCK> target_poses_;
00111 
00112 
00113   //TF specific
00117   std::vector<tf::Transform> initial_transforms_;
00121   std::vector<tf::Transform> calibrated_transforms_;
00125   std::vector<tf::StampedTransform> camera_internal_transforms_;
00129   std::vector<tf::StampedTransform> points_to_world_transforms_;
00133   std::vector<tf::Transform> target_transforms_;
00137   std::vector<tf::TransformBroadcaster> broadcasters_;
00141   tf::TransformListener listener_;
00142 
00143 };
00144 
00145 } //end industrial_extrinsic_cal namespace
00146 
00147 #endif /* RUNTIME_UTILS_H_ */


industrial_extrinsic_cal
Author(s): Chris Lewis
autogenerated on Wed Aug 26 2015 12:00:27