handeye_solver_base.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Intel Corporation.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Yu Yan */
36 
37 #pragma once
38 
39 #include <tf2_eigen/tf2_eigen.h>
40 #include <ros/console.h>
41 
43 {
44 enum SensorMountType
45 {
46  EYE_TO_HAND = 0,
47  EYE_IN_HAND = 1,
48 };
49 
51 {
52 public:
53  HandEyeSolverBase() = default;
54  virtual ~HandEyeSolverBase() = default;
55 
56  virtual void initialize() = 0;
57 
63  virtual const std::vector<std::string>& getSolverNames() const = 0;
64 
76  virtual bool solve(const std::vector<Eigen::Isometry3d>& effector_wrt_world,
77  const std::vector<Eigen::Isometry3d>& object_wrt_sensor, SensorMountType setup = EYE_TO_HAND,
78  const std::string& solver_name = "", std::string* error_message = nullptr) = 0;
79 
85  virtual const Eigen::Isometry3d& getCameraRobotPose() const = 0;
86 
97  std::pair<double, double> getReprojectionError(const std::vector<Eigen::Isometry3d>& effector_wrt_world,
98  const std::vector<Eigen::Isometry3d>& object_wrt_sensor,
99  const Eigen::Isometry3d& X, SensorMountType setup = EYE_TO_HAND)
100  {
101  auto ret = std::make_pair(std::numeric_limits<double>::quiet_NaN(), std::numeric_limits<double>::quiet_NaN());
102  if (effector_wrt_world.size() != object_wrt_sensor.size())
103  {
104  ROS_ERROR_NAMED("moveit_calibration_handeye_solver",
105  "Different number of optical and kinematic transforms when calculating reprojection error.");
106  return ret;
107  }
108 
109  if (effector_wrt_world.empty())
110  {
111  return ret;
112  }
113 
114  double rotation_err = 0;
115  double translation_err = 0;
116 
117  const size_t num_motions = effector_wrt_world.size() - 1;
118  for (size_t i = 0; i < num_motions; ++i)
119  {
120  // Calculate both sides of AX = XB
121  Eigen::Isometry3d A;
122  if (setup == EYE_IN_HAND)
123  A = effector_wrt_world[i].inverse() * effector_wrt_world[i + 1];
124  else
125  A = effector_wrt_world[i] * effector_wrt_world[i + 1].inverse();
126  Eigen::Isometry3d B = object_wrt_sensor[i] * object_wrt_sensor[i + 1].inverse();
127 
128  Eigen::Isometry3d AX = A * X;
129  Eigen::Isometry3d XB = X * B;
130 
131  // Rotation error
132  double r_err = Eigen::AngleAxisd(AX.rotation().transpose() * XB.rotation()).angle();
133  rotation_err += r_err * r_err;
134 
135  // Translation error
136  double t_err = ((AX.translation() - XB.translation()).norm() +
137  (AX.inverse().translation() - XB.inverse().translation()).norm()) /
138  2.;
139  translation_err += t_err * t_err;
140  }
141  ret = std::make_pair(std::sqrt(rotation_err / num_motions), std::sqrt(translation_err / num_motions));
142  return ret;
143  }
144 };
145 
146 } // namespace moveit_handeye_calibration
setup
moveit_handeye_calibration::HandEyeSolverBase::~HandEyeSolverBase
virtual ~HandEyeSolverBase()=default
moveit_handeye_calibration::HandEyeSolverBase
Definition: handeye_solver_base.h:82
moveit_handeye_calibration::HandEyeSolverBase::solve
virtual bool solve(const std::vector< Eigen::Isometry3d > &effector_wrt_world, const std::vector< Eigen::Isometry3d > &object_wrt_sensor, SensorMountType setup=EYE_TO_HAND, const std::string &solver_name="", std::string *error_message=nullptr)=0
Calculate camera-robot transform from the input pose samples.
tf2_eigen.h
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit_handeye_calibration::EYE_TO_HAND
@ EYE_TO_HAND
Definition: handeye_solver_base.h:110
moveit_handeye_calibration::EYE_IN_HAND
@ EYE_IN_HAND
Definition: handeye_solver_base.h:111
console.h
A
moveit_handeye_calibration::HandEyeSolverBase::HandEyeSolverBase
HandEyeSolverBase()=default
moveit_handeye_calibration::SensorMountType
SensorMountType
Definition: handeye_solver_base.h:76
moveit_handeye_calibration::HandEyeSolverBase::getSolverNames
virtual const std::vector< std::string > & getSolverNames() const =0
Get the names of available algorithms that can be used from the plugin.
moveit_handeye_calibration
Definition: handeye_solver_base.h:42
moveit_handeye_calibration::HandEyeSolverBase::initialize
virtual void initialize()=0
moveit_handeye_calibration::HandEyeSolverBase::getReprojectionError
std::pair< double, double > getReprojectionError(const std::vector< Eigen::Isometry3d > &effector_wrt_world, const std::vector< Eigen::Isometry3d > &object_wrt_sensor, const Eigen::Isometry3d &X, SensorMountType setup=EYE_TO_HAND)
Get the reprojection error for the given samples.
Definition: handeye_solver_base.h:129
moveit_handeye_calibration::HandEyeSolverBase::getCameraRobotPose
virtual const Eigen::Isometry3d & getCameraRobotPose() const =0
Get the result of the calibration, i.e. the camera pose with respect to the robot.


moveit_calibration_plugins
Author(s): Yu Yan
autogenerated on Fri Oct 18 2024 02:14:08