config_cam.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
35 #include <iostream>
36 #include <stdio.h>
37 #include <ros/ros.h>
38 #include <sensor_msgs/Image.h>
39 #include <sensor_msgs/CameraInfo.h>
40 #include <image_transport/image_transport.h>
41 #include <signal.h>
42 #include <fstream>
43 #include <tf/transform_listener.h>
44 #include <tf/tf.h>
45 #include <ros/package.h>
46 #include <math.h>
47 using namespace std;
48 
52 void sighandler(int sig)
53 {
54  ROS_ERROR("Signal %d caught...",sig);
55  cout<<"Shuting down road_recognition"<<endl;
56  exit(0);
57 }
58 
62 void Callback(const sensor_msgs::CameraInfoPtr& cam_info)
63 {
64  tf::TransformListener lt;
65  tf::StampedTransform trans_cam;
66 
67  string target_ref = "/atc/vehicle/center_bumper";
68  string ref = cam_info->header.frame_id;
69 
70  /* Obter as transformações dos referenciais */
71  try
72  {
73  lt.lookupTransform( ref.c_str() , target_ref.c_str() , ros::Time(0), trans_cam);
74  ROS_INFO("Found");
75  }
76  catch (tf::TransformException ex)
77  {
78  ROS_INFO("Transformation not found: entered catch for 1.5 seconds!");
79  if(lt.waitForTransform( ref.c_str() , target_ref.c_str(),ros::Time(0), ros::Duration(1.5)))
80  {
81  try
82  {
83  lt.lookupTransform( ref.c_str() , target_ref.c_str() , ros::Time(0), trans_cam);
84  ROS_INFO("Found");
85  }
86  catch (tf::TransformException ex)
87  {
88  ROS_ERROR("Transformation not found: tansforrmation not found after waiting 1.5 seconds\n.%s",ex.what());
89  }
90  }
91  else
92  {
93  ROS_ERROR("Transformation not found: Could not find valid transform after waiting 1.5 seconds\n.%s",ex.what());
94  exit(0);
95  }
96 
97  };
98 
99  double R,P,Y;
100  tf::Quaternion q;
101  q = trans_cam.getRotation();
102  double height = trans_cam.getOrigin().z() * 1000;
103  /* convert from quaternion to RPY */
104  tf::Matrix3x3(q).getRPY(R, P, Y);
105 
106  /* Show camera configurations*/
107  cout<<"---> Camera configurations"<<endl;
108  cout<<"imge size "<<endl<<"\t"<<cam_info->height<<" x "<<cam_info->width<<endl;
109  cout<<"distortion_model:"<<endl<<"\t"<<cam_info->distortion_model<<endl;
110  cout<<"focal lengthstrans_cam"<<endl<<"\t fx ="<<cam_info->K[0]<<" fy = "<<cam_info->K[4]<<endl;
111  cout<<"principal point"<<endl<<"\t cx ="<<cam_info->K[2]<<" cy = "<<cam_info->K[5]<<endl;
112  cout<<"cameraHeight = "<<endl;
113  cout<<"pitch ="<<P<<endl;
114  cout<<"yaw = "<<Y<<endl;
115 
116  /* Converter de radianos para graus */
117  P = (P + (M_PI/2)) * ( 180/M_PI );
118  Y = (Y + (M_PI/2)) * ( 180/M_PI );
119 
120  /* Save camera configuration do file */
121  /* Abrir o ficheiro */
122  std::string file_path=ros::package::getPath("caltech_lanes")+"/config/CameraInfo.conf";
123  cout<<"file_path:"<<file_path<<endl;
124  ofstream myfile(file_path.c_str(),ios::trunc);
125  if (myfile.is_open())
126  {
127  /* Escrever as definições da camera dectro do ficheiro */
128  myfile<<"\n# focal length\n";
129  myfile<<"focalLengthX "<<cam_info->K[0]<<"\n";
130  myfile<<"focalLengthY "<<cam_info->K[4]<<"\n";
131  myfile<<"\n# optical center \n";
132  myfile<<"opticalCenterX "<<cam_info->K[2]<<"\n";
133  myfile<<"opticalCenterY "<<cam_info->K[5]<<"\n";
134  myfile<<"\n# height of the camera in mm\n";
135  myfile<<"cameraHeight "<<height<<"\n";
136  myfile<<"\n# pitch of the camera\n";
137  myfile<<"pitch "<<P<<"\n";
138  myfile<<"\n# yaw of the camera\n";
139  myfile<<"yaw "<<Y<<"\n";
140  myfile<<"\n# imag width and height\n";
141  myfile<<"imageWidth "<<cam_info->width<<"\n";
142  myfile<<"imageHeight "<<cam_info->height<<"\n";
143  /* fechar o ficheiro */
144  myfile.close();
145  /* Configurações gravadas com sucesso */
146  cout<<"---> Camera configurations Updated"<<endl;
147  exit(0); /* terminar o programa */
148  }
149  else
150  {
151  cout << "Unable to open file"<<endl;
152  exit(0);
153  }
154 }
155 
159 int main(int argc, char **argv)
160 {
161  ros::init(argc, argv, "camera_configurations");
162 
163  string messages;
164  ros::NodeHandle nh("~");
165  /* obter os parametros de entrada do launch file */
166  nh.param("cam_info",messages,string("/snr/scam/wide/left/camera_info"));
167 // nh.param("ref",ref,string("/atc/camera/xb3/left") );
168  /* parametros subscritos do launch file */
169  cout<<"cam_info: "<<messages<<endl;
170 // cout<<"ref: "<<ref<<endl;
171  /* Obter as definições das cameras do Atlas e guardar para ficheiro */
172  signal(SIGINT, &sighandler);
173  ROS_INFO("messages = %s",messages.c_str());
174  ros::Subscriber sub = nh.subscribe(messages.c_str(), 1, Callback);
175  ros::spin();
176  return 0;
177 }
int main(int argc, char **argv)
Definition: config_cam.cpp:159
void sighandler(int sig)
Definition: config_cam.cpp:52
void Callback(const sensor_msgs::CameraInfoPtr &cam_info)
Definition: config_cam.cpp:62
Definition: ranker.h:42


caltech_lanes
Author(s): Ricardo Morais
autogenerated on Mon Mar 2 2015 01:31:31