handeye_solver_default.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 
40 #include <ros/ros.h>
41 
42 // Disable clang warnings
43 #if defined(__clang__)
44 #pragma clang diagnostic push
45 #pragma clang diagnostic ignored "-Wdeprecated-register"
46 #include <Python.h>
47 #pragma clang diagnostic pop
48 #elif defined(__GNUC__) || defined(__GNUG__)
49 #include <Python.h>
50 #endif
51 
52 #define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION
53 #include <numpy/arrayobject.h>
54 
56 {
57 constexpr auto TRANSFORM_MATRIX_DIMENSION = 4; // Width and height of a 4x4 transform matrix
58 
60 {
61 public:
62  HandEyeSolverDefault() = default;
63  ~HandEyeSolverDefault() = default;
64 
65  virtual void initialize() override;
66 
67  virtual const std::vector<std::string>& getSolverNames() const override;
68 
69  virtual bool solve(const std::vector<Eigen::Isometry3d>& effector_wrt_world,
70  const std::vector<Eigen::Isometry3d>& object_wrt_sensor, SensorMountType setup = EYE_TO_HAND,
71  const std::string& solver_name = "TsaiLenz1989", std::string* error_message = nullptr) override;
72 
73  virtual const Eigen::Isometry3d& getCameraRobotPose() const override;
74 
75 private:
81  bool toCArray(const Eigen::Isometry3d& pose, double (*c_arr)[TRANSFORM_MATRIX_DIMENSION]) const;
82 
83  std::vector<std::string> solver_names_; // Solver algorithm names
84  Eigen::Isometry3d camera_robot_pose_; // Computed camera pose with respect to a robot
85 };
86 
87 } // namespace moveit_handeye_calibration
setup
moveit_handeye_calibration::HandEyeSolverBase
Definition: handeye_solver_base.h:82
handeye_solver_base.h
ros.h
moveit_handeye_calibration::HandEyeSolverDefault::toCArray
bool toCArray(const Eigen::Isometry3d &pose, double(*c_arr)[TRANSFORM_MATRIX_DIMENSION]) const
Convert a Eigen::Isometry3d pose to a 4x4 C array.
Definition: handeye_solver_default.cpp:450
moveit_handeye_calibration::EYE_TO_HAND
@ EYE_TO_HAND
Definition: handeye_solver_base.h:110
moveit_handeye_calibration::HandEyeSolverDefault::getSolverNames
virtual const std::vector< std::string > & getSolverNames() const override
Get the names of available algorithms that can be used from the plugin.
Definition: handeye_solver_default.cpp:86
moveit_handeye_calibration::SensorMountType
SensorMountType
Definition: handeye_solver_base.h:76
moveit_handeye_calibration::HandEyeSolverDefault::camera_robot_pose_
Eigen::Isometry3d camera_robot_pose_
Definition: handeye_solver_default.h:84
moveit_handeye_calibration::HandEyeSolverDefault::solver_names_
std::vector< std::string > solver_names_
Definition: handeye_solver_default.h:83
moveit_handeye_calibration::HandEyeSolverDefault::HandEyeSolverDefault
HandEyeSolverDefault()=default
moveit_handeye_calibration::TRANSFORM_MATRIX_DIMENSION
constexpr auto TRANSFORM_MATRIX_DIMENSION
Definition: handeye_solver_default.h:57
moveit_handeye_calibration::HandEyeSolverDefault::~HandEyeSolverDefault
~HandEyeSolverDefault()=default
moveit_handeye_calibration
Definition: handeye_solver_base.h:42
moveit_handeye_calibration::HandEyeSolverDefault::getCameraRobotPose
virtual const Eigen::Isometry3d & getCameraRobotPose() const override
Get the result of the calibration, i.e. the camera pose with respect to the robot.
Definition: handeye_solver_default.cpp:91
moveit_handeye_calibration::HandEyeSolverDefault::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="TsaiLenz1989", std::string *error_message=nullptr) override
Calculate camera-robot transform from the input pose samples.
Definition: handeye_solver_default.cpp:96
moveit_handeye_calibration::HandEyeSolverDefault::initialize
virtual void initialize() override
Definition: handeye_solver_default.cpp:80
moveit_handeye_calibration::HandEyeSolverDefault
Definition: handeye_solver_default.h:59


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