Showing preview only (793K chars total). Download the full file or copy to clipboard to get everything.
Repository: ram-lab/plycal
Branch: master
Commit: d04d1451338a
Files: 47
Total size: 766.6 KB
Directory structure:
gitextract_smbq0rmy/
├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── PlyCal/
│ ├── CMakeLists.txt
│ ├── calibrator.cpp
│ ├── calibrator.h
│ ├── image_polygon.cpp
│ ├── image_polygon.h
│ ├── pointcloud_polygon.cpp
│ ├── pointcloud_polygon.h
│ └── utils.h
├── PlyCal_qt/
│ ├── CMakeLists.txt
│ ├── cqtopencvviewergl.cpp
│ ├── cqtopencvviewergl.h
│ ├── data_reader.cpp
│ ├── data_reader.h
│ ├── imageviewer.cpp
│ ├── imageviewer.h
│ ├── imageviewer.ui
│ ├── main.cpp
│ ├── mainwindow.cpp
│ ├── mainwindow.h
│ ├── mainwindow.ui
│ ├── pointcloudviewer.cpp
│ ├── pointcloudviewer.h
│ ├── pointcloudviewer.ui
│ ├── tfwindow.cpp
│ ├── tfwindow.h
│ └── tfwindow.ui
├── PlyCal_test/
│ ├── CMakeLists.txt
│ ├── test_image_polygon.cpp
│ ├── test_image_polygons.cpp
│ └── test_pointcloud_polygon.cpp
├── README.md
├── data/
│ ├── config.json
│ └── pointcloud/
│ ├── 0.pcd
│ ├── 1.pcd
│ ├── 2.pcd
│ ├── 3.pcd
│ ├── 4.pcd
│ ├── 5.pcd
│ ├── 6.pcd
│ └── 7.pcd
├── doc/
│ └── README.md
└── thirdParty/
├── edlines/
│ ├── EDLineDetector.cpp
│ └── EDLineDetector.h
└── json/
└── json.hpp
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
/build
.ycm_extra_conf.py
*.swp
CMakeLists.txt.user
================================================
FILE: CMakeLists.txt
================================================
CMAKE_MINIMUM_REQUIRED(VERSION 2.8)
project(PlyCal)
#cmake_policy(SET CMP0028 OLD)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
add_definitions(-std=c++11) # for qt creator
# Optionally compiling part
option(BUILD_PlyCal_GUI "enables PlyCal viewer" true)
option(BUILD_PlyCal_TEST "enables PlyCal test" false)
# default built type
IF(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE Release CACHE STRING "Choose the type of build, options are: None Debug Release RelWithDebInfo MinSizeRel." FORCE)
ENDIF(NOT CMAKE_BUILD_TYPE)
include_directories(
thirdParty
PlyCal
)
# The library prefix
set(LIB_PREFIX plycal)
# Include the subdirectories
add_subdirectory(PlyCal)
if(BUILD_PlyCal_GUI)
add_subdirectory(PlyCal_qt)
endif(BUILD_PlyCal_GUI)
if(BUILD_PlyCal_TEST)
add_subdirectory(PlyCal_test)
endif(BUILD_PlyCal_TEST)
================================================
FILE: LICENSE
================================================
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <https://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <https://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:
<program> Copyright (C) <year> <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<https://www.gnu.org/licenses/>.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<https://www.gnu.org/licenses/why-not-lgpl.html>.
================================================
FILE: PlyCal/CMakeLists.txt
================================================
if( CMAKE_BUILD_TYPE EQUAL "Release")
add_definitions( -DNODEBUG )
endif(CMAKE_BUILD_TYPE EQUAL "Release")
file(GLOB LIB_SRC
"*.cpp"
)
file(GLOB LIB_HEADER
"*.h"
)
find_package(
OpenCV
REQUIRED
)
find_package(
PCL
QUIET
REQUIRED
)
find_package(
Ceres
REQUIRED
)
find_package(
Boost
REQUIRED
COMPONENTS
system
thread
)
find_package(
Eigen3
REQUIRED
)
# Fix a compilation bug under ubuntu 16.04 (Xenial)
list(REMOVE_ITEM PCL_LIBRARIES "vtkproj4")
add_definitions(${PCL_DEFINITIONS})
include_directories(
${PCL_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${Eigen_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
)
link_directories(
${PCL_LIBRARY_DIRS}
${Boost_LIBRARY_DIRS}
)
set(
EDLINE_SRC
${PROJECT_SOURCE_DIR}/thirdParty/edlines/EDLineDetector.cpp
)
add_library(
plycal
SHARED
${LIB_SRC}
${LIB_HEADER}
${EDLINE_SRC}
)
target_link_libraries(
plycal
${OpenCV_LIBS}
${Boost_LIBRARIES}
${PCL_LIBRARIES}
${CERES_LIBRARIES}
)
set_target_properties(
plycal
PROPERTIES
OUTPUT_NAME
${LIB_PREFIX}
)
================================================
FILE: PlyCal/calibrator.cpp
================================================
/**
******************************************************************************
* @file calibrator.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-28
* @brief calibrator.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "calibrator.h"
#include <fstream>
#include <iostream>
#include <pcl/registration/icp.h>
#include <pcl/common/common.h>
#include <pcl/common/io.h>
#include <ceres/ceres.h>
#include <ceres/rotation.h>
using namespace lqh;
/* Private define ------------------------------------------------------------*/
/* Private typedef -----------------------------------------------------------*/
using PCC = pcl::PointCloud<pcl::PointXYZRGB>;
using PCI = pcl::PointCloud<pcl::PointXYZI>;
namespace
{
template <typename T>
static void ProjectPoint2Image(const T* const q_ptr, const T* const t_ptr,
const Eigen::Matrix<T, 3, 3>& k,
const Eigen::Matrix<T, 3, Eigen::Dynamic>& p3,
Eigen::Matrix<T, 3, Eigen::Dynamic>& p2)
{
Eigen::Map<const Eigen::Quaternion<T> > q(q_ptr);
Eigen::Map<const Eigen::Matrix<T, 1, 3> > t(t_ptr);
p2 = (q.matrix()*p3);
// p2.colwise() += t;
for(uint32_t i=0; i<p2.cols(); i++)
{
p2.col(i) += t;
p2.col(i) = p2.col(i)/p2(2,i);
}
p2 = k*p2;
}
/**
* @brief Edge to edge error (point to line error)
* 3D point P_i_j locates at 3D edge i, its index is j. 3D edge i has correspondense in
* image E_i(ax+by+c=0,a^2+b^2+c^2=1), project P_i_j into image with initial T(q,p) and
* get 2D point P'_i_j(u,v). If T(q,p) is correct or precise, P'_i_j should be on E_i.
* Thus, the error is the distance between P'_i_j and E_i
*/
struct Edge2EdgeError
{
const Eigen::Matrix3d& K; // camera matrix
const Eigen::Matrix3Xd& pts; // 3d points
const Eigen::Vector3d& coef; // 2d edge(line) coefficients
/**
* @brief Edge2EdgeError constructor
*
* @param k [in]: camera intrinsic parameter matrix K
* @param ps[in]: 3D edge pints set, P_i_j(j=0,1,...n), it's 3xn matrix
* @param cf[in]: 2D line coefficients (ax+by+c=0,a^2+b^2+c^2=1)
*/
Edge2EdgeError(const Eigen::Matrix3d& k, const Eigen::Matrix3Xd& ps, const Eigen::Vector3d& cf):
K(k), pts(ps), coef(cf) {}
/**
* @brief Ceres error compute function
*
* @tparam T double or Jet
* @param q [in]: Quaternion (rotation)
* @param p [in]: translation
* @param residuals[out]: error
*
* @return true: indicate success
*/
template<typename T>
bool operator()(const T* const q, const T* const p, T* residuals)const
{
Eigen::Matrix<T, 3, Eigen::Dynamic> points;
ProjectPoint2Image<T>(q,p, K.cast<T>(), pts.cast<T>(), points);
Eigen::Matrix<T, Eigen::Dynamic, 1> tmp = (coef.transpose().cast<T>())*points;
residuals[0] = tmp.cwiseAbs().sum();
return true; // important
}
};
struct Point2PolygonError
{
const Eigen::Matrix3d& K;
const Eigen::Matrix3Xd& pts;
const Eigen::Matrix3Xd& vertex;
Eigen::Matrix3Xd edge_normal;
Point2PolygonError(const Eigen::Matrix3d& k, const Eigen::Matrix3Xd& ps, const Eigen::Matrix3Xd& vx ):
K(k), pts(ps), vertex(vx)
{
Eigen::Vector3d center = vx.rowwise().mean();
edge_normal.resize(3, vx.cols());
edge_normal.row(2).setZero();
for(uint32_t i=0; i<vx.cols(); i++)
{
uint32_t next = (i == (vx.cols()-1)) ? 0 : i+1;
Eigen::Vector3d dir = vx.col(next) - vx.col(i);
edge_normal(0, i) = -dir(1);
edge_normal(1, i) = dir(0);
if(edge_normal.col(i).dot(center - vx.col(i)) < 0 )
{
edge_normal.col(i) *= -1;
}
}
}
template<typename T>
bool operator()(const T* const q, const T* const t, T* residuals)const
{
using Matrix3XT = Eigen::Matrix<T, 3, Eigen::Dynamic>;
Matrix3XT vtx = vertex.cast<T>();
Matrix3XT normals = edge_normal.cast<T>();
Matrix3XT points;
ProjectPoint2Image<T>(q, t, K.cast<T>(), pts.cast<T>(), points);
residuals[0] = T(0);
for(uint32_t i=0; i<pts.cols(); i++)
{
bool flag = false;
for(uint32_t j=0; j<vertex.cols(); j++)
{
if( normals.col(j).dot(points.col(i) - vtx.col(j)) < T(0) )
{
flag = true;
break;
}
}
// one point locates outside the polygon
if(flag)
{
residuals[0] += T(1);
}
}
return true; // important
}
};
}
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
Calibrator::Calibrator(const nlohmann::json& js):
is_valid_(false),
img_width_(0),
img_height_(0)
{
size_ = js["size"].get<uint32_t>();
if(size_ < 3 )
{
std::cerr << "E: size must >= 3\n " << __FUNCTION__;
return;
}
imgply_.reset( new ImagePolygon(js["img"], size_) );
pcply_.reset( new PointcloudPolygon(js["pc"], size_) );
polygons_.clear();
polygons_v_.clear();
polygons_v_.reserve(10);
track_error_threshold_ = js["track_error_threshold"].get<double>();
K_.setIdentity();
T_.setIdentity();
auto& k = js["cam"]["K"];
assert( k.size() == 3 );
for(uint8_t i=0; i<2; i++)
{
assert( k[i].size() == 3 );
K_.row(i) << k[i][0], k[i][1], k[i][2];
}
K_.row(2) << 0,0,1;
auto& t = js["tf"];
assert( t.size() == 4 );
for(uint8_t i=0; i<3; i++)
{
assert( t[i].size() == 4 );
T_.row(i) << t[i][0], t[i][1], t[i][2], t[i][3];
}
T_.row(3) << 0,0,0,1;
is_valid_ = true;
}
uint32_t Calibrator::Add(const cv::Mat& img, const PCI& pc,
cv::Mat& img_out, pcl::PointCloud<pcl::PointXYZRGB>& pcc)
{
polygons_.emplace_back(size_);
auto& ply = polygons_.back();
polygons_v_.push_back(&ply);
ply.img = imgply_->Add(img,img_out);
ply.pc = pcply_->Add(pc, pcc);
if(ply.img != nullptr && ply.pc != nullptr)
{
MatchLines(ply);
}
// if( polygons_.size() == 1)
// {
// MatchLines(ply);
// }
// else
// {
// auto it = std::prev(polygons_.end(),2);
// TrackLines(*it, ply);
// }
//return id
return polygons_v_.size()-1;
}
bool Calibrator::RefineImage(const cv::Mat& img,
cv::Mat& img_out, const std::vector<cv::Point2d>& pts)
{
assert(pts.size() == size_);
Eigen::Matrix3Xd vtx(3, size_);
vtx.row(2).setOnes();
for(uint8_t i=0; i<size_; i++)
{
vtx(0,i) = pts[i].x;
vtx(1,i) = pts[i].y;
}
auto& ply = polygons_.back();
ply.img = imgply_->Init(img, img_out, vtx);
if(ply.img == nullptr)
{
return false;
}
if(ply.pc == nullptr)
{
return true;
}
// both valid, match
MatchLines(ply);
// if( polygons_.size() == 1)
// {
// MatchLines(ply);
// }
// else
// {
// auto it = std::prev(polygons_.end(),2);
// TrackLines(*it, ply);
// }
return true;
}
bool Calibrator::RefinePointcloud(const PCI& pc, PCC& pcc, const Eigen::Vector4d& param )
{
auto& ply = polygons_.back();
pcply_->SetFilterParameters(param);
ply.pc = pcply_->Add(pc, pcc);
if(ply.pc == nullptr)
{
return false;
}
if(ply.img == nullptr)
{
return true;
}
// both valid, match
MatchLines(ply);
// if( polygons_.size() == 1)
// {
// MatchLines(ply);
// }
// else
// {
// auto it = std::prev(polygons_.end(),2);
// TrackLines(*it, ply);
// }
return true;
}
/**
* @brief Calibrator::Remove
* @todo: maybe we should use !!!skip
* @param id
* @return
*/
bool Calibrator::Remove(uint32_t id)
{
if(id >= polygons_v_.size())
{
return false;
}
polygons_v_.erase(polygons_v_.begin()+id);
auto it = polygons_.begin();
std::advance(it, id);
polygons_.erase(it);
return true;
}
// remove last one
bool Calibrator::Remove()
{
if(polygons_.size() == 0)
{
return false;
}
polygons_.pop_back();
polygons_v_.pop_back();
}
bool Calibrator::Compute(Eigen::Matrix4d &tf)
{
if(polygons_.size() == 0)
{
return false;
}
Optimize(tf);
T_ = tf;
return true;
}
void Calibrator::Optimize(Eigen::Matrix4d& tf)
{
Eigen::Matrix3d rot = T_.topLeftCorner(3,3);
Eigen::Quaterniond q (rot);
Eigen::Vector3d p = T_.topRightCorner(3,1);
//std::cout << "Before \nq:\n" << q.coeffs() << "\nt:\n" << p << std::endl;
ceres::Problem problem;
ceres::Solver::Summary summary;
ceres::Solver::Options options;
ceres::LossFunction* loss_function_edge (new ceres::SoftLOneLoss(1));
ceres::HuberLoss* loss_function_inlier (new ceres::HuberLoss(500));
ceres::LocalParameterization* quaternion_local_parameterization =
new ceres::EigenQuaternionParameterization;
for(const auto& ply : polygons_)
{
// add edge
for(uint32_t i=0; i<size_; i++)
{
if(ply.pc->edges[i].points.cols() == 0)
{
continue;
}
ceres::CostFunction* cost =
new ceres::AutoDiffCostFunction<Edge2EdgeError, 1,4,3>(
new Edge2EdgeError( K_, ply.pc->edges[i].points, ply.img->edges[ply.ids[i]].coef ));
problem.AddResidualBlock(cost, loss_function_edge,
q.coeffs().data(), p.data() );
}
// add inlier points
ceres::CostFunction* cost = new ceres::AutoDiffCostFunction<Point2PolygonError,1,4,3>(
new Point2PolygonError(K_, ply.pc->inliers, ply.img->vertexs) );
problem.AddResidualBlock(cost, NULL, q.coeffs().data(), p.data());
// problem.AddResidualBlock(cost, loss_function_inlier, q.coeffs().data(), p.data());
}
problem.SetParameterization(q.coeffs().data(), quaternion_local_parameterization);
//options.linear_solver_type = ceres::DENSE_SCHUR;
options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
options.max_num_iterations = 5000;
// or use all cpu cores
options.num_threads= boost::thread::hardware_concurrency() - 1;
#if (CERES_VERSION_MAJOR < 2)
options.num_linear_solver_threads = options.num_threads;
#endif
//options.minimizer_progress_to_stdout = true;
ceres::Solve(options, &problem, &summary);
std::cout << summary.FullReport() << std::endl;
tf = Eigen::Matrix4d::Identity();
tf.topLeftCorner(3,3) = q.matrix();
tf.topRightCorner(3,1) = p;
std::cout << "T: \n" << tf << std::endl;
}
void Calibrator::TrackLines(const Polygon& ply_prev, Polygon& ply) const
{
// image polygon keep orders, no futhur processing
// tracking pointcloud edge
// using PC = pcl::PointCloud<pcl::PointXYZ>;
// auto Mat2PC = [](const Eigen::Matrix3Xd& mat, PC& pc)
// {
// pc.points.reserve(mat.cols());
// for(uint32_t i=0; i<mat.cols(); i++)
// {
// pc.points.emplace_back(mat(0,i), mat(1,i), mat(2,i));
// }
// };
// PC::Ptr pc_prev (new PC);
// PC::Ptr pc (new PC);
// PC pc_out;
// Mat2PC(ply_prev.pc->inliers, *pc_prev);
// Mat2PC(ply.pc->inliers, *pc);
// pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> icp;
// icp.setInputSource(pc);
// icp.setInputTarget(pc_prev);
// icp.setMaximumIterations(200);
// icp.setTransformationEpsilon(1e-6);
// icp.setEuclideanFitnessEpsilon(1);
// icp.align(pc_out, Eigen::Matrix4d::Identity());
// Eigen::Matrix4d T = icp.getFinalTransformation();
// using PairUD = std::pair<uint32_t, double>;
// std::vector<PairUD> offsets(size_);
// for(uint32_t i=0; i<size_; i++)
// {
// offsets[i].first = i;
// offsets[i].second = 0;
// for(uint32_t j=0; j<size_; j++)
// {
// const auto& prev = ply_prev.pc->edges[(j+i)%size_];
// const auto& cur = ply.pc->edges[j];
// if(prev.coef.norm() < 0.1 || cur.points.cols() == 0)
// {
// continue;
// }
// for(uint32_t k=0; k<cur.points.cols(); k++)
// {
// offsets[i].second += prev.coef.cross(T*cur.points.col(k) - prev.p0).norm();
// }
// }
// }
// std::sort(offsets.begin(), offsets.end(), [](const PairUD& a, const PairUD& b)
// {
// return a.second < b.second;
// });
// uint32_t offset = offsets[0].first;
// for(uint32_t i=0; i<size_; i++)
// {
// ply.ids[i] = ply_prev.ids[(i+offset)%size_];
// }
}
/**
* @brief match the 2/3d Polygon, since both polygon save edges
* as clock-wise, just find the offset is enough
*
* @param ply [in/out]
*/
void Calibrator::MatchLines(Polygon& ply) const
{
// we find the offset based on the longest(most points) two edges
std::vector<uint32_t> ids(size_);
for(uint32_t i=0; i<size_; i++)
{
ids[i] = i;
}
// decrease order
std::sort(ids.begin(), ids.end(), [&ply](uint32_t a, uint32_t b)
{
return ply.pc->edges[a].points.cols() >
ply.pc->edges[b].points.cols();
});
const auto& edge_0 = ply.pc->edges[ids[0]];
const auto& edge_1 = ply.pc->edges[ids[1]];
int32_t gap = ids[1] - ids[0];
using PairUD = std::pair<uint32_t, double>;
std::vector<PairUD> offsets(size_);
Eigen::Matrix3d rot = T_.topLeftCorner(3,3);
Eigen::Vector3d trans = T_.topRightCorner(3,1);
auto err_proj = [this, &rot, &trans](const ImagePolygon::Edge2D& img,
const PointcloudPolygon::Edge3D& pc,
double& err)
{
Eigen::Vector2d dir_proj = (K_*(rot*pc.coef + trans)).head(2);
dir_proj.normalize();
Eigen::Vector2d dir_img(img.coef(1), -img.coef(0));
dir_img.normalize();
double err_angle = std::acos(dir_proj.dot(dir_img))/MATH_PI*180;
Eigen::Matrix3Xd pt_proj = rot*pc.points;
pt_proj.colwise() += trans;
pt_proj = K_*pt_proj;
for(uint32_t i=0; i<pt_proj.cols(); i++)
{
pt_proj.col(i) = pt_proj.col(i)/pt_proj(2,i);
}
double err_dis = (img.coef.transpose()*pt_proj).cwiseAbs().sum();
err += err_angle*err_dis;
};
for(uint32_t i=0; i<size_; i++)
{
offsets[i].first = i;
offsets[i].second = 0;
// 3d edge_0 <----> 2d edge i
uint32_t id1 = (static_cast<int32_t>(i)+gap) < 0 ? i+gap +size_ : (i+gap)%size_;
err_proj(ply.img->edges[i], edge_0, offsets[i].second);
err_proj(ply.img->edges[id1], edge_1, offsets[i].second);
}
// increase order, offsets[0] has smallest error
std::sort(offsets.begin(), offsets.end(), [](const PairUD& a, const PairUD&b)
{
return a.second < b.second;
});
// ids[0] 3d edge <----> offsets[0].first 2d edge
uint32_t id_img = offsets[0].first > ids[0] ? offsets[0].first - ids[0]:
offsets[0].first + size_ - ids[0];
std::cout << "pc[0-4]: ";
for(uint32_t i=0; i<size_; i++)
{
ply.ids[i] = (id_img+i)%size_;
std::cout << ply.ids[i] << ", ";
}
std::cout << std::endl;
}
uint32_t Calibrator::SavePolygonData(const std::string& dir)
{
Eigen::IOFormat csvfmt(Eigen::FullPrecision, Eigen::DontAlignCols, ", ", "\n", "", "", "", "");
uint32_t i = 0;
for(const auto& ply : polygons_)
{
std::ofstream pc_inlier(dir+"/pc_inlier_"+std::to_string(i)+".csv");
std::ofstream pc_edge(dir+"/pc_edge_"+std::to_string(i)+".csv");
std::ofstream img_coef(dir+"/img_coef_"+std::to_string(i)+".csv");
std::ofstream img_vertex(dir+"/img_vertex_"+std::to_string(i)+".csv");
if(!pc_inlier.good() || !pc_edge.good() ||
!img_coef.good() || !img_vertex.good())
{
break;
}
pc_inlier << ply.pc->inliers.format(csvfmt);
pc_inlier.close();
uint32_t num = 0;
for(const auto& it: ply.pc->edges)
{
num += it.points.cols();
}
Eigen::Matrix4Xd edges(4, num);
uint32_t id =0;
for(uint32_t j=0; j<ply.pc->edges.size(); j++)
{
const auto& it = ply.pc->edges[j].points;
if(it.cols() == 0)
{
continue;
}
edges.block(0,id, 1, it.cols() ).setConstant(j);
edges.block(1,id, 3, it.cols() ) = it;
id += it.cols();
}
pc_edge << edges.format(csvfmt);
pc_edge.close();
Eigen::Matrix3Xd coef(3, size_);
for(uint32_t j=0; j<ply.img->edges.size(); j++)
{
coef.col(j) = ply.img->edges[ply.ids[j]].coef;
}
img_coef << coef.format(csvfmt);
img_coef.close();
img_vertex << ply.img->vertexs.format(csvfmt);
img_vertex.close();
i++;
}
}
bool Calibrator::Project(pcl::PointCloud<pcl::PointXYZRGB>& pc, cv::Mat& img,
const Eigen::Matrix4d& tf)
{
const double resolution = 0.1;
const double depth_min = 1.0;
const double depth_gap = 10.0;
if(img_width_ != img.cols || img_height_ != img.rows)
{
img_width_ = img.cols;
img_height_ = img.rows;
}
// Eigen::Vector4f pt_min, pt_max;
// pcl::getMinMax3D(pc, pt_min, pt_max);
// double depth_gap = std::sqrt(pt_max(0)*pt_max(0) + pt_max(1)+pt_max(1)) - depth_gap + 0.01;
// if(depth_gap > 5)
// {
// depth_gap = 5.0;
// }
uint32_t num = static_cast<uint32_t>(depth_gap/resolution);
lqh::utils::color::rgbs colors = lqh::utils::color::get_rgbs(num);
cv::Mat im;
img.copyTo(im);
for(auto& p : pc.points)
{
Eigen::Vector3d pt = K_*(tf*Eigen::Vector4d(p.x, p.y, p.z, 1)).topRows(3);
if(pt(2) < 0.5)
{
continue;
}
int32_t u = static_cast<int32_t>(pt(0)/pt(2));
int32_t v = static_cast<int32_t>(pt(1)/pt(2));
if(u < 0 || u >= img.cols || v<0 || v >= img.rows)
{
continue;
}
cv::Vec3b color = im.at<cv::Vec3b>(cv::Point(u,v));
p.r = color[2];
p.g = color[1];
p.b = color[0];
double f = std::sqrt(p.x*p.x + p.y*p.y) - depth_min;
uint32_t idx = static_cast<uint32_t>(f/resolution);
if(idx >= num)
{
idx = num -1;
}
auto& c = colors[idx];
cv::circle(img, cv::Point2d(u,v), 2, cv::Scalar(c[2], c[1], c[0]), -1);
}
}
void Calibrator::SetTranformation(const Eigen::Matrix4d& tf)
{
T_ = tf;
// check pointcloud filter
if(img_height_ == 0 || img_width_ == 0)
{
return;
}
Eigen::Vector4d orig = pcply_->GetFilterParameters();
auto getYaw = [this](double x, double y)->double
{
Eigen::Vector4d v (0,0,0,1);
v.head(3) = K_.inverse()*Eigen::Vector3d(x,y,1);
v = T_.inverse()*v;
double angle = std::atan2(v(1), v(0))/MATH_PI*180;
return angle <0? 360+angle : angle;
};
double angle0 = getYaw(0,0);
double angle1 = getYaw(img_width_-1, img_height_-1);
if(angle0 > angle1)
{
std::swap(angle0, angle1);
}
if(angle1-angle0 <180)
{
if(orig(0)< angle0 || orig(0)>angle1 )
{
orig(0) = angle0;
}
if(angle1 - orig(0) > orig(1))
{
orig(1) = angle1 - orig(0);
}
}
else
{
if(orig(0)> angle0 && orig(0)<angle1 )
{
orig(0) = angle1;
}
double gap = orig(0) >= angle1 ? 360-angle1+angle0 : angle0-orig(0);
if(orig(1) > gap)
{
orig(1) = gap;
}
}
pcply_->SetFilterParameters(orig);
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/calibrator.h
================================================
/**
******************************************************************************
* @file calibrator.h
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-28
* @brief calibrator.h
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __CALIBRATOR_H
#define __CALIBRATOR_H
/* Includes ------------------------------------------------------------------*/
#include "stdint.h"
#include <string>
#include <memory>
#include <Eigen/Dense>
#include <opencv2/opencv.hpp>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include "image_polygon.h"
#include "pointcloud_polygon.h"
#include "json/json.hpp"
#include "utils.h"
/* Exported macro ------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
namespace lqh
{
class Calibrator
{
public:
explicit Calibrator(const nlohmann::json& js);
uint32_t Add(const cv::Mat& img, const pcl::PointCloud<pcl::PointXYZI>& pc,
cv::Mat& img_out, pcl::PointCloud<pcl::PointXYZRGB>& pcc);
bool RefineImage(const cv::Mat& img, cv::Mat& img_out, const std::vector<cv::Point2d>& pts);
bool RefinePointcloud(const pcl::PointCloud<pcl::PointXYZI>& pc,
pcl::PointCloud<pcl::PointXYZRGB>& pcc,
const Eigen::Vector4d& param );
uint32_t SavePolygonData(const std::string& dir);
void SetCameraK(const Eigen::Matrix3d& k)
{
K_ = k;
}
void SetTranformation(const Eigen::Matrix4d& tf);
bool Remove(uint32_t id);
bool Remove();
bool Compute(Eigen::Matrix4d& tf);
bool Compute()
{
return Compute(T_);
}
const Eigen::Matrix4d& GetTransformation()
{
return T_;
}
bool ImageGood(uint32_t id)
{
if(id >= polygons_v_.size())
{
return false;
}
return (polygons_v_[id]->img != nullptr);
}
bool PointcloudGood(uint32_t id)
{
if(id >= polygons_v_.size())
{
return false;
}
return (polygons_v_[id]->pc != nullptr);
}
bool Good()
{
return is_valid_;
}
bool Project(pcl::PointCloud<pcl::PointXYZRGB>& pc, cv::Mat& img)
{
Project(pc, img, T_);
}
bool Project(pcl::PointCloud<pcl::PointXYZRGB>& pc, cv::Mat& img,
const Eigen::Matrix4d& tf);
private:
struct Polygon
{
/**
* ids: corroesponences of 2d/3d Polygon
* same edge: $i$th 3d edge <---> ids[i] 2d edge
*/
std::vector<uint32_t> ids;
ImagePolygon::Polygon2D::ConstPtr img;
PointcloudPolygon::Polygon3D::ConstPtr pc;
Polygon(uint32_t size):img(nullptr), pc(nullptr)
{
ids.resize(size);
for(uint32_t i=0; i<size; i++)
{
ids[i] = i;
}
}
};
bool is_valid_;
uint32_t size_;
double track_error_threshold_;
uint32_t img_width_;
uint32_t img_height_;
Eigen::Matrix3d K_;
Eigen::Matrix4d T_;
std::unique_ptr<ImagePolygon> imgply_;
std::unique_ptr<PointcloudPolygon> pcply_;
std::vector<Polygon*> polygons_v_;
std::list<Polygon> polygons_;
void TrackLines(const Polygon& ply_prev, Polygon& ply) const;
void MatchLines(Polygon& ply) const;
void Optimize(Eigen::Matrix4d& tf);
};
}
/* Exported constants --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#endif /* !__CALIBRATOR_H */
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/image_polygon.cpp
================================================
/**
******************************************************************************
* @file image_polygon.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-22
* @brief image_polygon.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "image_polygon.h"
#include <iostream>
#include <cmath>
#include "utils.h"
using namespace lqh;
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
ImagePolygon::ImagePolygon(const nlohmann::json& js, uint8_t size):
size_(size), polygon_(nullptr)
{
//!!! we don't set default
// config line detector
auto ed = js["edlines"];
EDLineParam para;
para.minLineLen = ed["minLineLen"];
para.lineFitErrThreshold = ed["lineFitErrThreshold"];
para.ksize = ed["ksize"];
para.sigma = ed["sigma"];
para.gradientThreshold = ed["gradientThreshold"];
para.scanIntervals = ed["scanIntervals"];
para.anchorThreshold = ed["anchorThreshold"];
detector_.reset(new EDLineDetector(para));
feature_size_ = js["feature"]["size"];
feature_offset_ = js["feature"]["offset"];
feature_threshold_ = js["feature"]["threshold"];
merge_distance_threshold_ = js["merge"]["distance_threshold"];
merge_angle_threshold_ = js["merge"]["angle_threshold"];
merge_endpoint_distance_threshold_ = js["merge"]["endpoint_distance_threshold"];
filter_point_line_threshold_ = js["filter"]["point_line_threshold"];
filter_line_angle_threshold_ = js["filter"]["line_angle_threshold"];
filter_point_center_factor_ = js["filter"]["point_center_factor"];
if(filter_point_center_factor_ >1 || filter_point_center_factor_ <0)
{
std::cout << "W: point_dis_factor in (0,1) get " <<
filter_point_center_factor_ << "\n";
filter_point_center_factor_ = 0.2;
}
// random
// center to line distance
filter_point_center_max_ = 100;
filter_line_center_min_ = 50;
width_ = 0;
length_ = 0;
angle_width_ = 0;
angle_length_ = 0;
Eigen::Matrix3Xd pts(3,4);
pts.row(2).setOnes();
for(uint8_t i=0; i<4; i++)
{
pts(0,i) = js["init"][i][0].get<double>();
pts(1,i) = js["init"][i][1].get<double>();
}
polygon_ = InitPolygon(pts);
}
ImagePolygon::Polygon2D::Ptr ImagePolygon::InitPolygon(const Eigen::Matrix3Xd& pts)
{
// currently, only apply to rectangular
// @TODO
assert(pts.cols() == 4);
assert(pts.cols() == size_ );
using PairUD = std::pair<uint32_t, double>;
// sort the points(clock wise)
Eigen::Vector3d center = pts.rowwise().mean();
center(2) = 1;
std::vector<PairUD> verts( size_ );
for(uint32_t i=0; i<size_; i++)
{
verts[i].first = i;
verts[i].second = std::atan2(pts(1,i)-center(1), pts(0,i)-center(0)) + MATH_PI;
}
std::sort(verts.begin(), verts.end(), [](PairUD& a, PairUD& b)
{
return a.second < b.second;
});
Polygon2D::Ptr ply = std::make_shared<Polygon2D>(size_);
ply->center = center;
auto EistimateCoef = [](const Eigen::Vector3d& p0,
const Eigen::Vector3d& p1,
Eigen::Vector3d& coef)
{
Eigen::Vector3d dir = (p0-p1).normalized();
Eigen::Vector3d c = (p0+p1)/2;
coef(0) = -1*dir(1);
coef(1) = dir(0);
coef(2) = -1*(coef(0)*c(0) + coef(1)*c(1));
};
for(uint32_t i=0; i<size_; i++)
{
uint32_t next = (i== size_-1) ? 0: i+1;
ply->vertexs.col(i) = pts.col(verts[i].first);
EistimateCoef(pts.col(verts[i].first), pts.col(verts[next].first),
ply->edges[i].coef);
ply->edges[i].length = (pts.col(verts[i].first) - pts.col(verts[next].first)).norm();
double dir = std::atan2(-ply->edges[i].coef(0), ply->edges[i].coef(1))/MATH_PI*180;
ply->edges[i].dir = (dir<0)?dir+180:dir;
//ExtractLineFeature(img, pts.col(verts[i].first), pts.col(verts[next].first),
//center, polygon_->edges[i].feature);
}
UpdateParameters(ply);
return ply;
}
ImagePolygon::Polygon2D::ConstPtr ImagePolygon::Init(const cv::Mat& img,
cv::Mat& img_out, const Eigen::Matrix3Xd& pts)
{
Polygon2D::Ptr ply = InitPolygon(pts);
// SaveMarkedImage("init.png", img, ply);
return ExtractPolygon(img, img_out,ply);
}
ImagePolygon::Polygon2D::ConstPtr ImagePolygon::Add(const cv::Mat& img, cv::Mat& img_out)
{
if(polygon_ == nullptr)
{
std::cerr << "E: init first\n";
return nullptr;
}
return ExtractPolygon(img, img_out, polygon_);
}
ImagePolygon::Polygon2D::ConstPtr ImagePolygon::ExtractPolygon(const cv::Mat& img,
cv::Mat& img_out, Polygon2D::ConstPtr prev)
{
// we require color image
assert(img.channels() == 3);
std::list<Line2D> lines;
Polygon2D::Ptr ply;
bool res = ExtractLines(img, lines);
if(!res)
{
MarkImage(img_out, lines);
return nullptr;
}
// SaveMarkedImage("ExtractLines.png", img, lines);
res &= FilterLines(lines, prev);
if(!res)
{
MarkImage(img_out, lines);
return nullptr;
}
// SaveMarkedImage("FilterLines.png", img, lines);
res &= MergeLines(lines);
if(!res)
{
MarkImage(img_out, lines);
return nullptr;
}
// SaveMarkedImage("EMergeLines.png", img, lines);
res &= FilterLinesByRectangule(lines, prev);
if(!res)
{
MarkImage(img_out, lines);
return nullptr;
}
// SaveMarkedImage("FilterLinesByRectangule.png", img, lines);
res &= SortLines(lines, prev, ply);
if(res)
{
polygon_ = ply;
UpdateParameters();
MarkImage(img_out, ply);
return ply;
}
else
{
return nullptr;
}
}
bool ImagePolygon::ExtractLines(const cv::Mat& img, std::list<Line2D>& ls)
{
//cv::Mat img_hsv;
//cv::Mat imgs[3];
//cv::cvtColor(img, img_hsv, cv::COLOR_BGR2HSV);
//cv::split(img_hsv, imgs);
//auto& img_h = imgs[2];
//ls.clear();
//// set circle
//double x = polygon_->center(0);
//double y = polygon_->center(1);
//uint16_t r_max = static_cast<uint16_t>(filter_point_center_max_);
//uint16_t r_min = static_cast<uint16_t>(filter_line_center_min_);
//std::cout << "cx: " << x <<" cy: " << y
//<< "\n r_max: " << r_max << " r_min: " << r_min << std::endl;
////cv::Mat img_mask(img_h.rows, img_h.cols, CV_8U);
////cv::circle(img_mask, cv::Point2d(x,y), r_max, cv::Scalar(255), -1);
////cv::Mat img_roi;
////img_h.copyTo(img_roi, img_mask);
//double sum = 0;
//uint8_t p_max = 0;
//uint8_t p_min = 255;
//for(uint16_t i=y-r_min; i<y+r_min; i++ )
//{
//for(uint16_t j=x-r_min; j<x+r_min; j++)
//{
//const auto& pixel = img_h.at<uint8_t>(i,j);
//sum += pixel;
//if( p_max < pixel)
//{
//p_max = pixel;
//}
//if(p_min > pixel)
//{
//p_min = pixel;
//}
//}
//}
//uint8_t average = static_cast<uint8_t>(sum/(4*r_min*r_min));
//std::cout << "average: " << static_cast<int>(average)
//<< " p_min: " << static_cast<int>(p_min)
//<< " p_max: " << static_cast<int>(p_max) << std::endl;
//p_max += 4;
//p_min -= 4;
//for(uint16_t i=0; i<img.rows; i++)
//{
//for(uint16_t j=0; j<img.cols; j++)
//{
//double d = (i-y)*(i-y) + (j-x)*(j-x);
//d = std::sqrt(d);
//auto& pixel = img_h.at<uint8_t>(i,j);
//if(d >= filter_point_center_max_)
//{
//pixel = 0;
//}
//else
//{
//if(pixel > p_max)
//{
//pixel = 255 - (p_max - pixel);
////pixel = 0;
//}
//else if(pixel < p_min)
//{
//pixel = 255 - (pixel-p_min);
////pixel = 0;
//}
//else
//{
//pixel = 255;
//}
//}
//}
//}
//cv::threshold(img_h, img_h,0,180,cv::THRESH_BINARY+cv::THRESH_OTSU);
//img_h = img_h*255/180;
cv::Mat img_h;
cv::cvtColor(img, img_h, cv::COLOR_BGR2GRAY);
// cv::imwrite("img_gray.png", img_h);
if(detector_->EDline(img_h) < 0 )
{
std::cerr << "E: EDline detector fail to detect lines in the image\n";
return false;
}
for (uint16_t i =0; i<detector_->lineEquations_.size(); i++)
{
ls.emplace_back();
Line2D& last = ls.back();
// ax+by+c=0 direction vector=(-b a)
last.dir = std::atan2(-detector_->lineEquations_[i][0],
detector_->lineEquations_[i][1])/MATH_PI*180;
if(last.dir<0)
{
last.dir += 180;
}
last.p0 << detector_->lineEndpoints_[i][0],
detector_->lineEndpoints_[i][1],
1;
last.p1 << detector_->lineEndpoints_[i][2],
detector_->lineEndpoints_[i][3],
1;
last.coef << detector_->lineEquations_[i][0],
detector_->lineEquations_[i][1],
detector_->lineEquations_[i][2];
last.coef = last.coef/(last.coef.head(2).norm());
last.points.resize(2, detector_->lines_.sId[i+1]-detector_->lines_.sId[i]);
uint16_t col_index = 0;
for(uint16_t j=detector_->lines_.sId[i]; j<detector_->lines_.sId[i+1]; j++)
{
last.points.col(col_index++) << detector_->lines_.xCors[j],
detector_->lines_.yCors[j];
}
}
return true;
}
/**
* filter criteria
* 1. center to endpoint distances
* 2. center to line distance
* 3. endpoints to line distances
* 4. line direction angle error
*/
bool ImagePolygon::FilterLines(std::list<Line2D>& ls, Polygon2D::ConstPtr prev)
{
if(ls.size() < size_ )
{
return false;
}
auto l = ls.begin();
while( l != ls.end() )
{
auto ln = l;
l++;
double center2point_0 = (prev->center - ln->p0).norm();
double center2point_1 = (prev->center - ln->p1).norm();
double center2line = std::abs(prev->center.dot(ln->coef));
if( center2point_0 > filter_point_center_max_ ||
center2point_1 > filter_point_center_max_ ||
center2line < filter_line_center_min_ )
{
ls.erase( ln );
continue;
}
bool is_remove = true;
for(uint32_t i=0; i<size_; i++)
{
double d = std::abs(ln->p0.dot(prev->edges[i].coef));
d += std::abs(ln->p1.dot(prev->edges[i].coef));
double angle = std::abs(ln->dir - prev->edges[i].dir);
if(angle > 90)
{
angle = 180 - angle;
}
if(angle < filter_line_angle_threshold_ &&
d < filter_point_line_threshold_)
{
is_remove = false;
}
}
if(is_remove )
{
ls.erase( ln );
}
}
return ls.size() >= size_ ? true : false;
}
/**
* @brief merge all paralle lines
* @param ls
* @return
*/
bool ImagePolygon::MergeLines(std::list<Line2D>& ls)
{
if(ls.size() < size_)
{
std::cerr << "E: no enough line segments for " << __FUNCTION__
<< "\n get " << ls.size() << " lines\n";
return false;
}
auto ln = ls.begin();
while(ln != ls.end())
{
bool flag = false;
auto ln_nx = std::next(ln);
while(ln_nx != ls.end())
{
// distance error
double d = std::abs(ln->p0.transpose()*ln_nx->coef);
d += std::abs(ln->p1.transpose()*ln_nx->coef);
d += std::abs(ln_nx->p0.transpose()*ln->coef);
d += std::abs(ln_nx->p1.transpose()*ln->coef);
Eigen::Vector4d e2e;
e2e(0) = (ln->p0 - ln_nx->p0).norm();
e2e(1) = (ln->p0 - ln_nx->p1).norm();
e2e(2) = (ln->p1 - ln_nx->p0).norm();
e2e(3) = (ln->p1 - ln_nx->p1).norm();
// direction angle error
double angle = std::abs(ln->dir - ln_nx->dir);
if(angle > 90)
{
angle = 180 - angle;
}
if(angle < merge_angle_threshold_ &&
d < merge_distance_threshold_ &&
e2e.minCoeff() < merge_endpoint_distance_threshold_)
{
// merge two line segement
flag = true;
// find endpoints
Eigen::Matrix3Xd endpoint(3,4);
endpoint.col(0) = ln->p0;
endpoint.col(1) = ln->p1;
endpoint.col(2) = ln_nx->p0;
endpoint.col(3) = ln_nx->p1;
uint32_t axis = 0; // x-axis
if(std::abs(ln->dir - 90) < 10)
{
axis = 1; // y-axis
}
uint8_t id_max =0, id_min = 1;
for(uint8_t i=0; i<4; i++)
{
if(endpoint(axis, i) > endpoint(axis, id_max))
{
id_max = i;
}
else if (endpoint(axis, i) < endpoint(axis, id_min))
{
id_min = i;
}
}
ln->p0 = endpoint.col(id_min);
ln->p1 = endpoint.col(id_max);
ln->points.conservativeResize(Eigen::NoChange,
ln->points.cols()+ln_nx->points.cols());
ln->points.topRightCorner(2,ln_nx->points.cols()) = ln_nx->points;
// erase node
ln_nx++;
ls.erase(std::prev(ln_nx));
}
else
{
ln_nx++;
}
}
if(flag)
{
ln->dir = -1;
ln->coef.setZero();
}
ln++;
}
if(ls.size() < size_)
{
std::cerr << "E: no enough line segments after merging\n"
<< " get " << ls.size() << " lines\n";
return false;
}
// re-fit lines
for(auto&ln : ls)
{
if(ln.dir >=0 )
{
continue;
}
std::vector<cv::Point2d> pts;
pts.reserve(ln.points.cols());
for(uint32_t i=0; i<ln.points.cols(); i++)
{
pts.emplace_back(ln.points(0,i), ln.points(1,i));
}
std::vector<double> coef(4, 0);
cv::fitLine(pts, coef, cv::DIST_L1,0, 0.01, 0.01);
ln.coef(0) = coef[1];
ln.coef(1) = -coef[0];
ln.coef(2) = -1*(ln.coef(0)*coef[2] + ln.coef(1)*coef[3]);
ln.coef = ln.coef/(ln.coef.head(2).norm());
ln.dir = std::atan2(coef[1], coef[0])/MATH_PI*180;
if(ln.dir < 0)
{
ln.dir += 180;
}
}
return true;
}
//@TODO only apply to rectangular board
bool ImagePolygon::FilterLinesByRectangule(std::list<Line2D>& ls, Polygon2D::ConstPtr prev)
{
assert(ls.size()>=4 );
if(ls.size() < size_)
{
std::cerr << "E: no enough lines for " << __FUNCTION__
<< "\n get " << ls.size() << "lines \n";
return false;
}
struct RectangleEdges
{
double error;
uint32_t id0;
uint32_t id1;
RectangleEdges(double error_, uint32_t id0_, uint32_t id1_):
error(error_), id0(id0_), id1(id1_) {}
};
std::list<RectangleEdges> width;
std::list<RectangleEdges> length;
uint32_t id0 = 0;
for(auto l=ls.cbegin(); l!=ls.cend(); l++)
{
uint32_t id1 = id0+1;
Eigen::Vector3d ep2c = prev->center - (l->p0 + l->p1)/2;
for(auto next=std::next(l); next!=ls.cend(); next++)
{
double err_angle = LineAngleError(l->dir, next->dir);
if( err_angle < 10)
{
// parallel line
double dis = std::abs(next->coef.dot(l->p0));
dis += std::abs(next->coef.dot(l->p1));
dis += std::abs(l->coef.dot(next->p0));
dis += std::abs(l->coef.dot(next->p1));
dis = dis/4;
Eigen::Vector3d c2c = (next->p0+next->p1)/2 - (l->p0 + l->p1)/2 ;
c2c.normalize();
double err_c2c = c2c.cross(ep2c).norm();
double angle_width = LineAngleError(angle_width_,
LineAngleAverage(l->dir,next->dir));
double angle_length = LineAngleError(angle_length_,
LineAngleAverage(l->dir, next->dir));
if(angle_width > angle_length)
{
double dis_rate = std::abs(dis - width_)/width_;
if(dis_rate < 0.15)
{
length.emplace_back(dis_rate*err_angle*err_c2c, id0, id1);
}
}
else
{
double dis_rate = std::abs(dis - length_)/length_;
if(dis_rate < 0.15)
{
width.emplace_back(dis_rate*err_angle*err_c2c, id0, id1);
}
}
}
id1++;
}
id0++;
}
if(width.size()<1 || length.size() <1)
{
std::cerr << "E: FilterLinesByRectangule width: " << width.size()
<< " length: " << length.size() << std::endl;
return false;
}
auto RectangleEdgesSort = [](const RectangleEdges& a, const RectangleEdges& b)
{
return a.error < b.error;
};
if(width.size() > 1)
{
width.sort(RectangleEdgesSort);
}
if(length.size() > 1)
{
length.sort(RectangleEdgesSort);
}
std::set<uint32_t> edges;
edges.insert(width.front().id0);
edges.insert(width.front().id1);
edges.insert(length.front().id0);
edges.insert(length.front().id1);
id0 = 0;
auto ln = ls.begin();
while(ln != ls.end())
{
ln++;
if(edges.count(id0) == 0)
{
ls.erase(std::prev(ln));
}
id0++;
}
return true;
}
bool ImagePolygon::SortLines(std::list<Line2D>& ls, Polygon2D::ConstPtr prev, Polygon2D::Ptr& ply )
{
if(ls.size() != size_)
{
std::cerr << "E: too many/fewer line segments to sort\n"
<< " get " << ls.size() << " lines\n";
return false;
}
using PairUD = std::pair<uint32_t,double>;
Eigen::Vector3d center;
for(const auto& it:ls)
{
center += it.p0;
center += it.p1;
}
center = center / (ls.size()*2);
for(auto& it:ls)
{
Eigen::Vector3d mid = (it.p0 + it.p1)/2;
it.dir = std::atan2(mid(1)-center(1), mid(0)-center(0)) + MATH_PI;
}
ls.sort([](Line2D& a, Line2D& b)
{
return a.dir < b.dir;
});
// find all vertexs
std::vector<Eigen::Vector3d>vertexs(size_);
{
auto l = ls.cbegin();
for(auto& it:vertexs)
{
Eigen::Matrix2d A;
Eigen::Vector2d B;
A.row(0) = l->coef.head(2);
B(0) = -1*l->coef(2);
if(l != ls.cbegin())
{
auto pre = std::prev(l);
A.row(1) = pre->coef.head(2);
B(1) = -1*pre->coef(2);
}
else
{
A.row(1) = ls.back().coef.head(2);
B(1) = -1*ls.back().coef(2);
}
it.head(2) = A.inverse()*B;
it(2) = 1;
l++;
}
}
// find offset, index correspondence
uint32_t id_cors = 0;
{
double error = INT_MAX;
auto& l0 = ls.front();
double dir = std::atan2(-l0.coef(0), l0.coef(1))/MATH_PI*180;
if(dir < 0)
{
dir += 180;
}
for(uint32_t i=0; i<size_; i++)
{
double err = std::abs(prev->edges[i].dir - dir)*2;
err += std::abs(l0.p0.dot(prev->edges[i].coef));
err += std::abs(l0.p1.dot(prev->edges[i].coef));
if(err < error)
{
id_cors = i;
}
}
}
ply = std::make_shared<Polygon2D>(size_);
uint32_t id = 0;
for(const auto& it: ls)
{
uint32_t pindex = (id+id_cors)%size_;
ply->edges[pindex].coef = it.coef;
double dir = std::atan2(-it.coef(0), it.coef(1))/MATH_PI*180;
if(dir < 0)
{
dir += 180;
}
ply->edges[pindex].dir = dir;
Eigen::Vector3d p01 = vertexs[id] - vertexs[(id+1)%size_];
ply->edges[pindex].length = p01.head(2).norm();
ply->vertexs.col(pindex) = vertexs[id];
id++;
}
return true;
}
void ImagePolygon::UpdateParameters()
{
UpdateParameters(polygon_);
}
void ImagePolygon::UpdateParameters(Polygon2D::Ptr ply)
{
// update threshold
// Eigen::Vector3d center;
// center.setZero();
// for(auto& it: ply->vertexs)
// {
// center += it;
// }
// center = center/size_;
Eigen::Vector3d center = ply->vertexs.rowwise().mean();
ply->center = center;
Eigen::VectorXd center2point(size_);
Eigen::VectorXd center2line(size_);
for(uint32_t i=0; i<size_; i++)
{
center2point(i) = (center - ply->vertexs.col(i)).norm();
center2line(i) = std::abs( center.dot(ply->edges[i].coef) );
}
filter_point_center_max_ = center2point.maxCoeff()*(1+filter_point_center_factor_);
filter_line_center_min_ = center2line.minCoeff()*(1-filter_point_center_factor_);
//@TODO
double dis0=0, dis1=0;
dis0 += std::abs(ply->edges[2].coef.dot(ply->vertexs.col(0) ));
dis0 += std::abs(ply->edges[2].coef.dot(ply->vertexs.col(1) ));
dis0 += std::abs(ply->edges[0].coef.dot(ply->vertexs.col(2) ));
dis0 += std::abs(ply->edges[0].coef.dot(ply->vertexs.col(3) ));
dis0 = dis0 / 4;
double angle1 = LineAngleAverage(ply->edges[2].dir, ply->edges[0].dir);
dis1 += std::abs(ply->edges[1].coef.dot(ply->vertexs.col(0) ));
dis1 += std::abs(ply->edges[1].coef.dot(ply->vertexs.col(3) ));
dis1 += std::abs(ply->edges[3].coef.dot(ply->vertexs.col(1) ));
dis1 += std::abs(ply->edges[3].coef.dot(ply->vertexs.col(2) ));
dis1 = dis1 / 4;
double angle0 = LineAngleAverage(ply->edges[1].dir, ply->edges[3].dir);
if(dis0 < dis1)
{
width_ = dis0;
length_ = dis1;
angle_width_ = angle0;
angle_length_ = angle1;
}
else
{
width_ = dis1;
length_ = dis0;
angle_width_ = angle1;
angle_length_ = angle0;
}
std::cout << "width: " << width_ << " length: " << length_
<< "\n angle_width: " << angle_width_
<< " angle_length: " << angle_length_ << "\n";
}
double ImagePolygon::LineAngleError(double l0, double l1)
{
double e = std::abs(l0 - l1);
if(e >90)
{
e = 180 - e;
}
return e;
}
double ImagePolygon::LineAngleAverage(double l0, double l1)
{
double e = (l0+l1)/2;
if(std::abs(l0 - l1) > 90)
{
e = (l0+l1-180)/2;
}
return e;
}
void ImagePolygon::MarkImage(cv::Mat &img, const std::list<Line2D> &ls)
{
utils::color::rgbs colors = utils::color::get_rgbs(ls.size());
auto lines_it = ls.cbegin();
for (std::size_t i = 0; i < ls.size(); i++)
{
auto& it = *lines_it;
cv::Scalar color(colors[i][0], colors[i][1], colors[i][2]);
cv::Point2d p0(it.p0(0), it.p0(1));
cv::Point2d p1(it.p1(0), it.p1(1));
cv::line(img, p0, p1, color, 2 );
cv::circle(img, p0, 5, color);
cv::circle(img, p1, 4, color);
cv::putText(img, std::to_string(i),(p0+p1)/2,
cv::FONT_HERSHEY_SIMPLEX, 2, color, 2 );
lines_it++;
}
if(polygon_ != nullptr)
{
const auto& c = polygon_->center;
cv::circle(img, cv::Point2d(c(0), c(1)), filter_line_center_min_,
cv::Scalar(0,0,255), 2);
cv::circle(img, cv::Point2d(c(0), c(1)), filter_point_center_max_,
cv::Scalar(0,255,0), 2);
}
}
void ImagePolygon::MarkImage(cv::Mat& img, Polygon2D::ConstPtr ply)
{
utils::color::rgbs colors = utils::color::get_rgbs( size_ );
for (uint32_t i = 0; i < size_; i++)
{
uint32_t next = (i== size_-1)?0:i+1;
auto& it = ply->vertexs;
auto& ln = ply->edges[i];
cv::Scalar color(colors[i][2], colors[i][1], colors[i][0]);
cv::Point2d p0( it(0,i), it(1,i) );
cv::Point2d p1( it(0,next), it(1, next) );
// draw id
cv::putText(img, std::to_string(i),(p0+p1)/2,
cv::FONT_HERSHEY_SIMPLEX, 2, color, 2 );
// draw vertex
if(i == 0)
{
cv::circle(img, p0, 8, color, 3);
}
else
{
cv::circle(img, p0, 5, color);
}
// draw line
if( std::abs(ln.dir - 90 ) < 45)
{
p0.y = 0;
p0.x = -1*ln.coef(2)/ln.coef(0);
p1.y = img.rows;
p1.x = -1*(ln.coef(2) + ln.coef(1)*p1.y)/ln.coef(0);
}
else
{
p0.x = 0;
p0.y = -1*ln.coef(2)/ln.coef(1);
p1.x = img.cols;
p1.y = -1*(ln.coef(2) + ln.coef(0)*p1.x)/ln.coef(1);
}
cv::line(img, p0, p1, color, 1 );
}
}
bool ImagePolygon::SaveMarkedImage(const std::string& fn,
const cv::Mat& img, const std::list<Line2D>&ls)
{
cv::Mat img_line;
if(img.channels() == 1)
{
#if (CV_VERSION_MAJOR >= 4)
cv::cvtColor(img, img_line, cv::COLOR_GRAY2BGR);
#else
cv::cvtColor(img, img_line, CV_GRAY2BGR);
#endif
}
else
{
img_line = img.clone();
}
MarkImage(img_line, ls);
return cv::imwrite(fn, img_line);
}
bool ImagePolygon::SaveMarkedImage(const std::string& fn, const cv::Mat& img,
Polygon2D::ConstPtr ply)
{
cv::Mat img_line;
if(img.channels() == 1)
{
#if (CV_VERSION_MAJOR >= 4)
cv::cvtColor(img, img_line, cv::COLOR_GRAY2BGR);
#else
cv::cvtColor(img, img_line, CV_GRAY2BGR);
#endif
}
else
{
img_line = img.clone();
}
MarkImage(img_line, ply);
return cv::imwrite(fn, img_line);
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/image_polygon.h
================================================
/**
******************************************************************************
* @file image_polygon.h
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-22
* @brief image_polygon.h
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __IMAGE_POLYGON_H
#define __IMAGE_POLYGON_H
/* Includes ------------------------------------------------------------------*/
#include <string>
#include <vector>
#include <memory>
#include <stdint.h>
#include <Eigen/Dense>
#include "json/json.hpp"
#include "edlines/EDLineDetector.h"
/* Exported macro ------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
namespace lqh
{
class ImagePolygon
{
public:
using LineFeature = Eigen::Matrix<uint8_t,3,Eigen::Dynamic>;
struct Edge2D
{
double dir;
double length;
Eigen::Vector3d coef;
LineFeature feature;
};
struct Polygon2D
{
using ConstPtr = std::shared_ptr<const Polygon2D>;
using Ptr = std::shared_ptr<Polygon2D>;
Eigen::Vector3d center;
Eigen::Matrix3Xd vertexs;
std::vector<Edge2D> edges;
Polygon2D(uint32_t size)
{
center.setZero();
vertexs.resize(3, size);
edges.resize(size);
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
explicit ImagePolygon(const nlohmann::json& js, uint8_t size);
Polygon2D::ConstPtr Add(const cv::Mat& img, cv::Mat& img_out);
Polygon2D::ConstPtr Init(const cv::Mat& img, cv::Mat& img_out, const Eigen::Matrix3Xd& pts);
bool SaveMarkedImage(const std::string& fn, const cv::Mat& img,
Polygon2D::ConstPtr pyg);
private:
struct Line2D
{
double dir;
Eigen::Vector3d p0, p1;
Eigen::Vector3d coef;
Eigen::Matrix2Xi points;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
const uint32_t size_; // current implemention only support size_=4
uint32_t feature_size_;
uint32_t feature_offset_;
double feature_threshold_;
double merge_distance_threshold_;
double merge_angle_threshold_;
double merge_endpoint_distance_threshold_;
double filter_point_line_threshold_;
double filter_line_angle_threshold_;
double filter_point_center_factor_;
double filter_point_center_max_;
double filter_line_center_min_;
//@TODO only apply for rectangular board, size_ == 4
double width_;
double length_;
double angle_width_;
double angle_length_;
std::unique_ptr<EDLineDetector> detector_; // line detector
// edge descripter
Polygon2D::Ptr polygon_; // last polygon
Polygon2D::ConstPtr ExtractPolygon(const cv::Mat& img, cv::Mat& img_out,
Polygon2D::ConstPtr prev);
Polygon2D::Ptr InitPolygon(const Eigen::Matrix3Xd& pts);
bool ExtractLines(const cv::Mat& img, std::list<Line2D>& ls);
bool FilterLines(std::list<Line2D>& ls, Polygon2D::ConstPtr prev);
bool MergeLines(std::list<Line2D>& ls);
bool FilterLinesByRectangule(std::list<Line2D>& ls, Polygon2D::ConstPtr prev);
bool SortLines(std::list<Line2D>& ls, Polygon2D::ConstPtr prev, Polygon2D::Ptr& ply);
void UpdateParameters();
void UpdateParameters(Polygon2D::Ptr ply);
double LineAngleError(double l0, double l1);
double LineAngleAverage(double l0, double l1);
void MarkImage(cv::Mat& img_out, const std::list<Line2D>&ls);
void MarkImage(cv::Mat& img_out, Polygon2D::ConstPtr ply);
bool SaveMarkedImage(const std::string& fn, const cv::Mat& img,
const std::list<Line2D>&ls);
};
}
/* Exported constants --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#endif /* !__IMAGE_POLYGON_H */
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/pointcloud_polygon.cpp
================================================
/**
******************************************************************************
* @file pointcloud_polygon.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-26
* @brief pointcloud_polygon.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "pointcloud_polygon.h"
#include <cmath>
#include <map>
#include <functional>
#include <pcl/common/io.h>
#include <pcl/common/common.h>
#include <pcl/io/pcd_io.h>
#include <pcl/sample_consensus/sac_model_plane.h>
#include <pcl/sample_consensus/sac_model_line.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
using namespace lqh;
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
//#define NODEBUG
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
PointcloudPolygon::PointcloudPolygon(const nlohmann::json& js, uint8_t size):
size_(size), polygon_(nullptr)
{
pc_angle_resolution_ = js["angle_resolution"].get<double>();
filter_angle_start_ = js["filter"]["angle_start"].get<double>();
filter_angle_size_ = js["filter"]["angle_size"].get<double>();
filter_distance_ = js["filter"]["distance"].get<double>();
filter_floor_gap_ = js["filter"]["floor_gap"].get<double>();
plane_point_num_min_ = js["plane"]["point_num_min"].get<uint32_t>();
plane_distance_threshold_ = js["plane"]["distance_threshold"].get<double>();
ring_point_num_min_ = js["ring"]["point_num_min"].get<uint32_t>();
ring_endpoint_num_ = js["ring"]["endpoint_num"].get<uint32_t>();
if(ring_endpoint_num_ > ring_point_num_min_)
{
std::cout << "W: ring:endpoint_num_min must <= ring:point_num_min\n"
<< " set ring:endpoint_num = ring:point_num_min\n";
ring_endpoint_num_ = ring_point_num_min_;
}
edge_point_num_min_ = js["edge"]["point_num_min"].get<uint32_t>();
edge_distance_threshold_ = js["edge"]["distance_threshold"].get<double>();
}
PointcloudPolygon::Polygon3D::ConstPtr PointcloudPolygon::Add(
const pcl::PointCloud<pcl::PointXYZI>& pc,
pcl::PointCloud<pcl::PointXYZRGB>& pcc)
{
Polygon3D::Ptr ply = std::make_shared<Polygon3D>(size_);
std::vector<int> indices;
if(pcc.size() != pc.size())
{
pcl::copyPointCloud(pc, pcc);
}
for(auto& p : pcc.points)
{
p.rgba = 0xffffffff;
}
lqh::utils::color::rgbs colors = lqh::utils::color::get_rgbs(5);
ply->coef.setZero();
SectorFilter(pc, indices);
MarkPointcloud(pcc, colors[0], indices);
if(indices.size() < plane_point_num_min_)
{
return nullptr;
}
// SaveMarkedPointcloud("SectorFilter.pcd", pc, indices);
bool res = ExtractPlane(pc, indices, ply->coef);
if(!res)
{
return nullptr;
}
MarkPointcloud(pcc, colors[1], indices);
// SaveMarkedPointcloud("ExtractPlane.pcd", pc, indices);
Indices edge_left, edge_right, inliers;
ExtractRings(pc, indices, inliers, edge_left, edge_right);
MarkPointcloud(pcc, colors[2], inliers);
MarkPointcloud(pcc, colors[3], edge_left);
MarkPointcloud(pcc, colors[4], edge_right);
// SaveMarkedPointcloud("inlier.pcd", pc, inliers);
// SaveMarkedPointcloud("edge_left.pcd", pc, edge_left);
// SaveMarkedPointcloud("edge_right.pcd", pc, edge_right);
// vertexs, line coefficient is not valid
ply->inliers.resize(3, inliers.size());
for(uint32_t i=0; i<inliers.size(); i++)
{
auto& p = pc.points[inliers[i]];
ply->inliers.col(i) << p.x, p.y, p.z;
}
//ExtractEdges(pc, edge_left, ply->edges[0], ply->edges[1]);
//ExtractEdges(pc, edge_right, ply->edges[3], ply->edges[2]);
ExtractEdgesMems(pc, edge_left, ply->edges[0], ply->edges[1], true);
ExtractEdgesMems(pc, edge_right, ply->edges[3], ply->edges[2], false);
polygon_ = ply;
// SaveMarkedPointcloud("Add.pcd",pc, ply);
return ply;
}
void PointcloudPolygon::SetFilterParameters(const Eigen::Vector4d& p)
{
if(p(0) >=0 && p(0) <=360)
{
filter_angle_start_ = p(0);
}
if(p(1) >0 && p(1) < 360)
{
filter_angle_size_ = p(1);
}
if(p(2) > 0)
{
filter_distance_ = p(2);
}
if(p(3) > -10)
{
filter_floor_gap_ = p(3);
}
}
void PointcloudPolygon::SectorFilter(const PCI& pc, Indices& indices)
{
indices.clear();
indices.reserve(plane_point_num_min_*10);
Eigen::Vector4f min_pt, max_pt;
pcl::getMinMax3D(pc, min_pt, max_pt);
double z_threshold = min_pt(2)+ filter_floor_gap_;
for(uint32_t i=0; i<pc.points.size(); i++)
{
auto& p = pc.points[i];
double theta = std::atan2(p.y, p.x)/MATH_PI*180;
if(theta<0)
{
theta += 360;
}
double dis = std::sqrt(p.y*p.y + p.x*p.x);
double size = theta - filter_angle_start_;
if(size < 0)
{
size += 360;
}
if(p.z > z_threshold && dis < filter_distance_
&& size < filter_angle_size_)
{
indices.push_back(i);
}
}
}
bool PointcloudPolygon::ExtractPlane(const PCI& pc, Indices& indices,
Eigen::Vector4d& coef)
{
PCI::Ptr pc_ptr (new PCI);
pcl::copyPointCloud(pc, *pc_ptr);
pcl::IndicesPtr indices_ptr(new std::vector<int>);
indices_ptr->resize(indices.size());
std::copy(indices.begin(), indices.end(), indices_ptr->begin());
pcl::ModelCoefficients model_coef;
pcl::PointIndices ids;
pcl::SACSegmentation<pcl::PointXYZI> seg;
seg.setOptimizeCoefficients (true);
seg.setModelType (pcl::SACMODEL_PLANE);
seg.setMethodType (pcl::SAC_RANSAC);
seg.setDistanceThreshold (plane_distance_threshold_);
seg.setInputCloud(pc_ptr);
seg.setIndices(indices_ptr);
seg.segment(ids, model_coef);
if(ids.indices.size() > plane_point_num_min_ )
{
coef << model_coef.values[0], model_coef.values[1],
model_coef.values[2], model_coef.values[3];
std::swap(ids.indices, indices);
return true;
}
else
{
std::cerr << "E: Fail to extract plane" << std::endl;
return false;
}
}
bool PointcloudPolygon::ExtractRings(const PCI& pc, const Indices& indices,
Indices& inlier, Indices& left, Indices& right)
{
struct Point
{
int8_t pitch;
uint32_t id;
double yaw;
Point(uint32_t pid, int8_t ppitch, double pyaw):
pitch(ppitch),id(pid),yaw(pyaw) {}
};
if(indices.size() < plane_point_num_min_)
{
std::cerr << "E: no enough points to extract edge/inlier\n";
return false;
}
std::map<int16_t, std::vector<Point>> pts;
for(auto it:indices)
{
auto& p = pc.points[it];
double yaw = std::atan2(p.y, p.x);
double pitch_d = std::atan(p.z/std::sqrt(p.y*p.y+p.x*p.x))/MATH_PI*180;
int16_t pitch = std::round(pitch_d/pc_angle_resolution_);
pts[pitch].emplace_back(it, pitch, yaw);
}
left.reserve( pts.size()*ring_endpoint_num_ );
right.reserve( pts.size()*ring_endpoint_num_ );
inlier.reserve(indices.size() - pts.size()*ring_endpoint_num_*2);
for(auto& r: pts )
{
auto& ring = r.second;
// every ring must have certain points
if(ring.size() < ring_point_num_min_)
{
continue;
}
std::sort(ring.begin(), ring.end(),
[](const Point& a, const Point& b)
{
return a.yaw < b.yaw;
});
// clean every ring with 3 sigma principle
// sample the center 1/3
double mean = 0;
double sigma = 0;
uint32_t num = ring.size()-1;
uint32_t num_3 = num/3;
std::vector<double> yaw_err(num);
for(uint32_t i=0; i<num; i++)
{
double tmp = ring[i+1].yaw - ring[i].yaw;
yaw_err[i]=tmp;
if(i >= num_3 && i<num_3*2)
{
mean += tmp;
sigma += tmp*tmp;
}
}
mean = mean/(num_3);
sigma = std::sqrt((sigma- mean*mean)/num_3);
// from center to both end
// we don't check center point, we think it's valid
uint32_t center = num/2;
for(uint32_t i=center+1; i<num; i++)
{
if(std::abs(yaw_err[i]-mean) > 3*sigma)
{
ring.erase(ring.begin()+i+1, ring.end());
break;
}
}
for(int32_t i=center-1; i>=0; i--)
{
if(std::abs(yaw_err[i]-mean) > 3*sigma)
{
ring.erase(ring.begin(), ring.begin()+i+1);
break;
}
}
// save endpoints: edges
for(uint32_t i=0; i<ring_endpoint_num_; i++)
{
uint32_t id_right = ring.size()-1-i;
right.push_back(ring[i].id);
left.push_back(ring[id_right].id);
}
// save inside points: inlier
if( ring.size() > 2*ring_endpoint_num_ )
{
for(uint32_t i=ring_endpoint_num_;
i<ring.size()-ring_endpoint_num_; i++)
{
inlier.push_back(ring[i].id);
}
}
}
return true;
}
bool PointcloudPolygon::ExtractEdges(const PCI& pc, Indices& indices,
Edge3D& edge0, Edge3D& edge1)
{
Indices ids;
Eigen::Vector3d coef, pt;
FitLine(pc, indices, ids, coef, pt);
std::sort(ids.begin(), ids.end(), [&pc](const int a, const int b)
{
return pc.points[a].z < pc.points[b].z;
});
auto AssembleEdge = [&pc](const Indices& indices, Edge3D& edge)
{
edge.points.resize(3, indices.size());
for(uint32_t i=0; i<indices.size(); i++)
{
auto& p = pc.points[indices[i]];
edge.points.col(i) << p.x, p.y, p.z;
}
};
auto Yaw = [](const pcl::PointXYZI& p)->double
{
return std::atan2(p.y, p.x);
};
// only one line
if(ids.size() == indices.size())
{
double yaw_b = Yaw(pc.points[ids.front()]);
double yaw_t = Yaw(pc.points[ids.back()]);
double yaw_bt = yaw_t-yaw_b;
if(std::abs(yaw_bt) > MATH_PI)
{
yaw_bt = yaw_bt >MATH_PI ? 2*MATH_PI - yaw_bt : 2*MATH_PI+yaw_bt;
}
if(yaw_bt > 0)
{
edge0.coef = coef; // the line is first line
edge0.p0 = pt;
AssembleEdge(ids, edge0);
}
else
{
edge1.coef = coef;
edge1.coef = pt;
AssembleEdge(ids, edge1);
}
}
else
{
// two lines
// ids_another = indices - ids
std::vector<int> ids_another;
std::set_difference(
indices.begin(), indices.end(),
ids.begin(), ids.end(),
std::back_inserter( ids_another )
);
double err_dis = 0;
for(uint32_t i=0; i<ring_endpoint_num_; i++)
{
auto& it = pc.points[indices[i]];
Eigen::Vector3d pt_i(it.x, it.y, it.z);
err_dis += coef.cross(pt_i - pt).norm();
}
err_dis = err_dis/ring_endpoint_num_;
if(err_dis > edge_distance_threshold_)
{
// fitline is the second line
edge1.coef = coef;
AssembleEdge(ids, edge1);
AssembleEdge(ids_another, edge0);
}
else
{
edge0.coef = coef;
AssembleEdge(ids, edge0);
AssembleEdge(ids_another, edge1);
}
}
return true;
}
bool PointcloudPolygon::ExtractEdgesMems(const PCI& pc, Indices& indices,
Edge3D& edge0, Edge3D& edge1, bool is_left)
{
Indices first, second;
first.reserve(indices.size()/2);
// left find y-max, right find y-min
double y_m = pc.points[indices[0]].y;
uint32_t id_sep = 0;
if(is_left)
{
uint32_t i = 0;
for(auto id : indices)
{
if(pc.points[id].y >= y_m)
{
y_m = pc.points[id].y;
id_sep = i;
}
i++;
}
if (id_sep == 0)
{
id_sep = indices.size()-1;
}
}
else
{
uint32_t i = 0;
for(auto id : indices)
{
if(pc.points[id].y < y_m)
{
y_m = pc.points[id].y;
id_sep = i;
}
i++;
}
if(id_sep == indices.size()-1)
{
id_sep = 0;
}
}
for(uint32_t i=0; i<=id_sep; i++)
{
first.push_back(indices[i]);
}
for(uint32_t i=id_sep; i<indices.size(); i++)
{
second.push_back(indices[i]);
}
auto makeEdge = [&pc, this](Indices& indice, Edge3D& edge)
{
if(indice.size() > 3)
{
Indices inlier;
FitLine(pc, indice, inlier, edge.coef, edge.p0);
edge.points.resize(3, inlier.size());
uint32_t i=0;
for(auto it: inlier)
{
edge.points(0,i)= pc.points[it].x;
edge.points(1,i)= pc.points[it].y;
edge.points(2,i)= pc.points[it].z;
i++;
}
}
};
makeEdge(first, edge0);
makeEdge(second, edge1);
return true;
};
void PointcloudPolygon::FitLine(const PCI& pc, const Indices& indices,
Indices& inlier, Eigen::Vector3d& coef, Eigen::Vector3d& pt)
{
PCI::Ptr pc_ptr(new PCI);
pc_ptr->points.reserve(indices.size());
for(auto it:indices)
{
pc_ptr->points.push_back( pc.points[it] );
}
pcl::ModelCoefficients model_coef;
pcl::PointIndices ids;
pcl::SACSegmentation<pcl::PointXYZI> seg;
seg.setOptimizeCoefficients (true);
seg.setModelType (pcl::SACMODEL_LINE);
seg.setMethodType (pcl::SAC_RANSAC);
seg.setDistanceThreshold (edge_distance_threshold_);
seg.setInputCloud(pc_ptr);
seg.segment(ids, model_coef);
pt(0) = model_coef.values[0];
pt(1) = model_coef.values[1];
pt(2) = model_coef.values[2];
coef(0) = model_coef.values[3];
coef(1) = model_coef.values[4];
coef(2) = model_coef.values[5];
coef.normalize();
inlier.reserve(ids.indices.size());
for(auto it:ids.indices)
{
inlier.push_back(indices[it]);
}
}
bool PointcloudPolygon::SaveMarkedPointcloud(const std::string& fn, const PCI& pc,
const Indices& indices) const
{
pcl::PointCloud<pcl::PointXYZRGB> pcc;
pcl::copyPointCloud(pc, pcc);
for(auto& it:pcc.points)
{
it.rgba = 0xffffffff;
}
for(auto it: indices)
{
pcc.points[it].rgba = 0xffff0000;
}
return pcl::io::savePCDFileBinary(fn, pcc);
}
bool PointcloudPolygon::SaveMarkedPointcloud(const std::string& fn,
const pcl::PointCloud<pcl::PointXYZI>& pc,
Polygon3D::ConstPtr ply) const
{
pcl::PointCloud<pcl::PointXYZRGB> pcc;
pcc.points.reserve(ply->inliers.cols() + ply->edges[0].points.cols()*
ply->edges.size());
lqh::utils::color::rgbs colors = lqh::utils::color::get_rgbs(size_+1);
pcl::PointXYZRGB p;
for(uint32_t i=0; i<size_; i++)
{
p.r = colors[i][0];
p.g = colors[i][1];
p.b = colors[i][2];
auto& ps = ply->edges[i].points;
for(uint32_t j=0; j<ps.cols(); j++)
{
p.x = ps(0,j);
p.y = ps(1,j);
p.z = ps(2,j);
pcc.push_back(p);
}
}
p.r = colors.back()[0];
p.g = colors.back()[1];
p.b = colors.back()[2];
for(uint32_t i=0; i<ply->inliers.cols(); i++)
{
p.x = ply->inliers(0,i);
p.y = ply->inliers(1,i);
p.z = ply->inliers(2,i);
pcc.push_back(p);
}
return pcl::io::savePCDFileBinary(fn, pcc);
}
bool PointcloudPolygon::SaveEdgePoints(const std::string& fn_prefix)
{
Eigen::IOFormat fmt(Eigen::FullPrecision, 0, ", ", "\n", "", "", "", "");
for(uint8_t i=0; i<polygon_->edges.size(); i++)
{
std::ofstream f(fn_prefix+std::to_string(i)+".csv");
if( !f.good() )
{
return false;
}
f << polygon_->edges[i].points.transpose().format(fmt);
f.close();
}
return true;
}
void PointcloudPolygon::MarkPointcloud(pcl::PointCloud<pcl::PointXYZRGB>& pcc,
const lqh::utils::color::rgb& color,
const Indices& indices) const
{
for(auto it : indices)
{
auto& p = pcc.points[it];
p.r = color[0];
p.g = color[1];
p.b = color[2];
}
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/pointcloud_polygon.h
================================================
/**
******************************************************************************
* @file pointcloud_polygon.h
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-26
* @brief pointcloud_polygon.h
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __POINTCLOUD_POLYGON_H
#define __POINTCLOUD_POLYGON_H
/* Includes ------------------------------------------------------------------*/
#include <string>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <Eigen/Dense>
#include "utils.h"
#include "json/json.hpp"
/* Exported macro ------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
namespace lqh
{
class PointcloudPolygon
{
public:
struct Edge3D
{
// @TODO
Eigen::Vector3d p0; // maybe invalid
Eigen::Vector3d coef; // maybe invalid
Eigen::Matrix3Xd points;
Edge3D():p0(0,0,0),coef(0,0,0) {}
};
struct Polygon3D
{
using ConstPtr = std::shared_ptr<const Polygon3D>;
using Ptr = std::shared_ptr<Polygon3D>;
Eigen::Vector4d coef;
Eigen::Matrix3Xd inliers;
std::vector<Eigen::Vector3d> vertexs; // maybe invalid
std::vector<Edge3D> edges;
Polygon3D(uint32_t size)
{
vertexs.resize(size, Eigen::Vector3d::Zero());
edges.resize(size);
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
explicit PointcloudPolygon(const nlohmann::json& js, uint8_t size);
Polygon3D::ConstPtr Add(const pcl::PointCloud<pcl::PointXYZI>& pc,
pcl::PointCloud<pcl::PointXYZRGB>& pcc);
void SetFilterParameters(const Eigen::Vector4d& p);
Eigen::Vector4d GetFilterParameters()
{
return Eigen::Vector4d(filter_angle_start_, filter_angle_size_,
filter_distance_, filter_floor_gap_);
}
bool SaveMarkedPointcloud(const std::string& fn,
const pcl::PointCloud<pcl::PointXYZI>& pc,
Polygon3D::ConstPtr ply) const;
bool SaveEdgePoints(const std::string& fn_prefix);
private:
using PCI = pcl::PointCloud<pcl::PointXYZI>;
using Indices = std::vector<int>;
const uint8_t size_;
double pc_angle_resolution_;
double filter_angle_start_;
double filter_angle_size_;
double filter_distance_;
double filter_floor_gap_;
uint32_t plane_point_num_min_;
double plane_distance_threshold_;
uint32_t ring_point_num_min_;
uint32_t ring_endpoint_num_;
uint32_t edge_point_num_min_;
double edge_distance_threshold_;
Polygon3D::Ptr polygon_;
void SectorFilter(const PCI& pc, Indices& indices);
bool ExtractPlane(const PCI& pc, Indices& indices, Eigen::Vector4d& coef);
Polygon3D::Ptr ExtractEdgeInlier(const PCI& pc, const Indices& indices);
bool ExtractRings(const PCI& pc, const Indices& indices,
Indices& inlier, Indices& left, Indices& right);
bool ExtractEdges(const PCI& pc, Indices& indices,
Edge3D& edge0, Edge3D& edge1);
void FitLine(const PCI& pc, const Indices& indices,
Indices& inlier, Eigen::Vector3d& coef, Eigen::Vector3d& pt);
void MarkPointcloud(pcl::PointCloud<pcl::PointXYZRGB>& pcc,
const lqh::utils::color::rgb& color,
const Indices& indices) const;
bool SaveMarkedPointcloud(const std::string& fn, const PCI& pc,
const Indices& indices) const;
bool ExtractEdgesMems(const PCI& pc, Indices& indices,
Edge3D& edge0, Edge3D& edge1, bool is_left);
};
}
/* Exported constants --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#endif /* !__POINTCLOUD_POLYGON_H */
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal/utils.h
================================================
/*
* utils.h
* Copyright (C) 2016 Nick.Liao <simplelife_nick@hotmail.com>
*
* Distributed under terms of the MIT license.
*/
#ifndef UTILS_H
#define UTILS_H
#include <stdint.h>
#include <iostream>
#include <string>
#include <memory>
#include <mutex>
#include <condition_variable>
#include <cmath>
#include <boost/asio/io_service.hpp>
#include <boost/bind.hpp>
#include <boost/thread/thread.hpp>
//#define LQH_DEBUG
namespace lqh
{
const double MATH_PI = 3.1415926535897932384626433832;
namespace utils
{
/**
* @brief
* @note: used only in main thread
*/
class pm
{
private:
boost::thread_group threadpool_;
boost::asio::io_service service_;
std::unique_ptr<boost::asio::io_service::work> work_;
public:
// type
class helper
{
friend class pm;
private:
std::mutex mtx_;
std::condition_variable cv_;
uint32_t cnt_;
// we don't want them to be called outside
void increase()
{
std::lock_guard<std::mutex> lg(mtx_);
cnt_++;
}
void decrease()
{
std::unique_lock<std::mutex> lg(mtx_);
cnt_--;
lg.unlock();
cv_.notify_one();
}
void wait()
{
std::unique_lock<std::mutex> ulk(mtx_);
while(cnt_)
{
cv_.wait(ulk, [this] {return !cnt_;} );
cnt_ = 0;
}
}
public:
helper():cnt_(0) {};
};
// member function
pm(uint32_t t_num=0):
work_(new boost::asio::io_service::work(service_))
{
uint32_t hard_num = boost::thread::hardware_concurrency();
t_num = t_num >0?t_num:(hard_num > 1? hard_num-1:1);
for(uint32_t i=0; i<hard_num; i++)
{
threadpool_.create_thread(
boost::bind(&boost::asio::io_service::run, &service_)
);
}
#ifdef LQH_DEBUG
std::cout << "Hardware support thread(s): " << hard_num << std::endl
<< "PM start thread(s): " << t_num << std::endl;
#endif
}
~pm()
{
work_ = nullptr;
threadpool_.join_all();
}
template <typename F>
void post(helper& h, F f)
{
auto handler = [f, &h]()
{
f();
h.decrease();
};
h.increase();
service_.post(handler);
}
void wait(helper& h)
{
h.wait();
}
};
class color
{
private:
public:
using rgb = std::array<uint8_t,3>;
using rgbs = std::vector<rgb>;
static rgb HSL2RGB(double H, double S, double L)
{
rgb res{{0,0,0}};
H = H<0 || H>360 ? 180:H;
S = S<0 || S>1 ? 0.5:S;
L = L<0 || L>1 ? 0.5:L;
double C = (1-std::abs(2*L-1))*S;
double X = C*(1-std::abs(std::fmod(H/60, 2) -1));
double m = L - C/2;
double RR, GG, BB;
if(H <60)
{
RR = C;
GG = X;
BB = 0;
}
else if(H <120)
{
RR = X;
GG = C;
BB = 0;
}
else if(H <180)
{
RR = 0;
GG = C;
BB = X;
}
else if(H <240)
{
RR = 0;
GG = X;
BB = C;
}
else if(H <300)
{
RR = X;
GG = 0;
BB = C;
}
else
{
RR = X;
GG = 0;
BB = C;
}
res[0] = static_cast<uint8_t>((RR+m)*255);
res[1] = static_cast<uint8_t>((GG+m)*255);
res[2] = static_cast<uint8_t>((BB+m)*255);
return res;
};
static rgbs get_rgbs(uint32_t n, double S=0.5, double L=0.5 )
{
n = !n ? 1:n; // at least 1
rgbs res(n);
double step = 360/n;
double H = 0;
for(uint32_t i=0; i<n; i++, H+= step)
{
res[i] = HSL2RGB(H,S,L);
}
return res;
}
};
}
}
#endif /* !UTILS_H */
================================================
FILE: PlyCal_qt/CMakeLists.txt
================================================
set(CMAKE_INCLUDE_CURRENT_DIR ON)
# Let CMake do the job for us
set(CMAKE_AUTOMOC ON) # For meta object compiler
set(CMAKE_AUTORCC ON) # Resource files
set(CMAKE_AUTOUIC ON) # UI file
add_compile_options(-fPIC)
find_package(
Qt5
REQUIRED
COMPONENTS
Core
Gui
Widgets
)
find_package(
VTK
REQUIRED
)
include_directories(
${VTK_INCLUDE_DIRS}
${Qt5Widgets_INCLUDE_DIRS}
)
link_directories(
${VTK_LIBRARY_DIRS}
)
file(GLOB UI_SRC
"*.cpp"
)
add_executable(
${PROJECT_NAME}-qt
${UI_SRC}
)
target_link_libraries(
${PROJECT_NAME}-qt
${VTK_LIBRARIES}
${LIB_PREFIX}
Qt5::Core
Qt5::Widgets
Qt5::Gui
)
================================================
FILE: PlyCal_qt/cqtopencvviewergl.cpp
================================================
#include "cqtopencvviewergl.h"
#include <QMouseEvent>
#include <QDebug>
CQtOpenCVViewerGl::CQtOpenCVViewerGl(QWidget *parent) :
QOpenGLWidget(parent),
is_pick_points_(false)
{
points_.reserve(4);
mBgColor = QColor::fromRgb(150, 150, 150);
}
void CQtOpenCVViewerGl::initializeGL()
{
makeCurrent();
initializeOpenGLFunctions();
float r = ((float)mBgColor.darker().red())/255.0f;
float g = ((float)mBgColor.darker().green())/255.0f;
float b = ((float)mBgColor.darker().blue())/255.0f;
glClearColor(r,g,b,1.0f);
}
void CQtOpenCVViewerGl::resizeGL(int width, int height)
{
makeCurrent();
glViewport(0, 0, (GLint)width, (GLint)height);
glMatrixMode(GL_PROJECTION);
glLoadIdentity();
glOrtho(0, width, -height, 0, 0, 1);
glMatrixMode(GL_MODELVIEW);
recalculatePosition();
emit imageSizeChanged(mRenderWidth, mRenderHeight);
updateScene();
}
void CQtOpenCVViewerGl::updateScene()
{
if (this->isVisible()) update();
}
void CQtOpenCVViewerGl::paintGL()
{
makeCurrent();
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
renderImage();
}
void CQtOpenCVViewerGl::renderImage()
{
drawMutex.lock();
makeCurrent();
glClear(GL_COLOR_BUFFER_BIT);
if (!mRenderQtImg.isNull())
{
glLoadIdentity();
glPushMatrix();
{
if (mResizedImg.width() <= 0)
{
if (mRenderWidth == mRenderQtImg.width() && mRenderHeight == mRenderQtImg.height())
mResizedImg = mRenderQtImg;
else
mResizedImg = mRenderQtImg.scaled(QSize(mRenderWidth, mRenderHeight),
Qt::IgnoreAspectRatio,
Qt::SmoothTransformation);
}
// ---> Centering image in draw area
glRasterPos2i(mRenderPosX, mRenderPosY);
glPixelZoom(1, -1);
glDrawPixels(mResizedImg.width(), mResizedImg.height(), GL_RGBA, GL_UNSIGNED_BYTE, mResizedImg.bits());
}
glPopMatrix();
// end
glFlush();
}
drawMutex.unlock();
}
void CQtOpenCVViewerGl::recalculatePosition()
{
mImgRatio = (float)mOrigImage.cols/(float)mOrigImage.rows;
mRenderWidth = this->size().width();
mRenderHeight = floor(mRenderWidth / mImgRatio);
if (mRenderHeight > this->size().height())
{
mRenderHeight = this->size().height();
mRenderWidth = floor(mRenderHeight * mImgRatio);
}
mRenderPosX = floor((this->size().width() - mRenderWidth) / 2);
mRenderPosY = -floor((this->size().height() - mRenderHeight) / 2);
mResizedImg = QImage();
}
bool CQtOpenCVViewerGl::showImage(const cv::Mat& image, bool isInside)
{
// for pick poitns
if(!isInside)
{
image.copyTo(img_);
}
drawMutex.lock();
if (image.channels() == 3)
#if (CV_VERSION_MAJOR >= 4)
cv::cvtColor(image, mOrigImage, cv::COLOR_BGR2RGBA);
#else
cvtColor(image, mOrigImage, CV_BGR2RGBA);
#endif
else if (image.channels() == 1)
#if (CV_VERSION_MAJOR >= 4)
cv::cvtColor(image, mOrigImage, cv::COLOR_GRAY2RGBA);
#else
cvtColor(image, mOrigImage, CV_GRAY2RGBA);
#endif
else if (image.channels() == 4)
mOrigImage = image;
else return false;
mRenderQtImg = QImage((const unsigned char*)(mOrigImage.data),
mOrigImage.cols, mOrigImage.rows,
mOrigImage.step1(), QImage::Format_RGB32);
recalculatePosition();
updateScene();
drawMutex.unlock();
return true;
}
void CQtOpenCVViewerGl::mousePressEvent(QMouseEvent *event)
{
if(!is_pick_points_ || event->button() != Qt::LeftButton)
{
return;
}
int off_x = 0, off_y = 0;
int img_x = 0, img_y = 0;
if(width()/height() > mImgRatio )
{
img_y = height();
off_y = 0;
img_x = floor(height()*mImgRatio);
off_x = floor((width() - img_x)/2);
}
else
{
img_x = width();
off_x = 0;
img_y = floor(width()/mImgRatio);
off_y = floor((height() - img_y)/2);
}
double x = static_cast<double>(event->x() - off_x)/img_x*img_.cols;
double y = static_cast<double>(event->y() - off_y)/img_y*img_.rows;
points_.emplace_back(x,y);
cv::Mat img;
img_.copyTo(img);
for(const auto& p: points_)
{
cv::circle(img, p, 5, cv::Scalar(0,0,255),-1);
}
showImage(img, true);
}
================================================
FILE: PlyCal_qt/cqtopencvviewergl.h
================================================
#ifndef CQTOPENCVVIEWERGL_H
#define CQTOPENCVVIEWERGL_H
#include <QOpenGLWidget>
#include <QOpenGLFunctions_2_0>
#include <opencv2/opencv.hpp>
#include <opencv2/core/core.hpp>
#include <mutex>
#include <memory>
class CQtOpenCVViewerGl : public QOpenGLWidget, protected QOpenGLFunctions_2_0
{
Q_OBJECT
public:
explicit CQtOpenCVViewerGl(QWidget *parent = 0);
void startPickPoints()
{
is_pick_points_ = true;
points_.clear();
}
void stopPickPoints()
{
is_pick_points_ = false;
points_.clear();
}
void getPickpoints(std::vector<cv::Point2d>& pts)
{
pts.clear();
if(points_.size() >= 4)
{
pts = points_;
}
stopPickPoints();
return;
}
signals:
void imageSizeChanged( int outW, int outH ); /// Used to resize the image outside the widget
public slots:
bool showImage(const cv::Mat& image, bool isInside = false); /// Used to set the image to be viewed
protected:
void initializeGL(); /// OpenGL initialization
void paintGL(); /// OpenGL Rendering
void resizeGL(int width, int height); /// Widget Resize Event
void updateScene();
void renderImage();
// pick points
void mousePressEvent(QMouseEvent* event);
private:
QImage mRenderQtImg; /// Qt image to be rendered
QImage mResizedImg;
cv::Mat mOrigImage; /// original OpenCV image to be shown
QColor mBgColor; /// Background color
float mImgRatio; /// width/height = cols/rows ratio
int mRenderWidth;
int mRenderHeight;
int mRenderPosX;
int mRenderPosY;
std::mutex drawMutex;
bool is_pick_points_;
cv::Mat img_;
std::vector<cv::Point2d> points_;
void recalculatePosition();
};
#endif // CQTOPENCVVIEWERGL_H
================================================
FILE: PlyCal_qt/data_reader.cpp
================================================
/**
******************************************************************************
* @file data_reader.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-20
* @brief data_reader.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "data_reader.h"
#include <QDebug>
#include <QDir>
#include <QFile>
#include <QStringList>
#include <string>
#include <pcl/io/pcd_io.h>
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
const QString DataReader::kPointcloudFolderName ("pointcloud");
const QString DataReader::kImageFolderName("image_orig");
const QString DataReader::kLaserscanFolderName("laser");
const QString DataReader::kTransformFileNmae ("tf.txt");
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
DataReader::DataReader(const QString& path):
dataset_root_(path),
image_extension_("jpeg"),
is_valid_(false),
flag_kd_(0x00),
size_(0),
index_(0)
{
size_ = getDataNum(path);
is_valid_ = size_>0 ? true:false;
K_ = cv::Mat(3, 3, CV_32FC1);
D_ = cv::Mat(5,1,CV_32FC1);
}
uint32_t DataReader::getDataNum(const QString &path)
{
QDir dir(path);
if(!dir.exists())
{
return false;
}
QStringList items = dir.entryList(QDir::Dirs|QDir::Files|QDir::NoDotAndDotDot);
if(!items.contains(kPointcloudFolderName))
{
return 0;
}
if(!items.contains(kImageFolderName))
{
return 0;
}
// if(!items.contains(kLaserscanFolderName))
// {
// return 0;
// }
// if(!items.contains(kTransformFileNmae))
// {
// return 0;
// }
QStringList imgs = QDir(path + QDir::separator() + kImageFolderName)
.entryList(QDir::Files|QDir::NoDotAndDotDot);
if(imgs.size() > 0)
{
QFileInfo fi(imgs[0]);
image_extension_ = fi.completeSuffix();
}
return imgs.count();
}
pcl::PointCloud<pcl::PointXYZI>::Ptr DataReader::getPointcloud()
{
QString fp = dataset_root_ + QDir::separator() + kPointcloudFolderName +
QDir::separator() + QString("%1.pcd").arg(index_);
pcl::PointCloud<pcl::PointXYZI>::Ptr pc(new pcl::PointCloud<pcl::PointXYZI>);
if(pcl::io::loadPCDFile(fp.toStdString(), *pc) == 1)
{
pc = nullptr;
}
return pc;
}
std::shared_ptr<cv::Mat> DataReader::getImage()
{
if(flag_kd_ &0x03 != 0x03)
{
// K, D not set
return nullptr;
}
QString fp = dataset_root_ + QDir::separator() + kImageFolderName +
QDir::separator() + QString("%1.").arg(index_) + image_extension_;
cv::Mat img_orig = cv::imread(fp.toStdString(), cv::IMREAD_COLOR);
if(img_orig.data == NULL)
{
std::cerr << "Fail to read " << fp.toStdString() << std::endl;
return nullptr;
}
std::shared_ptr<cv::Mat> img = std::make_shared<cv::Mat>();
cv::undistort(img_orig, *img, K_, D_);
return img;
}
bool DataReader::moveNext()
{
if(index_ >= (size_-1))
{
return false;
}
index_++;
return true;
}
void DataReader::setCameraK(const Eigen::Matrix3d &k)
{
K_ = cv::Mat(3,3,CV_32FC1);
for(uint8_t i=0; i<9; i++)
{
K_.ptr<float>(i/3)[i%3] = k(i/3,i%3);
}
flag_kd_ |= 0x01;
}
void DataReader::setCameraD(const Eigen::Matrix<double,5,1>& d)
{
D_ = cv::Mat(5,1,CV_32FC1);
D_.ptr<float>(0)[0] = d(0);
D_.ptr<float>(1)[0] = d(1);
D_.ptr<float>(2)[0] = d(2);
D_.ptr<float>(3)[0] = d(3);
D_.ptr<float>(4)[0] = d(4);
flag_kd_ |= 0x02;
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal_qt/data_reader.h
================================================
/**
******************************************************************************
* @file data_reader.h
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-20
* @brief data_reader.h
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __DATA_READER_H
#define __DATA_READER_H
/* Includes ------------------------------------------------------------------*/
#include <stdint.h>
#include <QString>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <opencv2/opencv.hpp>
/* Exported macro ------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
class DataReader
{
public:
DataReader(const QString& path);
bool isValid()
{
return is_valid_;
}
pcl::PointCloud<pcl::PointXYZI>::Ptr getPointcloud();
std::shared_ptr<cv::Mat> getImage();
bool moveNext();
uint32_t getDatasetSize()
{
return size_;
}
uint32_t getCurrentId()
{
return index_;
}
void setCameraK(const Eigen::Matrix3d& k);
void setCameraD(const Eigen::Matrix<double,5,1>& d);
private:
static const QString kPointcloudFolderName;
static const QString kImageFolderName;
static const QString kLaserscanFolderName;
static const QString kTransformFileNmae;
QString dataset_root_;
QString image_extension_;
bool is_valid_;
uint8_t flag_kd_;
uint32_t index_;
uint32_t size_;
cv::Mat K_;
cv::Mat D_;
uint32_t getDataNum(const QString& path);
};
/* Exported constants --------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#endif /* !__DATA_READER_H */
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal_qt/imageviewer.cpp
================================================
#include "imageviewer.h"
#include "ui_imageviewer.h"
#include <QMenu>
#include <QFileDialog>
#include <QMessageBox>
#include <QDebug>
ImageViewer::ImageViewer(QWidget *parent) :
QMainWindow(parent),
ui(new Ui::ImageViewer),
img_(nullptr)
{
ui->setupUi(this);
setWindowFlags(Qt::Window
| Qt::WindowMinimizeButtonHint
| Qt::WindowMaximizeButtonHint);
}
ImageViewer::~ImageViewer()
{
delete ui;
}
/**
* @brief show image in standlone window
* @param img
*/
void ImageViewer::showImage(std::shared_ptr<cv::Mat> img)
{
ui->image_widget->showImage(*img);
img_ = img;
}
void ImageViewer::startPickPoints()
{
ui->image_widget->startPickPoints();
}
void ImageViewer::quitPickPoints()
{
ui->image_widget->stopPickPoints();
}
void ImageViewer::getPickPoitns(std::vector<cv::Point2d>& pts)
{
ui->image_widget->getPickpoints(pts);
}
void ImageViewer::contextMenuEvent(QContextMenuEvent *event)
{
if(img_ == nullptr)
{
return;
}
QMenu menu(this);
menu.addAction(ui->actionSave_Image);
menu.exec(event->globalPos());
}
void ImageViewer::on_actionSave_Image_triggered()
{
QString fn = QFileDialog::getSaveFileName(this,
tr("Save Image"),
"",
tr("Image(*.png)"));
qDebug() << fn;
if(fn.isEmpty())
{
return;
}
if(!cv::imwrite(fn.toStdString(), *img_))
{
QMessageBox::warning(this, tr("Error"), tr("Fail to save image"));
}
}
================================================
FILE: PlyCal_qt/imageviewer.h
================================================
#ifndef IMAGEVIEWER_H
#define IMAGEVIEWER_H
#include <QMainWindow>
#include <QContextMenuEvent>
#include <memory>
#include <opencv2/opencv.hpp>
namespace Ui {
class ImageViewer;
}
class ImageViewer : public QMainWindow
{
Q_OBJECT
public:
explicit ImageViewer(QWidget *parent = 0);
~ImageViewer();
void startPickPoints();
void quitPickPoints();
void getPickPoitns(std::vector<cv::Point2d>& pts);
public slots:
void showImage(std::shared_ptr<cv::Mat> img);
protected:
void contextMenuEvent(QContextMenuEvent *event) override;
private slots:
void on_actionSave_Image_triggered();
private:
Ui::ImageViewer *ui;
std::shared_ptr<cv::Mat> img_;
};
#endif // IMAGEVIEWER_H
================================================
FILE: PlyCal_qt/imageviewer.ui
================================================
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ImageViewer</class>
<widget class="QMainWindow" name="ImageViewer">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>800</width>
<height>600</height>
</rect>
</property>
<property name="windowTitle">
<string>Image Viewer</string>
</property>
<widget class="QWidget" name="centralwidget">
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="CQtOpenCVViewerGl" name="image_widget" native="true"/>
</item>
</layout>
</widget>
<action name="actionSave_Image">
<property name="text">
<string>Save Image</string>
</property>
<property name="toolTip">
<string>save this image</string>
</property>
</action>
</widget>
<customwidgets>
<customwidget>
<class>CQtOpenCVViewerGl</class>
<extends>QWidget</extends>
<header>cqtopencvviewergl.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
================================================
FILE: PlyCal_qt/main.cpp
================================================
#include "mainwindow.h"
#include <QApplication>
int main(int argc, char *argv[])
{
QApplication a(argc, argv);
MainWindow w;
w.show();
return a.exec();
}
================================================
FILE: PlyCal_qt/mainwindow.cpp
================================================
#include "mainwindow.h"
#include "ui_mainwindow.h"
#include <QAction>
#include <QDebug>
#include <QFileDialog>
#include <QDir>
#include <QMessageBox>
#include <QCloseEvent>
#include <QThread>
#include <QInputDialog>
#include <QLineEdit>
#include <QDateTime>
#include <QTimer>
#include <string>
#include <fstream>
MainWindow::MainWindow(QWidget *parent) :
QMainWindow(parent),
ui(new Ui::MainWindow),
sid_(INT_MAX),
is_calibrated_(false),
data_reader_(nullptr),
img_(nullptr), pc_(nullptr)
{
ui->setupUi(this);
config_path_ = QFileDialog::getOpenFileName(this,
tr("Open File"),
".",
tr("Config JSON Files(*.json)"));
if(config_path_.isEmpty())
{
QTimer::singleShot(0,this, &QApplication::quit);
return;
}
std::ifstream f(config_path_.toStdString());
if(!f.good())
{
f.close();
QTimer::singleShot(0,this, &QApplication::quit);
return;
}
try
{
f >> js_;
}
catch(nlohmann::json::parse_error& e)
{
std::cerr << e.what();
f.close();
QTimer::singleShot(0,this, &QApplication::quit);
return;
}
calibrator_.reset(new lqh::Calibrator(js_));
auto& flt = js_["pc"]["filter"];
ui->angle_start_slide->setValue(static_cast<int>(flt["angle_start"]));
ui->angle_size_slide->setValue(static_cast<int>(flt["angle_size"]));
ui->distance_slide->setValue(static_cast<int>(10*flt["distance"].get<double>()) );
ui->floor_gap_slide->setValue(static_cast<int>(10*flt["floor_gap"].get<double>()) );
img_viewer_.reset(new ImageViewer);
img_viewer_->show();
pc_viewer_.reset(new PointcloudViewer);
pc_viewer_->show();
connect(ui->angle_start_slide, &QSlider::valueChanged, this, &MainWindow::processSlider);
connect(ui->angle_size_slide, &QSlider::valueChanged, this, &MainWindow::processSlider);
connect(ui->distance_slide, &QSlider::valueChanged, this, &MainWindow::processSlider);
connect(ui->floor_gap_slide, &QSlider::valueChanged, this, &MainWindow::processSlider);
}
MainWindow::~MainWindow()
{
delete ui;
}
void MainWindow::closeEvent(QCloseEvent * event)
{
if(img_viewer_)
{
img_viewer_->close();
img_viewer_.release();
}
if(pc_viewer_)
{
pc_viewer_->close();
img_viewer_.release();
}
event->accept();
}
void MainWindow::on_actionSet_K_triggered()
{
bool ok = false;
QString last;
auto& K = js_["cam"]["K"];
for(uint8_t i=0; i<9; i++)
{
last.append(QString("%1 ").arg(K[i/3][i%3].get<double>()));
}
QString ks = QInputDialog::getText(this,
tr("Camera matrix, K"),
tr("K"),
QLineEdit::Normal,
last,
&ok);
if(!ok)
{
return;
}
if(!ks.isEmpty())
{
ks.replace(QChar('\n'), QChar(' '));
QStringList ns = ks.simplified().split(" ");
if(ns.size() == 9)
{
Eigen::Matrix3d CK;
for(uint8_t i=0; i<9; i++)
{
CK(i/3,i%3) = ns[i].toDouble();
K[i/3][i%3] = CK(i/3,i%3);
}
if(data_reader_ != nullptr)
{
data_reader_->setCameraK(CK);
}
calibrator_->SetCameraK(CK);
return;
}
}
QMessageBox::warning(this, tr("Error"), tr("Invalid parameters"));
}
void MainWindow::on_actionSet_D_triggered()
{
bool ok = false;
auto& D = js_["cam"]["D"];
QString last = QString("%1 %2 %3 %4 %5")
.arg(D[0].get<double>())
.arg(D[1].get<double>())
.arg(D[2].get<double>())
.arg(D[3].get<double>())
.arg(D[4].get<double>());
QString ks = QInputDialog::getText(this,
tr("Distortion Parameters"),
tr("D"),
QLineEdit::Normal,
last,
&ok);
if(!ok)
{
return;
}
if(!ks.isEmpty())
{
Eigen::Matrix<double,5,1> CD;
ks.replace(QChar('\n'), QChar(' '));
QStringList ns = ks.split(" ");
if(ns.size() == 5)
{
for(uint8_t i=0; i<5; i++)
{
CD(i) = ns[i].toDouble();
D[i] = CD(i);
}
if(data_reader_ != nullptr)
{
data_reader_->setCameraD(CD);
}
return;
}
}
QMessageBox::warning(this, tr("Error"), tr("Invalid parameters"));
}
void MainWindow::on_actionOpen_Dataset_triggered()
{
QString dir = QFileDialog::getExistingDirectory(this, tr("Open Directory"),
QDir::homePath(),
QFileDialog::ShowDirsOnly);
if(!dir.isEmpty())
{
data_reader_.reset(new DataReader(dir));
if(!data_reader_->isValid())
{
data_reader_ = nullptr;
QMessageBox::warning(this, tr("Warn"), tr("The directory is invalid"));
return;
}
Eigen::Matrix3d K;
Eigen::Matrix<double,5,1> D;
auto& JK = js_["cam"]["K"];
auto& JD = js_["cam"]["D"];
for(uint8_t i=0; i<9; i++)
{
K(i/3,i%3) = JK[i/3][i%3];
if(i<5)
{
D(i) = JD[i];
}
}
data_reader_->setCameraK(K);
data_reader_->setCameraD(D);
data_root_ = dir;
ui->total_data_num->setText(QString::number(data_reader_->getDatasetSize()));
showTFWindow();
// on_next_pose_clicked();
}
}
void MainWindow::on_next_pose_clicked()
{
if(is_calibrated_)
{
//after calibration
if(sid_ < sensor_data_.size()-1)
{
sid_++;
}
else
{
if(data_reader_->moveNext())
{
sensor_data_.emplace_back(data_reader_->getCurrentId());
auto& last = sensor_data_.back();
last.img = data_reader_->getImage();
last.pc = data_reader_->getPointcloud();
if(!last.img )
{
sensor_data_.pop_back();
QMessageBox::warning(this, tr("Error"), tr("Fail to read image"));
return;
}
if(!last.pc)
{
sensor_data_.pop_back();
QMessageBox::warning(this, tr("Error"), tr("Fail to read pointcloud"));
return;
}
last.pid = INT_MAX; // invalid
sid_ = sensor_data_.size()-1;
}
else
{
// last one and fail to read more, so do noting
return;
}
}
showCalibrateResult();
}
else
{
// before calibration
processData();
}
}
void MainWindow::on_quick_next_pose_clicked()
{
if(is_calibrated_)
{
// previous
if (sid_ >0)
{
sid_--;
}
showCalibrateResult();
}
else
{
// quick next
setEnabledAll(false);
setCursor(Qt::WaitCursor);
bool res = processData();
while(res)
{
res = processData();
QCoreApplication::processEvents(QEventLoop::AllEvents);
// QThread::msleep(5);
}
setCursor(Qt::ArrowCursor);
setEnabledAll(true);
}
}
void MainWindow::on_delete_pose_clicked()
{
if(sensor_data_.size() > 0 )
{
sensor_data_.back().img_good = false;
sensor_data_.back().pc_good = false;
calibrator_->Remove();
}
processData(false);
}
void MainWindow::on_calibrate_clicked()
{
if(sensor_data_.size() < 1)
{
QMessageBox::warning(this, tr("Error"), tr("No enough data to do calibration, at lease 3"));
return;
}
setEnabledAll(false);
setCursor(Qt::WaitCursor);
// calibrator_->SavePolygonData(std::string("/home/nick/tmp"));
bool res = calibrator_->Compute();
setCursor(Qt::ArrowCursor);
setEnabledAll(true);
if(!res)
{
QMessageBox::warning(this, tr("Error"), tr("Fail to calibrate"));
return;
}
is_calibrated_ = true;
ui->quick_next_pose->setText(tr("Previous"));
showCalibrateResult();
pc_viewer_->showCoordinateSystem(Eigen::Affine3f(calibrator_->GetTransformation().inverse().cast<float>()), 1, 0.5);
auto T = calibrator_->GetTransformation();
auto& tf = js_["tf"];
tf.clear();
for(uint8_t i=0; i<4; i++)
{
tf.push_back(std::vector<double> {T(i,0), T(i,1), T(i,2), T(i,3)});
}
}
void MainWindow::on_pick_points_start_clicked()
{
img_viewer_->startPickPoints();
}
void MainWindow::on_pick_points_quit_clicked()
{
img_viewer_->quitPickPoints();
}
void MainWindow::on_pick_points_end_clicked()
{
std::vector<cv::Point2d> pts;
img_viewer_->getPickPoitns(pts);
if(pts.size() != js_["size"])
{
QMessageBox::warning(this, tr("Error"), tr("Must choose ")
+ QString::number(js_["size"].get<int>())
+tr(" points"));
return;
}
auto& img_i = js_["img"]["init"];
img_i.clear();
for(int i=0; i<js_["size"].get<int>(); i++)
{
img_i.push_back(std::vector<double> {pts[i].x, pts[i].y});
}
auto& last = sensor_data_.back();
if( calibrator_->RefineImage(*last.img, *last.img_marked, pts) )
{
last.img_good = true;
}
img_viewer_->showImage(last.img_marked);
updateLabels();
}
void MainWindow::updateLabels()
{
if(sensor_data_.size() > 0)
{
ui->current_data_id->setText(QString::number(sid_));
uint32_t num = sensor_data_.size();
if(!sensor_data_.back().good())
{
num -= 1;
}
ui->processed_data_num->setText(QString::number(num));
}
else
{
ui->current_data_id->setText("Null");
ui->processed_data_num->setText("0");
}
}
bool MainWindow::processData(bool is_check)
{
if(data_reader_ == nullptr)
{
QMessageBox::warning(this, tr("Error"), tr("Open dataset first"));
return false;
}
if( is_check && sensor_data_.size()>0 && !sensor_data_.back().good() )
{
QMessageBox::warning(this, tr("Error"), tr("Current data is not good, adjust or delete"));
return false;
}
if(sensor_data_.size() > 0 && !data_reader_->moveNext())
{
return false;
}
sensor_data_.emplace_back(data_reader_->getCurrentId());
sid_ = sensor_data_.size()-1;
auto& last = sensor_data_.back();
last.img = data_reader_->getImage();
if(!last.img )
{
sensor_data_.pop_back();
QMessageBox::warning(this, tr("Error"), tr("Fail to read image"));
return false;
}
last.pc = data_reader_->getPointcloud();
if(!last.pc)
{
sensor_data_.pop_back();
QMessageBox::warning(this, tr("Error"), tr("Fail to read pointcloud"));
return false;
}
last.img_marked = std::make_shared<cv::Mat>();
last.img->copyTo(*last.img_marked);
last.pc_marked.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
last.pid = calibrator_->Add(*last.img, *last.pc, *last.img_marked, *last.pc_marked);
if(calibrator_->ImageGood(last.pid))
{
last.img_good = true;
}
if(calibrator_->PointcloudGood(last.pid))
{
last.pc_good = true;
}
img_viewer_->showImage(last.img_marked);
pc_viewer_->showPointcloud(last.pc_marked);
sid_ = sensor_data_.size()-1;
updateLabels();
return true;
}
void MainWindow::setEnabledAll(bool status)
{
QList<QPushButton*> btns = ui->centralWidget->findChildren<QPushButton*>();
for(auto& it : btns)
{
it->setEnabled(status);
}
QList<QSlider*> sliders = ui->pointcloud_group->findChildren<QSlider*>();
for(auto& it : sliders)
{
it->setEnabled(status);
}
}
void MainWindow::showCalibrateResult()
{
auto& sd = sensor_data_[sid_];
if(sd.img_proj == nullptr || sd.pc_proj == nullptr)
{
sd.img_proj.reset(new cv::Mat);
sd.img->copyTo(*sd.img_proj);
sd.pc_proj.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::copyPointCloud(*sd.pc, *sd.pc_proj);
for(auto& p: sd.pc_proj->points)
{
p.rgba = 0xffffffff;
}
calibrator_->Project(*sd.pc_proj, *sd.img_proj);
}
img_viewer_->showImage(sd.img_proj);
pc_viewer_->showPointcloud(sd.pc_proj);
updateLabels();
}
void MainWindow::on_actionSave_Result_triggered()
{
if(!is_calibrated_)
{
QMessageBox::warning(this, tr("Error"), tr("Not calibrate yet"));
return;
}
QString fp = data_root_ + QDir::separator()
+ "calibration_" + QDateTime::currentDateTime().toString("yyyy-M-d-h-m-s")
+".json";
std::ofstream f(fp.toStdString());
if(!f.good())
{
QMessageBox::warning(this, tr("Error"), tr("Fail to open file ")+fp);
return;
}
const Eigen::Matrix4d& tf = calibrator_->GetTransformation();
nlohmann::json js;
for(uint8_t i=0; i<4; i++)
{
js["T"].push_back({tf(i,0), tf(i,1), tf(i,2), tf(i,3)});
}
js["K"] = js_["cam"]["K"];
js["D"] = js_["cam"]["D"];
f << js.dump(4);
f.close();
QMessageBox::information(this, tr("Success"), tr("Save calibration result to ")+fp);
}
void MainWindow::processSlider()
{
Eigen::Vector4d param;
param(0) = ui->angle_start_slide->value();
param(1) = ui->angle_size_slide->value();
param(2) = ui->distance_slide->value()/10.0;
param(3) = ui->floor_gap_slide->value()/10.0;
ui->angle_start_text->setText( QString::number(param(0)) );
ui->angle_size_text->setText( QString::number(param(1)) );
ui->distance_text->setText( QString::number(param(2)) );
ui->floor_gap_text->setText( QString::number(param(3)) );
if(sensor_data_.size() == 0 || calibrator_ == nullptr)
{
return;
}
auto& filter = js_["pc"]["filter"];
filter["angle_start"] = param(0);
filter["angle_size"] = param(1);
filter["distance"] = param(2);
filter["floor_gap"] = param(3);
auto& sd = sensor_data_.back();
calibrator_->RefinePointcloud(*sd.pc, *sd.pc_marked, param);
if(calibrator_->PointcloudGood(sd.pid))
{
sd.pc_good = true;
}
pc_viewer_->showPointcloud(sd.pc_marked);
}
void MainWindow::on_actionSave_Config_triggered()
{
std::ofstream f(config_path_.toStdString());
if(!f.good())
{
QMessageBox::warning(this, tr("Error"), tr("Fail to open config file"));
return;
}
f << js_.dump(4);
f.close();
}
void MainWindow::updateWithTransformation(Eigen::Matrix4d tf)
{
std::shared_ptr<cv::Mat> img_mark = std::make_shared<cv::Mat>();
img_->copyTo(*img_mark);
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcc (new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::copyPointCloud(*pc_, *pcc);
for(auto& p : pcc->points)
{
p.rgba = 0xffffffff;
}
// calibrator_->SetTranformation(tf_);
calibrator_->SetTranformation(tf);
calibrator_->Project(*pcc, *img_mark);
img_viewer_->showImage(img_mark);
pc_viewer_->showPointcloud(pcc);
}
void MainWindow::tfwindowClose()
{
this->move(tfwindow_->pos());
this->show();
tfwindow_.reset(nullptr);
on_next_pose_clicked();
}
void MainWindow::showTFWindow()
{
img_ = data_reader_->getImage();
pc_ = data_reader_->getPointcloud();
if(img_ == nullptr || pc_ == nullptr )
{
QMessageBox::warning(this, tr("Error"), tr("Fail to read image or pointcloud"));
data_reader_.reset(nullptr);
return;
}
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcc (new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::copyPointCloud(*pc_, *pcc);
for(auto& p : pcc->points)
{
p.rgba = 0xffffffff;
}
std::shared_ptr<cv::Mat> img_mark = std::make_shared<cv::Mat>();
img_->copyTo(*img_mark);
tfwindow_.reset(new TFwindow(calibrator_->GetTransformation()));
connect(tfwindow_.get(), &TFwindow::newTransformation, this, &MainWindow::updateWithTransformation);
connect(tfwindow_.get(), &TFwindow::tfwindowClose, this, &MainWindow::tfwindowClose);
calibrator_->Project(*pcc, *img_mark);
img_viewer_->showImage(img_mark);
pc_viewer_->showPointcloud(pcc);
tfwindow_->move(this->pos());
tfwindow_->show();
this->hide();
}
================================================
FILE: PlyCal_qt/mainwindow.h
================================================
#ifndef MAINWINDOW_H
#define MAINWINDOW_H
#include <QMainWindow>
#include <memory>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include "tfwindow.h"
#include "pointcloudviewer.h"
#include "imageviewer.h"
#include "json/json.hpp"
#include "calibrator.h"
#include "data_reader.h"
namespace Ui
{
class MainWindow;
}
class MainWindow : public QMainWindow
{
Q_OBJECT
public:
explicit MainWindow(QWidget *parent = 0);
~MainWindow();
public slots:
void updateWithTransformation(Eigen::Matrix4d tf);
void tfwindowClose();
protected:
void closeEvent(QCloseEvent *);
private:
struct SensorData
{
bool img_good;
bool pc_good;
uint32_t id;
uint32_t pid;
std::shared_ptr<cv::Mat> img;
pcl::PointCloud<pcl::PointXYZI>::Ptr pc;
std::shared_ptr<cv::Mat> img_marked;
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_marked;
std::shared_ptr<cv::Mat> img_proj;
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc_proj;
SensorData(uint32_t index):img_good(false), pc_good(false),
id(index),
img(nullptr), pc(nullptr),
img_marked(nullptr), pc_marked(nullptr),
img_proj(nullptr), pc_proj(nullptr){}
bool good()
{
return (img_good && pc_good);
}
};
Ui::MainWindow *ui;
QString config_path_;
nlohmann::json js_;
bool is_calibrated_;
uint32_t sid_;
QString data_root_;
std::shared_ptr<cv::Mat> img_;
pcl::PointCloud<pcl::PointXYZI>::Ptr pc_;
std::unique_ptr<DataReader> data_reader_;
std::unique_ptr<PointcloudViewer> pc_viewer_;
std::unique_ptr<ImageViewer> img_viewer_;
std::unique_ptr<TFwindow> tfwindow_;
std::unique_ptr<lqh::Calibrator> calibrator_;
std::vector<SensorData> sensor_data_;
void updateLabels();
bool processData(bool is_check = true);
void setEnabledAll(bool status);
void showCalibrateResult();
void showTFWindow();
private slots:
void on_actionSet_K_triggered();
void on_actionSet_D_triggered();
void on_actionOpen_Dataset_triggered();
void on_next_pose_clicked();
void on_quick_next_pose_clicked();
void on_delete_pose_clicked();
void on_calibrate_clicked();
void on_pick_points_start_clicked();
void on_pick_points_end_clicked();
void on_pick_points_quit_clicked();
void on_actionSave_Result_triggered();
void processSlider();
void on_actionSave_Config_triggered();
};
#endif // MAINWINDOW_H
================================================
FILE: PlyCal_qt/mainwindow.ui
================================================
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>MainWindow</class>
<widget class="QMainWindow" name="MainWindow">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>641</width>
<height>521</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>600</width>
<height>500</height>
</size>
</property>
<property name="windowTitle">
<string>Multi-Sensor Extrinsic Calibration</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<widget class="QWidget" name="centralWidget">
<property name="styleSheet">
<string notr="true">QSlider{
outline: none;
border:none;
}
QPushButton{
outline: none;
border: 2px solid #8f8f91;
border-radius: 20px;
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #f6f7fa, stop: 1 #dadbde);
}
QPushButton::pressed{
background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1,
stop: 0 #dadbde, stop: 1 #f6f7fa);
}
QPushButton::disabled{
border: none;
}
QPushButton:flat {
border: none; /* no border for a flat push button */
}
QPushButton:default {
border-color: navy; /* make the default button prominent */
}
#centralWidget
{
background-color: rgb(255, 255, 255);
}</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout" stretch="1,6,2">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="topMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>6</number>
</property>
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>Current Data ID</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="current_data_id">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLabel{
color: rgb(115, 210, 22);
background-color: #ccc;
}</string>
</property>
<property name="text">
<string>0</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="text">
<string>Processed Data Num</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="processed_data_num">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLabel{
color: rgb(115, 210, 22);
background-color: #ccc;
}</string>
</property>
<property name="text">
<string>0</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_9">
<property name="text">
<string>Total Data Num</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="total_data_num">
<property name="font">
<font>
<pointsize>16</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLabel{
color: rgb(239, 41, 41);
background-color: #ccc;
}</string>
</property>
<property name="text">
<string>0</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="2,3">
<property name="spacing">
<number>10</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<property name="topMargin">
<number>10</number>
</property>
<property name="bottomMargin">
<number>10</number>
</property>
<item>
<widget class="QGroupBox" name="image_group">
<property name="title">
<string>Image Control</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>40</number>
</property>
<property name="leftMargin">
<number>10</number>
</property>
<property name="topMargin">
<number>10</number>
</property>
<property name="rightMargin">
<number>10</number>
</property>
<property name="bottomMargin">
<number>10</number>
</property>
<item>
<widget class="QPushButton" name="pick_points_start">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Start Selection</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="pick_points_quit">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Quit Selection</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="pick_points_end">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Finish Selection</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="pointcloud_group">
<property name="title">
<string>PointCloud Control</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="1,1,1,0" columnstretch="1,0,8,0">
<property name="leftMargin">
<number>10</number>
</property>
<property name="rightMargin">
<number>10</number>
</property>
<property name="spacing">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label_3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Angle Start</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Distance</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSlider" name="angle_size_slide">
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="maximum">
<number>360</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QSlider" name="distance_slide">
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QSlider" name="angle_start_slide">
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
</size>
</property>
<property name="maximum">
<number>360</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Angle Size</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="angle_start_text">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>000</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="angle_size_text">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>000</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="distance_text">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>40</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>00.0</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Floor Gap</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QSlider" name="floor_gap_slide">
<property name="maximum">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QLabel" name="floor_gap_text">
<property name="text">
<string>0.0</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="spacing">
<number>40</number>
</property>
<property name="leftMargin">
<number>10</number>
</property>
<property name="topMargin">
<number>10</number>
</property>
<property name="rightMargin">
<number>10</number>
</property>
<property name="bottomMargin">
<number>10</number>
</property>
<item>
<widget class="QPushButton" name="next_pose">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Next Pose</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="quick_next_pose">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Quick Next</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="delete_pose">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Delete Pose</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="calibrate">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Calibrate</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QToolBar" name="toolBar">
<property name="windowTitle">
<string>toolBar</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<attribute name="toolBarArea">
<enum>TopToolBarArea</enum>
</attribute>
<attribute name="toolBarBreak">
<bool>false</bool>
</attribute>
<addaction name="actionSave_Config"/>
<addaction name="actionSave_Result"/>
<addaction name="actionSet_K"/>
<addaction name="actionSet_D"/>
<addaction name="actionOpen_Dataset"/>
</widget>
<action name="actionSave_Config">
<property name="text">
<string>Save Config</string>
</property>
<property name="toolTip">
<string>save result and config to files</string>
</property>
<property name="shortcut">
<string>Ctrl+S</string>
</property>
</action>
<action name="actionSet_K">
<property name="text">
<string>Set K</string>
</property>
<property name="toolTip">
<string>set camera matrix</string>
</property>
</action>
<action name="actionSet_D">
<property name="text">
<string>Set D</string>
</property>
<property name="toolTip">
<string>set distortion coefficients</string>
</property>
</action>
<action name="actionOpen_Dataset">
<property name="text">
<string>Open Dataset</string>
</property>
<property name="toolTip">
<string>choose dataset directory</string>
</property>
</action>
<action name="actionSave_Result">
<property name="text">
<string>Save Result</string>
</property>
<property name="toolTip">
<string>Save calibration result</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources/>
<connections/>
</ui>
================================================
FILE: PlyCal_qt/pointcloudviewer.cpp
================================================
#include "pointcloudviewer.h"
#include "ui_pointcloudviewer.h"
#include <QMenu>
#include <QDebug>
PointcloudViewer::PointcloudViewer(QWidget *parent) :
QMainWindow(parent),
ui(new Ui::PointcloudViewer)
{
ui->setupUi(this);
setWindowFlags(Qt::Window
| Qt::WindowMinimizeButtonHint
| Qt::WindowMaximizeButtonHint);
viewer_ = std::unique_ptr<pcl::visualization::PCLVisualizer>(
new pcl::visualization::PCLVisualizer("viewer", false));
ui->qvtkWidget->SetRenderWindow(viewer_->getRenderWindow());
viewer_->setupInteractor(ui->qvtkWidget->GetInteractor(), ui->qvtkWidget->GetRenderWindow());
ui->qvtkWidget->update();
viewer_->resetCamera();
showCoordinateSystem(Eigen::Affine3f::Identity(), 0, 2);
}
PointcloudViewer::~PointcloudViewer()
{
delete ui;
}
/**
* @brief show(add/update) pointcloud in the viewer
* @param [in] pc xyzrgb pointcloud pointer
* @param [in] index pointcloud id
*/
void PointcloudViewer::showPointcloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc, int index)
{
std::string pc_name = std::string("cloud_")+std::to_string(index);
if(cloud_names_.count(index))
{
// update
viewer_->updatePointCloud(pc, pc_name);
}
else
{
//add
cloud_names_.insert(index);
viewer_->addPointCloud(pc, pc_name);
}
ui->qvtkWidget->update();
}
/**
* @brief show coordinate in the viewer
* @param [in] tf the coordinate transformation
* @param [in] index the coordinate id
* @param [in] scale the scale, default 1.0
*/
void PointcloudViewer::showCoordinateSystem(const Eigen::Affine3f& tf, int index, double scale)
{
std::string frame_name = std::string("frame_") + std::to_string(index);
if(frame_names_.count(index))
{
viewer_->updateCoordinateSystemPose(frame_name, tf);
}
else
{
frame_names_.insert(index);
viewer_->addCoordinateSystem(scale, tf, frame_name);
}
}
void PointcloudViewer::contextMenuEvent(QContextMenuEvent *event)
{
qDebug() << "right click";
QMenu menu(this);
menu.addAction(ui->actionSave_PointCloud);
menu.exec(event->globalPos());
}
void PointcloudViewer::on_actionSave_PointCloud_triggered()
{
qDebug() << "right click";
}
================================================
FILE: PlyCal_qt/pointcloudviewer.h
================================================
#ifndef POINTCLOUDVIEWER_H
#define POINTCLOUDVIEWER_H
#include <QMainWindow>
#include <QContextMenuEvent>
#include <set>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <vtkRenderWindow.h>
namespace Ui {
class PointcloudViewer;
}
class PointcloudViewer : public QMainWindow
{
Q_OBJECT
public:
explicit PointcloudViewer(QWidget *parent = 0);
~PointcloudViewer();
public slots:
void showPointcloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc, int index = 0);
void showCoordinateSystem(const Eigen::Affine3f& tf, int index, double scale=1.0);
protected:
void contextMenuEvent(QContextMenuEvent *event) override;
private slots:
void on_actionSave_PointCloud_triggered();
private:
Ui::PointcloudViewer *ui;
std::unique_ptr<pcl::visualization::PCLVisualizer> viewer_;
std::set<int> cloud_names_;
std::set<int> frame_names_;
};
#endif // POINTCLOUDVIEWER_H
================================================
FILE: PlyCal_qt/pointcloudviewer.ui
================================================
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>PointcloudViewer</class>
<widget class="QMainWindow" name="PointcloudViewer">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>800</width>
<height>600</height>
</rect>
</property>
<property name="windowTitle">
<string>PointCloud Viewer</string>
</property>
<widget class="QWidget" name="centralwidget">
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QVTKWidget" name="qvtkWidget"/>
</item>
</layout>
</widget>
<action name="actionSave_PointCloud">
<property name="text">
<string>Save PointCloud</string>
</property>
<property name="toolTip">
<string>save this pointcloud</string>
</property>
</action>
</widget>
<customwidgets>
<customwidget>
<class>QVTKWidget</class>
<extends>QWidget</extends>
<header>QVTKWidget.h</header>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
================================================
FILE: PlyCal_qt/tfwindow.cpp
================================================
#include "tfwindow.h"
#include "ui_tfwindow.h"
#include <Eigen/Geometry>
static const double PI(3.141592653589793238462);
TFwindow::TFwindow(const Eigen::Matrix4d& tf, QWidget *parent) :
QMainWindow(parent),
ui(new Ui::TFwindow)
{
ui->setupUi(this);
auto setWidget = [](double data, QSlider* sld, QLabel* lb)
{
int32_t val = static_cast<int32_t>(std::round(data*500+500));
if (val <0 )
{
val = 0;
}
if(val > 1000)
{
val = 1000;
}
sld->setValue(val);
lb->setText(QString("%1").arg((val-500.0)/500.0, 6, 'f',3,' '));
};
setWidget(tf(0,3), ui->tx_slide, ui->tx_text);
setWidget(tf(1,3), ui->ty_slide, ui->ty_text);
setWidget(tf(2,3), ui->tz_slide, ui->tz_text);
// xyz - euler
Eigen::Matrix3d rotation = tf.topLeftCorner(3,3);
// [0:pi]x[-pi:pi]x[-pi:pi]
Eigen::Vector3d angle = rotation.eulerAngles(0, 1, 2)/PI*180;
Eigen::Vector3i r = angle.cast<int>();
uint16_t v = r(0) <0 ? 0 : (r(0)>180? 180: r(0));
ui->rx_slide->setValue( v );
ui->rx_text->setText( QString::number(v) );
v = r(1) < -180 ? 0 : (r(1) > 180 ? 360 : r(1) +180);
ui->ry_slide->setValue( v );
ui->ry_text->setText( QString::number(r(1)) );
v = r(2) < -180 ? 0 : (r(2) > 180 ? 360 : r(2) +180);
ui->rz_slide->setValue( v );
ui->rz_text->setText( QString::number(r(2)) );
connect(ui->rx_slide, &QSlider::valueChanged, this, &TFwindow::process);
connect(ui->ry_slide, &QSlider::valueChanged, this, &TFwindow::process);
connect(ui->rz_slide, &QSlider::valueChanged, this, &TFwindow::process);
connect(ui->tx_slide, &QSlider::valueChanged, this, &TFwindow::process);
connect(ui->ty_slide, &QSlider::valueChanged, this, &TFwindow::process);
connect(ui->tz_slide, &QSlider::valueChanged, this, &TFwindow::process);
}
TFwindow::~TFwindow()
{
delete ui;
}
void TFwindow::process()
{
Eigen::Matrix4d tf;
tf.setIdentity();
tf(0,3) = (ui->tx_slide->value() - 500)/500.0;
ui->tx_text->setText(QString::number(tf(0,3)));
tf(1,3) = (ui->ty_slide->value() - 500)/500.0;
ui->ty_text->setText(QString::number(tf(1,3)));
tf(2,3) = (ui->tz_slide->value() - 500)/500.0;
ui->tz_text->setText(QString::number(tf(2,3)));
ui->rx_text->setText(QString::number(ui->rx_slide->value()));
double rx = ui->rx_slide->value()/180.0*PI;
ui->ry_text->setText(QString::number(ui->ry_slide->value()-180));
double ry = (ui->ry_slide->value()-180.0)/180.0*PI;
ui->rz_text->setText(QString::number(ui->rz_slide->value()-180));
double rz = (ui->rz_slide->value()-180.0)/180.0*PI;
Eigen::Quaterniond ag = Eigen::AngleAxisd(rx, Eigen::Vector3d::UnitX())
* Eigen::AngleAxisd(ry, Eigen::Vector3d::UnitY())
* Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ());
tf.topLeftCorner(3,3) = ag.matrix();
tf.row(3) << 0,0,0,1;
emit newTransformation(tf);
}
void TFwindow::closeEvent(QCloseEvent *event)
{
emit tfwindowClose();
event->accept();
}
================================================
FILE: PlyCal_qt/tfwindow.h
================================================
#ifndef TFWINDIOW_H
#define TFWINDIOW_H
#include <QMainWindow>
#include <QCloseEvent>
#include <Eigen/Dense>
namespace Ui {
class TFwindow;
}
class TFwindow : public QMainWindow
{
Q_OBJECT
public:
explicit TFwindow(const Eigen::Matrix4d& tf, QWidget *parent = 0);
~TFwindow();
signals:
void newTransformation(Eigen::Matrix4d tf);
// void newTransformation();
void tfwindowClose();
protected:
void closeEvent(QCloseEvent *event) override;
private:
Ui::TFwindow *ui;
private slots:
void process();
};
#endif // TFWINDIOW_H
================================================
FILE: PlyCal_qt/tfwindow.ui
================================================
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>TFwindow</class>
<widget class="QMainWindow" name="TFwindow">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>796</width>
<height>399</height>
</rect>
</property>
<property name="windowTitle">
<string>MainWindow</string>
</property>
<widget class="QWidget" name="centralwidget">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Rotation</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>X</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QSlider" name="rx_slide">
<property name="maximum">
<number>180</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="rx_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Y</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSlider" name="ry_slide">
<property name="maximum">
<number>360</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="ry_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Z</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QSlider" name="rz_slide">
<property name="maximum">
<number>360</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLabel" name="rz_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Translation</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="label_7">
<property name="text">
<string>X</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QSlider" name="tx_slide">
<property name="maximum">
<number>1000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="tx_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Y</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSlider" name="ty_slide">
<property name="maximum">
<number>1000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="ty_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_11">
<property name="text">
<string>Z</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QSlider" name="tz_slide">
<property name="maximum">
<number>1000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLabel" name="tz_text">
<property name="text">
<string>000</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</widget>
<resources/>
<connections/>
</ui>
================================================
FILE: PlyCal_test/CMakeLists.txt
================================================
if( CMAKE_BUILD_TYPE EQUAL "Release")
add_definitions( -DNODEBUG )
endif(CMAKE_BUILD_TYPE EQUAL "Release")
add_executable(
test_image_polygon
test_image_polygon.cpp
)
target_link_libraries(
test_image_polygon
plycal
)
add_executable(
test_image_polygons
test_image_polygons.cpp
)
target_link_libraries(
test_image_polygons
plycal
)
add_executable(
test_pointcloud_polygon
test_pointcloud_polygon.cpp
)
target_link_libraries(
test_pointcloud_polygon
plycal
)
================================================
FILE: PlyCal_test/test_image_polygon.cpp
================================================
/**
******************************************************************************
* @file test_imagepolygon.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-25
* @brief test_imagepolygon.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "image_polygon.h"
#include <iostream>
#include <fstream>
#include <Eigen/Dense>
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
int main(int argc, char** argv)
{
std::string config_path, img_path;
if(argc >= 3)
{
config_path = std::string(argv[1]);
img_path = std::string(argv[2]);
}
else
{
std::cerr << "Usage: " << argv[0] << " config_path image_path"
<< std::endl;
return 1;
}
std::cout << "----------------------------------------"<< std::endl
<< "config path: " << config_path << std::endl
<< "image path: " << img_path << std::endl
<< "----------------------------------------" << std::endl;
// parse config file
std::ifstream f (config_path);
if ( !f.good() )
{
std::cerr << "[ERROR]\tconfig file doesn't exist" << std::endl;
return 2;
}
std::string content{ std::istreambuf_iterator<char>(f),
std::istreambuf_iterator<char>() };
f.close();
auto js= nlohmann::json::parse(content);
auto& corners = js["img"]["init"];
Eigen::Matrix3Xd points;
points.resize(3,4);
points.row(2).setOnes();
for(uint8_t i=0; i<4; i++)
{
points(0,i) = corners[i][0].get<double>();
points(1,i) = corners[i][1].get<double>();
}
cv::Mat img = cv::imread(img_path, cv::IMREAD_COLOR);
cv::Mat img_out;
lqh::ImagePolygon cvx(js["img"], 4);
cvx.Init(img, img_out, points);
lqh::ImagePolygon::Polygon2D::ConstPtr ply = cvx.Add(img, img_out);
cvx.SaveMarkedImage("ExtractPolygon.jpg", img, ply);
std::cout << "-----------------END----------------\n";
return 0;
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal_test/test_image_polygons.cpp
================================================
/**
******************************************************************************
* @file test_image_polygons.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2018-01-02
* @brief test_image_polygons.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2018 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "image_polygon.h"
#include <fstream>
#include <Eigen/Dense>
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
int main(int argc, char** argv)
{
std::string config_path, img_root_path;
uint32_t num = 0;
if(argc >= 4)
{
config_path = std::string(argv[1]);
img_root_path = std::string(argv[2]);
num = std::stoi(std::string(argv[3]));
}
else
{
std::cerr << "Usage: " << argv[0] << " config_path image_root_path image_num"
<< std::endl;
return 1;
}
std::cout << "\n----------------------------------------"
<< "\nconfig path: " << config_path
<< "\nimage path: " << img_root_path
<< "\nimage num: " << num
<< "\n----------------------------------------" << std::endl;
// parse config file
std::ifstream f (config_path);
if ( !f.good() )
{
std::cerr << "[ERROR]\tconfig file doesn't exist" << std::endl;
return 2;
}
std::string content{ std::istreambuf_iterator<char>(f),
std::istreambuf_iterator<char>() };
f.close();
auto js= nlohmann::json::parse(content);
auto& corners = js["img"]["init"];
Eigen::Matrix3Xd points;
points.resize(3,4);
points.row(2).setOnes();
for(uint8_t i=0; i<4; i++)
{
points(0,i) = corners[i][0].get<double>();
points(1,i) = corners[i][1].get<double>();
}
std::string img_path = img_root_path + "/0.jpeg";
cv::Mat img = cv::imread(img_path, cv::IMREAD_COLOR);
cv::Mat img_out;
lqh::ImagePolygon cvx(js["img"], 4);
cvx.Init(img, img_out, points);
for(uint32_t i=0; i<num; i++)
{
std::cout << "Process: " << i << "\n";
img_path = img_root_path + "/" + std::to_string(i) + ".jpeg";
std::string fn_out = std::to_string(i) + ".png";
cv::Mat img = cv::imread(img_path, cv::IMREAD_COLOR);
lqh::ImagePolygon::Polygon2D::ConstPtr ply = cvx.Add(img, img_out);
if(ply != nullptr)
{
cvx.SaveMarkedImage(fn_out, img, ply);
std::cout << "-------------OK\n";
}
else
{
std::cout << "-------------Fail\n";
}
}
std::cout << "-----------------END----------------\n";
return 0;
}
/*****************************END OF FILE**************************************/
================================================
FILE: PlyCal_test/test_pointcloud_polygon.cpp
================================================
/**
******************************************************************************
* @file test_pointcloud_polygon.cpp
* @author Nick.Liao
* @version V1.0.0
* @date 2017-12-26
* @brief test_pointcloud_polygon.cpp
******************************************************************************
* @attention
*
* Copyright (C) 2017 Nick.Liao <simplelife_nick@hotmail.com>
* Distributed under terms of the MIT license.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <string>
#include <iostream>
#include <fstream>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/io/pcd_io.h>
#include "json/json.hpp"
#include "pointcloud_polygon.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
/**
* @brief
* @param
* @note
* @return None
*/
int main(int argc, char** argv)
{
std::string config_path, pc_path;
std::string edge_prefix;
if(argc >= 3)
{
config_path = std::string(argv[1]);
pc_path = std::string(argv[2]);
edge_prefix = std::string(argv[3]);
}
else
{
std::cerr << "Usage: " << argv[0] << " config_path pointlcoud_path"
<< std::endl;
return 1;
}
std::cout << "----------------------------------------"<< std::endl
<< "config path: " << config_path << std::endl
<< "pointcloud path: " << pc_path << std::endl
<< "----------------------------------------" << std::endl;
// parse config file
std::ifstream f (config_path);
if ( !f.good() )
{
std::cerr << "[ERROR]\tconfig file doesn't exist" << std::endl;
return 2;
}
std::string content{ std::istreambuf_iterator<char>(f),
std::istreambuf_iterator<char>() };
f.close();
auto js= nlohmann::json::parse(content);
pcl::PointCloud<pcl::PointXYZI> pc;
pcl::PointCloud<pcl::PointXYZRGB> pcc;
if(pcl::io::loadPCDFile(pc_path, pc) == -1)
{
std::cerr << "[ERROR]\tfail to read pointcoud" << std::endl;
return 3;
}
lqh::PointcloudPolygon pp(js["pc"], 4);
pp.Add(pc, pcc);
pp.SaveEdgePoints(edge_prefix);
std::cout << "-----------------END----------------\n";
return 0;
}
/*****************************END OF FILE**************************************/
================================================
FILE: README.md
================================================
# Extrinsic Calibration of the camera and LiDAR via polygon plane
This project includes the extrinsic calibration library and gui tool for calibrating the extrinsic parameter(6-DoF rigid-body transformation) between the camera and LiDAR. This method needs convex polygon plane as calibration object and the camera intrinsic parameter(K, D) are needed (if images are not undistorted).
*note: current implemention only support rectangular plane*
## Dependency list
- [pcl](http://pointclouds.org/)
- [ceres](http://ceres-solver.org/)
- Eigen 3
- VTK
- Qt 5 (system)
## Build
we test on `Ubuntu 16.04`, if you already install ros kinect and then you only need to compile and install ceres-solver.
```sh
$ mkdir build& cd build
$ cmake .. # build library and QT GUI
$ cmake -DBUILD_PlyCal_TEST=True .. #build test tools(only for debug usage)
$ make
```
## Test
We have tested the current qt-based tool with RSLidar-16, RSlidar-32, Rslidar-mems by rectangular plane. And we provide test data and config file under `./data`directory which was collected with RSLidar-16 and usb webcam.
## Usage
[中文使用说明](./doc/README.md)
Before using the gui tool:
1. Calibrate camera and put intrinsic parameter `D, K` at config file or set by gui.
2. Collect synced image(png,jpg,jpeg) and pointcloud (pcd), put them into `some_place/image_orig` and `some_place/pointcloud` directory, respectively. Name the file like `0.jpg, 1.jpg, ..., n.jpg`.

## Reference
For the method you can read the paper:
```
@INPROCEEDINGS{8665256,
author={Q. {Liao} and Z. {Chen} and Y. {Liu} and Z. {Wang} and M. {Liu}},
booktitle={2018 IEEE International Conference on Robotics and Biomimetics (ROBIO)},
title={Extrinsic Calibration of Lidar and Camera with Polygon},
year={2018},
volume={},
number={},
pages={200-205},
keywords={calibration;cameras;feature extraction;image fusion;image sensors;micromechanical devices;optical radar;sensor fusion;stereo image processing;heterogeneous exteroceptive sensors;heterogeneous sensory systems;multisensor information;polygon board;t6/32-beam Lidar;extrinsic calibration;MEMS-Lidar;point-cloud;laser range finder;2D feature space;3D feature space;Calibration;Cameras;Laser radar;Three-dimensional displays;Sensors;Image edge detection;Two dimensional displays},
doi={10.1109/ROBIO.2018.8665256},
ISSN={},
month={Dec},}
```
================================================
FILE: data/config.json
================================================
{
"cam": {
"D": [
-0.343338393354793,
0.0806974339575093,
-0.000525540233605921,
0.00260712954510535,
0.0
],
"K": [
[
1085.87150849092,
0.0,
967.618455232044
],
[
0.0,
1085.71794017434,
512.798695326787
],
[
0.0,
0.0,
1.0
]
]
},
"img": {
"edlines": {
"anchorThreshold": 10,
"gradientThreshold": 80,
"ksize": 3,
"lineFitErrThreshold": 2,
"minLineLen": 30,
"scanIntervals": 1,
"sigma": 1
},
"feature": {
"offset": 3,
"size": 8,
"threshold": 0.8
},
"filter": {
"line_angle_threshold": 8,
"point_center_factor": 0.4,
"point_line_threshold": 80
},
"init": [
[
1200.8,
273.6
],
[
1509.6,
420.0
],
[
1589.6,
775.2
],
[
888.0,
645.6
]
],
"merge": {
"angle_threshold": 2,
"distance_threshold": 35,
"endpoint_distance_threshold": 80
}
},
"pc": {
"angle_resolution": 1.5,
"edge": {
"distance_threshold": 0.05,
"point_num_min": 5
},
"filter": {
"angle_size": 73.0,
"angle_start": 327.0,
"distance": 5.3,
"floor_gap": 1.2
},
"plane": {
"distance_threshold": 0.06,
"point_num_min": 20
},
"ring": {
"endpoint_num": 2,
"point_num_min": 7
}
},
"size": 4,
"tf": [
[
-0.0587731866433256,
-0.997313988353226,
0.0437095088827632,
0.0584119503362388
],
[
0.0680705634344673,
-0.0476870940689982,
-0.996540184565063,
-0.104226321432097
],
[
0.995947845484644,
-0.0555945113679224,
0.0706904475884742,
0.0
],
[
0.0,
0.0,
0.0,
1.0
]
],
"track_error_threshold": 30
}
================================================
FILE: doc/README.md
================================================
# PlyCal
> LIAO Qinghai 2019.2.25
[for English Version click here](#english-version)
本程序只实现了利用四边形板校准,暂未实现利用任意polygon的校准。
## 准备
如example文件夹所示,使用本软件需要一个config.json文件和图像、点云对应的文件。
config.json:参考example/config.json,正常只需要修改其中相机的K、D。此文件路径无要求
dataset:dataset指example下的`image_orig`和`pointcloud`,这两个文件夹名称不可以更改且必须在同一文件夹下。`image_orig`内需要有N(N>=4)张未反畸变的图片,`pointcloud`中有N份对应的pcd点云文件,二者应该时间上已经对应同步。
## 操作
1. 打卡config文件。在终端启动./PlyCal-qt后会直接进入config.json文件的选择。
2. 打开dataset。如下图为主界面,点击`Open Dataset`选择保护`image_orig`和`pointcloud`的文件夹。主界面会显示总的数据帧数。

3. 手动调整初值。打开dataset后主界面会隐藏,出现如下的调整初值的界面和一个显示点云的窗口、一个显示图像的窗口(此时点云会投影到图像、图像颜色也会投影到点云)。再下图的界面中手工条件rotation、translation且观察图像界面中的点云深度投影,OK是关掉下界面即可。

4. 手动条件polygon。返回主界面后,目前还不能第一次在点云和图像中都直接检测出四边形。对于图像,可以先点击`Start Selection`,然后鼠标在图片窗口中点击目标四边形的四个角点,完成后点击`Finish Selection`,正常检测结果如下图。对于点云,使用`Pointcloud Control`下的四个sliderbar来切割点云,缩小检测的范围,正常结果如下。


5. 检测。第一帧手动调整结束后,可以使用`Next Pose`来一帧一帧的处理下一帧,或者使用`Quick`快速处理,当数据检测结果不好时可以回到步骤4手动调整或者`Delete`
6. 校准。点击`Calibrate`调用校准优化,结果在终端有打印,也可以点击`Save Result`。config文件此时也可以保存(会覆写之前的config)。
# English Version
(Translated with AI):
This program only implements calibration with quadrilateral plates, not with any polygon for the moment.
## Intend
As shown in the example folder, to use this software you need a config.json file and the corresponding files for the image and point cloud.
config.json: refer to example/config.json, normally you only need to change the K and D of the camera in it, there is no requirement for the path of this file.
dataset: dataset refers to image_orig and pointcloud under example, the name of these two folders can not be changed and must be in the same folder. image_orig needs to have N (N>=4) undistorted images in it, and there are N corresponding pcd pointcloud files in pointcloud, the two should be synchronised in time. be synchronised in time.
## Manipulate
1. Punch the config file. In the terminal launching . /PlyCal-qt will take you directly to the config.json file selection.
2. Open dataset. as shown below for the main interface, click Open Dataset to select the folder protecting image_orig and pointcloud. The main interface will show the total number of data frames.

3. Adjust the initial value manually. After opening dataset, the main interface will be hidden, and the following interface for adjusting the initial value will appear, together with a window for displaying the point cloud and a window for displaying the image (at this time, the point cloud
gitextract_smbq0rmy/
├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── PlyCal/
│ ├── CMakeLists.txt
│ ├── calibrator.cpp
│ ├── calibrator.h
│ ├── image_polygon.cpp
│ ├── image_polygon.h
│ ├── pointcloud_polygon.cpp
│ ├── pointcloud_polygon.h
│ └── utils.h
├── PlyCal_qt/
│ ├── CMakeLists.txt
│ ├── cqtopencvviewergl.cpp
│ ├── cqtopencvviewergl.h
│ ├── data_reader.cpp
│ ├── data_reader.h
│ ├── imageviewer.cpp
│ ├── imageviewer.h
│ ├── imageviewer.ui
│ ├── main.cpp
│ ├── mainwindow.cpp
│ ├── mainwindow.h
│ ├── mainwindow.ui
│ ├── pointcloudviewer.cpp
│ ├── pointcloudviewer.h
│ ├── pointcloudviewer.ui
│ ├── tfwindow.cpp
│ ├── tfwindow.h
│ └── tfwindow.ui
├── PlyCal_test/
│ ├── CMakeLists.txt
│ ├── test_image_polygon.cpp
│ ├── test_image_polygons.cpp
│ └── test_pointcloud_polygon.cpp
├── README.md
├── data/
│ ├── config.json
│ └── pointcloud/
│ ├── 0.pcd
│ ├── 1.pcd
│ ├── 2.pcd
│ ├── 3.pcd
│ ├── 4.pcd
│ ├── 5.pcd
│ ├── 6.pcd
│ └── 7.pcd
├── doc/
│ └── README.md
└── thirdParty/
├── edlines/
│ ├── EDLineDetector.cpp
│ └── EDLineDetector.h
└── json/
└── json.hpp
SYMBOL INDEX (490 symbols across 20 files)
FILE: PlyCal/calibrator.cpp
function ProjectPoint2Image (line 39) | static void ProjectPoint2Image(const T* const q_ptr, const T* const t_ptr,
type Edge2EdgeError (line 64) | struct Edge2EdgeError
method Edge2EdgeError (line 77) | Edge2EdgeError(const Eigen::Matrix3d& k, const Eigen::Matrix3Xd& ps, c...
type Point2PolygonError (line 104) | struct Point2PolygonError
method Point2PolygonError (line 111) | Point2PolygonError(const Eigen::Matrix3d& k, const Eigen::Matrix3Xd& p...
FILE: PlyCal/calibrator.h
function namespace (line 43) | namespace lqh
FILE: PlyCal/image_polygon.cpp
type RectangleEdges (line 566) | struct RectangleEdges
method RectangleEdges (line 572) | RectangleEdges(double error_, uint32_t id0_, uint32_t id1_):
FILE: PlyCal/image_polygon.h
function class (line 37) | class ImagePolygon
FILE: PlyCal/pointcloud_polygon.cpp
type Point (line 230) | struct Point
method Point (line 236) | Point(uint32_t pid, int8_t ppitch, double pyaw):
FILE: PlyCal/pointcloud_polygon.h
function namespace (line 33) | namespace lqh
FILE: PlyCal/utils.h
function namespace (line 26) | namespace lqh
FILE: PlyCal_qt/cqtopencvviewergl.h
function startPickPoints (line 17) | void startPickPoints()
function stopPickPoints (line 22) | void stopPickPoints()
function getPickpoints (line 27) | void getPickpoints(std::vector<cv::Point2d>& pts)
FILE: PlyCal_qt/data_reader.h
function class (line 32) | class DataReader
FILE: PlyCal_qt/imageviewer.h
function namespace (line 11) | namespace Ui {
function class (line 15) | class ImageViewer : public QMainWindow
FILE: PlyCal_qt/main.cpp
function main (line 4) | int main(int argc, char *argv[])
FILE: PlyCal_qt/mainwindow.h
function namespace (line 18) | namespace Ui
function class (line 23) | class MainWindow : public QMainWindow
FILE: PlyCal_qt/pointcloudviewer.h
function namespace (line 15) | namespace Ui {
function class (line 19) | class PointcloudViewer : public QMainWindow
FILE: PlyCal_qt/tfwindow.h
function namespace (line 9) | namespace Ui {
function class (line 13) | class TFwindow : public QMainWindow
FILE: PlyCal_test/test_image_polygon.cpp
function main (line 39) | int main(int argc, char** argv)
FILE: PlyCal_test/test_image_polygons.cpp
function main (line 39) | int main(int argc, char** argv)
FILE: PlyCal_test/test_pointcloud_polygon.cpp
function main (line 44) | int main(int argc, char** argv)
FILE: thirdParty/edlines/EDLineDetector.cpp
function writeMat (line 73) | void writeMat(cv::Mat m, string name, int n)
function writeImage (line 92) | void writeImage(cv::Mat img, std::string name)
FILE: thirdParty/edlines/EDLineDetector.h
type Pixel (line 58) | struct Pixel
type EdgeChains (line 63) | struct EdgeChains
type LineChains (line 70) | struct LineChains
type std (line 78) | typedef std::list<Pixel> PixelChain;
type EDLineParam (line 81) | struct EDLineParam
function class (line 104) | class EDLineDetector
FILE: thirdParty/json/json.hpp
type nlohmann (line 125) | namespace nlohmann
type adl_serializer (line 128) | struct adl_serializer
method from_json (line 6920) | static void from_json(BasicJsonType&& j, ValueType& val) noexcept(
method to_json (line 6936) | static void to_json(BasicJsonType& j, ValueType&& val) noexcept(
class basic_json (line 139) | class basic_json
type detail (line 166) | namespace detail
class exception (line 200) | class exception : public std::exception
method exception (line 213) | exception(int id_, const char* what_arg) : id(id_), m(what_arg) {}
method name (line 215) | static std::string name(const std::string& ename, int id_)
class parse_error (line 268) | class parse_error : public exception
method parse_error (line 279) | static parse_error create(int id_, std::size_t byte_, const std::s...
method parse_error (line 299) | parse_error(int id_, std::size_t byte_, const char* what_arg)
class invalid_iterator (line 340) | class invalid_iterator : public exception
method invalid_iterator (line 343) | static invalid_iterator create(int id_, const std::string& what_arg)
method invalid_iterator (line 350) | invalid_iterator(int id_, const char* what_arg)
class type_error (line 392) | class type_error : public exception
method type_error (line 395) | static type_error create(int id_, const std::string& what_arg)
method type_error (line 402) | type_error(int id_, const char* what_arg) : exception(id_, what_ar...
class out_of_range (line 435) | class out_of_range : public exception
method out_of_range (line 438) | static out_of_range create(int id_, const std::string& what_arg)
method out_of_range (line 445) | out_of_range(int id_, const char* what_arg) : exception(id_, what_...
class other_error (line 472) | class other_error : public exception
method other_error (line 475) | static other_error create(int id_, const std::string& what_arg)
method other_error (line 482) | other_error(int id_, const char* what_arg) : exception(id_, what_a...
type value_t (line 515) | enum class value_t : uint8_t
type is_basic_json (line 556) | struct is_basic_json : std::false_type {}
type index_sequence (line 571) | struct index_sequence
method size (line 575) | static constexpr std::size_t size() noexcept
type merge_and_renumber (line 582) | struct merge_and_renumber
type make_index_sequence (line 589) | struct make_index_sequence
type make_index_sequence<0> (line 593) | struct make_index_sequence<0> : index_sequence<> {}
type make_index_sequence<1> (line 594) | struct make_index_sequence<1> : index_sequence<0> {}
type conjunction (line 612) | struct conjunction : std::true_type {}
type conjunction<B1> (line 613) | struct conjunction<B1> : B1 {}
type negation (line 617) | struct negation : std::integral_constant<bool, not B::value> {}
type priority_tag (line 620) | struct priority_tag : priority_tag < N - 1 > {}
type priority_tag<0> (line 621) | struct priority_tag<0> {}
type external_constructor (line 628) | struct external_constructor
type external_constructor<value_t::boolean> (line 631) | struct external_constructor<value_t::boolean>
method construct (line 634) | static void construct(BasicJsonType& j, typename BasicJsonType::bo...
type external_constructor<value_t::string> (line 643) | struct external_constructor<value_t::string>
method construct (line 646) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 654) | static void construct(BasicJsonType& j, typename BasicJsonType::st...
type external_constructor<value_t::number_float> (line 663) | struct external_constructor<value_t::number_float>
method construct (line 666) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_unsigned> (line 675) | struct external_constructor<value_t::number_unsigned>
method construct (line 678) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::number_integer> (line 687) | struct external_constructor<value_t::number_integer>
method construct (line 690) | static void construct(BasicJsonType& j, typename BasicJsonType::nu...
type external_constructor<value_t::array> (line 699) | struct external_constructor<value_t::array>
method construct (line 702) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 710) | static void construct(BasicJsonType& j, typename BasicJsonType::ar...
method construct (line 720) | static void construct(BasicJsonType& j, const CompatibleArrayType&...
method construct (line 730) | static void construct(BasicJsonType& j, const std::vector<bool>& arr)
method construct (line 744) | static void construct(BasicJsonType& j, const std::valarray<T>& arr)
type external_constructor<value_t::object> (line 755) | struct external_constructor<value_t::object>
method construct (line 758) | static void construct(BasicJsonType& j, const typename BasicJsonTy...
method construct (line 766) | static void construct(BasicJsonType& j, typename BasicJsonType::ob...
method construct (line 775) | static void construct(BasicJsonType& j, const CompatibleObjectType...
type is_compatible_object_type_impl (line 821) | struct is_compatible_object_type_impl : std::false_type {}
type is_compatible_object_type_impl<true, RealType, CompatibleObjectType> (line 824) | struct is_compatible_object_type_impl<true, RealType, CompatibleObje...
type is_compatible_object_type (line 832) | struct is_compatible_object_type
type is_basic_json_nested_type (line 842) | struct is_basic_json_nested_type
type is_compatible_array_type (line 851) | struct is_compatible_array_type
type is_compatible_integer_type_impl (line 865) | struct is_compatible_integer_type_impl : std::false_type {}
type is_compatible_integer_type_impl<true, RealIntegerType, CompatibleNumberIntegerType> (line 868) | struct is_compatible_integer_type_impl<true, RealIntegerType, Compat...
type is_compatible_integer_type (line 881) | struct is_compatible_integer_type
type has_from_json (line 893) | struct has_from_json
type has_non_default_from_json (line 910) | struct has_non_default_from_json
type has_to_json (line 925) | struct has_to_json
function to_json (line 945) | void to_json(BasicJsonType& j, T b) noexcept
function to_json (line 952) | void to_json(BasicJsonType& j, const CompatibleString& s)
function to_json (line 958) | void to_json(BasicJsonType& j, typename BasicJsonType::string_t&& s)
function to_json (line 965) | void to_json(BasicJsonType& j, FloatType val) noexcept
function to_json (line 972) | void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noe...
function to_json (line 979) | void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noex...
function to_json (line 986) | void to_json(BasicJsonType& j, EnumType e) noexcept
function to_json (line 993) | void to_json(BasicJsonType& j, const std::vector<bool>& e)
function to_json (line 1002) | void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
function to_json (line 1009) | void to_json(BasicJsonType& j, std::valarray<T> arr)
function to_json (line 1015) | void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
function to_json (line 1022) | void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
function to_json (line 1028) | void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
function to_json (line 1035) | void to_json(BasicJsonType& j, T (&arr)[N])
function to_json (line 1041) | void to_json(BasicJsonType& j, const std::pair<Args...>& p)
function to_json_tuple_impl (line 1047) | void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequ...
function to_json (line 1053) | void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
function get_arithmetic_value (line 1067) | void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1093) | void from_json(const BasicJsonType& j, typename BasicJsonType::boole...
function from_json (line 1103) | void from_json(const BasicJsonType& j, typename BasicJsonType::strin...
function from_json (line 1113) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1119) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1125) | void from_json(const BasicJsonType& j, typename BasicJsonType::numbe...
function from_json (line 1132) | void from_json(const BasicJsonType& j, EnumType& e)
function from_json (line 1140) | void from_json(const BasicJsonType& j, typename BasicJsonType::array...
function from_json (line 1152) | void from_json(const BasicJsonType& j, std::forward_list<T, Allocato...
function from_json (line 1168) | void from_json(const BasicJsonType& j, std::valarray<T>& l)
function from_json_array_impl (line 1179) | void from_json_array_impl(const BasicJsonType& j, CompatibleArrayTyp...
function from_json_array_impl (line 1193) | auto from_json_array_impl(const BasicJsonType& j, CompatibleArrayTyp...
function from_json_array_impl (line 1211) | void from_json_array_impl(const BasicJsonType& j, std::array<T, N>& ...
function from_json (line 1223) | void from_json(const BasicJsonType& j, CompatibleArrayType& arr)
function from_json (line 1235) | void from_json(const BasicJsonType& j, CompatibleObjectType& obj)
function from_json (line 1265) | void from_json(const BasicJsonType& j, ArithmeticType& val)
function from_json (line 1296) | void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
function from_json_tuple_impl (line 1302) | void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_se...
function from_json (line 1308) | void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
type to_json_fn (line 1313) | struct to_json_fn
method call (line 1317) | auto call(BasicJsonType& j, T&& val, priority_tag<1> /*unused*/) c...
method call (line 1324) | void call(BasicJsonType& /*unused*/, T&& /*unused*/, priority_tag<...
type from_json_fn (line 1346) | struct from_json_fn
method call (line 1350) | auto call(const BasicJsonType& j, T& val, priority_tag<1> /*unused...
method call (line 1358) | void call(const BasicJsonType& /*unused*/, T& /*unused*/, priority...
type static_const (line 1381) | struct static_const
type input_adapter_protocol (line 1404) | struct input_adapter_protocol
class input_stream_adapter (line 1425) | class input_stream_adapter : public input_adapter_protocol
method input_stream_adapter (line 1435) | explicit input_stream_adapter(std::istream& i)
method input_stream_adapter (line 1467) | input_stream_adapter(const input_stream_adapter&) = delete;
method input_stream_adapter (line 1468) | input_stream_adapter& operator=(input_stream_adapter&) = delete;
method get_character (line 1473) | std::char_traits<char>::int_type get_character() override
method unget_character (line 1478) | void unget_character() override
class input_buffer_adapter (line 1490) | class input_buffer_adapter : public input_adapter_protocol
method input_buffer_adapter (line 1493) | input_buffer_adapter(const char* b, const std::size_t l)
method input_buffer_adapter (line 1504) | input_buffer_adapter(const input_buffer_adapter&) = delete;
method input_buffer_adapter (line 1505) | input_buffer_adapter& operator=(input_buffer_adapter&) = delete;
method get_character (line 1507) | std::char_traits<char>::int_type get_character() noexcept override
method unget_character (line 1517) | void unget_character() noexcept override
class input_adapter (line 1534) | class input_adapter
method input_adapter (line 1540) | input_adapter(std::istream& i)
method input_adapter (line 1544) | input_adapter(std::istream&& i)
method input_adapter (line 1554) | input_adapter(CharT b, std::size_t l)
method input_adapter (line 1566) | input_adapter(CharT b)
method input_adapter (line 1575) | input_adapter(IteratorType first, IteratorType last)
method input_adapter (line 1607) | input_adapter(T (&array)[N])
method input_adapter (line 1615) | input_adapter(const ContiguousContainer& c)
class lexer (line 1638) | class lexer
type token_type (line 1646) | enum class token_type
method lexer (line 1709) | explicit lexer(detail::input_adapter_t adapter)
method lexer (line 1713) | lexer(const lexer&) = delete;
method lexer (line 1714) | lexer& operator=(lexer&) = delete;
method get_decimal_point (line 1722) | static char get_decimal_point() noexcept
method get_codepoint (line 1748) | int get_codepoint()
method next_byte_in_range (line 1796) | bool next_byte_in_range(std::initializer_list<int> ranges)
method token_type (line 1832) | token_type scan_string()
method strtof (line 2263) | static void strtof(float& f, const char* str, char** endptr) noexcept
method strtof (line 2268) | static void strtof(double& f, const char* str, char** endptr) noex...
method strtof (line 2273) | static void strtof(long double& f, const char* str, char** endptr)...
method token_type (line 2318) | token_type scan_number()
method token_type (line 2650) | token_type scan_literal(const char* literal_text, const std::size_...
method reset (line 2670) | void reset() noexcept
method get (line 2687) | std::char_traits<char>::int_type get()
method unget (line 2699) | void unget()
method add (line 2711) | void add(int c)
method number_integer_t (line 2722) | constexpr number_integer_t get_number_integer() const noexcept
method number_unsigned_t (line 2728) | constexpr number_unsigned_t get_number_unsigned() const noexcept
method number_float_t (line 2734) | constexpr number_float_t get_number_float() const noexcept
method move_string (line 2740) | std::string move_string()
method get_position (line 2750) | constexpr std::size_t get_position() const noexcept
method get_token_string (line 2758) | std::string get_token_string() const
method token_type (line 2792) | token_type scan()
class parser (line 2890) | class parser
type parse_event_t (line 2899) | enum class parse_event_t : uint8_t
method parser (line 2919) | explicit parser(detail::input_adapter_t adapter,
method parse (line 2935) | void parse(const bool strict, BasicJsonType& result)
method accept (line 2971) | bool accept(const bool strict = true)
method parse_internal (line 2992) | void parse_internal(bool keep, BasicJsonType& result)
method accept_internal (line 3280) | bool accept_internal()
method token_type (line 3384) | token_type get_token()
method expect (line 3392) | bool expect(token_type t)
method throw_exception (line 3411) | [[noreturn]] void throw_exception() const
class primitive_iterator_t (line 3462) | class primitive_iterator_t
method difference_type (line 3467) | constexpr difference_type get_value() const noexcept
method set_begin (line 3473) | void set_begin() noexcept
method set_end (line 3479) | void set_end() noexcept
method is_begin (line 3485) | constexpr bool is_begin() const noexcept
method is_end (line 3491) | constexpr bool is_end() const noexcept
method primitive_iterator_t (line 3506) | primitive_iterator_t operator+(difference_type i)
method difference_type (line 3513) | constexpr difference_type operator-(primitive_iterator_t lhs, prim...
method primitive_iterator_t (line 3523) | primitive_iterator_t& operator++()
method primitive_iterator_t (line 3529) | primitive_iterator_t const operator++(int)
method primitive_iterator_t (line 3536) | primitive_iterator_t& operator--()
method primitive_iterator_t (line 3542) | primitive_iterator_t const operator--(int)
method primitive_iterator_t (line 3549) | primitive_iterator_t& operator+=(difference_type n)
method primitive_iterator_t (line 3555) | primitive_iterator_t& operator-=(difference_type n)
type internal_iterator (line 3575) | struct internal_iterator
class iteration_proxy (line 3585) | class iteration_proxy
class iteration_proxy_internal (line 4185) | class iteration_proxy_internal
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
method iteration_proxy (line 4250) | explicit iteration_proxy(typename IteratorType::reference cont)
method iteration_proxy_internal (line 4254) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 4260) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
class iter_impl (line 3608) | class iter_impl
method iter_impl (line 3645) | iter_impl() = default;
method iter_impl (line 3653) | explicit iter_impl(pointer object) noexcept : m_object(object)
method iter_impl (line 3693) | iter_impl(const iter_impl<typename std::remove_const<BasicJsonType...
method iter_impl (line 3702) | iter_impl& operator=(const iter_impl<typename std::remove_const<Ba...
method set_begin (line 3714) | void set_begin() noexcept
method set_end (line 3751) | void set_end() noexcept
method reference (line 3782) | reference operator*() const
method pointer (line 3819) | pointer operator->() const
method iter_impl (line 3853) | iter_impl const operator++(int)
method iter_impl (line 3864) | iter_impl& operator++()
method iter_impl (line 3896) | iter_impl const operator--(int)
method iter_impl (line 3907) | iter_impl& operator--()
method iter_impl (line 4029) | iter_impl& operator+=(difference_type i)
method iter_impl (line 4058) | iter_impl& operator-=(difference_type i)
method iter_impl (line 4067) | iter_impl operator+(difference_type i) const
method iter_impl (line 4078) | iter_impl operator+(difference_type i, const iter_impl& it)
method iter_impl (line 4089) | iter_impl operator-(difference_type i) const
method difference_type (line 4100) | difference_type operator-(const iter_impl& other) const
method reference (line 4121) | reference operator[](difference_type n) const
method key (line 4152) | typename object_t::key_type key() const
method reference (line 4168) | reference value() const
class iteration_proxy (line 4181) | class iteration_proxy
class iteration_proxy_internal (line 4185) | class iteration_proxy_internal
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
method iteration_proxy (line 4250) | explicit iteration_proxy(typename IteratorType::reference cont)
method iteration_proxy_internal (line 4254) | iteration_proxy_internal begin() noexcept
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
method iteration_proxy_internal (line 4260) | iteration_proxy_internal end() noexcept
method iteration_proxy_internal (line 4194) | explicit iteration_proxy_internal(IteratorType it) noexcept : an...
method iteration_proxy_internal (line 4197) | iteration_proxy_internal& operator*()
method iteration_proxy_internal (line 4203) | iteration_proxy_internal& operator++()
method key (line 4218) | std::string key() const
method value (line 4239) | typename IteratorType::reference value() const
class json_reverse_iterator (line 4285) | class json_reverse_iterator : public std::reverse_iterator<Base>
method json_reverse_iterator (line 4295) | json_reverse_iterator(const typename base_iterator::iterator_type&...
method json_reverse_iterator (line 4299) | json_reverse_iterator(const base_iterator& it) noexcept : base_ite...
method json_reverse_iterator (line 4302) | json_reverse_iterator const operator++(int)
method json_reverse_iterator (line 4308) | json_reverse_iterator& operator++()
method json_reverse_iterator (line 4314) | json_reverse_iterator const operator--(int)
method json_reverse_iterator (line 4320) | json_reverse_iterator& operator--()
method json_reverse_iterator (line 4326) | json_reverse_iterator& operator+=(difference_type i)
method json_reverse_iterator (line 4332) | json_reverse_iterator operator+(difference_type i) const
method json_reverse_iterator (line 4338) | json_reverse_iterator operator-(difference_type i) const
method difference_type (line 4344) | difference_type operator-(const json_reverse_iterator& other) const
method reference (line 4350) | reference operator[](difference_type n) const
method key (line 4356) | auto key() const -> decltype(std::declval<Base>().key())
method reference (line 4363) | reference value() const
type output_adapter_protocol (line 4375) | struct output_adapter_protocol
class output_vector_adapter (line 4388) | class output_vector_adapter : public output_adapter_protocol<CharType>
method output_vector_adapter (line 4391) | explicit output_vector_adapter(std::vector<CharType>& vec) : v(vec...
method write_character (line 4393) | void write_character(CharType c) override
method write_characters (line 4398) | void write_characters(const CharType* s, std::size_t length) override
class output_stream_adapter (line 4409) | class output_stream_adapter : public output_adapter_protocol<CharType>
method output_stream_adapter (line 4412) | explicit output_stream_adapter(std::basic_ostream<CharType>& s) : ...
method write_character (line 4414) | void write_character(CharType c) override
method write_characters (line 4419) | void write_characters(const CharType* s, std::size_t length) override
class output_string_adapter (line 4430) | class output_string_adapter : public output_adapter_protocol<CharType>
method output_string_adapter (line 4433) | explicit output_string_adapter(std::basic_string<CharType>& s) : s...
method write_character (line 4435) | void write_character(CharType c) override
method write_characters (line 4440) | void write_characters(const CharType* s, std::size_t length) override
class output_adapter (line 4450) | class output_adapter
method output_adapter (line 4453) | output_adapter(std::vector<CharType>& vec)
method output_adapter (line 4456) | output_adapter(std::basic_ostream<CharType>& s)
method output_adapter (line 4459) | output_adapter(std::basic_string<CharType>& s)
class binary_reader (line 4479) | class binary_reader
method binary_reader (line 4490) | explicit binary_reader(input_adapter_t adapter) : ia(std::move(ada...
method BasicJsonType (line 4505) | BasicJsonType parse_cbor(const bool strict)
method BasicJsonType (line 4526) | BasicJsonType parse_msgpack(const bool strict)
method little_endianess (line 4544) | static constexpr bool little_endianess(int num = 1) noexcept
method BasicJsonType (line 4555) | BasicJsonType parse_cbor_internal(const bool get_char = true)
method BasicJsonType (line 4873) | BasicJsonType parse_msgpack_internal()
method get (line 5207) | int get()
method NumberType (line 5226) | NumberType get_number()
method get_string (line 5266) | std::string get_string(const NumberType len)
method get_cbor_string (line 5290) | std::string get_cbor_string()
method BasicJsonType (line 5366) | BasicJsonType get_cbor_array(const NumberType len)
method BasicJsonType (line 5377) | BasicJsonType get_cbor_object(const NumberType len)
method get_msgpack_string (line 5403) | std::string get_msgpack_string()
method BasicJsonType (line 5472) | BasicJsonType get_msgpack_array(const NumberType len)
method BasicJsonType (line 5483) | BasicJsonType get_msgpack_object(const NumberType len)
method check_eof (line 5502) | void check_eof(const bool expect_eof = false) const
class binary_writer (line 5538) | class binary_writer
method binary_writer (line 5546) | explicit binary_writer(output_adapter_t<CharType> adapter) : oa(ad...
method write_cbor (line 5554) | void write_cbor(const BasicJsonType& j)
method write_msgpack (line 5798) | void write_msgpack(const BasicJsonType& j)
method write_number (line 6045) | void write_number(NumberType n)
class serializer (line 6074) | class serializer
method serializer (line 6085) | serializer(output_adapter_t<char> s, const char ichar)
method serializer (line 6092) | serializer(const serializer&) = delete;
method serializer (line 6093) | serializer& operator=(const serializer&) = delete;
method dump (line 6112) | void dump(const BasicJsonType& val, const bool pretty_print,
method bytes_following (line 6311) | static constexpr std::size_t bytes_following(const uint8_t u)
method extra_space (line 6329) | static std::size_t extra_space(const string_t& s,
method escape_codepoint (line 6419) | static void escape_codepoint(int codepoint, string_t& result, std:...
method dump_escaped (line 6484) | void dump_escaped(const string_t& s, const bool ensure_ascii) const
method dump_integer (line 6638) | void dump_integer(NumberType x)
method dump_float (line 6679) | void dump_float(number_float_t x)
method decode (line 6755) | static void decode(uint8_t& state, const uint8_t byte)
method throw_if_invalid_utf8 (line 6789) | static void throw_if_invalid_utf8(const std::string& str)
class json_ref (line 6838) | class json_ref
method json_ref (line 6843) | json_ref(value_type&& value)
method json_ref (line 6847) | json_ref(const value_type& value)
method json_ref (line 6851) | json_ref(std::initializer_list<json_ref> init)
method json_ref (line 6856) | json_ref(Args&& ... args)
method json_ref (line 6861) | json_ref(json_ref&&) = default;
method json_ref (line 6862) | json_ref(const json_ref&) = delete;
method json_ref (line 6863) | json_ref& operator=(const json_ref&) = delete;
method value_type (line 6865) | value_type moved_or_copied() const
method value_type (line 6874) | value_type const& operator*() const
method value_type (line 6879) | value_type const* operator->() const
type adl_serializer (line 6908) | struct adl_serializer
method from_json (line 6920) | static void from_json(BasicJsonType&& j, ValueType& val) noexcept(
method to_json (line 6936) | static void to_json(BasicJsonType& j, ValueType&& val) noexcept(
class json_pointer (line 6954) | class json_pointer
class basic_json (line 6958) | class basic_json
method json_pointer (line 6982) | explicit json_pointer(const std::string& s = "") : reference_tokens(...
method to_string (line 6999) | std::string to_string() const noexcept
method array_index (line 7022) | static int array_index(const std::string& s)
method pop_back (line 7041) | std::string pop_back()
method is_root (line 7054) | bool is_root() const
method json_pointer (line 7059) | json_pointer top() const
method split (line 7147) | static std::vector<std::string> split(const std::string& reference_s...
method replace_substring (line 7222) | static void replace_substring(std::string& s, const std::string& f,
method escape (line 7234) | static std::string escape(std::string s)
method unescape (line 7242) | static void unescape(std::string& s)
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 7365) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function value_t (line 9127) | constexpr value_t type() const noexcept
function is_primitive (line 9157) | constexpr bool is_primitive() const noexcept
function is_structured (line 9184) | constexpr bool is_structured() const noexcept
function is_null (line 9206) | constexpr bool is_null() const noexcept
function is_boolean (line 9228) | constexpr bool is_boolean() const noexcept
function is_number (line 9258) | constexpr bool is_number() const noexcept
function is_number_integer (line 9287) | constexpr bool is_number_integer() const noexcept
function is_number_unsigned (line 9315) | constexpr bool is_number_unsigned() const noexcept
function is_number_float (line 9343) | constexpr bool is_number_float() const noexcept
function is_object (line 9365) | constexpr bool is_object() const noexcept
function is_array (line 9387) | constexpr bool is_array() const noexcept
function is_string (line 9409) | constexpr bool is_string() const noexcept
function is_discarded (line 9436) | constexpr bool is_discarded() const noexcept
type merge_and_renumber<index_sequence<I1...>, index_sequence<I2...>> (line 585) | struct merge_and_renumber<index_sequence<I1...>, index_sequence<I2...>>
type conjunction<B1, Bn...> (line 615) | struct conjunction<B1, Bn...> : std::conditional<bool(B1::value), conjun...
function object_t (line 9486) | object_t* get_impl_ptr(object_t* /*unused*/) noexcept
function object_t (line 9492) | constexpr const object_t* get_impl_ptr(const object_t* /*unused*/) const...
function array_t (line 9498) | array_t* get_impl_ptr(array_t* /*unused*/) noexcept
function array_t (line 9504) | constexpr const array_t* get_impl_ptr(const array_t* /*unused*/) const n...
function string_t (line 9510) | string_t* get_impl_ptr(string_t* /*unused*/) noexcept
function string_t (line 9516) | constexpr const string_t* get_impl_ptr(const string_t* /*unused*/) const...
function boolean_t (line 9522) | boolean_t* get_impl_ptr(boolean_t* /*unused*/) noexcept
function boolean_t (line 9528) | constexpr const boolean_t* get_impl_ptr(const boolean_t* /*unused*/) con...
function number_integer_t (line 9534) | number_integer_t* get_impl_ptr(number_integer_t* /*unused*/) noexcept
function number_integer_t (line 9540) | constexpr const number_integer_t* get_impl_ptr(const number_integer_t* /...
function number_unsigned_t (line 9546) | number_unsigned_t* get_impl_ptr(number_unsigned_t* /*unused*/) noexcept
function number_unsigned_t (line 9552) | constexpr const number_unsigned_t* get_impl_ptr(const number_unsigned_t*...
function number_float_t (line 9558) | number_float_t* get_impl_ptr(number_float_t* /*unused*/) noexcept
function number_float_t (line 9564) | constexpr const number_float_t* get_impl_ptr(const number_float_t* /*unu...
function ReferenceType (line 9581) | static ReferenceType get_ref_impl(ThisType& obj)
function ValueType (line 9666) | ValueType get() const noexcept(noexcept(
function ValueType (line 9717) | ValueType get() const noexcept(noexcept(
function PointerType (line 9754) | PointerType get() noexcept
function PointerType (line 9766) | constexpr const PointerType get() const noexcept
function PointerType (line 9800) | PointerType get_ptr() noexcept
function PointerType (line 9828) | constexpr const PointerType get_ptr() const noexcept
function ReferenceType (line 9877) | ReferenceType get_ref()
function ReferenceType (line 9890) | ReferenceType get_ref() const
function reference (line 9979) | reference at(size_type idx)
function const_reference (line 10026) | const_reference at(size_type idx) const
function reference (line 10077) | reference at(const typename object_t::key_type& key)
function const_reference (line 10128) | const_reference at(const typename object_t::key_type& key) const
function reference (line 10174) | reference operator[](size_type idx)
function const_reference (line 10220) | const_reference operator[](size_type idx) const
function reference (line 10258) | reference operator[](const typename object_t::key_type& key)
function const_reference (line 10307) | const_reference operator[](const typename object_t::key_type& key) const
function reference (line 10347) | reference operator[](T* key)
function const_reference (line 10397) | const_reference operator[](T* key) const
function ValueType (line 10459) | ValueType value(const typename object_t::key_type& key, const ValueType&...
function string_t (line 10481) | string_t value(const typename object_t::key_type& key, const char* defau...
function ValueType (line 10529) | ValueType value(const json_pointer& ptr, const ValueType& default_value)...
function string_t (line 10552) | string_t value(const json_pointer& ptr, const char* default_value) const
function reference (line 10582) | reference front()
function const_reference (line 10590) | const_reference front() const
function reference (line 10626) | reference back()
function const_reference (line 10636) | const_reference back() const
function IteratorType (line 10693) | IteratorType erase(IteratorType pos)
function IteratorType (line 10798) | IteratorType erase(IteratorType first, IteratorType last)
function size_type (line 10885) | size_type erase(const typename object_t::key_type& key)
function erase (line 10920) | void erase(const size_type idx)
function iterator (line 10971) | iterator find(KeyT&& key)
function const_iterator (line 10988) | const_iterator find(KeyT&& key) const
function size_type (line 11022) | size_type count(KeyT&& key) const
function iterator (line 11062) | iterator begin() noexcept
function const_iterator (line 11072) | const_iterator begin() const noexcept
function const_iterator (line 11102) | const_iterator cbegin() const noexcept
function iterator (line 11133) | iterator end() noexcept
function const_iterator (line 11143) | const_iterator end() const noexcept
function const_iterator (line 11173) | const_iterator cend() const noexcept
function reverse_iterator (line 11203) | reverse_iterator rbegin() noexcept
function const_reverse_iterator (line 11211) | const_reverse_iterator rbegin() const noexcept
function reverse_iterator (line 11240) | reverse_iterator rend() noexcept
function const_reverse_iterator (line 11248) | const_reverse_iterator rend() const noexcept
function const_reverse_iterator (line 11277) | const_reverse_iterator crbegin() const noexcept
function const_reverse_iterator (line 11306) | const_reverse_iterator crend() const noexcept
function iterator_wrapper (line 11373) | static iteration_proxy<const_iterator> iterator_wrapper(const_reference ...
function empty (line 11429) | bool empty() const noexcept
function size_type (line 11501) | size_type size() const noexcept
function size_type (line 11571) | size_type max_size() const noexcept
function clear (line 11641) | void clear() noexcept
function push_back (line 11712) | void push_back(basic_json&& val)
function reference (line 11738) | reference operator+=(basic_json&& val)
function push_back (line 11748) | void push_back(const basic_json& val)
function reference (line 11772) | reference operator+=(const basic_json& val)
function push_back (line 11798) | void push_back(const typename object_t::value_type& val)
function reference (line 11822) | reference operator+=(const typename object_t::value_type& val)
function push_back (line 11853) | void push_back(initializer_list_t init)
function reference (line 11871) | reference operator+=(initializer_list_t init)
function emplace_back (line 11899) | void emplace_back(Args&& ... args)
function emplace (line 11947) | std::pair<iterator, bool> emplace(Args&& ... args)
function iterator (line 11995) | iterator insert(const_iterator pos, const basic_json& val)
function iterator (line 12019) | iterator insert(const_iterator pos, basic_json&& val)
function iterator (line 12048) | iterator insert(const_iterator pos, size_type cnt, const basic_json& val)
function iterator (line 12098) | iterator insert(const_iterator pos, const_iterator first, const_iterator...
function iterator (line 12156) | iterator insert(const_iterator pos, initializer_list_t ilist)
function insert (line 12199) | void insert(const_iterator first, const_iterator last)
function update (line 12241) | void update(const_reference j)
function update (line 12292) | void update(const_iterator first, const_iterator last)
function swap (line 12343) | void swap(reference other) noexcept (
function swap (line 12375) | void swap(array_t& other)
function swap (line 12408) | void swap(object_t& other)
function swap (line 12441) | void swap(string_t& other)
function friend (line 12608) | friend bool operator!=(const_reference lhs, const_reference rhs) noexcept
function friend (line 12661) | friend bool operator<(const_reference lhs, const_reference rhs) noexcept
function friend (line 12770) | friend bool operator<=(const_reference lhs, const_reference rhs) noexcept
function friend (line 12816) | friend bool operator>(const_reference lhs, const_reference rhs) noexcept
function friend (line 12862) | friend bool operator>=(const_reference lhs, const_reference rhs) noexcept
function friend (line 12929) | friend std::ostream& operator<<(std::ostream& o, const basic_json& j)
function JSON_DEPRECATED (line 12952) | JSON_DEPRECATED
function basic_json (line 13030) | static basic_json parse(detail::input_adapter i,
function basic_json (line 13042) | static basic_json parse(detail::input_adapter& i,
function accept (line 13051) | static bool accept(detail::input_adapter i)
function accept (line 13056) | static bool accept(detail::input_adapter& i)
function basic_json (line 13112) | static basic_json parse(IteratorType first, IteratorType last,
function accept (line 13125) | static bool accept(IteratorType first, IteratorType last)
function JSON_DEPRECATED (line 13138) | JSON_DEPRECATED
function friend (line 13169) | friend std::istream& operator>>(std::istream& i, basic_json& j)
function to_cbor (line 13347) | static void to_cbor(const basic_json& j, detail::output_adapter<uint8_t> o)
function to_cbor (line 13352) | static void to_cbor(const basic_json& j, detail::output_adapter<char> o)
function to_msgpack (line 13435) | static std::vector<uint8_t> to_msgpack(const basic_json& j)
function to_msgpack (line 13442) | static void to_msgpack(const basic_json& j, detail::output_adapter<uint8...
function to_msgpack (line 13447) | static void to_msgpack(const basic_json& j, detail::output_adapter<char> o)
function basic_json (line 13543) | static basic_json from_cbor(detail::input_adapter i,
function basic_json (line 13554) | static basic_json from_cbor(A1 && a1, A2 && a2, const bool strict = true)
function basic_json (line 13630) | static basic_json from_msgpack(detail::input_adapter i,
function basic_json (line 13641) | static basic_json from_msgpack(A1 && a1, A2 && a2, const bool strict = t...
function reference (line 13688) | reference operator[](const json_pointer& ptr)
function const_reference (line 13716) | const_reference operator[](const json_pointer& ptr) const
function reference (line 13759) | reference at(const json_pointer& ptr)
function const_reference (line 13802) | const_reference at(const json_pointer& ptr) const
function basic_json (line 13829) | basic_json flatten() const
function basic_json (line 13866) | basic_json unflatten() const
function basic_json (line 13927) | basic_json patch(const basic_json& json_patch) const
function basic_json (line 14224) | static basic_json diff(const basic_json& source, const basic_json& target,
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14370) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14433) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14505) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14559) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14614) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14668) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
function NLOHMANN_BASIC_JSON_TPL_DECLARATION (line 14721) | NLOHMANN_BASIC_JSON_TPL_DECLARATION
type std (line 14767) | namespace std
function swap (line 14775) | inline void swap(nlohmann::json& j1,
type hash<nlohmann::json> (line 14786) | struct hash<nlohmann::json>
type less< ::nlohmann::detail::value_t> (line 14805) | struct less< ::nlohmann::detail::value_t>
Condensed preview — 47 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (826K chars).
[
{
"path": ".gitignore",
"chars": 52,
"preview": "/build\n.ycm_extra_conf.py\n*.swp\nCMakeLists.txt.user\n"
},
{
"path": "CMakeLists.txt",
"chars": 873,
"preview": "CMAKE_MINIMUM_REQUIRED(VERSION 2.8)\nproject(PlyCal)\n\n#cmake_policy(SET CMP0028 OLD)\nset(CMAKE_CXX_STANDARD 11)\nset(CMAKE"
},
{
"path": "LICENSE",
"chars": 35149,
"preview": " GNU GENERAL PUBLIC LICENSE\n Version 3, 29 June 2007\n\n Copyright (C) 2007 Free "
},
{
"path": "PlyCal/CMakeLists.txt",
"chars": 1056,
"preview": "if( CMAKE_BUILD_TYPE EQUAL \"Release\")\n\tadd_definitions( -DNODEBUG )\nendif(CMAKE_BUILD_TYPE EQUAL \"Release\")\n\nfile(GLOB L"
},
{
"path": "PlyCal/calibrator.cpp",
"chars": 18634,
"preview": "/**\n ******************************************************************************\n * @file\tcalibrator.cpp\n * @autho"
},
{
"path": "PlyCal/calibrator.h",
"chars": 3859,
"preview": "/**\n ******************************************************************************\n * @file\tcalibrator.h\n * @author\t"
},
{
"path": "PlyCal/image_polygon.cpp",
"chars": 23008,
"preview": "/**\n ******************************************************************************\n * @file\timage_polygon.cpp\n * @au"
},
{
"path": "PlyCal/image_polygon.h",
"chars": 4037,
"preview": "/**\n ******************************************************************************\n * @file\timage_polygon.h\n * @auth"
},
{
"path": "PlyCal/pointcloud_polygon.cpp",
"chars": 15388,
"preview": "/**\n ******************************************************************************\n * @file\tpointcloud_polygon.cpp\n "
},
{
"path": "PlyCal/pointcloud_polygon.h",
"chars": 4040,
"preview": "/**\n ******************************************************************************\n * @file\tpointcloud_polygon.h\n * "
},
{
"path": "PlyCal/utils.h",
"chars": 3209,
"preview": "/*\n * utils.h\n * Copyright (C) 2016 Nick.Liao <simplelife_nick@hotmail.com>\n *\n * Distributed under terms of the MIT lic"
},
{
"path": "PlyCal_qt/CMakeLists.txt",
"chars": 626,
"preview": "set(CMAKE_INCLUDE_CURRENT_DIR ON)\n# Let CMake do the job for us\nset(CMAKE_AUTOMOC ON) # For meta object compiler\nset(CMA"
},
{
"path": "PlyCal_qt/cqtopencvviewergl.cpp",
"chars": 3957,
"preview": "#include \"cqtopencvviewergl.h\"\n#include <QMouseEvent>\n#include <QDebug>\n\nCQtOpenCVViewerGl::CQtOpenCVViewerGl(QWidget *p"
},
{
"path": "PlyCal_qt/cqtopencvviewergl.h",
"chars": 1911,
"preview": "#ifndef CQTOPENCVVIEWERGL_H\n#define CQTOPENCVVIEWERGL_H\n\n#include <QOpenGLWidget>\n#include <QOpenGLFunctions_2_0>\n#inclu"
},
{
"path": "PlyCal_qt/data_reader.cpp",
"chars": 4385,
"preview": "/**\n ******************************************************************************\n * @file\tdata_reader.cpp\n * @auth"
},
{
"path": "PlyCal_qt/data_reader.h",
"chars": 2159,
"preview": "/**\n ******************************************************************************\n * @file\tdata_reader.h\n * @author"
},
{
"path": "PlyCal_qt/imageviewer.cpp",
"chars": 1536,
"preview": "#include \"imageviewer.h\"\n#include \"ui_imageviewer.h\"\n\n#include <QMenu>\n#include <QFileDialog>\n#include <QMessageBox>\n#in"
},
{
"path": "PlyCal_qt/imageviewer.h",
"chars": 721,
"preview": "#ifndef IMAGEVIEWER_H\n#define IMAGEVIEWER_H\n\n#include <QMainWindow>\n#include <QContextMenuEvent>\n\n#include <memory>\n\n#in"
},
{
"path": "PlyCal_qt/imageviewer.ui",
"chars": 1393,
"preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>ImageViewer</class>\n <widget class=\"QMainWindow\" name="
},
{
"path": "PlyCal_qt/main.cpp",
"chars": 172,
"preview": "#include \"mainwindow.h\"\n#include <QApplication>\n\nint main(int argc, char *argv[])\n{\n QApplication a(argc, argv);\n "
},
{
"path": "PlyCal_qt/mainwindow.cpp",
"chars": 16992,
"preview": "#include \"mainwindow.h\"\n#include \"ui_mainwindow.h\"\n\n#include <QAction>\n#include <QDebug>\n#include <QFileDialog>\n#include"
},
{
"path": "PlyCal_qt/mainwindow.h",
"chars": 2544,
"preview": "#ifndef MAINWINDOW_H\n#define MAINWINDOW_H\n\n#include <QMainWindow>\n#include <memory>\n\n#include <pcl/point_cloud.h>\n#inclu"
},
{
"path": "PlyCal_qt/mainwindow.ui",
"chars": 19300,
"preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>MainWindow</class>\n <widget class=\"QMainWindow\" name=\""
},
{
"path": "PlyCal_qt/pointcloudviewer.cpp",
"chars": 2309,
"preview": "#include \"pointcloudviewer.h\"\n#include \"ui_pointcloudviewer.h\"\n\n#include <QMenu>\n#include <QDebug>\n\n\nPointcloudViewer::P"
},
{
"path": "PlyCal_qt/pointcloudviewer.h",
"chars": 969,
"preview": "#ifndef POINTCLOUDVIEWER_H\n#define POINTCLOUDVIEWER_H\n\n#include <QMainWindow>\n#include <QContextMenuEvent>\n\n#include <se"
},
{
"path": "PlyCal_qt/pointcloudviewer.ui",
"chars": 1358,
"preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>PointcloudViewer</class>\n <widget class=\"QMainWindow\" "
},
{
"path": "PlyCal_qt/tfwindow.cpp",
"chars": 3014,
"preview": "#include \"tfwindow.h\"\n#include \"ui_tfwindow.h\"\n\n#include <Eigen/Geometry>\n\nstatic const double PI(3.14159265358979323846"
},
{
"path": "PlyCal_qt/tfwindow.h",
"chars": 564,
"preview": "#ifndef TFWINDIOW_H\n#define TFWINDIOW_H\n\n#include <QMainWindow>\n#include <QCloseEvent>\n\n#include <Eigen/Dense>\n\nnamespac"
},
{
"path": "PlyCal_qt/tfwindow.ui",
"chars": 5151,
"preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>TFwindow</class>\n <widget class=\"QMainWindow\" name=\"TF"
},
{
"path": "PlyCal_test/CMakeLists.txt",
"chars": 483,
"preview": "if( CMAKE_BUILD_TYPE EQUAL \"Release\")\n\tadd_definitions( -DNODEBUG )\nendif(CMAKE_BUILD_TYPE EQUAL \"Release\")\n\n\nadd_execut"
},
{
"path": "PlyCal_test/test_image_polygon.cpp",
"chars": 2796,
"preview": "/**\n ******************************************************************************\n * @file\ttest_imagepolygon.cpp\n *"
},
{
"path": "PlyCal_test/test_image_polygons.cpp",
"chars": 3287,
"preview": "/**\n ******************************************************************************\n * @file\ttest_image_polygons.cpp\n "
},
{
"path": "PlyCal_test/test_pointcloud_polygon.cpp",
"chars": 2786,
"preview": "/**\n ******************************************************************************\n * @file\ttest_pointcloud_polygon.c"
},
{
"path": "README.md",
"chars": 2393,
"preview": "# Extrinsic Calibration of the camera and LiDAR via polygon plane\nThis project includes the extrinsic calibration librar"
},
{
"path": "data/config.json",
"chars": 2632,
"preview": "{\n \"cam\": {\n \"D\": [\n -0.343338393354793,\n 0.0806974339575093,\n -0.00052554023"
},
{
"path": "doc/README.md",
"chars": 3955,
"preview": "# PlyCal\n> LIAO Qinghai 2019.2.25\n\n[for English Version click here](#english-version)\n\n\n本程序只实现了利用四边形板校准,暂未实现利用任意polygon"
},
{
"path": "thirdParty/edlines/EDLineDetector.cpp",
"chars": 55603,
"preview": "/*IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.\n\n By downloading, copying, installing or using the s"
},
{
"path": "thirdParty/edlines/EDLineDetector.h",
"chars": 18761,
"preview": "/*IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.\n\n By downloading, copying, installing or using the s"
},
{
"path": "thirdParty/json/json.hpp",
"chars": 513969,
"preview": "/*\n __ _____ _____ _____\n __| | __| | | | JSON for Modern C++\n| | |__ | | | | | | version 3.0.1\n|___"
}
]
// ... and 8 more files (download for full content)
About this extraction
This page contains the full source code of the ram-lab/plycal GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 47 files (766.6 KB), approximately 193.7k tokens, and a symbol index with 490 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.