Repository: goodrobots/vision_landing Branch: master Commit: b7fc1e3e31af Files: 24 Total size: 212.4 KB Directory structure: gitextract__k5kjdkx/ ├── .gitignore ├── LICENSE ├── README.md ├── calibration/ │ ├── aruco_calibration_board_a4.yml │ ├── d435-1280x720.yml │ ├── d435-640x480.yml │ ├── ocam5cr-calibration-1280x720.yml │ ├── ocam5cr-calibration-640x480.alt.yml │ ├── ocam5cr-calibration-640x480.yml │ ├── r200-calibration-1280x720.yml │ ├── r200-calibration-1920x1080.yml │ ├── r200-calibration-640x480.yml │ ├── raspicamv1-calibration-1280x720.yml │ ├── raspicamv1-calibration-640x480.yml │ ├── raspicamv2-calibration-640x480.yml │ ├── sj4000-calibration-1280x720.yml │ └── sj4000-calibration-640x480.yml ├── markers/ │ └── 2x2map.yml ├── src/ │ ├── CMakeLists.txt │ ├── args.hxx │ ├── pkQueueTS.hpp │ └── track_targets.cpp ├── vision_landing └── vision_landing.service ================================================ FILE CONTENTS ================================================ ================================================ FILE: .gitignore ================================================ CMakeCache.txt CMakeFiles/ cmake_install.cmake Makefile src/install_manifest.txt track_targets vision_landing.conf ================================================ FILE: LICENSE ================================================ GNU GENERAL PUBLIC LICENSE Version 3, 29 June 2007 Copyright (C) 2007 Free Software Foundation, Inc. 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 . 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: {project} Copyright (C) {year} {fullname} 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 . 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 . ================================================ FILE: README.md ================================================ # vision_landing _**WARNING: This project is currently discontinued and is of academic interest only. ArduPilot and PX4 autopilots do not yet safely support vision based precision landing. PLEASE DO NOT USE THIS CODE other than for experimental or learning purposes. IT WILL behave dangerously. You have been warned.**_ ### Precision landing using visual targets. This is a project to achieve precision landing on drones using ArduCopter firmware, using (monocular) vision alone. Fiducial markers are printed and used as landing targets, and these targets provide orientation, location and distance information when combined with accurate size information of the markers and calibrated camera information. No rangefinder is necessary, as the distance to target is obtained automatically through pose estimation of the markers. Demonstrations -------------------- ### vision_landing from RTL ### vision_landing using Infrared ### vision_landing using multiple video/data streams, colormapped in realtime ### Detection altitude using 720p video Landing marker detected and locked on at 23 meters altitude, using very poor quality 720p video. Much higher altitude can be expected using better quality camera/settings. ### Detection altitude using 1080p video Landing marker detected and locked on at 32 meters altitude, using very poor quality 1080p video. Much higher altitude can be expected using better quality camera/settings. Dependencies -------------------- **OpenCV (>3.0 recommended)** If possible find packages for your OS for version 3.0 or above (or install from source, for the brave), or else install 2.x packages for your OS. For debian/ubuntu which currently only has opencv2.4, you probably want to install at least these packages: - libopencv-dev - libopencv-calib3d-dev - libopencv-highgui-dev - libopencv-imgproc-dev Note that this was developed using OpenCV 3.2, although current dev/testing is under 4.0.1. SolvePNP which is the underlying function for pose estimation that aruco uses is somewhat broken in 2.4 so aruco includes it's own routines, only using solvepnp in OpenCV >3.0. **Aruco (>3.0.0)** It is recommended to install 3.1.0 from https://github.com/fnoop/aruco as it has some fixes that haven't been released yet. Installation is straight forward: ``` git clone https://github.com/fnoop/aruco git checkout 3.1.0 cd aruco cmake . && make && sudo make install ``` **Dronekit** Install the latest dronekit: ``` sudo pip install dronekit ``` Printing Targets/Markers -------------------- The landing targets used in this project are called 'fiducial markers'. Fiducial markers are encoded objects (think QR codes or bar codes) that are used by computer vision systems as reference points in a scene. There are numerous different types of encodings, which are called 'dictionaries'. The marker library used in this project (Aruco) has its own set of dictionaries, but it also supports other dictionary types such as AprilTags. In order to perform the recommended calibration (detailed below in the next section), it is necessary to print a specific A4 marker board: https://github.com/goodrobots/vision_landing/blob/master/calibration/aruco_calibration_board_a4.pdf It is important to print this on A4 size paper in exactly the size and proportions given in the PDF, as there are specific properties of the board that are expected by the calibration process. When it comes to the landing markers themselves, the size and format depends on the nature of the craft and landing situations. The higher the craft normally flies or will start landing from, the larger the target needs to be in order to be detected. However, larger targets are more difficult to produce, transport and store, and they become unreadable at lower altitudes as they exceed the Field of View of the camera. If precision landing is acceptable from a lower altitude then a smaller target can be used. Alternatively, multiple targets can be used with varying sizes, so a larger target can be used for high altitude lock-on, then the vision system can switch to smaller targets at lower altitude for better precision and to keep within the FoV. Aruco recommends the 'ARUCO_MIP_36h12' dictionary for the best compromise between marker size and robustness. This is a 36bit (6x6) 250 element dictionary and the intermarker distance is smaller than other aruco dictionaries such as 16h3 (4x4), so it's possible after further testing that these dictionaries with smaller marker size are better for precision landing. Indeed, practical testing has shown that using a dictionary with a smaller grid size (and hence larger element or 'pixel' size) gives much better results from altitude. If a larger dictionary with lots of different tags is not required, then it is recommended to use a dictionary such as the AprilTags 16h5 dictionary. So to start with, it is recommended to print a couple of markers (at your choice of size, A4 or A3 are easy to print and a good start): https://github.com/goodrobots/vision_landing/blob/master/markers/aruco_mip_36h12_00012.png https://github.com/goodrobots/vision_landing/blob/master/markers/aruco_mip_36h12_00036.png Once printed, measure the size of the marker (black edge to black edge) and this is fed as the marker size parameter to vision_landing. However, note that you should either print the white border or mount the marker on a white background that leaves a white border around the black marker itself - the white border is important for reliable detection. It is important that the markers do not deform, bend, flap or move, so it's advisable to mount them on something solid like board or perspex. Cardboard mounting up to A1 size is easy to find in local print, craft or stationary shops. It is particularly important to make sure the A4 calibration page is rigid when doing the calibration. In order to address the problem of large markers exceeding the camera FoV at lower altitudes, multiple markers of differing sizes can be used. As the craft descends in altitude locked on to a large marker, at some point a smaller marker will come into view and can be locked on to. Marker boards can be used for increased robustness and accuracy. An example of such a multiple marker board is included as an A1 PDF: https://github.com/goodrobots/vision_landing/blob/master/markers/a1-landing.pdf After testing and experimentation, it was found to have less markers as close together as possible in a circular pattern, with small pattern grids and larger intermarker distances gave better results. An updated marker board as below is preset as default in the config file: https://github.com/goodrobots/vision_landing/blob/master/markers/april16h5-landing-a1.pdf Also during development and testing, it was found that as the smaller markers come into view, the detection bounces between the two which can cause oscillations or other unexpected (and undesirable!) behaviour of the UAV. A configurable filter that helps to debounce the detection thresholds has been implemented and can be set in the config: ``` ## Marker tracking history - number of frames that each marker is tracked for active marker transition markerhistory=30 ## Marker tracking threshold - percentage of frames in tracking history that marker must be detected to be activated markerthreshold=80 ``` The above settings mean that a 30 frame marker buffer is used (equal to 1 second at 30fps), and that of the last 30 frames, the smaller marker must be accurately detected in at least 80% of those 30 frames before vision_landing will lock on to that new smaller marker. This greatly helps when landing on a pattern of concentric diminishing markers. Camera Calibration -------------------- In order to perform any accurate Computer Vision work, you must first calibrate your camera. Every camera and lens combination has different focal lengths, field of view, aperture, sensor size, optical center and lens distortions (eg. fisheye also known as positive radial distortion, or barrel distortion). Even cameras or lenses of the same make/model will have small manufacturing tolerance/mistakes. All of these must be known and compensated for. OpenCV (which is what the vision code in this project uses) uses optional 'Camera Matrix' and 'Distortion Coefficients' matrices (collectively called intrinsics) which are used to 'undistort' the raw image for accurate further processing and can also be used to automatically calculate focal length and field of view, necessary in turn to calculate the target angular offsets for precision landing and pose estimation used for accurate distance measurements. There are numerous calibration methods for opencv, but there is a simple interactive routine included in the Aruco software installed as a dependency, so that process is recommended and documented briefly here: - Print the A4 calibration board detailed above - Run aruco_calibration program: ```aruco_calibration live mycamera_calibration.yml -m /calibration/aruco_calibration_board_a4.yml -size 0.033``` - Move the calibration board so it's in every position of the screen, particularly the outer edges (this is very important to capture the distortion of the lens at it's most extreme) and press 's' to capture a calibration snapshot at each position. - After taking enough snapshots (more the better, at least 10 is good), press 'c' to produce the calibration. With the above command, it will produce a 'mycamera_calibration.yml' Installation -------------------- First ensure the above dependencies are already installed. There are two main components: - vision_landing, a python script - track_targets, a c++ program track_targets must be compiled and installed into the main directory before vision_landing can be run. vision_landing calls track_targets to do the actual target detection and vector calculations. ``` git clone https://github.com/goodrobots/vision_landing cd vision_landing/src cmake . && make && make install ``` You should now have a track_targets file in the same directory as the vision_landing script (the root of the vision_landing project). ### Service Installation In order to provide startup at system boot and 'graceful' stop, a systemd manifest is provided (vision_landing.service). To install, either alter the manifest with the full path to where vision_landing has been downloaded to (replace all instances of /usr/local/vision_landing with new path), or perhaps easier is to copy or symlink the directory to /usr/local and the provided manifest can be used without alteration. The following should be executed from the root of vision_landing project (ie. in the same directory as the vision_landing script and track_targets after install): ``` sudo ln -s `pwd` /usr/local sudo cp vision_landing.service /etc/systemd/system sudo systemctl daemon-reload ``` ### Maverick - Automated Installation The [Maverick](http://github.com/goodrobots/maverick) project pre-installs everything necessary for vision_landing. Flash-able OS images are available for multiple platforms. To start vision_landing, ensure anything else that is using the camera is stopped, and simply use: `maverick start vision_landing` Running -------------------- To run this project, you MUST have accurate calibration data for your camera sensor/lens combination. This can be quite challenging to accomplish, so sample calibration data for Odroid oCam 5cr and Raspberry Pi cameras (v1 only) are included in the calibration directory. More will hopefully be added in the future. Note that even these supplied calibrations will not necessarily be perfect or even be guaranteed to work for your particular camera/lens combination, even if they are the same model. It is highly recommended to take 10 minutes to perform the calibration. ### Systemd running Systemd is the recommended way to run vision_landing, and assumes that the 'Recommended Installation' in the previous section has been completed. Using systemd, starting vision_landing is as simple as executing: ```sudo systemctl start vision_landing``` It can be stopped by executing: ```sudo systemctl stop vision_landing``` Note that when using systemd for control, mandatory and optional parameters are set using vision_landing.conf. ### Manual running vision_landing can also be run without systemd by just calling the main script and relying on the config file for correct configuration, or calling with the necessary mandatory and optional parameters. It is highly recommended to use the config file for ease of use and minimum confusion. **Examples** ``` ./vision_landing # (uses values in vision_landing.conf) ./vision_landing --input /dev/ttyS0 --markersize 0.235 --calibration calibration/ocam5cr-calibration-640x480.yml ./vision_landing --markerid 580 --markerdict TAG36h11 --input /dev/ttyS0 0.235 --calibration calibration/ocam5cr-calibration-640x480.yml ./vision_landing --simulator --input /dev/video2 --output "appsrc ! autovideoconvert ! v4l2video11h264enc ! h264parse ! rtph264pay config-interval=1 pt=96 ! udpsink host=192.168.1.70 port=5000 sync=false" --markerdict TAG36h11 --input tcp:localhost:5777 --markersize 0.235 --calibration calibration/ocam5cr-calibration-640x480.yml ./vision_landing --input /dev/video2 --output /srv/maverick/data/video/landing.mpg --markerdict TAG36h11 --input tcp:localhost:5777 --markersize 0.235 --width 1280 --height 720 --calibration calibration/ocam5cr-calibration-1280x720.yml ``` ### Mandatory parameters - **connect**: This is the dronekit connection string, eg. /dev/ttyS0 (for serial connection to FC), tcp:localhost:5770 (tcp connection to mavproxy), udp:localhost:14560 (udp connection to mavproxy). - **markersize**: This is the size of the fiducial marker in meters. So a typical april tag printed on A3 will be around 23.5cm from black edge to black edge, so the value here would be 0.235. - **calibration**: This is the file containing calibration data, eg. calibration/ocam5cr-calibration-640x480.yml ### Optional parameters ** Note that the --fakerangefinder flag is needed unless you have a proper laser rangefinder or running arducopter >3.5-rc2 ** - **--input**: This is the video stream 'pipeline' used to look for targets. It defaults to /dev/video0 which is what most USB cameras show up as (/dev/video2 typically for odroid xu4 with hardware encoding activated). Video files can be used for testing by just specifying the video file name here. A gstreamer pipeline can also be used here as long as it ends in appsink (eg. v4l2src device=/dev/video2 ! decodebin ! videoconvert ! appsink) - **--output**: This is the output 'pipeline' that can be used to save the video stream with AR data overlaid. This can either be a video file name (which will be uncompressed and very large), or you can create gstreamer pipelines. Example pipeline for odroid xu4 with hardware encoding activated to stream h264 compressed video with AR markers in realtime would be (note gstreamer pipeline must start with appsrc): ```appsrc ! autovideoconvert ! v4l2video11h264enc ! h264parse ! rtph264pay config-interval=1 pt=96 ! udpsink host=192.168.1.x port=5000 sync=false``` - **--markerid**: Specify a marker ID to detect. If specified, only a target matching this ID will be used for landing and any other target will be rejected. If not specified, all targets in the specified or default dictionary will be detected and the closest will be chosen for landing. - **--markerdict**: Type of marker dictionary to use. Only one dictionary can be detected at any one time. Supported dictionaries are: ARUCO ARUCO_MIP_16h3 ARUCO_MIP_25h7 ARUCO_MIP_36h12 ARTOOLKITPLUS ARTOOLKITPLUSBCH TAG16h5 TAG25h7 TAG25h9 TAG36h11 TAG36h10. Defaults to ARUCO_MIP_36h12. - **--simulator**: If this flag is set, when the dronekit connection is made the script will wait for prearm checks to pass and then take off to preset altitude and then initiate landing. This is typically used when connecting to SITL simulator to test precision landing. - **--width**: Set the width of the incoming video stream. Note that camera intrinsics are resized but this will only work if the area of camera is sensor is the same as the calibration. If a different aspect ratio is used then an appropriate calibration should be used, ie. 1280x720 resolution will not work with 640x480 calibration data. - **--height**: As width, but for height. - **--fps**: This attempts to set frames per second of incoming video but this is often not supported by the camera driver. It can be used as a 'fudge factor' if saved video files look too fast or slow. - **--brightness**: This can be used to increase or decrease gain or brightness in high or low light conditions. - **--fakerangefinder**: This flag tells vision_landing to also send fake rangefinder data based on distance detected from a selected target. This is necessary for arducopter firmware <3.5-rc2. - **--verbose**: Turn on some extra info/debug output ## Intel RealSense enhancements The *realsense* branch of this project adds some enhancements when using an Intel RealSense camera. These units actually have three cameras inside - a color RGB camera, two near-InfraRed cameras, and they also have a laser projector for throwing IR patterns onto flat surfaces that are otherwise hard to map. From the two infrared cameras, a depth map is calculated. All of this is done in custom ASIC hardware on the unit so no additional processing is necessary on the host computer. In addition, the units are factory calibrated and intrinsic calibration data is automatically available for each individual unit through the librealsense library/api. They are an excellent, cheap option for obtaining stereo depth data. However, for the purposes of vision_landing they have advantages and disadvantages. On the downside, the cameras are very low quality mobile-pinhole type lenses/sensors. They are configured by default for indoor use, and configuring them for outdoor use is tricky. In particular, the color RGB camera is very poor and is terrible at high contrasting colours - unfortunately exactly what the landing markers are - the white bleeds onto the black and makes detection difficult and unreliable. On the upside, the two IR cameras are global shutter and high framerate (up to 90fps). This makes them actually very good for Computer Vision, and excellent results can be obtained using these cameras. It seems that the toner of laser printers absorb IR very well, so targets printed on a laser printer have excellent contrast to the IR cameras and are very clear from altitude. In addition, the streams from the three cameras can be read simultaneously, as well as the synthetic streams for depth, and corrected and synchronised streams between the cameras. This means we can use the IR camera for the marker detection and estimation, and use either the color stream or depth mapping for visualisation. ================================================ FILE: calibration/aruco_calibration_board_a4.yml ================================================ %YAML:1.0 aruco_bc_dict: ARUCO_MIP_36h12 aruco_bc_nmarkers: 20 aruco_bc_mInfoType: 0 aruco_bc_markers: - { id:161, corners:[ [ -1250., -1450., 0. ], [ -750., -1450., 0. ], [ -750., -1950., 0. ], [ -1250., -1950., 0. ] ] } - { id:227, corners:[ [ -250., -1450., 0. ], [ 250., -1450., 0. ], [ 250., -1950., 0. ], [ -250., -1950., 0. ] ] } - { id:85, corners:[ [ 750., -1450., 0. ], [ 1250., -1450., 0. ], [ 1250., -1950., 0. ], [ 750., -1950., 0. ] ] } - { id:166, corners:[ [ -750., -950., 0. ], [ -250., -950., 0. ], [ -250., -1450., 0. ], [ -750., -1450., 0. ] ] } - { id:244, corners:[ [ 250., -950., 0. ], [ 750., -950., 0. ], [ 750., -1450., 0. ], [ 250., -1450., 0. ] ] } - { id:144, corners:[ [ -1250., -450., 0. ], [ -750., -450., 0. ], [ -750., -950., 0. ], [ -1250., -950., 0. ] ] } - { id:90, corners:[ [ -250., -450., 0. ], [ 250., -450., 0. ], [ 250., -950., 0. ], [ -250., -950., 0. ] ] } - { id:214, corners:[ [ 750., -450., 0. ], [ 1250., -450., 0. ], [ 1250., -950., 0. ], [ 750., -950., 0. ] ] } - { id:153, corners:[ [ -750., 50., 0. ], [ -250., 50., 0. ], [ -250., -450., 0. ], [ -750., -450., 0. ] ] } - { id:7, corners:[ [ 250., 50., 0. ], [ 750., 50., 0. ], [ 750., -450., 0. ], [ 250., -450., 0. ] ] } - { id:143, corners:[ [ -1250., 550., 0. ], [ -750., 550., 0. ], [ -750., 50., 0. ], [ -1250., 50., 0. ] ] } - { id:219, corners:[ [ -250., 550., 0. ], [ 250., 550., 0. ], [ 250., 50., 0. ], [ -250., 50., 0. ] ] } - { id:78, corners:[ [ 750., 550., 0. ], [ 1250., 550., 0. ], [ 1250., 50., 0. ], [ 750., 50., 0. ] ] } - { id:159, corners:[ [ -750., 1050., 0. ], [ -250., 1050., 0. ], [ -250., 550., 0. ], [ -750., 550., 0. ] ] } - { id:209, corners:[ [ 250., 1050., 0. ], [ 750., 1050., 0. ], [ 750., 550., 0. ], [ 250., 550., 0. ] ] } - { id:13, corners:[ [ -1250., 1550., 0. ], [ -750., 1550., 0. ], [ -750., 1050., 0. ], [ -1250., 1050., 0. ] ] } - { id:247, corners:[ [ -250., 1550., 0. ], [ 250., 1550., 0. ], [ 250., 1050., 0. ], [ -250., 1050., 0. ] ] } - { id:237, corners:[ [ 750., 1550., 0. ], [ 1250., 1550., 0. ], [ 1250., 1050., 0. ], [ 750., 1050., 0. ] ] } - { id:100, corners:[ [ -750., 2050., 0. ], [ -250., 2050., 0. ], [ -250., 1550., 0. ], [ -750., 1550., 0. ] ] } - { id:6, corners:[ [ 250., 2050., 0. ], [ 750., 2050., 0. ], [ 750., 1550., 0. ], [ 250., 1550., 0. ] ] } ================================================ FILE: calibration/d435-1280x720.yml ================================================ %YAML:1.0 --- image_width: 1280 image_height: 720 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 9.5184581361560402e+02, 0., 6.9603166699329518e+02, 0., 8.5119274893929366e+02, 3.5100439081567129e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 1.3354150548207788e-01, -4.2352076836541502e-03, 7.2103047346773974e-02, -6.6299211011281861e-02, -2.0028506424249306e+00 ] ================================================ FILE: calibration/d435-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: f data: [ 2.12665997e+01, 0., 3.91298920e+02, 0., 1.00516953e+02, 1.99458557e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: f data: [ -7.61123234e-03, 8.11523496e-05, -1.29759137e-03, 1.34489697e-03, -2.41024395e-07 ] ================================================ FILE: calibration/ocam5cr-calibration-1280x720.yml ================================================ %YAML:1.0 --- image_width: 1280 image_height: 720 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 1.3440884040820424e+03, 0., 6.9905156745199122e+02, 0., 1.3467815094749353e+03, 3.8248170253646941e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ -4.7871621275114645e-01, 5.4981010471419212e-01, -2.5231381980395746e-03, -7.2442090246576209e-04, -6.5971250176164065e-01 ] ================================================ FILE: calibration/ocam5cr-calibration-640x480.alt.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 6.6121494917337247e+02, 0., 3.2828841718686101e+02, 0., 6.5618744814267620e+02, 1.9107124426366272e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ -4.2521027321415589e-01, 1.6184870648672697e-01, 1.0785595182920660e-02, -4.6897192269970264e-03, 8.5242077077199302e-03 ] ================================================ FILE: calibration/ocam5cr-calibration-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 5.9735378164978681e+02, 0., 3.2679919454715503e+02, 0., 6.0372905645583614e+02, 2.8010613705134386e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ -3.9267258438550706e-01, 2.3586462855322002e-01, -1.0512656347201383e-02, -6.8267662796361807e-04, -1.3795994095762154e-01 ] ================================================ FILE: calibration/r200-calibration-1280x720.yml ================================================ %YAML:1.0 --- image_width: 1280 image_height: 720 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 9.2816139520991885e+02, 0., 6.4301704018620785e+02, 0., 9.2778873253260781e+02, 3.7498666412608128e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 9.5751948597244715e-02, -6.5241365732573608e-01, -2.0828586224311361e-03, -7.0621354398648674e-04, 8.7552357956889237e-01 ] ================================================ FILE: calibration/r200-calibration-1920x1080.yml ================================================ %YAML:1.0 --- image_width: 1920 image_height: 1080 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 1.4302707103631117e+03, 0., 9.8298453177709575e+02, 0., 1.4290231496186070e+03, 5.6279173856551881e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 8.4267570788474924e-02, -6.2358151257688899e-01, 8.3815550773588268e-04, 2.1128443195196503e-03, 9.3539169816479428e-01 ] ================================================ FILE: calibration/r200-calibration-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 6.0783617044102618e+02, 0., 3.1581780741003723e+02, 0., 6.1120408601302597e+02, 2.5008129529549603e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 1.4816645713462362e-01, -1.0182391728955875e+00, -1.8143434742778767e-03, -3.6992078893083903e-03, 1.4676077663793050e+00 ] ================================================ FILE: calibration/raspicamv1-calibration-1280x720.yml ================================================ %YAML:1.0 --- image_width: 1280 image_height: 720 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 1.0870591972997881e+03, 0., 5.1985156867369221e+02, 0., 1.1095304896744867e+03, 6.5370374660295761e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 6.7506039599485021e-02, -5.9048530625047245e-02, 1.7155220868880776e-03, -5.2020426468591507e-02, 2.7634211934173425e-02 ] ================================================ FILE: calibration/raspicamv1-calibration-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 6.5896698580363773e+02, 0., 3.1002321894647190e+02, 0., 6.5682077412787862e+02, 2.3106121559640056e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 1.1852650267166695e-01, -5.1934013894639219e-01, -3.0733227337306872e-03, -5.5608500948949660e-03, 2.6916737484502573e-01 ] ================================================ FILE: calibration/raspicamv2-calibration-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 4.9260281220532505e+02, 0., 3.2983271307718115e+02, 0., 4.9185805133583187e+02, 2.4829905879256435e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ 1.7239420667429373e-01, -5.5553264866253949e-01, 2.4128347703893300e-03, 2.7407429940248681e-03, 4.9313531402738187e-01 ] ================================================ FILE: calibration/sj4000-calibration-1280x720.yml ================================================ %YAML:1.0 --- image_width: 1280 image_height: 720 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 1.8593258445340257e+03, 0., 6.3832828268340643e+02, 0., 1.7109359494675668e+03, 3.4853591106543831e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ -7.3405019069485866e-01, 7.3735108609330446e-01, 2.6216434201067888e-02, 7.1663397680407998e-02, 1.2758125148276322e+00 ] ================================================ FILE: calibration/sj4000-calibration-640x480.yml ================================================ %YAML:1.0 --- image_width: 640 image_height: 480 camera_matrix: !!opencv-matrix rows: 3 cols: 3 dt: d data: [ 3.7037165052172065e+02, 0., 3.1804464317636484e+02, 0., 3.6986507401947409e+02, 2.3433401660781536e+02, 0., 0., 1. ] distortion_coefficients: !!opencv-matrix rows: 1 cols: 5 dt: d data: [ -3.0928475932553318e-01, 1.1286735280595565e-01, 2.7916987103310091e-04, 2.9956904211408351e-04, -1.9893030862940957e-02 ] ================================================ FILE: markers/2x2map.yml ================================================ %YAML:1.0 --- aruco_bc_dict: ARUCO_MIP_36h12 aruco_bc_nmarkers: 4 aruco_bc_mInfoType: 0 aruco_bc_markers: - { id:161, corners:[ [ -550., -50., 0. ], [ -50., -50., 0. ], [ -50., -550., 0. ], [ -550., -550., 0. ] ] } - { id:227, corners:[ [ 50., -50., 0. ], [ 550., -50., 0. ], [ 550., -550., 0. ], [ 50., -550., 0. ] ] } - { id:85, corners:[ [ -550., 550., 0. ], [ -50., 550., 0. ], [ -50., 50., 0. ], [ -550., 50., 0. ] ] } - { id:166, corners:[ [ 50., 550., 0. ], [ 550., 550., 0. ], [ 550., 50., 0. ], [ 50., 50., 0. ] ] } ================================================ FILE: src/CMakeLists.txt ================================================ cmake_minimum_required (VERSION 2.8) project (track_targets) find_package(aruco REQUIRED ) find_package(OpenCV REQUIRED) option(USE_TIMERS "Set to OFF to disable timers" OFF) iF(USE_TIMERS) add_definitions(-DUSE_TIMERS) ENDIF() add_executable(track_targets track_targets.cpp) set(EXTRA_C_FLAGS_RELEASE "${EXTRA_C_FLAGS_RELEASE} -std=c++0x -pthread -march=armv8-a+crc -mfpu=neon-vfpv4 -mtune=cortex-a53 -ftree-vectorize -mfloat-abi=hard -O3 ") set(cpp_compile_flags "-std=gnu++11 -pthread") add_definitions(${cpp_compile_flags}) include_directories(${aruco_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) target_link_libraries(track_targets aruco ${aruco_LIBS} ${OpenCV_LIBS} pthread) link_directories(${aruco_LIB_DIR} ${OpenCV_INSTALL_PATH}/lib}) link_libraries(pthread) install(PROGRAMS track_targets DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/..) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -latomic") ================================================ FILE: src/args.hxx ================================================ /* Copyright (c) 2016 Taylor C. Richberger * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to * deal in the Software without restriction, including without limitation the * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or * sell copies of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * * The above copyright notice and this permission notice shall be included in * all copies or substantial portions of the Software. * * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS * IN THE SOFTWARE. */ // https://github.com/Taywee/args /** \file args.hxx * \brief this single-header lets you use all of the args functionality * * The important stuff is done inside the args namespace */ #ifndef ARGS_HXX #define ARGS_HXX #include #include #include #include #include #include #include #include #include #include #ifdef ARGS_TESTNAMESPACE namespace argstest { #else /** \namespace args * \brief contains all the functionality of the args library */ namespace args { #endif /** Getter to grab the value from the argument type. * * If the Get() function of the type returns a reference, so does this, and * the value will be modifiable. */ template auto get(Option &option_) -> decltype(option_.Get()) { return option_.Get(); } /** (INTERNAL) Count UTF-8 glyphs * * This is not reliable, and will fail for combinatory glyphs, but it's * good enough here for now. * * \param string The string to count glyphs from * \return The UTF-8 glyphs in the string */ std::string::size_type Glyphs(const std::string &string_) { std::string::size_type length = 0; for (const char c: string_) { if ((c & 0xc0) != 0x80) { ++length; } } return length; } /** (INTERNAL) Wrap a string into a vector of lines * * This is quick and hacky, but works well enough. You can specify a * different width for the first line * * \param width The width of the body * \param the widtho f the first line, defaults to the width of the body * \return the vector of lines */ std::vector Wrap(const std::string &in, const std::string::size_type width, std::string::size_type firstlinewidth = 0) { // Preserve existing line breaks const auto newlineloc = in.find('\n'); if (newlineloc != in.npos) { auto first = Wrap(std::string(in, 0, newlineloc), width); auto second = Wrap(std::string(in, newlineloc + 1), width); first.insert( std::end(first), std::make_move_iterator(std::begin(second)), std::make_move_iterator(std::end(second))); return first; } if (firstlinewidth == 0) { firstlinewidth = width; } auto currentwidth = firstlinewidth; std::istringstream stream(in); std::vector output; std::ostringstream line; std::string::size_type linesize = 0; while (stream) { std::string item; stream >> item; auto itemsize = Glyphs(item); if ((linesize + 1 + itemsize) > currentwidth) { if (linesize > 0) { output.push_back(line.str()); line.str(std::string()); linesize = 0; currentwidth = width; } } if (itemsize > 0) { if (linesize) { ++linesize; line << " "; } line << item; linesize += itemsize; } } if (linesize > 0) { output.push_back(line.str()); } return output; } #ifdef ARGS_NOEXCEPT /// Error class, for when ARGS_NOEXCEPT is defined enum class Error { None, Usage, Parse, Validation, Map, Extra, Help }; #else /** Base error class */ class Error : public std::runtime_error { public: Error(const std::string &problem) : std::runtime_error(problem) {} virtual ~Error() {}; }; /** Errors that occur during usage */ class UsageError : public Error { public: UsageError(const std::string &problem) : Error(problem) {} virtual ~UsageError() {}; }; /** Errors that occur during regular parsing */ class ParseError : public Error { public: ParseError(const std::string &problem) : Error(problem) {} virtual ~ParseError() {}; }; /** Errors that are detected from group validation after parsing finishes */ class ValidationError : public Error { public: ValidationError(const std::string &problem) : Error(problem) {} virtual ~ValidationError() {}; }; /** Errors in map lookups */ class MapError : public ParseError { public: MapError(const std::string &problem) : ParseError(problem) {} virtual ~MapError() {}; }; /** Error that occurs when a singular flag is specified multiple times */ class ExtraError : public ParseError { public: ExtraError(const std::string &problem) : ParseError(problem) {} virtual ~ExtraError() {}; }; /** An exception that indicates that the user has requested help */ class Help : public Error { public: Help(const std::string &flag) : Error(flag) {} virtual ~Help() {}; }; #endif /** A simple unified option type for unified initializer lists for the Matcher class. */ struct EitherFlag { const bool isShort; const char shortFlag; const std::string longFlag; EitherFlag(const std::string &flag) : isShort(false), shortFlag(), longFlag(flag) {} EitherFlag(const char *flag) : isShort(false), shortFlag(), longFlag(flag) {} EitherFlag(const char flag) : isShort(true), shortFlag(flag), longFlag() {} /** Get just the long flags from an initializer list of EitherFlags */ static std::unordered_set GetLong(std::initializer_list flags) { std::unordered_set longFlags; for (const EitherFlag &flag: flags) { if (!flag.isShort) { longFlags.insert(flag.longFlag); } } return longFlags; } /** Get just the short flags from an initializer list of EitherFlags */ static std::unordered_set GetShort(std::initializer_list flags) { std::unordered_set shortFlags; for (const EitherFlag &flag: flags) { if (flag.isShort) { shortFlags.insert(flag.shortFlag); } } return shortFlags; } }; /** A class of "matchers", specifying short and flags that can possibly be * matched. * * This is supposed to be constructed and then passed in, not used directly * from user code. */ class Matcher { private: const std::unordered_set shortFlags; const std::unordered_set longFlags; public: /** Specify short and long flags separately as iterators * * ex: `args::Matcher(shortFlags.begin(), shortFlags.end(), longFlags.begin(), longFlags.end())` */ template Matcher(ShortIt shortFlagsStart, ShortIt shortFlagsEnd, LongIt longFlagsStart, LongIt longFlagsEnd) : shortFlags(shortFlagsStart, shortFlagsEnd), longFlags(longFlagsStart, longFlagsEnd) {} /** Specify short and long flags separately as iterables * * ex: `args::Matcher(shortFlags, longFlags)` */ template Matcher(Short &&shortIn, Long &&longIn) : shortFlags(std::begin(shortIn), std::end(shortIn)), longFlags(std::begin(longIn), std::end(longIn)) {} /** Specify a mixed single initializer-list of both short and long flags * * This is the fancy one. It takes a single initializer list of * any number of any mixed kinds of flags. Chars are * automatically interpreted as short flags, and strings are * automatically interpreted as long flags: * * args::Matcher{'a'} * args::Matcher{"foo"} * args::Matcher{'h', "help"} * args::Matcher{"foo", 'f', 'F', "FoO"} */ Matcher(std::initializer_list in) : shortFlags(EitherFlag::GetShort(in)), longFlags(EitherFlag::GetLong(in)) {} Matcher(Matcher &&other) : shortFlags(std::move(other.shortFlags)), longFlags(std::move(other.longFlags)) {} ~Matcher() {} /** (INTERNAL) Check if there is a match of a short flag */ bool Match(const char flag) const { return shortFlags.find(flag) != shortFlags.end(); } /** (INTERNAL) Check if there is a match of a long flag */ bool Match(const std::string &flag) const { return longFlags.find(flag) != longFlags.end(); } /** (INTERNAL) Get all flag strings as a vector, with the prefixes embedded */ std::vector GetFlagStrings(const std::string &shortPrefix, const std::string &longPrefix) const { std::vector flagStrings; flagStrings.reserve(shortFlags.size() + longFlags.size()); for (const char flag: shortFlags) { flagStrings.emplace_back(shortPrefix + std::string(1, flag)); } for (const std::string &flag: longFlags) { flagStrings.emplace_back(longPrefix + flag); } return flagStrings; } /** (INTERNAL) Get all flag strings as a vector, with the prefixes and names embedded */ std::vector GetFlagStrings(const std::string &shortPrefix, const std::string &longPrefix, const std::string &name, const std::string &shortSeparator, const std::string longSeparator) const { const std::string bracedname(std::string("[") + name + "]"); std::vector flagStrings; flagStrings.reserve(shortFlags.size() + longFlags.size()); for (const char flag: shortFlags) { flagStrings.emplace_back(shortPrefix + std::string(1, flag) + shortSeparator + bracedname); } for (const std::string &flag: longFlags) { flagStrings.emplace_back(longPrefix + flag + longSeparator + bracedname); } return flagStrings; } }; /** Base class for all match types */ class Base { protected: bool matched; const std::string help; #ifdef ARGS_NOEXCEPT /// Only for ARGS_NOEXCEPT Error error; #endif public: Base(const std::string &help_) : matched(false), help(help_) {} virtual ~Base() {} virtual bool Matched() const noexcept { return matched; } operator bool() const noexcept { return Matched(); } virtual std::tuple GetDescription(const std::string &shortPrefix, const std::string &longPrefix, const std::string &shortSeparator, const std::string &longSeparator) const { std::tuple description; std::get<1>(description) = help; return description; } virtual void Reset() noexcept { matched = false; #ifdef ARGS_NOEXCEPT error = Error::None; #endif } #ifdef ARGS_NOEXCEPT /// Only for ARGS_NOEXCEPT virtual Error GetError() const { return error; } #endif }; /** Base class for all match types that have a name */ class NamedBase : public Base { protected: const std::string name; bool kickout; public: NamedBase(const std::string &name_, const std::string &help_) : Base(help_), name(name_), kickout(false) {} virtual ~NamedBase() {} virtual std::tuple GetDescription(const std::string &shortPrefix, const std::string &longPrefi, const std::string &shortSeparator, const std::string &longSeparator) const override { std::tuple description; std::get<0>(description) = Name(); std::get<1>(description) = help; return description; } virtual std::string Name() const { return name; } /// Sets a kick-out value for building subparsers void KickOut(bool kickout_) noexcept { this->kickout = kickout_; } /// Gets the kick-out value for building subparsers bool KickOut() const noexcept { return kickout; } }; /** Base class for all flag options */ class FlagBase : public NamedBase { private: const bool extraError; protected: const Matcher matcher; public: FlagBase(const std::string &name_, const std::string &help_, Matcher &&matcher_, const bool extraError_ = false) : NamedBase(name_, help_), extraError(extraError_), matcher(std::move(matcher_)) {} virtual ~FlagBase() {} virtual FlagBase *Match(const std::string &flag) { if (matcher.Match(flag)) { if (extraError && matched) { #ifdef ARGS_NOEXCEPT error = Error::Extra; #else std::ostringstream problem; problem << "Flag '" << flag << "' was passed multiple times, but is only allowed to be passed once"; throw ExtraError(problem.str()); #endif } matched = true; return this; } return nullptr; } virtual FlagBase *Match(const char flag) { if (matcher.Match(flag)) { if (extraError && matched) { #ifdef ARGS_NOEXCEPT error = Error::Extra; #else std::ostringstream problem; problem << "Flag '" << flag << "' was passed multiple times, but is only allowed to be passed once"; throw ExtraError(problem.str()); #endif } matched = true; return this; } return nullptr; } virtual std::tuple GetDescription(const std::string &shortPrefix, const std::string &longPrefix, const std::string &shortSeparator, const std::string &longSeparator) const override { std::tuple description; const auto flagStrings = matcher.GetFlagStrings(shortPrefix, longPrefix); std::ostringstream flagstream; for (auto it = std::begin(flagStrings); it != std::end(flagStrings); ++it) { if (it != std::begin(flagStrings)) { flagstream << ", "; } flagstream << *it; } std::get<0>(description) = flagstream.str(); std::get<1>(description) = help; return description; } }; /** Base class for value-accepting flag options */ class ValueFlagBase : public FlagBase { public: ValueFlagBase(const std::string &name_, const std::string &help_, Matcher &&matcher_, const bool extraError_ = false) : FlagBase(name_, help_, std::move(matcher_), extraError_) {} virtual ~ValueFlagBase() {} virtual void ParseValue(const std::string &value) = 0; virtual std::tuple GetDescription(const std::string &shortPrefix, const std::string &longPrefix, const std::string &shortSeparator, const std::string &longSeparator) const override { std::tuple description; const auto flagStrings = matcher.GetFlagStrings(shortPrefix, longPrefix, Name(), shortSeparator, longSeparator); std::ostringstream flagstream; for (auto it = std::begin(flagStrings); it != std::end(flagStrings); ++it) { if (it != std::begin(flagStrings)) { flagstream << ", "; } flagstream << *it; } std::get<0>(description) = flagstream.str(); std::get<1>(description) = help; return description; } }; /** Base class for positional options */ class PositionalBase : public NamedBase { protected: bool ready; public: PositionalBase(const std::string &name_, const std::string &help_) : NamedBase(name_, help_), ready(true) {} virtual ~PositionalBase() {} bool Ready() { return ready; } virtual void ParseValue(const std::string &value_) = 0; virtual void Reset() noexcept override { matched = false; ready = true; #ifdef ARGS_NOEXCEPT error = Error::None; #endif } }; /** Class for all kinds of validating groups, including ArgumentParser */ class Group : public Base { private: std::vector children; std::function validator; public: /** Default validators */ struct Validators { static bool Xor(const Group &group) { return group.MatchedChildren() == 1; } static bool AtLeastOne(const Group &group) { return group.MatchedChildren() >= 1; } static bool AtMostOne(const Group &group) { return group.MatchedChildren() <= 1; } static bool All(const Group &group) { return group.Children().size() == group.MatchedChildren(); } static bool AllOrNone(const Group &group) { return (All(group) || None(group)); } static bool AllChildGroups(const Group &group) { return std::find_if(std::begin(group.Children()), std::end(group.Children()), [](const Base* child) -> bool { return dynamic_cast(child) && !child->Matched(); }) == std::end(group.Children()); } static bool DontCare(const Group &group) { return true; } static bool CareTooMuch(const Group &group) { return false; } static bool None(const Group &group) { return group.MatchedChildren() == 0; } }; /// If help is empty, this group will not be printed in help output Group(const std::string &help_ = std::string(), const std::function &validator_ = Validators::DontCare) : Base(help_), validator(validator_) {} /// If help is empty, this group will not be printed in help output Group(Group &group_, const std::string &help_ = std::string(), const std::function &validator_ = Validators::DontCare) : Base(help_), validator(validator_) { group_.Add(*this); } virtual ~Group() {} /** Return the first FlagBase that matches flag, or nullptr * * \param flag The flag with prefixes stripped * \return the first matching FlagBase pointer, or nullptr if there is no match */ template FlagBase *Match(const T &flag) { for (Base *child: children) { if (FlagBase *flagBase = dynamic_cast(child)) { if (FlagBase *match = flagBase->Match(flag)) { return match; } } else if (Group *group = dynamic_cast(child)) { if (FlagBase *match = group->Match(flag)) { return match; } } } return nullptr; } /** Get the next ready positional, or nullptr if there is none * * \return the first ready PositionalBase pointer, or nullptr if there is no match */ PositionalBase *GetNextPositional() { for (Base *child: children) { auto next = dynamic_cast(child); auto group = dynamic_cast(child); if (group) { next = group->GetNextPositional(); } if (next && next->Ready()) { return next; } } return nullptr; } /** Get whether this has any FlagBase children * * \return Whether or not there are any FlagBase children */ bool HasFlag() const { for (Base *child: children) { if (dynamic_cast(child)) { return true; } if (auto group = dynamic_cast(child)) { if (group->HasFlag()) { return true; } } } return false; } /** Append a child to this Group. */ void Add(Base &child) { children.emplace_back(&child); } /** Get all this group's children */ const std::vector &Children() const { return children; } /** Count the number of matched children this group has */ std::vector::size_type MatchedChildren() const { return std::count_if(std::begin(children), std::end(children), [](const Base *child){return child->Matched();}); } /** Whether or not this group matches validation */ virtual bool Matched() const noexcept override { return validator(*this); } /** Get validation */ bool Get() const { return Matched(); } /** Get all the child descriptions for help generation */ std::vector> GetChildDescriptions(const std::string &shortPrefix, const std::string &longPrefix, const std::string &shortSeparator, const std::string &longSeparator, const unsigned int indent = 0) const { std::vector> descriptions; for (const auto &child: children) { if (const auto group = dynamic_cast(child)) { // Push that group description on the back if not empty unsigned char addindent = 0; if (!group->help.empty()) { descriptions.emplace_back(group->help, "", indent); addindent = 1; } auto groupDescriptions = group->GetChildDescriptions(shortPrefix, longPrefix, shortSeparator, longSeparator, indent + addindent); descriptions.insert( std::end(descriptions), std::make_move_iterator(std::begin(groupDescriptions)), std::make_move_iterator(std::end(groupDescriptions))); } else if (const auto named = dynamic_cast(child)) { const auto description = named->GetDescription(shortPrefix, longPrefix, shortSeparator, longSeparator); descriptions.emplace_back(std::get<0>(description), std::get<1>(description), indent); } } return descriptions; } /** Get the names of positional parameters */ std::vector GetPosNames() const { std::vector names; for (const auto &child: children) { if (const Group *group = dynamic_cast(child)) { auto groupNames = group->GetPosNames(); names.insert( std::end(names), std::make_move_iterator(std::begin(groupNames)), std::make_move_iterator(std::end(groupNames))); } else if (const PositionalBase *pos = dynamic_cast(child)) { names.emplace_back(pos->Name()); } } return names; } virtual void Reset() noexcept override { for (auto &child: children) { child->Reset(); } #ifdef ARGS_NOEXCEPT error = Error::None; #endif } #ifdef ARGS_NOEXCEPT /// Only for ARGS_NOEXCEPT virtual Error GetError() const override { if (error != Error::None) { return error; } auto it = std::find_if(std::begin(children), std::end(children), [](const Base *child){return child->GetError() != Error::None;}); if (it == std::end(children)) { return Error::None; } else { return (*it)->GetError(); } } #endif }; /** The main user facing command line argument parser class */ class ArgumentParser : public Group { private: std::string prog; std::string proglinePostfix; std::string description; std::string epilog; std::string longprefix; std::string shortprefix; std::string longseparator; std::string terminator; bool allowJoinedShortValue; bool allowJoinedLongValue; bool allowSeparateShortValue; bool allowSeparateLongValue; public: /** A simple structure of parameters for easy user-modifyable help menus */ struct HelpParams { /** The width of the help menu */ unsigned int width = 80; /** The indent of the program line */ unsigned int progindent = 2; /** The indent of the program trailing lines for long parameters */ unsigned int progtailindent = 4; /** The indent of the description and epilogs */ unsigned int descriptionindent = 4; /** The indent of the flags */ unsigned int flagindent = 6; /** The indent of the flag descriptions */ unsigned int helpindent = 40; /** The additional indent each group adds */ unsigned int eachgroupindent = 2; /** The minimum gutter between each flag and its help */ unsigned int gutter = 1; /** Show the terminator when both options and positional parameters are present */ bool showTerminator = true; /** Show the {OPTIONS} on the prog line when this is true */ bool showProglineOptions = true; /** Show the positionals on the prog line when this is true */ bool showProglinePositionals = true; } helpParams; ArgumentParser(const std::string &description_, const std::string &epilog_ = std::string()) : Group("", Group::Validators::AllChildGroups), description(description_), epilog(epilog_), longprefix("--"), shortprefix("-"), longseparator("="), terminator("--"), allowJoinedShortValue(true), allowJoinedLongValue(true), allowSeparateShortValue(true), allowSeparateLongValue(true) {} /** The program name for help generation */ const std::string &Prog() const { return prog; } /** The program name for help generation */ void Prog(const std::string &prog_) { this->prog = prog_; } /** The description that appears on the prog line after options */ const std::string &ProglinePostfix() const { return proglinePostfix; } /** The description that appears on the prog line after options */ void ProglinePostfix(const std::string &proglinePostfix_) { this->proglinePostfix = proglinePostfix_; } /** The description that appears above options */ const std::string &Description() const { return description; } /** The description that appears above options */ void Description(const std::string &description_) { this->description = description_; } /** The description that appears below options */ const std::string &Epilog() const { return epilog; } /** The description that appears below options */ void Epilog(const std::string &epilog_) { this->epilog = epilog_; } /** The prefix for long flags */ const std::string &LongPrefix() const { return longprefix; } /** The prefix for long flags */ void LongPrefix(const std::string &longprefix_) { this->longprefix = longprefix_; } /** The prefix for short flags */ const std::string &ShortPrefix() const { return shortprefix; } /** The prefix for short flags */ void ShortPrefix(const std::string &shortprefix_) { this->shortprefix = shortprefix_; } /** The separator for long flags */ const std::string &LongSeparator() const { return longseparator; } /** The separator for long flags */ void LongSeparator(const std::string &longseparator_) { if (longseparator_.empty()) { #ifdef ARGS_NOEXCEPT error = Error::Usage; #else throw UsageError("longseparator can not be set to empty"); #endif } else { this->longseparator = longseparator_; } } /** The terminator that forcibly separates flags from positionals */ const std::string &Terminator() const { return terminator; } /** The terminator that forcibly separates flags from positionals */ void Terminator(const std::string &terminator_) { this->terminator = terminator_; } /** Get the current argument separation parameters. * * See SetArgumentSeparations for details on what each one means. */ void GetArgumentSeparations( bool &allowJoinedShortValue_, bool &allowJoinedLongValue_, bool &allowSeparateShortValue_, bool &allowSeparateLongValue_) const { allowJoinedShortValue_ = this->allowJoinedShortValue; allowJoinedLongValue_ = this->allowJoinedLongValue; allowSeparateShortValue_ = this->allowSeparateShortValue; allowSeparateLongValue_ = this->allowSeparateLongValue; } /** Change allowed option separation. * * \param allowJoinedShortValue Allow a short flag that accepts an argument to be passed its argument immediately next to it (ie. in the same argv field) * \param allowJoinedLongValue Allow a long flag that accepts an argument to be passed its argument separated by the longseparator (ie. in the same argv field) * \param allowSeparateShortValue Allow a short flag that accepts an argument to be passed its argument separated by whitespace (ie. in the next argv field) * \param allowSeparateLongValue Allow a long flag that accepts an argument to be passed its argument separated by whitespace (ie. in the next argv field) */ void SetArgumentSeparations( const bool allowJoinedShortValue_, const bool allowJoinedLongValue_, const bool allowSeparateShortValue_, const bool allowSeparateLongValue_) { this->allowJoinedShortValue = allowJoinedShortValue_; this->allowJoinedLongValue = allowJoinedLongValue_; this->allowSeparateShortValue = allowSeparateShortValue_; this->allowSeparateLongValue = allowSeparateLongValue_; } /** Pass the help menu into an ostream */ void Help(std::ostream &help) const { bool hasoptions = false; bool hasarguments = false; const auto description_text = Wrap(this->description, helpParams.width - helpParams.descriptionindent); const auto epilog_text = Wrap(this->epilog, helpParams.width - helpParams.descriptionindent); std::ostringstream prognameline; prognameline << prog; if (HasFlag()) { hasoptions = true; if (helpParams.showProglineOptions) { prognameline << " {OPTIONS}"; } } for (const std::string &posname: GetPosNames()) { hasarguments = true; if (helpParams.showProglinePositionals) { prognameline << " [" << posname << ']'; } } if (!proglinePostfix.empty()) { prognameline << ' ' << proglinePostfix; } const auto proglines = Wrap(prognameline.str(), helpParams.width - (helpParams.progindent + 4), helpParams.width - helpParams.progindent); auto progit = std::begin(proglines); if (progit != std::end(proglines)) { help << std::string(helpParams.progindent, ' ') << *progit << '\n'; ++progit; } for (; progit != std::end(proglines); ++progit) { help << std::string(helpParams.progtailindent, ' ') << *progit << '\n'; } help << '\n'; for (const auto &line: description_text) { help << std::string(helpParams.descriptionindent, ' ') << line << "\n"; } help << "\n"; help << std::string(helpParams.progindent, ' ') << "OPTIONS:\n\n"; for (const auto &desc: GetChildDescriptions(shortprefix, longprefix, allowJoinedShortValue ? "" : " ", allowJoinedLongValue ? longseparator : " ")) { const auto groupindent = std::get<2>(desc) * helpParams.eachgroupindent; const auto flags = Wrap(std::get<0>(desc), helpParams.width - (helpParams.flagindent + helpParams.helpindent + helpParams.gutter)); const auto info = Wrap(std::get<1>(desc), helpParams.width - (helpParams.helpindent + groupindent)); std::string::size_type flagssize = 0; for (auto flagsit = std::begin(flags); flagsit != std::end(flags); ++flagsit) { if (flagsit != std::begin(flags)) { help << '\n'; } help << std::string(groupindent + helpParams.flagindent, ' ') << *flagsit; flagssize = Glyphs(*flagsit); } auto infoit = std::begin(info); // groupindent is on both sides of this inequality, and therefore can be removed if ((helpParams.flagindent + flagssize + helpParams.gutter) > helpParams.helpindent || infoit == std::end(info)) { help << '\n'; } else { // groupindent is on both sides of the minus sign, and therefore doesn't actually need to be in here help << std::string(helpParams.helpindent - (helpParams.flagindent + flagssize), ' ') << *infoit << '\n'; ++infoit; } for (; infoit != std::end(info); ++infoit) { help << std::string(groupindent + helpParams.helpindent, ' ') << *infoit << '\n'; } } if (hasoptions && hasarguments && helpParams.showTerminator) { for (const auto &item: Wrap(std::string("\"") + terminator + "\" can be used to terminate flag options and force all following arguments to be treated as positional options", helpParams.width - helpParams.flagindent)) { help << std::string(helpParams.flagindent, ' ') << item << '\n'; } } help << "\n"; for (const auto &line: epilog_text) { help << std::string(helpParams.descriptionindent, ' ') << line << "\n"; } } /** Generate a help menu as a string. * * \return the help text as a single string */ std::string Help() const { std::ostringstream help; Help(help); return help.str(); } /** Parse all arguments. * * \param begin an iterator to the beginning of the argument list * \param end an iterator to the past-the-end element of the argument list * \return the iterator after the last parsed value. Only useful for kick-out */ template It ParseArgs(It begin, It end) { // Reset all Matched statuses and errors Reset(); bool terminated = false; // Check all arg chunks for (auto it = begin; it != end; ++it) { const auto &chunk = *it; if (!terminated && chunk == terminator) { terminated = true; // If a long arg was found } else if (!terminated && chunk.find(longprefix) == 0 && chunk.size() > longprefix.size()) { const auto argchunk = chunk.substr(longprefix.size()); // Try to separate it, in case of a separator: const auto separator = longseparator.empty() ? argchunk.npos : argchunk.find(longseparator); // If the separator is in the argument, separate it. const auto arg = (separator != argchunk.npos ? std::string(argchunk, 0, separator) : argchunk); if (auto base = Match(arg)) { if (auto argbase = dynamic_cast(base)) { if (separator != argchunk.npos) { if (allowJoinedLongValue) { argbase->ParseValue(argchunk.substr(separator + longseparator.size())); } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' was passed a joined argument, but these are disallowed"; throw ParseError(problem.str()); #endif } } else { ++it; if (it == end) { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' requires an argument but received none"; throw ParseError(problem.str()); #endif } if (allowSeparateLongValue) { argbase->ParseValue(*it); } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' was passed a separate argument, but these are disallowed"; throw ParseError(problem.str()); #endif } } } else if (separator != argchunk.npos) { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Passed an argument into a non-argument flag: " << chunk; throw ParseError(problem.str()); #endif } if (base->KickOut()) { return ++it; } } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag could not be matched: " << arg; throw ParseError(problem.str()); #endif } // Check short args } else if (!terminated && chunk.find(shortprefix) == 0 && chunk.size() > shortprefix.size()) { const auto argchunk = chunk.substr(shortprefix.size()); for (auto argit = std::begin(argchunk); argit != std::end(argchunk); ++argit) { const auto arg = *argit; if (auto base = Match(arg)) { if (auto argbase = dynamic_cast(base)) { const std::string value(++argit, std::end(argchunk)); if (!value.empty()) { if (allowJoinedShortValue) { argbase->ParseValue(value); } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' was passed a joined argument, but these are disallowed"; throw ParseError(problem.str()); #endif } } else { ++it; if (it == end) { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' requires an argument but received none"; throw ParseError(problem.str()); #endif } if (allowSeparateShortValue) { argbase->ParseValue(*it); } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag '" << arg << "' was passed a separate argument, but these are disallowed"; throw ParseError(problem.str()); #endif } } // Because this argchunk is done regardless break; } if (base->KickOut()) { return ++it; } } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Flag could not be matched: '" << arg << "'"; throw ParseError(problem.str()); #endif } } } else { auto pos = GetNextPositional(); if (pos) { pos->ParseValue(chunk); if (pos->KickOut()) { return ++it; } } else { #ifdef ARGS_NOEXCEPT error = Error::Parse; return it; #else std::ostringstream problem; problem << "Passed in argument, but no positional arguments were ready to receive it: " << chunk; throw ParseError(problem.str()); #endif } } } if (!Matched()) { #ifdef ARGS_NOEXCEPT error = Error::Validation; #else std::ostringstream problem; problem << "Group validation failed somewhere!"; throw ValidationError(problem.str()); #endif } return end; } /** Parse all arguments. * * \param args an iterable of the arguments * \return the iterator after the last parsed value. Only useful for kick-out */ template auto ParseArgs(const T &args) -> decltype(std::begin(args)) { return ParseArgs(std::begin(args), std::end(args)); } /** Convenience function to parse the CLI from argc and argv * * Just assigns the program name and vectorizes arguments for passing into ParseArgs() * * \return whether or not all arguments were parsed. This works for detecting kick-out, but is generally useless as it can't do anything with it. */ bool ParseCLI(const int argc, const char * const * argv) { if (prog.empty()) { prog.assign(argv[0]); } const std::vector args(argv + 1, argv + argc); return ParseArgs(args) == std::end(args); } }; std::ostream &operator<<(std::ostream &os, const ArgumentParser &parser) { parser.Help(os); return os; } /** Boolean argument matcher */ class Flag : public FlagBase { public: Flag(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const bool extraError_ = false): FlagBase(name_, help_, std::move(matcher_), extraError_) { group_.Add(*this); } virtual ~Flag() {} /** Get whether this was matched */ bool Get() const { return Matched(); } }; /** Help flag class * * Works like a regular flag, but throws an instance of Help when it is matched */ class HelpFlag : public Flag { public: HelpFlag(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_): Flag(group_, name_, help_, std::move(matcher_)) {} virtual ~HelpFlag() {} virtual FlagBase *Match(const std::string &arg) override { if (FlagBase::Match(arg)) { #ifdef ARGS_NOEXCEPT error = Error::Help; #else throw Help(arg); #endif return this; } return nullptr; } virtual FlagBase *Match(const char arg) override { if (FlagBase::Match(arg)) { #ifdef ARGS_NOEXCEPT error = Error::Help; #else throw Help(std::string(1, arg)); #endif return this; } return nullptr; } /** Get whether this was matched */ bool Get() const noexcept { return Matched(); } }; /** A flag class that simply counts the number of times it's matched */ class CounterFlag : public Flag { private: const int startcount; int count; public: CounterFlag(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const int startcount_ = 0): Flag(group_, name_, help_, std::move(matcher_)), startcount(startcount_), count(startcount_) {} virtual ~CounterFlag() {} virtual FlagBase *Match(const std::string &arg) override { auto me = FlagBase::Match(arg); if (me) { ++count; } return me; } virtual FlagBase *Match(const char arg) override { auto me = FlagBase::Match(arg); if (me) { ++count; } return me; } /** Get the count */ int &Get() noexcept { return count; } virtual void Reset() noexcept override { FlagBase::Reset(); count = startcount; } }; /** A default Reader class for argument classes * * Simply uses a std::istringstream to read into the destination type, and * raises a ParseError if there are any characters left. */ template struct ValueReader { bool operator ()(const std::string &name, const std::string &value, T &destination) { std::istringstream ss(value); ss >> destination; if (ss.rdbuf()->in_avail() > 0) { #ifdef ARGS_NOEXCEPT return false; #else std::ostringstream problem; problem << "Argument '" << name << "' received invalid value type '" << value << "'"; throw ParseError(problem.str()); #endif } return true; } }; /** std::string specialization for ValueReader * * By default, stream extraction into a string splits on white spaces, and * it is more efficient to ust copy a string into the destination. */ template <> struct ValueReader { bool operator()(const std::string &name, const std::string &value, std::string &destination) { destination.assign(value); return true; } }; /** An argument-accepting flag class * * \tparam T the type to extract the argument as * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) */ template < typename T, typename Reader = ValueReader> class ValueFlag : public ValueFlagBase { private: T value; Reader reader; public: ValueFlag(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const T &defaultValue_ = T(), const bool extraError_ = false): ValueFlagBase(name_, help_, std::move(matcher_), extraError_), value(defaultValue_) { group_.Add(*this); } virtual ~ValueFlag() {} virtual void ParseValue(const std::string &value_) override { #ifdef ARGS_NOEXCEPT if (!reader(name, value_, this->value)) { error = Error::Parse; } #else reader(name, value_, this->value); #endif } /** Get the value */ T &Get() noexcept { return value; } }; /** An argument-accepting flag class that pushes the found values into a list * * \tparam T the type to extract the argument as * \tparam List the list type that houses the values * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) */ template < typename T, template class List = std::vector, typename Reader = ValueReader> class ValueFlagList : public ValueFlagBase { private: List values; Reader reader; public: ValueFlagList(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const List &defaultValues_ = List()): ValueFlagBase(name_, help_, std::move(matcher_)), values(defaultValues_) { group_.Add(*this); } virtual ~ValueFlagList() {} virtual void ParseValue(const std::string &value_) override { T v; #ifdef ARGS_NOEXCEPT if (!reader(name, value_, v)) { error = Error::Parse; } #else reader(name, value_, v); #endif values.insert(std::end(values), v); } /** Get the values */ List &Get() noexcept { return values; } virtual std::string Name() const override { return name + std::string("..."); } virtual void Reset() noexcept override { ValueFlagBase::Reset(); values.clear(); } }; /** A mapping value flag class * * \tparam K the type to extract the argument as * \tparam T the type to store the result as * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) * \tparam Map The Map type. Should operate like std::map or std::unordered_map */ template < typename K, typename T, typename Reader = ValueReader, template class Map = std::unordered_map> class MapFlag : public ValueFlagBase { private: const Map map; T value; Reader reader; public: MapFlag(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const Map &map_, const T &defaultValue_ = T(), const bool extraError_ = false): ValueFlagBase(name_, help_, std::move(matcher_), extraError_), map(map_), value(defaultValue_) { group_.Add(*this); } virtual ~MapFlag() {} virtual void ParseValue(const std::string &value_) override { K key; #ifdef ARGS_NOEXCEPT if (!reader(name, value_, key)) { error = Error::Parse; } #else reader(name, value_, key); #endif auto it = map.find(key); if (it == std::end(map)) { #ifdef ARGS_NOEXCEPT error = Error::Map; #else std::ostringstream problem; problem << "Could not find key '" << key << "' in map for arg '" << name << "'"; throw MapError(problem.str()); #endif } else { this->value = it->second; } } /** Get the value */ T &Get() noexcept { return value; } }; /** A mapping value flag list class * * \tparam K the type to extract the argument as * \tparam T the type to store the result as * \tparam List the list type that houses the values * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) * \tparam Map The Map type. Should operate like std::map or std::unordered_map */ template < typename K, typename T, template class List = std::vector, typename Reader = ValueReader, template class Map = std::unordered_map> class MapFlagList : public ValueFlagBase { private: const Map map; List values; Reader reader; public: MapFlagList(Group &group_, const std::string &name_, const std::string &help_, Matcher &&matcher_, const Map &map_, const List &defaultValues_ = List()): ValueFlagBase(name_, help_, std::move(matcher_)), map(map_), values(defaultValues_) { group_.Add(*this); } virtual ~MapFlagList() {} virtual void ParseValue(const std::string &value) override { K key; #ifdef ARGS_NOEXCEPT if (!reader(name, value, key)) { error = Error::Parse; } #else reader(name, value, key); #endif auto it = map.find(key); if (it == std::end(map)) { #ifdef ARGS_NOEXCEPT error = Error::Map; #else std::ostringstream problem; problem << "Could not find key '" << key << "' in map for arg '" << name << "'"; throw MapError(problem.str()); #endif } else { this->values.emplace_back(it->second); } } /** Get the value */ List &Get() noexcept { return values; } virtual std::string Name() const override { return name + std::string("..."); } virtual void Reset() noexcept override { ValueFlagBase::Reset(); values.clear(); } }; /** A positional argument class * * \tparam T the type to extract the argument as * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) */ template < typename T, typename Reader = ValueReader> class Positional : public PositionalBase { private: T value; Reader reader; public: Positional(Group &group_, const std::string &name_, const std::string &help_, const T &defaultValue_ = T()): PositionalBase(name_, help_), value(defaultValue_) { group_.Add(*this); } virtual ~Positional() {} virtual void ParseValue(const std::string &value_) override { #ifdef ARGS_NOEXCEPT if (!reader(name, value_, this->value)) { error = Error::Parse; } #else reader(name, value_, this->value); #endif ready = false; matched = true; } /** Get the value */ T &Get() noexcept { return value; } }; /** A positional argument class that pushes the found values into a list * * \tparam T the type to extract the argument as * \tparam List the list type that houses the values * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) */ template < typename T, template class List = std::vector, typename Reader = ValueReader> class PositionalList : public PositionalBase { private: List values; Reader reader; public: PositionalList(Group &group_, const std::string &name_, const std::string &help_, const List &defaultValues_ = List()): PositionalBase(name_, help_), values(defaultValues_) { group_.Add(*this); } virtual ~PositionalList() {} virtual void ParseValue(const std::string &value_) override { T v; #ifdef ARGS_NOEXCEPT if (!reader(name, value_, v)) { error = Error::Parse; } #else reader(name, value_, v); #endif values.insert(std::end(values), v); matched = true; } virtual std::string Name() const override { return name + std::string("..."); } /** Get the values */ List &Get() noexcept { return values; } virtual void Reset() noexcept override { PositionalBase::Reset(); values.clear(); } }; /** A positional argument mapping class * * \tparam K the type to extract the argument as * \tparam T the type to store the result as * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) * \tparam Map The Map type. Should operate like std::map or std::unordered_map */ template < typename K, typename T, typename Reader = ValueReader, template class Map = std::unordered_map> class MapPositional : public PositionalBase { private: const Map map; T value; Reader reader; public: MapPositional(Group &group_, const std::string &name_, const std::string &help_, const Map &map_, const T &defaultValue_ = T()): PositionalBase(name_, help_), map(map_), value(defaultValue_) { group_.Add(*this); } virtual ~MapPositional() {} virtual void ParseValue(const std::string &value_) override { K key; #ifdef ARGS_NOEXCEPT if (!reader(name, value_, key)) { error = Error::Parse; } #else reader(name, value_, key); #endif auto it = map.find(key); if (it == std::end(map)) { #ifdef ARGS_NOEXCEPT error = Error::Map; #else std::ostringstream problem; problem << "Could not find key '" << key << "' in map for arg '" << name << "'"; throw MapError(problem.str()); #endif } else { this->value = it->second; ready = false; matched = true; } } /** Get the value */ T &Get() noexcept { return value; } }; /** A positional argument mapping list class * * \tparam K the type to extract the argument as * \tparam T the type to store the result as * \tparam List the list type that houses the values * \tparam Reader The functor type used to read the argument, taking the name, value, and destination reference with operator(), and returning a bool (if ARGS_NOEXCEPT is defined) * \tparam Map The Map type. Should operate like std::map or std::unordered_map */ template < typename K, typename T, template class List = std::vector, typename Reader = ValueReader, template class Map = std::unordered_map> class MapPositionalList : public PositionalBase { private: const Map map; List values; Reader reader; public: MapPositionalList(Group &group_, const std::string &name_, const std::string &help_, const Map &map_, const List &defaultValues_ = List()): PositionalBase(name_, help_), map(map_), values(defaultValues_) { group_.Add(*this); } virtual ~MapPositionalList() {} virtual void ParseValue(const std::string &value_) override { K key; #ifdef ARGS_NOEXCEPT if (!reader(name, value_, key)) { error = Error::Parse; } #else reader(name, value_, key); #endif auto it = map.find(key); if (it == std::end(map)) { #ifdef ARGS_NOEXCEPT error = Error::Map; #else std::ostringstream problem; problem << "Could not find key '" << key << "' in map for arg '" << name << "'"; throw MapError(problem.str()); #endif } else { this->values.emplace_back(it->second); matched = true; } } /** Get the value */ List &Get() noexcept { return values; } virtual std::string Name() const override { return name + std::string("..."); } virtual void Reset() noexcept override { PositionalBase::Reset(); values.clear(); } }; } #endif ================================================ FILE: src/pkQueueTS.hpp ================================================ /************************************************************************************** * * IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. * * By downloading, copying, installing or using the software you agree to this license. * If you do not agree to this license, do not download, install, * copy or use the software. * * License Agreement * For pkQueueTS * * pkQueueTS - http://pklab.net/index.php?id=395 * Copyright (C) 2016 PkLab.net all rights reserved. * * Third party copyrights are property of their respective owners. * * Redistribution and use in source and binary forms, with or without modification, * are permitted provided that the following conditions are met: * * 1. Redistributions of source code must retain the above copyright notice, * this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright notice, * this list of conditions and the following disclaimer in the documentation * and/or other materials provided with the distribution. * 3. The name of the author may not be used to endorse or promote products * derived from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO * EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *****************************************************************************************/ #ifndef PKQUEUETS_H #define PKQUEUETS_H #if __cplusplus < 199711L #error "This file requires C++ 11 !" #endif #include #include #include #include #include #include #include using namespace std; using namespace cv; //! \defgroup pkQueueTS A Thread safe queue by PkLab //! @{ /** \brief Thread Safe Queue result codes */ enum pkQueueResults { PK_QTS_OK, //!< The result is correct PK_QTS_TIMEOUT, //!< A time-out has reached while push or pop PK_QTS_EMPTY, //!< The queue is empty and we wont wait }; /** \brief Simple structure for an OpenCV Mat with deep copy constructor and assignment operator. * * This class encapsulates a `cv::Mat` and provides custom assignment operator and * copy constructor to perform deep copy of matrix data too. * * This is because the `cv::Mat` assignment operator and the copy constructor * just copy the Mat header but not the matrix data. * * This class is useful for Mats buffering. For example: * - `std::queue::push(cv::Mat)` just creates a copy of `cv::Mat` header in the queue. * - `std::queue::push(MatCapsule)` creates a deep copy of `cv::Mat` in the queue. * * \tparam TAdditionalStorage Here you can attach your own data type to hold any kind of information. * In case your data type contains simple types, like a structure, you can forget about copying. * If your data type holds any pointers or complex data type, you have to take care * its copy constructor and assignment operator. * * \see * - Assignment operator [cv::Mat::operator=](http://docs.opencv.org/master/d3/d63/classcv_1_1Mat.html#aed1f81fe7efaacc2bd95149cdfa34302) * - Copy constructor [cv::Mat::Mat(const Mat &m)](http://docs.opencv.org/master/d3/d63/classcv_1_1Mat.html#a294eaf8a95d2f9c7be19ff594d06278e) * */ template class MatCapsule_ { public: //! The OpenCV Mat Mat mat; /** \brief Storage for additional information (Template) * * You can define you own data type to hold any kind of information. * - In case your `TAdditionalStorage` holds just simple types you can forget about copying. * - In case `TAdditionalStorage` holds any pointers or complex data type, you have to take care * of copy constructor and assignment operator. */ TAdditionalStorage vars; /** \brief Default constructor */ MatCapsule_() { } /** \brief Class destructor. Called by queue::pop */ ~MatCapsule_() { } /** \brief The copy constructor. Called by queue::push * * Performs a deep copy of the `mat` member and its data. * Calls the `TAdditionalStorage` copy constructor if any. */ MatCapsule_(const MatCapsule_& src) { vars = TAdditionalStorage(src.vars); //Calls the copy constructor for the data type src.mat.copyTo(mat); } /** \brief The assignment operator. Called BY queue::front * \warning In case you have any member pointers you need to clone them. * This is because, next calls to queue::pop calls the class destructor destroying all data. * With `cv::Mat` the matrix data is still valid thanks to its internal memory counter. */ MatCapsule_& operator=(const MatCapsule_& src) { //Sanity check if (this == &src) return *this; vars = src.vars; // Calls assignment operator for the data type mat = src.mat; // Just copy the Mat header return *this; } }; /** \brief For your convenience, If you don't need any additional storage */ typedef MatCapsule_ MatCapsule; /** \brief Abstract base class for handling custom pkQueueTS::Push event. * * It provides an abstract interface to create custom OnPush event handler. * The OnPush event could be used to perform any custom actions like memory analysis on the pkQueueTS. * * ### How to use the OnPush event * Because this class is pure virtual, you have to derive your own class and write your own OnPush(). * The "OnPush" constructor pkQueueTS::pkQueueTS(pkQueueOnPushBase* onPushHandler) should * be used * * In this case, pkQueueTS::Push() calls `YourDerivedClass::OnPush()` within its own lock. */ class pkQueueOnPushBase { public: /** \brief OnPush event handler interface * * User has to defines its own class and implements the method to take needed actions. * * \param queueSize Queue size after current push. * \param elementPtr Pointer to the last pushed element in the queue <`&m_queue.back()`> * \note This is called by pkQueueTS::Push() within a proper lock on the queue. * Therefore the OnPush() method is thread safe vs those threads that are writing /reading * the queue, also in case of multiple producer/consumer. * \warning Do not use `elementPtr` out of here because pointed to object will be destroyed * on next pkQueueTS::Pop(). */ virtual void OnPush(size_t queueSize, const void *elementPtr) = 0; }; /////////////////////////////////////////////////////////////////////////////// /** \brief Thread Safe Queue * * \author * pkQueueTS - http://pklab.net/index.php?id=395 * Copyright (C) 2016 PkLab.net all rights reserved. * * This is a thread safe queue, multiple producer multiple consumer. * It's based on [std::queue](http://en.cppreference.com/w/cpp/container/queue) with single lock. * A [condition_variable](http://en.cppreference.com/w/cpp/thread/condition_variable) * with time-out is used to wait for new data. * * ## A thread safe queue for OpenCV Mats * * This class can be used to manage queue of [OpenCV Mats](http://docs.opencv.org/master/d3/d63/classcv_1_1Mat.html). * Thanks to [Automatic Memory Management](http://docs.opencv.org/master/d1/dfb/intro.html) of `cv::Mat` * and C++/STL memory recycling, use of `std::queue` with `cv::Mat` is memory effective. * * Unfortunately `cv::Mat` can't be used directly as element because its assignment operator and copy constructor * just copy the Mat header but not the matrix data. A simple solution is to encapsulates `cv::Mat` * into a structure or class and to write adequate assignment and constructor. The template class * MatCapsule_ (or its simple alias `MatCapsule` ) is provided here to this purpose. * * Definitely you can write: * * \snippet pkQueueTS_TestSimple.cpp pkQueueTS_BasicUsage * * ## Additional storage * * The template class MatCapsule_ allows to attach any kind of additional storage to the capsule. * For example you can have: * * \snippet pkQueueTS_TestSimple.cpp pkQueueTS_Additional_storage * * ## Memory statistics * * You can easily measure memory usage and allocations performed while using this class. * Just write your own `OnPush` event handler and collect wanted measurement (see pkQueueOnPushBase). * * For example you can collect all addresses of pushed elements using a simple `std::map` as below: * * \snippet pkQueueTS_TestSimple.cpp pkQueueTS_Stats * * Please see http://pklab.net/?&id=396 for a detailed example and analysis */ template class pkQueueTS { public: /** \brief Default constructor */ pkQueueTS():m_onPushHandler(nullptr) { } /** \overload * \brief "OnPush" Constructor * * If the "OnPush" constructor is used, a custom object will be invoked each time * pkQueueTS::Push() is called. In other words you have an OnPush event handler * that can be used to perform any custom actions on the queue. * * \param onPushHandler A pointer to custom object be derived from * the abstract class pkQueueOnPushBase */ pkQueueTS(pkQueueOnPushBase* onPushHandler) { m_onPushHandler = onPushHandler; } /** \brief Default destructor * * Calls element destructor for all elements in the queue (if any). * \warning If element is a pointer, the pointed to objects are not destroyed. */ ~pkQueueTS() { lock_guard lock(m_mutex); while (!m_queue.empty()) m_queue.pop(); //if you are here than you are discarding some elements } /** \brief Retrieves the oldest element in the queue, if any or if wait. * * Blocks the caller thread until a new element is available or after the specified * time-out duration. When/If the element has been retrieved correctly is it's removed * from the queue. * * \param [out] element If PK_QTS_OK is returned, contains the oldest element in the queue. * \param timeoutMs You can specify a time (milliseconds) to wait for a valid elements * - `timeoutMs = 0` [default] means no wait at all * - `timeoutMs > 0` means wait for given time out * \return pkQueueResults One of the following: * - PK_QTS_OK The element has been retrieved correctly * - PK_QTS_TIMEOUT The queue is empty but we wont wait * - PK_QTS_EMPTY Time out has reached waiting a valid element */ pkQueueResults Pop(TElement &element, unsigned timeoutMs = 0) { unique_lock lock(m_mutex); // wait for a data (ignoring spurious awakenings) while (m_queue.empty()) { // if no data and won't wait; if (timeoutMs == 0) { return PK_QTS_EMPTY; } // else wait data with time-out else if (cv_status::timeout == m_dataReady.wait_for(lock, chrono::milliseconds(timeoutMs))) { // Time out while waiting a valid element return PK_QTS_TIMEOUT; } } // data available element = m_queue.front(); //calls TElement::=operator m_queue.pop(); return PK_QTS_OK; } /** \brief Inserts an element at the end of the queue * * \param element The element to add. * \return The queue size after that the element has been added */ size_t Push(const TElement &element) { unique_lock lock(m_mutex); m_queue.push(element); //calls TElement::copy_constructor size_t N = m_queue.size(); if (m_onPushHandler) { void * ptr = &(m_queue.back()); m_onPushHandler->OnPush(N, ptr); } // The notifying thread does not need to hold the lock on the // same mutex as the one held by the waiting thread(s); // in fact doing so is a pessimization lock.unlock(); m_dataReady.notify_one(); return N; } /** \brief Returns the size of the queue */ size_t Size() { lock_guard lock(m_mutex); return m_queue.size(); } /** \brief Test whether queue is empty */ bool Empty() const { lock_guard lock(m_mutex); return m_queue.empty(); } private: std::queue m_queue; std::condition_variable m_dataReady; mutable std::mutex m_mutex; pkQueueOnPushBase* m_onPushHandler; }; //! @} #endif //PKQUEUETS_H ================================================ FILE: src/track_targets.cpp ================================================ /** track_targets https://github.com/fnoop/vision_landing This program uses opencv and aruco to detect fiducial markers in a stream. It uses tracking across images in order to avoid ambiguity problem with a single marker. For each target detected, it performs pose estimation and outputs the marker ID and translation vectors. These vectors are used by vision_landing mavlink messages to enable precision landing by vision alone. Compile with cmake: cmake . && make or manually: g++ src/track_targets.cpp -o track_targets -std=gnu++11 `pkg-config --cflags --libs aruco` Run separately with: ./track_targets -d TAG36h11 /dev/video0 calibration.yml 0.235 ./track_targets -w 1280 -g 720 -d TAG36h11 -o 'appsrc ! autovideoconvert ! v4l2video11h264enc extra-controls="encode,h264_level=10,h264_profile=4,frame_level_rate_control_enable=1,video_bitrate=2097152" ! h264parse ! rtph264pay config-interval=1 pt=96 ! udpsink host=192.168.1.70 port=5000 sync=false' /dev/video2 calibration/ocam5cr-calibration-1280x720.yml 0.235 ./track_targets -w 1280 -g 720 -d TAG36h11 -o /srv/maverick/data/videos/landing.avi /dev/video2 calibration/ocam5cr-calibration-1280x720.yml 0.235 ./track_targets -b 0.8 -d TAG36h11 -o 'appsrc ! autovideoconvert ! v4l2video11h264enc extra-contros="encode,h264_level=10,h264_profile=4,frame_level_rate_control_enable=1,video_bitrate=2097152" ! h264parse ! rtph264pay config-interval=1 pt=96 ! udpsink host=192.168.1.70 port=5000 sync=false' -i 1 -v /dev/video2 calibration/ocam5cr-calibration-640x480.yml 0.235 **/ #include #include #include #include #include #include #include #include #include #include #include "args.hxx" #include "pkQueueTS.hpp" #include #include #include #include "aruco/aruco.h" #include "aruco/timers.h" using namespace cv; using namespace aruco; // Setup sig handling static volatile sig_atomic_t sigflag = 0; static volatile sig_atomic_t stateflag = 0; // 0 = stopped, 1 = started void handle_sig(int sig) { std::cout << "info:SIGNAL:" << sig << ":Received" << std::endl; sigflag = 1; } void handle_sigusr1(int sig) { std::cout << "info:SIGNAL:SIGUSR1:Received:" << sig << ":Switching on Vision Processing" << std::endl; stateflag = 1; } void handle_sigusr2(int sig) { std::cout << "info:SIGNAL:SIGUSR2:Received:" << sig << ":Switching off Vision Processing" << std::endl; stateflag = 0; } // Setup fps tracker double CLOCK() { struct timespec t; clock_gettime(CLOCK_MONOTONIC, &t); return (t.tv_sec * 1000) + (t.tv_nsec * 1e-6); } double _avgdur = 0; double _fpsstart = 0; double _avgfps = 0; double _fps1sec = 0; double avgdur(double newdur) { _avgdur = 0.98 * _avgdur + 0.02 * newdur; return _avgdur; } double avgfps() { if (CLOCK() - _fpsstart > 1000) { _fpsstart = CLOCK(); _avgfps = 0.7 * _avgfps + 0.3 * _fps1sec; _fps1sec = 0; } _fps1sec++; return _avgfps; } // Define function to draw AR landing marker void drawARLandingCube(cv::Mat &Image, Marker &m, const CameraParameters &CP) { Mat objectPoints(8, 3, CV_32FC1); double halfSize = m.ssize / 2; objectPoints.at(0, 0) = -halfSize; objectPoints.at(0, 1) = -halfSize; objectPoints.at(0, 2) = 0; objectPoints.at(1, 0) = halfSize; objectPoints.at(1, 1) = -halfSize; objectPoints.at(1, 2) = 0; objectPoints.at(2, 0) = halfSize; objectPoints.at(2, 1) = halfSize; objectPoints.at(2, 2) = 0; objectPoints.at(3, 0) = -halfSize; objectPoints.at(3, 1) = halfSize; objectPoints.at(3, 2) = 0; objectPoints.at(4, 0) = -halfSize; objectPoints.at(4, 1) = -halfSize; objectPoints.at(4, 2) = m.ssize; objectPoints.at(5, 0) = halfSize; objectPoints.at(5, 1) = -halfSize; objectPoints.at(5, 2) = m.ssize; objectPoints.at(6, 0) = halfSize; objectPoints.at(6, 1) = halfSize; objectPoints.at(6, 2) = m.ssize; objectPoints.at(7, 0) = -halfSize; objectPoints.at(7, 1) = halfSize; objectPoints.at(7, 2) = m.ssize; std::vector imagePoints; cv::projectPoints(objectPoints, m.Rvec, m.Tvec, CP.CameraMatrix, CP.Distorsion, imagePoints); // draw lines of different colours for (int i = 0; i < 4; i++) cv::line(Image, imagePoints[i], imagePoints[(i + 1) % 4], Scalar(0, 255, 0, 255), 1, cv::LINE_AA); for (int i = 0; i < 4; i++) cv::line(Image, imagePoints[i + 4], imagePoints[4 + (i + 1) % 4], Scalar(0, 255, 0, 255), 1, cv::LINE_AA); for (int i = 0; i < 4; i++) cv::line(Image, imagePoints[i], imagePoints[i + 4], Scalar(0, 255, 0, 255), 1, cv::LINE_AA); } // Print the calculated distance at bottom of image void drawVectors(Mat &in, Scalar color, int lineWidth, int vOffset, int MarkerId, double X, double Y, double Distance, double cX, double cY) { char cad[100]; sprintf(cad, "ID:%i, Distance:%0.3fm, X:%0.3f, Y:%0.3f, cX:%0.3f, cY:%0.3f", MarkerId, Distance, X, Y, cX, cY); Point cent(10, vOffset); cv::putText(in, cad, cent, FONT_HERSHEY_SIMPLEX, std::max(0.5f, float(lineWidth) * 0.3f), color, lineWidth); } // Summarise a marker history over the past 10 frames int markerHistory(std::map> &marker_history_queue, uint32_t thisId, uint32_t marker_history) { // Work out current history for this marker uint32_t histsum = 0; for (unsigned int j = 0; j < marker_history; j++) { uint32_t _val = marker_history_queue[thisId].front(); // fetch value off front of queue histsum += _val; // add value to history sum marker_history_queue[thisId].pop(); // pop value off front of queue marker_history_queue[thisId].push(_val); // push value back onto end of queue } return histsum; } // Change active marker and reset all marker histories void changeActiveMarker(std::map> &marker_history_queue, uint32_t &active_marker, uint32_t newId, uint32_t marker_history) { // Set the new marker as active active_marker = newId; // Reset all marker histories. This ensures that another marker change can't happen for at least x frames where x is history size for (auto &markerhist : marker_history_queue) { for (unsigned int j = 0; j < marker_history; j++) { marker_history_queue[markerhist.first].push(0); marker_history_queue[markerhist.first].pop(); } } } // Setup our incoming threaded camera feed struct TimeCapsuleVars { uint64_t timeStamp = 0; uint64_t frameNum = 0; }; typedef MatCapsule_ MatTimeCapsule; pkQueueTS incomingQueue; atomic grabState; // Initiate camera cv::VideoCapture vreader; // Thread to control capture device and push frames onto the threadsafe queue void incomingThread() { // Enable capture input grabState = true; // Incoming frame MatTimeCapsule iframe; uint64_t frameNum = 0; std::cout << "Starting incomingThread()" << std::endl; while (grabState) { // Read the next frame in from the camera and push it to back of queue // std::cout << "debug:Pushing camera frame to queue" << std::endl; vreader.grab(); // Lodge clock for start of frame, after grabbing the frame but before decompressing/converting it. // This is as close as we can get to the shutter time, for a better match to inertial frame. frameNum++; iframe.vars.frameNum = frameNum; iframe.vars.timeStamp = CLOCK() * 1e+6; // Now process the grabbed frame vreader.retrieve(iframe.mat); // Push the timeframe capsule onto the queue, ready for collection and processing incomingQueue.Push(iframe); // If there is more than 1 frame in the queue, pop the rest to prevent buildup while (incomingQueue.Size() > 1) incomingQueue.Pop(iframe); } } // Setup our outgoing threaded video stream pkQueueTS< MatCapsule > outgoingQueue; atomic pushState; // Initiate stream cv::VideoWriter vwriter; // Thread to control writer device, read frames from the threadsafe queue and push into the video stream void outgoingThread() { // Enable stream output pushState = true; // Outgoing frame MatCapsule oframe; std::cout << "Starting outgoingThread()" << std::endl; while (pushState) { int qsize = outgoingQueue.Size(); // Read frame in from the queue and push it to stream if (qsize > 0) { std::cout << "debug:Pushing output frame to stream:" << qsize << std::endl; // If the queue already has more than 1 frame then pop it, to prevent buildup // We only want to send the latest frame while (qsize > 1) { outgoingQueue.Pop(oframe); qsize--; } // Pop the frame off the queue and push to stream outgoingQueue.Pop(oframe); vwriter.write(oframe.mat); } } } // main.. int main(int argc, char **argv) { // Unbuffer stdout and stdin std::cout.setf(std::ios::unitbuf); std::ios_base::sync_with_stdio(false); // Make sure std::cout does not show scientific notation std::cout.setf(ios::fixed); // Setup arguments for parser args::ArgumentParser parser("Track fiducial markers and estimate pose, output translation vectors for vision_landing"); args::HelpFlag help(parser, "help", "Display this help menu", {'h', "help"}); args::Flag verbose(parser, "verbose", "Verbose", {'v', "verbose"}); args::ValueFlag markerid(parser, "markerid", "Marker ID", {'i', "id"}); args::ValueFlag dict(parser, "dict", "Marker Dictionary", {'d', "dict"}); args::ValueFlag output(parser, "output", "Output Stream", {'o', "output"}); args::ValueFlag width(parser, "width", "Video Input Resolution - Width", {'w', "width"}); args::ValueFlag height(parser, "height", "Video Input Resolution - Height", {'g', "height"}); args::ValueFlag fps(parser, "fps", "Video Output FPS - Kludge factor", {'f', "fps"}); args::ValueFlag brightness(parser, "brightness", "Camera Brightness/Gain", {'b', "brightness"}); args::ValueFlag sizemapping(parser, "sizemapping", "Marker Size Mappings, in marker_id:size format, comma separated", {'z', "sizemapping"}); args::ValueFlag markerhistory(parser, "markerhistory", "Marker tracking history, in frames", {"markerhistory"}); args::ValueFlag markerthreshold(parser, "markerthreshold", "Marker tracking threshold, percentage", {"markerthreshold"}); args::ValueFlag fourcc(parser, "fourcc", "FourCC CoDec code", {'c', "fourcc"}); args::Positional input(parser, "input", "Input Stream"); args::Positional calibration(parser, "calibration", "Calibration Data"); args::Positional markersize(parser, "markersize", "Marker Size"); // Parse arguments try { parser.ParseCLI(argc, argv); } catch (args::Help) { std::cout << parser; return 0; } catch (args::ParseError e) { std::cerr << e.what() << std::endl; std::cerr << parser; return 1; } catch (args::ValidationError e) { std::cerr << e.what() << std::endl; std::cerr << parser; return 1; } if (!input || !calibration || !markersize) { std::cout << parser; return 1; } // Open camera vreader.open( args::get(input) ); // Bail if camera can't be opened if (!vreader.isOpened()) { std::cerr << "Error: Input stream can't be opened" << std::endl; return 1; } // Register signals signal(SIGINT, handle_sig); signal(SIGTERM, handle_sig); signal(SIGUSR1, handle_sigusr1); signal(SIGUSR2, handle_sigusr2); // If resolution is specified then use, otherwise use default int inputwidth = 640; int inputheight = 480; if (width) inputwidth = args::get(width); if (height) inputheight = args::get(height); // If fps is specified then use, otherwise use default int inputfps = 30; if (fps) inputfps = args::get(fps); // If brightness is specified then use, otherwise use default if (brightness) vreader.set(CAP_PROP_BRIGHTNESS, args::get(brightness)); // Set camera properties vreader.set(cv::CAP_PROP_FRAME_WIDTH, inputwidth); vreader.set(cv::CAP_PROP_FRAME_HEIGHT, inputheight); vreader.set(cv::CAP_PROP_FPS, inputfps); // vreader.set(CAP_PROP_BUFFERSIZE, 0); // Doesn't work yet with V4L2 // Read and parse camera calibration data aruco::CameraParameters CamParam; CamParam.readFromXMLFile(args::get(calibration)); if (!CamParam.isValid()) { std::cerr << "Calibration Parameters not valid" << std::endl; return -1; } // Take a single image and resize calibration parameters based on input stream dimensions // Note we read directly from vreader here because we haven't turned the reader thread on yet Mat rawimage; vreader >> rawimage; CamParam.resize(rawimage.size()); // Calculate the fov from the calibration intrinsics const double pi = std::atan(1) * 4; const double fovx = 2 * atan(inputwidth / (2 * CamParam.CameraMatrix.at(0, 0))) * (180.0 / pi); const double fovy = 2 * atan(inputheight / (2 * CamParam.CameraMatrix.at(1, 1))) * (180.0 / pi); std::cout << "info:FoVx~" << fovx << ":FoVy~" << fovy << ":vWidth~" << inputwidth << ":vHeight~" << inputheight << std::endl; // Turn on incoming thread std::thread inThread(incomingThread); MatTimeCapsule iframe; // If output specified then setup the pipeline unless output is set to 'window' if (output && args::get(output) != "window") { if (fourcc) { std::string _fourcc = args::get(fourcc); vwriter.open(args::get(output), VideoWriter::fourcc(_fourcc[0], _fourcc[1], _fourcc[2], _fourcc[3]), inputfps, cv::Size(inputwidth, inputheight), true); } else { vwriter.open(args::get(output), 0, inputfps, cv::Size(inputwidth, inputheight), true); } if (!vwriter.isOpened()) { std::cerr << "Error can't create video writer" << std::endl; return 1; } } // Turn on writer thread std::thread outThread(outgoingThread); MatCapsule oframe; // Setup the marker detection double MarkerSize = args::get(markersize); MarkerDetector MDetector; MarkerDetector::Params &MParams = MDetector.getParameters(); MDetector.setDetectionMode(aruco::DM_VIDEO_FAST, 0.02); MParams.setAutoSizeSpeedUp(true,0.3); MParams.maxThreads = 1; // -1 = all MParams.setCornerRefinementMethod(aruco::CORNER_SUBPIX); MParams.NAttemptsAutoThresFix = 3; // This is the number of random threshold iterations when no markers found // Tracking variables float Ti = MParams.minSize; int ThresHold = MParams.ThresHold; std::map MTracker; // use a map so that for each id, we use a different pose tracker if (dict) MDetector.setDictionary(args::get(dict), 0.f); // Start framecounter at 0 for fps tracking int frameno = 0; // Create a map of marker sizes from 'sizemapping' config setting std::map markerSizes; std::stringstream ss(args::get(sizemapping)); // First split each mapping into a vector std::vector _size_mappings; std::string _size_mapping; while (std::getline(ss, _size_mapping, ',')) { _size_mappings.push_back(_size_mapping); } // Next tokenize each vector element into the markerSizes map for (std::string const &_s : _size_mappings) { auto _i = _s.find(':'); markerSizes[atoi(_s.substr(0, _i).data())] = atof(_s.substr(_i + 1).data()); } // Debug print the constructed map std::cout << "info:Size Mappings:"; for (const auto &p : markerSizes) { std::cout << p.first << "=" << p.second << ", "; } std::cout << std::endl; // Setup marker thresholding uint32_t active_marker; // Use a map of queues to track state of each marker in the last x frames std::map> marker_history_queue; // If marker history or threshold is set in parameters use them, otherwise set defaults uint32_t marker_history; if (args::get(markerhistory)) { marker_history = args::get(markerhistory); } else { marker_history = 15; } std::cout << "debug:Marker History:" << marker_history << std::endl; uint32_t marker_threshold; marker_threshold = args::get(markerthreshold); std::cout << "debug:Marker Threshold:" << marker_threshold << std::endl; // Print a specific info message to signify end of initialisation std::cout << "info:initcomp:Initialisation Complete" << std::endl; // Main loop while (true) { // If signal for interrupt/termination was received, break out of main loop and exit if (sigflag) { std::cout << "info:Signal Detected:Exiting track_targets" << std::endl; break; } // If tracking not active, skip if (!stateflag) { // Add a 1ms sleep to slow down the loop if nothing else is being done nanosleep((const struct timespec[]){{0, 10000000L}}, NULL); continue; } // Start Timers double framestart = CLOCK(); ScopedTimerEvents Timer("detectloop"); // Read a camera frame from the incoming thread, with 1 second timeout // std::cout << "debug:Incoming queue size:" << incomingQueue.Size() << std::endl; pkQueueResults res = incomingQueue.Pop(iframe, 1000); if (res != PK_QTS_OK) { if (verbose && res == PK_QTS_TIMEOUT) std::cout << "debug:Time out reading from the camera thread" << std::endl; if (verbose && res == PK_QTS_EMPTY) std::cout << "debug:Camera thread is empty" << std::endl; this_thread::yield(); continue; } Timer.add("PopImage"); // Skip this loop iteration if the frame was empty if (iframe.mat.empty()) continue; // Detect markers std::vector Markers = MDetector.detect(iframe.mat); Timer.add("MarkerDetect"); // Order the markers in ascending size - we want to start with the smallest. std::map markerAreas; std::map markerIds; for (auto &marker : Markers) { markerAreas[marker.getArea()] = marker.id; markerIds[marker.id] = true; // If the marker doesn't already exist in the threshold tracking, add and populate with full set of zeros if (marker_history_queue.count(marker.id) == 0) { for (unsigned int i = 0; i < marker_history; i++) marker_history_queue[marker.id].push(0); } } // Iterate through marker history and update for this frame for (auto &markerhist : marker_history_queue) { // If marker was detected in this frame, push a 1 (markerIds.count(markerhist.first)) ? markerhist.second.push(1) : markerhist.second.push(0); // If the marker history has reached history limit, pop the oldest element if (markerhist.second.size() > marker_history) { markerhist.second.pop(); } } // If marker is set in config, use that to lock on if (markerid) { active_marker = args::get(markerid); // Otherwise find the smallest marker that has a size mapping } else { for (auto &markerArea : markerAreas) { uint32_t thisId = markerArea.second; if (markerSizes[thisId]) { // If the current history for this marker is >threshold, then set as the active marker and clear marker histories. Otherwise, skip to the next sized marker. uint32_t _histsum = markerHistory(marker_history_queue, thisId, marker_history); float _histthresh = marker_history * ((float)marker_threshold / (float)100); if (_histsum > _histthresh) { if (active_marker == thisId) break; // Don't change to the same thing changeActiveMarker(marker_history_queue, active_marker, thisId, marker_history); if (verbose) { std::cout << "debug:changing active_marker:" << thisId << ":" << _histsum << ":" << _histthresh << ":" << std::endl; std::cout << "debug:marker history:"; for (auto &markerhist : marker_history_queue) { std::cout << markerhist.first << ":" << markerHistory(marker_history_queue, markerhist.first, marker_history) << ":"; } std::cout << std::endl; } break; } } } } // If a marker lock hasn't been found by this point, use the smallest found marker with the default marker size if (!active_marker) { for (auto &markerArea : markerAreas) { uint32_t thisId = markerArea.second; // If the history threshold for this marker is >50%, then set as the active marker and clear marker histories. Otherwise, skip to the next sized marker. uint32_t _histsum = markerHistory(marker_history_queue, thisId, marker_history); float _histthresh = marker_history * ((float)marker_threshold / (float)100); if (_histsum > _histthresh) { if (verbose) std::cout << "debug:changing active_marker:" << thisId << std::endl; changeActiveMarker(marker_history_queue, active_marker, thisId, marker_history); break; } } } Timer.add("MarkerLock"); // Iterate through the markers, in order of size, and do pose estimation for (auto &markerArea : markerAreas) { if (markerArea.second != active_marker) continue; // Don't do pose estimation if not active marker, save cpu cycles float _size; // If marker size mapping exists for this marker, use it for pose estimation if (markerSizes[markerArea.second]) { _size = markerSizes[markerArea.second]; // Otherwise use generic marker size } else if (MarkerSize) { _size = MarkerSize; if (verbose) std::cout << "debug:defaulting to generic marker size: " << markerArea.second << std::endl; } // Find the Marker in the Markers map and do pose estimation. I'm sure there's a better way of iterating through the map.. for (unsigned int i = 0; i < Markers.size(); i++) { if (Markers[i].id == markerArea.second) { MTracker[markerArea.second].estimatePose(Markers[i], CamParam, _size); } } } Timer.add("PoseEstimation"); // Iterate through each detected marker and send data for active marker and draw green AR cube, otherwise draw red AR square for (unsigned int i = 0; i < Markers.size(); i++) { double processtime = CLOCK() - framestart; // If marker id matches current active marker, draw a green AR cube if (Markers[i].id == active_marker) { if (output) { Markers[i].draw(iframe.mat, Scalar(0, 255, 0), 2, false); } // If pose estimation was successful, calculate data and output to anyone listening. if (Markers[i].Tvec.at(0, 2) > 0) { // Calculate vector norm for distance double distance = sqrt(pow(Markers[i].Tvec.at(0, 0), 2) + pow(Markers[i].Tvec.at(0, 1), 2) + pow(Markers[i].Tvec.at(0, 2), 2)); // Calculate angular offsets in radians of center of detected marker double xoffset = (Markers[i].getCenter().x - inputwidth / 2.0) * (fovx * (pi / 180)) / inputwidth; double yoffset = (Markers[i].getCenter().y - inputheight / 2.0) * (fovy * (pi / 180)) / inputheight; if (verbose) { Ti = MParams.minSize; ThresHold = MParams.ThresHold; std::cout << "debug:active_marker:" << active_marker << ":center~" << Markers[i].getCenter() << ":area~" << Markers[i].getArea() << ":marker~" << Markers[i] << ":vectornorm~" << distance << ":Ti~" << Ti << ":ThresHold~" << ThresHold << ":Markers~" << Markers.size() << ":processtime~" << processtime << ":timestamp~" << iframe.vars.timeStamp << std::endl; } // This is the main message that track_targets outputs, containing the active target data std::cout << "target:" << Markers[i].id << ":" << xoffset << ":" << yoffset << ":" << distance << ":" << processtime << ":" << iframe.vars.timeStamp << ":" << CLOCK() * 1e+6 << std::endl << std::flush; // std::cout << "target:" << Markers[i].id << ":" << xoffset << ":" << yoffset << ":" << distance << ":" << processtime << ":" << CLOCK() * 1e+6 << std::endl << std::flush; std::fflush(stdout); // explicitly flush stdout buffer Timer.add("SendMessage"); // Draw AR cube and distance if (output) { // don't burn cpu cycles if no output drawARLandingCube(iframe.mat, Markers[i], CamParam); CvDrawingUtils::draw3dAxis(iframe.mat, Markers[i], CamParam); drawVectors(iframe.mat, Scalar(0, 255, 0), 1, (i + 1) * 20, Markers[i].id, xoffset, yoffset, distance, Markers[i].getCenter().x, Markers[i].getCenter().y); Timer.add("DrawGreenAR"); } } // Otherwise draw a red square } else { if (verbose) std::cout << "debug:inactive_marker:center~" << Markers[i].getCenter() << ":area~" << Markers[i].getArea() << ":marker~" << Markers[i] << ":Ti~" << Ti << ":ThresHold~" << ThresHold << ":Markers~" << Markers.size() << ":processtime~" << processtime << std::endl; if (output) { // don't burn cpu cycles if no output Markers[i].draw(iframe.mat, Scalar(0, 0, 255), 2, false); drawVectors(iframe.mat, Scalar(0, 0, 255), 1, (i + 1) * 20, Markers[i].id, 0, 0, Markers[i].Tvec.at(0, 2), Markers[i].getCenter().x, Markers[i].getCenter().y); Timer.add("DrawRedAR"); } } } Timer.add("UseMarkers"); if (output && args::get(output) != "window") { oframe.mat = iframe.mat.clone(); // iframe.mat.copyTo(oframe.mat); Timer.add("Out-CloneMat"); outgoingQueue.Push(oframe); Timer.add("Out-PushImage"); } else if (output && args::get(output) == "window") { imshow("vision_landing", iframe.mat); Timer.add("OutputImage"); } // Lodge clock for end of frame double framedur = CLOCK() - framestart; // Print fps info every 100 frames char framestr[100]; sprintf(framestr, "info:avgframedur~%fms:fps~%f:frameno~%d:", avgdur(framedur), avgfps(), frameno++); if (verbose && (frameno % 100 == 1)) { std::cout << framestr << std::endl; } Timer.add("EndofLoop"); } // Stop incoming thread and flush queue std::cout << "info:track_targets complete, exiting" << std::endl; grabState = false; pushState = false; while (PK_QTS_EMPTY != incomingQueue.Pop(iframe, 0)); inThread.join(); while (PK_QTS_EMPTY != outgoingQueue.Pop(oframe, 0)); outThread.join(); vreader.release(); vwriter.release(); std::cout.flush(); return 0; } ================================================ FILE: vision_landing ================================================ #!/usr/bin/env python2 # -*- coding: utf-8 -*- # vision_landing # https://github.com/fnoop/vision_landing # # This python script connects to arducopter using dronekit, to control precision landing. # The control is purely visual using pose estimation from fiducial markers (eg. aruco or april tags), no additional rangefinder is needed. # It launches a separate program track_targets which does the actual cv work and captures the resulting vectors from non-blocking thread handler. from threading import Thread, Event from Queue import LifoQueue, Queue, Empty from subprocess import Popen, PIPE from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative from pymavlink import mavutil from time import sleep, time from datetime import datetime, timedelta from sys import exit, stdout, stderr from os import path, makedirs, symlink, remove from math import pi from re import sub, search from collections import deque from math import sqrt import signal import logging import ctypes ### ================================ ### Define Functions ### ================================ # Return correctly typed config parser option def get_config_value(parser, section, option): """Parses config value as python type""" try: return parser.getint(section, option) except ValueError: pass try: return parser.getfloat(section, option) except ValueError: pass try: return parser.getboolean(section, option) except ValueError: pass return parser.get(section, option) # Setup monotonic clock CLOCK_MONOTONIC_RAW = 4 class timespec(ctypes.Structure): _fields_ = [ ('tv_sec', ctypes.c_long), ('tv_nsec', ctypes.c_long) ] librt = ctypes.CDLL('librt.so.1', use_errno=True) clock_gettime = librt.clock_gettime clock_gettime.argtypes = [ctypes.c_int, ctypes.POINTER(timespec)] def monotonic_time(): t = timespec() if clock_gettime(CLOCK_MONOTONIC_RAW , ctypes.pointer(t)) != 0: errno_ = ctypes.get_errno() raise OSError(errno_, os.strerror(errno_)) return (t.tv_sec * 1e+9) + t.tv_nsec ### ================================ ### End Define Functions ### ================================ ### ================================ ### Define Classes ### ================================ # Threaded Reader class connects the output from the track_targets process to a non-blocking reader, and adds any messages to a queue. # The queue is then read by the main loop and if anything is waiting it calls a method to process from the track_targets object. class ThreadedReader: def __init__(self, stdout, stderr): self.stdout = stdout self.stderr = stderr self.queue = LifoQueue() self._stop = Event() def insertQueue(pipe, queue, qtype="stdout"): while not self.stopped(): self.clear() # Clear the queue before adding anything - we only want the latest data line = pipe.readline().rstrip() + ":{:.0f}".format(monotonic_time()) if args.verbose: log.debug("Adding line: {} : {}".format(qtype, line)) if line and qtype == "stdout": queue.put(line) elif line and qtype == "stderr": queue.put("error:"+line) self.threadout = Thread(target = insertQueue, args = (self.stdout, self.queue)) self.threadout.daemon = True self.threadout.start() self.threaderr = Thread(target = insertQueue, args = (self.stderr, self.queue, "stderr")) self.threaderr.daemon = True self.threaderr.start() def size(self): return self.queue.qsize() def readline(self, timeout = None): try: line = self.queue.get(block = timeout is not None, timeout = timeout) self.queue.task_done() return line except Empty: log.debug("empty queue") return None def clear(self): #with self.queue.mutex: # self.queue.clear() while self.size() > 10: # self.readline() tmpline = self.queue.get(False) log.debug("clearing queue: {} : {}".format(self.size(), tmpline)) self.queue.task_done() return def stop(self): self._stop.set() def stopped(self): return self._stop.isSet() # TrackTime class is used to synchronise time between the companion computer and the flight controller. # This is necessary to ensure that the vision frames are matched as closely as possible with the inertial frames. # Note: This requires a Craft object to be passed, in order to perform the actual sync. class TrackTime: def __init__(self, craft): self.fctime_nanos = 0 self.mytime_nanos = 0 self.local_tracker = {} self.delta = None self.difference = None self.delta_buffer = deque(maxlen=50) # Circular buffer to track timesync deltas self.difference_buffer = deque(maxlen=50) # Circular buffer to track difference between two systems self.debug = False self.vehicle = craft.vehicle # Setup time struct to hold local monotonic clock queries self.t = timespec() # Setup listener decorator @self.vehicle.on_message("TIMESYNC") def listener_timesync(subself, name, message): try: if message.ts1 < self.mytime_nanos: #log.info("Newer timesync message already received, ignoring") return False self.mytime_nanos = message.ts1 # Set the time that the message was sent _cts = self.current_timestamp() _avg_ts = (self.local_tracker[message.ts1] + _cts)/2 self._delta = _cts - _avg_ts # Calculuate the time delta self.delta_buffer.append(self._delta) # Push the delta into the circular buffer # If the averaged delta has been reached, use that, and update the delta from the latest buffer if self.delta: self.delta = sum(list(self.delta_buffer)) / len(list(self.delta_buffer)) self.fctime_nanos = message.tc1 - self.delta # Otherwise use the spot delta from the incoming message else: self.fctime_nanos = message.tc1 - self._delta self.difference_buffer.append(self.mytime_nanos - self.fctime_nanos) self.difference = sum(list(self.difference_buffer)) / len(list(self.difference_buffer)) if self.debug: log.debug("Timesync message received:"+", ".join([str(message), str(self._delta), str(self.fctime_nanos)])) except: if self.debug: log.debug("Error, unexpected timesync timestamp received:"+str(message.ts1)) # Blocking method to call once during startup, to calculate delta def initial_sync(self): # Keep sending timesync requests until the delta buffer is full, or a timeout is reached start_timesync = self.current_timestamp() while len(list(self.delta_buffer)) < 50 and self.current_timestamp() - start_timesync < (15 * 1000000000): self.update() sleep(0.1) # Ardupilot can't cope with too many timesync messages being sent in a short time period, the results are nonsense # When full, average the delta buffer and then set that to use as the ongoing delta if len(self.delta_buffer) == 50: self.delta = sum(list(self.delta_buffer)) / len(list(self.delta_buffer)) else: log.warning("Error creating timesync delta buffer - unpredictable results will follow") # Method to return monotonic clock time def current_timestamp(self): return monotonic_time() # Request a timesync update from the flight controller def update(self, ts=0, tc=0): if ts == 0: ts = self.current_timestamp() self.local_tracker[ts] = self.current_timestamp() # Create entry to correlate sending timestamp with actual localtime msg = self.vehicle.message_factory.timesync_encode( tc, # tc1 ts # ts1 ) self.vehicle.send_mavlink(msg) self.vehicle.flush() # Note: This returns the 'actual' time of the FC with the delay compensated from the last sync event def actual(self): return self.fctime_nanos # Return actual + time elapsed since actual set def estimate(self): estmynanos = self.current_timestamp() - self.difference estfcnanos = self.actual() + (self.current_timestamp() - self.mytime_nanos) #log.debug("Estimate time: current-difference:"+str(estmynanos/1000000)+", fctime_nanos+elapsed:"+str(estfcnanos/1000000)+", difference:"+str((estmynanos - estfcnanos) / 1000000)) return estmynanos def toFcTime(self, inTime): return inTime - self.difference # TrackTargets class launches, controls and handles the separate track_targets process that does the actual vision processing. class TrackTargets: def __init__(self, args, calibration): self.state = None self.shutdown = False # Setup timing containers self.frame_times = [] self.start_t = time() # Work out starting parameters self.setup(args, calibration) # Launch tracking process and process output log.info("Launching track_targets with arguments:" + " ".join(self.track_arguments)) self.launch() def setup(self, args, calibration): # Define the basic arguments to track_targets self.track_arguments = [cwd+'/track_targets'] # If marker dictionary is set, pass it through if args.markerdict: self.track_arguments.extend(['-d', args.markerdict]) # If output is set, pass it through if args.output: now = datetime.now() nowtime = now.strftime("%Y-%m-%d-%H-%M-%S") args_output = sub("-xxx", "-"+str(nowtime), args.output) self.track_arguments.extend(['-o', args_output]) # If marker id is set, pass it through if args.markerid: self.track_arguments.extend(['-i', args.markerid]) # If width is set, pass it through if args.width: self.track_arguments.extend(['-w', str(args.width)]) # If height is set, pass it through if args.height: self.track_arguments.extend(['-g', str(args.height)]) # If fps is set, pass it through if args.fps: self.track_arguments.extend(['-f', str(args.fps)]) # If verbose is set, pass it through if args.verbose: self.track_arguments.extend(['-v']) # If brightness is set, pass it through if args.brightness: self.track_arguments.extend(['-b', str(args.brightness)]) # If fourcc codec is set, pass it through if args.fourcc: self.track_arguments.extend(['-c', args.fourcc]) # If sizemapping is set, pass it through if args.sizemapping: self.track_arguments.extend(['-z', args.sizemapping]) # If markerhistory is set, pass it through if args.markerhistory: self.track_arguments.extend(['--markerhistory', str(args.markerhistory)]) # If markerthreshold is set, pass it through if args.markerthreshold: self.track_arguments.extend(['--markerthreshold', str(args.markerthreshold)]) # Add positional arguments self.track_arguments.extend([args.input, calibration, str(args.markersize)]) def launch(self): self.process = Popen(self.track_arguments, stdin = PIPE, stdout = PIPE, stderr = PIPE, shell = False, bufsize=1) self.reader = ThreadedReader(self.process.stdout, self.process.stderr) self.state = "initialising" def processline(self, line): # Unpack data from track_targets data trackdata = line.rstrip().split(":") # If not target data, log and skip to next data if trackdata[0] != "target": datatype = trackdata[0] if trackdata[0] == "error": log.error("track_targets: " +str(trackdata[1:])) elif trackdata[0] == "debug" and args.verbose: log.debug("track_targets: " + datatype[0].upper() + datatype[1:] + str(trackdata[1:])) elif trackdata[0] == "info": log.info("track_targets: " + str(trackdata[1:])) if trackdata[1] == "initcomp": self.state = "initialised" return # Unpack and cast target data to correct types try: [id,x,y,z,processtime,sensorTimestamp,sendTimestamp,receiveTimestamp] = trackdata[1:] [id,x,y,z,processtime,sensorTimestamp,sendTimestamp,receiveTimestamp] = [int(id),float(x),float(y),float(z),float(processtime),float(sensorTimestamp),float(sendTimestamp),float(receiveTimestamp)] except: log.debug("track_targets: error in data: " + str(line.rstrip())) return # If fake rangefinder distance is required, send it if args.fakerangefinder: craft.send_distance_message(int(z*100)) # Send the landing_target message to arducopter # NOTE: This sends the current estimated fctime, NOT the time the frame was actually captured. # So this does not allow for the CV processing time. This should be sending when the frame is actually captured, before processing. nowTime = monotonic_time() # If data is less than 250ms since the image shuttr, send the message. if nowTime - sensorTimestamp < 250 * 1e+6: craft.send_land_message(x, y, z, tracktime.toFcTime(sensorTimestamp) / 1000, id) # Send sensor timestamp adjusted to timesync, in micros # Track frame timing to calculate fps, running average over last 10 frames end_t = time() time_taken = end_t - self.start_t self.start_t = end_t self.frame_times.append(time_taken) self.frame_times = self.frame_times[-10:] fps = len(self.frame_times) / sum(self.frame_times) log.info("Fctime:{:.0f}:{:.0f}, Fps:{:.2f}, Alt:{}, Rng:{}, Marker:{}, Distance:{}, xOffset:{}, yOffset:{}, processTime:{:.0f}, sensorTime:{:.0f}, sendTime:{:.0f}, receiveTime:{:.0f}, currentTime:{:.0f}, sensorDiff:{}, sendDiff:{}, receiveDiff:{}".format(tracktime.actual(), tracktime.estimate(), fps, craft.vehicle.location.global_relative_frame.alt, craft.vehicle.rangefinder.distance, id, z, x, y, processtime, sensorTimestamp, sendTimestamp, receiveTimestamp, nowTime, nowTime - sensorTimestamp, nowTime - sendTimestamp, nowTime - receiveTimestamp)) def start(self): if self.state == "initialised": log.info("Requesting track_targets to start tracking:"+str(craft.vehicle.mode)) self.process.send_signal(signal.SIGUSR1) self.state = "started" else: log.info("Request to start track_targets tracking failed, state is not 'initialised'") def stop(self): log.info("Requesting track_targets to stop tracking:"+str(craft.vehicle.mode)) self.state = "initialised" self.process.send_signal(signal.SIGUSR2) def end(self): log.info("Shutting down track_targets") # Stop threaded reader self.reader.stop() # track_targets should always be stopped by now, but be sure self.process.poll() if self.process.returncode == None: self.process.terminate() self.shutdown = True # The Craft class connects to the flight controller and sends controlling messages class Craft: def __init__(self, connectstr): self.debug = False self.mode = None self.connected = None self.vehicle = None self.connect(connectstr) self.precloiter_opt = self.find_precloiter_opt() if self.precloiter_opt: log.info("Precision loiter switch found: Channel "+str(self.precloiter_opt)) def connect(self, connectstr): try: # self.vehicle = connect(connectstr, wait_ready=True, rate=1) # self.vehicle = connect(connectstr, wait_ready=True) # self.vehicle = connect(connectstr, wait_ready=['system_status','mode'], baud=921600) self.vehicle = connect(connectstr, wait_ready=['system_status','mode']) self.connected = True except Exception,e: log.critical("Error connecting to vehicle:"+str(repr(e))) self.connected = False # Define function to send distance_message mavlink message for mavlink based rangefinder, must be >10hz # http://mavlink.org/messages/common#DISTANCE_SENSOR def send_distance_message(self, dist): msg = self.vehicle.message_factory.distance_sensor_encode( 0, # time since system boot, not used 1, # min distance cm 10000, # max distance cm dist, # current distance, must be int 0, # type = laser? 0, # onboard id, not used mavutil.mavlink.MAV_SENSOR_ROTATION_PITCH_270, # must be set to MAV_SENSOR_ROTATION_PITCH_270 for mavlink rangefinder, represents downward facing 0 # covariance, not used ) self.vehicle.send_mavlink(msg) self.vehicle.flush() if args.verbose: log.debug("Sending mavlink distance_message:" +str(dist)) # Define function to send landing_target mavlink message for mavlink based precision landing # http://mavlink.org/messages/common#LANDING_TARGET def send_land_message(self, x,y,z, time_usec=0, target_num=0): msg = self.vehicle.message_factory.landing_target_encode( time_usec, # time target data was processed, as close to sensor capture as possible target_num, # target num, not used mavutil.mavlink.MAV_FRAME_BODY_NED, # frame, not used x, # X-axis angular offset, in radians y, # Y-axis angular offset, in radians z, # distance, in meters 0, # Target x-axis size, in radians 0, # Target y-axis size, in radians 0, # x float X Position of the landing target on MAV_FRAME 0, # y float Y Position of the landing target on MAV_FRAME 0, # z float Z Position of the landing target on MAV_FRAME (1,0,0,0), # q float[4] Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) 2, # type of landing target: 2 = Fiducial marker 1, # position_valid boolean ) self.vehicle.send_mavlink(msg) self.vehicle.flush() if args.verbose: log.debug("Sending mavlink landing_target - time_usec:{:.0f}, x:{}, y:{}, z:{}".format(time_usec, str(x), str(y), str(z))) # Define function that arms and takes off, used for testing in SITL # Lifted from dronekit-python examples def arm_and_takeoff(self, targetAltitude): log.info("Basic pre-arm checks") # Don't let the user try to arm until autopilot is ready while not self.vehicle.is_armable: log.info(" Waiting for vehicle to initialise...") sleep(1) log.info("Arming motors") # Copter should arm in GUIDED mode self.vehicle.mode = VehicleMode("GUIDED") self.vehicle.armed = True while not self.vehicle.armed: log.info(" Waiting for arming...") sleep(1) log.info("Taking off!") self.vehicle.simple_takeoff(targetAltitude) # Take off to target altitude # Wait until the vehicle reaches a safe height before processing the goto (otherwise the command # after Vehicle.simple_takeoff will execute immediately). while True: log.info(" Altitude: " + str(self.vehicle.location.global_relative_frame.alt)) if self.vehicle.location.global_relative_frame.alt>=targetAltitude*0.95: #Trigger just below target alt. log.info("Reached target altitude") break sleep(1) # Scan through option channels for one set to 39 (precision loiter) def find_precloiter_opt(self): _optch = None for ch in range(7,16): try: if self.vehicle.parameters['CH'+str(ch)+'_OPT'] == 39: _optch = ch except: pass return _optch # Class for signal tracking and handling. This is used to accept Ctrl-C or SIGHUP/SIGKILL type events. class SigTrack: def __init__(self): self.counter = 0 def add(self): self.counter += 1 def count(self): return self.counter def handle_sig(self, signal, frame): log.info("Signal handler called, calling shutdown and cleanup logic") track_targets.end() sigtracker.add() log.debug("Sigtracker count:"+str(sigtracker.count())) if sigtracker.count() >= 3: log.warning("Signal handler called three times, exiting immediately") exit(1) ### ================================ ### End Define Classes ### ================================ ### -------------------------------- ### Parse arguments, setup logging ### -------------------------------- # Find full directory path of this script, used for loading config and other files cwd = path.dirname(path.abspath(__file__)) # Find current time, used for dating files now = datetime.now() nowtime = now.strftime("%Y-%m-%d-%H-%M-%S") # Configure argument parsing import argparse import ConfigParser parser = argparse.ArgumentParser(description='Vision based precision landing') parser.add_argument('--config', '-c', default=cwd+"/vision_landing.conf", help="config file location, defaults to same directory as vision_landing") parser.add_argument('--connect', help="dronekit vehicle connection target string, eg. /dev/ttyS0, tcp:localhost:5770, udp:localhost:14560") parser.add_argument('--markersize', help="Target marker size, in meters, required") parser.add_argument('--sizemapping', '-z', help="Marker Size Mappings, in marker_id:size format, comma separated") parser.add_argument('--markerhistory', help="Marker tracking history, in frames, defaults to 15") parser.add_argument('--markerthreshold', help="Marker tracking threshold, in percentage, defaults to 50") parser.add_argument('--calibration', help="camera calibration data, required") parser.add_argument('--input', '-i', default="/dev/video0", help="camera input, defaults to /dev/video0") parser.add_argument('--output', '-o', help="gstreamer output pipeline, defaults to none") parser.add_argument('--markerdict', '-d', default="ARUCO_MIP_36h12", help="Target marker dictionary, defaults to ARUCO_MIP_36h12") parser.add_argument('--markerid', '-id', help="Target ID (optional, if not specified will use closest target)") parser.add_argument('--simulator', '-s', action='store_true', help="Perform initial simulator actions for testing, takeoff and initiate land") parser.add_argument('--width', '-w', help="Video Input Resolution - Width") parser.add_argument('--height', '-g', help="Video Input Resolution - Height") parser.add_argument('--fps', '-f', help="Video Output FPS - Kludge factor") parser.add_argument('--verbose', '-v', action='store_true', help="Verbose/Debug output") parser.add_argument('--brightness', '-b', help="Camera Brightness/Gain") parser.add_argument('--fourcc', '-u', help="Specify FourCC codec") parser.add_argument('--fakerangefinder', '-r', action='store_true', help="Fake RangeFinder Data") parser.add_argument('--logdir', '-l', help="Log directory, if not specified will log to stdout") parser.add_argument('--controlprocessing', '-p', action='store_true', help="Control Vision Processing - enable/disable based on arming status and landing/precloiter mode") parser.add_argument('--estimator', '-e', help="ACPrecLand estimator, 0=Raw, 1=EKF. Defaults to 0 (Raw)") args = parser.parse_args() # First parse config file, and set defaults defaults = {} if path.isfile(args.config): config = ConfigParser.SafeConfigParser() config.read([args.config]) for key, value in config.items("Defaults"): defaults[key] = get_config_value(config, "Defaults", key) parser.set_defaults(**defaults) args = parser.parse_args() else: print print "Error: Config file "+str(args.config)+" does not exist" print exit(1) # If we don't have the mandatory arguments, exit if not args.calibration or not args.markersize or not args.connect: print if not args.calibration: print "Error: missing required argument 'calibration'" if not args.markersize: print "Error: missing required argument 'markersize'" if not args.connect: print "Error: missing required argument 'connect'" print parser.print_usage() exit(1) # Setup logging console = logging.StreamHandler() if args.logdir: # If logdir specified, create if it doesn't exist if not path.exists(args.logdir): makedirs(args.logdir) # Add timestamped logfile out logging.basicConfig(filename=args.logdir+'/vision_landing.'+nowtime+'.log', format='%(asctime)s %(levelname)s %(message)s', level=logging.DEBUG) # Create handly symlink to current logfile if path.exists(args.logdir+'/last.log'): remove(args.logdir+'/last.log') symlink(args.logdir+'/vision_landing.'+nowtime+'.log', args.logdir+'/last.log') else: logging.basicConfig(format='%(asctime)s %(levelname)s %(message)s', level=logging.DEBUG) log = logging.getLogger(__name__) # Check if calibration data exists if path.isfile(cwd+"/calibration/"+args.calibration): calibration = cwd+"/calibration/"+args.calibration elif path.isfile(args.calibration): calibration = args.calibration else: log.critical("Error: specified calibration does not exist.") exit(1) ### -------------------------------- ### Start track_targets CV process ### and attach threaded reader ### -------------------------------- # Check track_targets exists if not path.isfile(cwd+"/track_targets"): log.critical("Error: track_targets does not exist. Please run 'make install' in src/ directory") exit(1) # Run the vision tracker as a thread try: track_targets = TrackTargets(args, calibration) sleep(1) except Exception as error: log.critical("Error starting track_targets:"+ str(error)) exit(1) track_targets.process.poll() if track_targets.process.returncode != None: log.critical("Error starting track_targets: ".format(track_targets.process.returncode)) exit(1) # Define a function that stops and clears up cv process def cleanup(): # Do a final check to see if tracker process still running, try to shut down if so track_targets.process.poll() if track_targets.process.returncode == None: track_targets.end() # Close connection to the drone try: craft.vehicle.close() except: pass ### -------------------------------- ### Start up procedure - setup signal handlers, ### connect to drone, start syncing time with drone, ### setup drone parameters ### -------------------------------- # Setup signal handlers sigtracker = SigTrack() signal.signal(signal.SIGINT, sigtracker.handle_sig) signal.signal(signal.SIGTERM, sigtracker.handle_sig) # Connect to the Vehicle log.info("Connecting to drone on: %s" % args.connect) craft = Craft(args.connect) if not craft.connected: log.critical("Error: Could not connect to drone") cleanup() exit(1) else: log.info("Connected to drone") # Create a new TrackTime object to try and keep sync with the flight controller log.info("Starting time synchronisation with flight controller") tracktime = TrackTime(craft) tracktime.debug = False # Perform the initial sync with the flight controller. This blocks until the sync is complete and good enough. while True: tracktime.initial_sync() if not tracktime.delta: log.warning("Timesync not supported by flight controller. THIS CAN LEAD TO DANGEROUS AND UNPREDICTABLE BEHAVIOUR.") break log.info("Initial timesync complete, offset is {} ms".format(tracktime.delta/1000000)) log.info("Initial timesync difference is {} ms".format(tracktime.difference/1000000)) log.info("Initial timesync delta buffer: {}".format(list(tracktime.delta_buffer))) _dvariance = map(lambda x: (x - tracktime.delta)**2, tracktime.delta_buffer) _variance = sum(_dvariance) * 1.0 / len(_dvariance) # Calculate standard deviation of delta (latency) variance # A median standard deviation would probably be better here to represent jitter stddev = round((_variance ** 0.5 / 1000000), 2) jitterpercent = round((stddev / (tracktime.delta/1000000)) * 100, 2) log.info("Initial timesync jitter (standard deviation of delta buffer): {} ms, {}% of average latency".format(stddev, jitterpercent)) if tracktime.delta/1000000 >= 40: log.warning("Error: Timesync not good enough, trying again") tracktime.delta_buffer.clear() # Clear the buffer to force a fresh resync continue else: break if jitterpercent > 25: log.info("WARNING: Timesync jitter is very high. This will signficantly affect video frame -> inertial frame correlation.") # Set some parameters important to precision landing log.info("Setting flight controller parameters") craft.vehicle.parameters['PLND_ENABLED'] = 1 craft.vehicle.parameters['PLND_TYPE'] = 1 # Mavlink landing backend # Set estimator type to 'raw', as ekf estimator can be very erratic try: if 'PLND_EST_TYPE' in craft.vehicle.parameters: try: craft.vehicle.parameters['PLND_EST_TYPE'] = int(args.estimator) log.info("plnd estimator: {}, {}".format(craft.vehicle.parameters['PLND_EST_TYPE'], args.estimator)) except Exception as e: log.info("plnd estimator error: {} - setting estimator to type 0".format(repr(e))) craft.vehicle.parameters['PLND_EST_TYPE'] = 0 except: pass # Set the precland buffer to 250ms. This should give enough buffer space for even very slow computers try: if 'PLND_BUFFER' in craft.vehicle.parameters: craft.vehicle.parameters['PLND_BUFFER'] = 250 except: pass if args.fakerangefinder: # Following are for mavlink based rangefinder (not needed for 3.5-rc2+) craft.vehicle.parameters['RNGFND_TYPE'] = 10 craft.vehicle.parameters['RNGFND_MIN_CM'] = 1 craft.vehicle.parameters['RNGFND_MAX_CM'] = 10000 craft.vehicle.parameters['RNGFND_GNDCLEAR'] = 5 log.info("Faking RangeFinder data with distance_sensor messages") # If simulator option set, perform initial takeoff and initiate land if args.simulator: if args.fakerangefinder: # Following are for SITL rangefinder craft.vehicle.parameters['RNGFND_TYPE'] = 1 craft.vehicle.parameters['RNGFND_MIN_CM'] = 0 craft.vehicle.parameters['RNGFND_MAX_CM'] = 4000 craft.vehicle.parameters['RNGFND_PIN'] = 0 craft.vehicle.parameters['RNGFND_SCALING'] = 12.12 # Take off to 25m altitude and start landing if not already armed if not craft.vehicle.armed: craft.arm_and_takeoff(100) # Start landing log.info("Starting landing...") craft.vehicle.mode = VehicleMode("LAND") # Clear the vision tracking queue, we don't want to blast mavlink messages for everything stacked up while True: line = track_targets.reader.readline() if not line: break elif not search("^target:", line): if search("^error:", line): log.error("track_targets: "+sub("^error:","",line)) # Make sure to catch and process initcomp if it's in this initial queue elif search("initcomp", line): track_targets.processline(line) else: log.info("track_targets: "+line) ### -------------------------------- ### Main Loop ### Monitor for landing/precloiter mode ### Listen for incoming cv tracking results ### -------------------------------- log.info("Entering main tracking loop") loop_counter = 0 while True: # Update timesync tracktime.update() # If craft mode has changed, take action if (args.controlprocessing and (craft.vehicle.armed and (craft.vehicle.mode == "LAND" or (craft.vehicle.mode == "LOITER" and (craft.precloiter_opt and craft.vehicle.channels[str(craft.precloiter_opt)] > 1800))))) and track_targets.state == "initialised": track_targets.start() elif (args.controlprocessing and (not craft.vehicle.armed or (craft.vehicle.mode != "LAND" and (craft.vehicle.mode != "LOITER" and (craft.precloiter_opt and craft.vehicle.channels[str(craft.precloiter_opt)] <= 1800))))) and track_targets.state == "started": track_targets.stop() elif not args.controlprocessing and track_targets.state == "initialised": track_targets.start() # See if there are any tracking results in the queue #log.debug("Main loop: Before readline: {:.0f}".format(monotonic_time())) line = track_targets.reader.readline(1) #log.debug("Main loop: After readline: {:.0f}".format(monotonic_time())) if line: if args.verbose: log.debug("queue size:{}, ourtime:{:.0f}, line:{}".format(track_targets.reader.size(), monotonic_time(), line)) track_targets.processline(line) #log.debug("Main loop: After processline: {:.0f}".format(monotonic_time())) else: # Add a short 100ms sleep to slow down the loop, otherwise it consumes 100% cpu. log.debug("Main loop queue read empty, sleeping for a few ms") sleep(0.1) if args.simulator and not craft.vehicle.armed and not track_targets.shutdown: log.info("Landed") track_targets.end() track_targets.process.poll() # Poll the track_targets process and populate returncode, exit main loop when track_targets shut down if track_targets.process.returncode != None and track_targets.shutdown: log.info("Tracking process return code:"+str(track_targets.process.returncode)+", exiting main loop") break elif track_targets.process.returncode != None and not track_targets.shutdown and track_targets.state == "started": log.error("Error: Tracking process shut down unexpectedly ("+str(track_targets.process.returncode)+"), restarting") track_targets = TrackTargets(args, calibration) loop_counter += 1 cleanup() log.info("Vision_landing shutdown complete, exiting") exit(track_targets.process.returncode) ================================================ FILE: vision_landing.service ================================================ [Unit] Description=Vision Landing System [Service] ExecStart=/usr/local/vision_landing/vision_landing TimeoutStartSec=0 [Install] WantedBy=multi-user.target