client.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: file.h 3496 2011-11-22 15:14:32Z fnovotny $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  * Contact visp@irisa.fr if any conditions of this licensing are
34  * not clear to you.
35  *
36  * Description:
37  * Client node
38  *
39  * Authors:
40  * Filip Novotny
41  *
42  *
43  *****************************************************************************/
44 
50 #include "client.h"
51 #include <geometry_msgs/Transform.h>
52 #include "visp_hand2eye_calibration/TransformArray.h"
53 #include <visp_bridge/3dpose.h>
54 #include "names.h"
55 
56 #include <visp/vpCalibration.h>
57 #include <visp/vpExponentialMap.h>
58 
60 {
62 {
64  = n_.advertise<geometry_msgs::Transform> (visp_hand2eye_calibration::camera_object_topic, 1000);
66  = n_.advertise<geometry_msgs::Transform> (visp_hand2eye_calibration::world_effector_topic, 1000);
67 
69  = n_.serviceClient<visp_hand2eye_calibration::reset> (visp_hand2eye_calibration::reset_service);
71  = n_.serviceClient<visp_hand2eye_calibration::compute_effector_camera> (
74  = n_.serviceClient<visp_hand2eye_calibration::compute_effector_camera_quick> (
76 }
77 
79 {
80  ROS_INFO("Waiting for topics...");
81  ros::Duration(1.).sleep();
83  if(!ros::ok()) return;
84  ros::Duration(1).sleep();
85  }
86 
87 
88  // We want to calibrate the hand to eye extrinsic camera parameters from 6 couple of poses: cMo and wMe
89  const int N = 6;
90  // Input: six couple of poses used as input in the calibration proces
91  vpHomogeneousMatrix cMo; // eye (camera) to object transformation. The object frame is attached to the calibrartion grid
92  vpHomogeneousMatrix wMe; // world to hand (end-effector) transformation
93  vpHomogeneousMatrix eMc; // hand (end-effector) to eye (camera) transformation
94 
95  // Initialize an eMc transformation used to produce the simulated input transformations cMo and wMe
96  vpTranslationVector etc(0.1, 0.2, 0.3);
97  vpThetaUVector erc;
98  erc[0] = vpMath::rad(10); // 10 deg
99  erc[1] = vpMath::rad(-10); // -10 deg
100  erc[2] = vpMath::rad(25); // 25 deg
101 
102 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
103  eMc.build(etc, erc);
104 #else
105  eMc.buildFrom(etc, erc);
106 #endif
107  ROS_INFO("1) GROUND TRUTH:");
108 
109  ROS_INFO_STREAM("hand to eye transformation: " <<std::endl<<visp_bridge::toGeometryMsgsTransform(eMc)<<std::endl);
110 
111  vpColVector v_c(6); // camera velocity used to produce 6 simulated poses
112  for (int i = 0; i < N; i++)
113  {
114  v_c = 0;
115  if (i == 0)
116  {
117  // Initialize first poses
118 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
119  cMo.build(0, 0, 0.5, 0, 0, 0); // z=0.5 m
120  wMe.build(0, 0, 0, 0, 0, 0); // Id
121 #else
122  cMo.buildFrom(0, 0, 0.5, 0, 0, 0); // z=0.5 m
123  wMe.buildFrom(0, 0, 0, 0, 0, 0); // Id
124 #endif
125  }
126  else if (i == 1)
127  v_c[3] = M_PI / 8;
128  else if (i == 2)
129  v_c[4] = M_PI / 8;
130  else if (i == 3)
131  v_c[5] = M_PI / 10;
132  else if (i == 4)
133  v_c[0] = 0.5;
134  else if (i == 5)
135  v_c[1] = 0.8;
136 
137  vpHomogeneousMatrix cMc; // camera displacement
138  cMc = vpExponentialMap::direct(v_c); // Compute the camera displacement due to the velocity applied to the camera
139  if (i > 0)
140  {
141  // From the camera displacement cMc, compute the wMe and cMo matrixes
142  cMo = cMc.inverse() * cMo;
143  wMe = wMe * eMc * cMc * eMc.inverse();
144 
145  }
146 
147  geometry_msgs::Transform pose_c_o;
148  pose_c_o = visp_bridge::toGeometryMsgsTransform(cMo);
149  geometry_msgs::Transform pose_w_e;
150  pose_w_e = visp_bridge::toGeometryMsgsTransform(wMe);
153  emc_quick_comm.request.camera_object.transforms.push_back(pose_c_o);
154  emc_quick_comm.request.world_effector.transforms.push_back(pose_w_e);
155 
156  }
157  ros::Duration(1.).sleep();
158 
159 }
160 
162 {
163  vpHomogeneousMatrix eMc;
164  vpThetaUVector erc;
165  ROS_INFO("2) QUICK SERVICE:");
167  {
168  ROS_INFO_STREAM("hand_camera: "<< std::endl << emc_quick_comm.response.effector_camera);
169  }
170  else
171  {
172  ROS_ERROR("Failed to call service");
173  }
174 }
175 
177 {
178  vpHomogeneousMatrix eMc;
179  vpThetaUVector erc;
180  ROS_INFO("3) TOPIC STREAM:");
182  {
183  ROS_INFO_STREAM("hand_camera: " << std::endl << emc_comm.response.effector_camera);
184  }
185  else
186  {
187  ROS_ERROR("Failed to call service");
188  }
189 
190 }
191 }
192 
193 /*
194  * Local variables:
195  * c-basic-offset: 2
196  * End:
197  */
visp_hand2eye_calibration::Client::camera_object_publisher_
ros::Publisher camera_object_publisher_
Definition: client.h:62
visp_hand2eye_calibration::Client::compute_effector_camera_quick_service_
ros::ServiceClient compute_effector_camera_quick_service_
Definition: client.h:66
visp_hand2eye_calibration::Client::reset_comm
visp_hand2eye_calibration::reset reset_comm
Definition: client.h:68
visp_hand2eye_calibration::Client::computeFromTopicStream
void computeFromTopicStream()
Definition: client.cpp:176
visp_hand2eye_calibration::Client::initAndSimulate
void initAndSimulate()
Definition: client.cpp:78
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
visp_hand2eye_calibration::Client::emc_quick_comm
visp_hand2eye_calibration::compute_effector_camera_quick emc_quick_comm
Definition: client.h:70
visp_hand2eye_calibration::world_effector_topic
std::string world_effector_topic
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
visp_hand2eye_calibration::Client::n_
ros::NodeHandle n_
Definition: client.h:61
visp_hand2eye_calibration::camera_object_topic
std::string camera_object_topic
visp_bridge::toGeometryMsgsTransform
geometry_msgs::Transform toGeometryMsgsTransform(const vpHomogeneousMatrix &mat)
3dpose.h
visp_hand2eye_calibration::Client::world_effector_publisher_
ros::Publisher world_effector_publisher_
Definition: client.h:63
visp_hand2eye_calibration::Client::emc_comm
visp_hand2eye_calibration::compute_effector_camera emc_comm
Definition: client.h:69
visp_hand2eye_calibration::Client::Client
Client()
Definition: client.cpp:61
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
visp_hand2eye_calibration
Definition: calibrator.cpp:61
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
visp_hand2eye_calibration::Client::reset_service_
ros::ServiceClient reset_service_
Definition: client.h:64
ros::Duration::sleep
bool sleep() const
visp_hand2eye_calibration::Client::compute_effector_camera_service_
ros::ServiceClient compute_effector_camera_service_
Definition: client.h:65
names.h
File containing names of topics or services used all accross the package.
visp_hand2eye_calibration::reset_service
std::string reset_service
visp_hand2eye_calibration::compute_effector_camera_quick_service
std::string compute_effector_camera_quick_service
ROS_INFO
#define ROS_INFO(...)
visp_hand2eye_calibration::compute_effector_camera_service
std::string compute_effector_camera_service
visp_hand2eye_calibration::Client::computeUsingQuickService
void computeUsingQuickService()
Definition: client.cpp:161
ros::Duration
client.h
Client node calling a quick compute service, a compute service and 2 publishing to world_effector_top...


visp_hand2eye_calibration
Author(s): Filip Novotny
autogenerated on Sat Aug 24 2024 02:54:54