diff --git a/.circleci/config.yml b/.circleci/config.yml index ffa2367d80..c12d6bd149 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -5,19 +5,83 @@ jobs: - image: circleci/python:3-stretch-node steps: - checkout + - run: git submodule sync + - run: git submodule update --init - setup_remote_docker: docker_layer_caching: true + - restore_cache: + keys: + - v1-{{ .Branch }} + - v1- + paths: + - ~/caches/revolve.tar + - run: + name: Load Docker image layer cache + command: | + set +o pipefail + docker load -i ~/caches/revolve.tar | true - run: name: "Build Docker image" - command: docker build -t cigroup/revolve:$CIRCLE_BRANCH . + command: docker build --cache-from=app -t cigroup/revolve:${CIRCLE_BRANCH//\//_} . +# - run: +# name: "Build documentation" +# command: | +# DOXY_BUILD=/revolve/docker/make_dosc.sh +# docker run -it cigroup/revolve:${CIRCLE_BRANCH//\//_} ${DOXY_BUILD} + - run: + name: Save Docker image layer cache + command: | + mkdir -p ~/caches + docker save -o ~/caches/revolve.tar cigroup/revolve:${CIRCLE_BRANCH//\//_} + - save_cache: + key: v1-{{ .Branch }}-{{ epoch }} + paths: + - ~/caches/revolve.tar + test: + docker: + - image: circleci/python:3-stretch-node + + steps: + - setup_remote_docker: + docker_layer_caching: true + - restore_cache: + keys: + - v1-{{ .Branch }} + paths: + - ~/caches/revolve.tar + - run: + name: Load Docker image layer cache + command: | + set +o pipefail + docker load -i ~/caches/revolve.tar | true - run: name: "Run Python tests" command: | PY_TESTS=/revolve/docker/test_python.sh - docker run -it cigroup/revolve:$CIRCLE_BRANCH ${PY_TESTS} + docker run -it cigroup/revolve:${CIRCLE_BRANCH//\//_} ${PY_TESTS} + + deploy: + docker: + - image: circleci/python:3-stretch-node + + steps: + - setup_remote_docker: + docker_layer_caching: true + + - restore_cache: + keys: + - v1-{{ .Branch }} + paths: + - ~/caches/revolve.tar + + - run: + name: Load Docker image layer cache + command: | + set +o pipefail + docker load -i ~/caches/revolve.tar | true - run: name: "Save Docker image" @@ -25,10 +89,22 @@ jobs: set -e TAG=0.1.$CIRCLE_BUILD_NUM docker login -u $DOCKER_USER -p $DOCKER_PASS - docker push cigroup/revolve:$CIRCLE_BRANCH + docker push cigroup/revolve:${CIRCLE_BRANCH//\//_} -# - run: -# name: "Build documentation" -# command: | -# DOXY_BUILD=/revolve/docker/make_dosc.sh -# docker run -it cigroup/revolve:$CIRCLE_BRANCH ${DOXY_BUILD} +workflows: + version: 2 + build_test_deploy: + jobs: + - build + - test: + requires: + - build + - deploy: + requires: + - build + - test + filters: + branches: + only: + - master + - development diff --git a/.gitignore b/.gitignore index ab595133d7..2d71a28844 100644 --- a/.gitignore +++ b/.gitignore @@ -45,6 +45,8 @@ htmlcov/ nosetests.xml coverage.xml *,cover +experiments/examples/output/ +test.py # Translations *.mo @@ -67,8 +69,10 @@ target/ # Virtual env .venv*/ +.python-version +Pipfile +Pipfile.lock # Revolve related *.sdf -*.urdf -*.yaml +*.urdf \ No newline at end of file diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000000..c8afd881e1 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "thirdparty/limbo"] + path = thirdparty/limbo + url = https://github.com/resibots/limbo.git diff --git a/ACKNOWLEDGMENTS b/ACKNOWLEDGMENTS deleted file mode 100644 index 2cc3567fce..0000000000 --- a/ACKNOWLEDGMENTS +++ /dev/null @@ -1,15 +0,0 @@ -Software License Agreement (Apache License) - -Copyright (C) 2015 Vrije Universiteit Amsterdam - -Licensed under the Apache License, Version 2.0 (the "License"); -you may not use this file except in compliance with the License. -You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - -Unless required by applicable law or agreed to in writing, software -distributed under the License is distributed on an "AS IS" BASIS, -WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -See the License for the specific language governing permissions and -limitations under the License. diff --git a/AUTHORS b/AUTHORS deleted file mode 100644 index 5416d23167..0000000000 --- a/AUTHORS +++ /dev/null @@ -1,23 +0,0 @@ -# This is the official list of Revolve authors. - -# Names should be added to this file as: -# Name or Organization -# The email address is not required for organizations. - -# Organisations supporting the project -Vrije Universiteit Amsterdam - -# Original author -Elte Hupkes - -# Major developers -Milan Jelisavcic -Matteo De Carlo - -# Other contributors -Dmitriy Egorov -Gongjin Lan -Jakub Orlowski -Karine Miras -Panagiotis Eustratiadis -Rafael Kiesel diff --git a/CMakeLists.txt b/CMakeLists.txt index 43bbd6191c..d07590dc81 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,4 +2,8 @@ cmake_minimum_required(VERSION 2.8.12) project(revolve) +if (BUILD_RASPBERRY) + add_subdirectory(thirdparty/PIGPIO) +endif() + add_subdirectory(cpprevolve) \ No newline at end of file diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md deleted file mode 100644 index 8989646f95..0000000000 --- a/CONTRIBUTING.md +++ /dev/null @@ -1,120 +0,0 @@ -A tool is provided in Revolve (and other repositories) to check for correct style. Your code must have no errors after running the following command from the root of the source tree: - -```bash -sh tools/code_check.sh -``` - -The tool does not catch all style errors. See the Style section below for more information. - -## Ten Tips for Clean Code -1. You are responsible for the quality of your code -1. When writing code, use meaningful names -1. Write code that expresses the intent -1. Comments are often lies waiting to happen -1. Leave your code better than you found it -1. Single responsibility principle (every method/function should do only one thing) -1. Write tests -1. Work in short cycles: incremental and iterative -1. Independent architecture -1. Practice, practice, practice - -## Coding Rules - -1. Write tests - > A pull request will only be accepted if it has tested. See the Test coverage section below for more information. - -2. Compiler warnings - > Code must have zero compile warnings. This currently only applies to Linux. - -3. Documentation - > Document all your code. Every class, function, member variable must have Doxygen comments. All code in source files must have documentation that describes the functionality. This will help reviewers and future developers. - -4. Small commits - > A large pull request is hard to review and will take a long time. It is worth your time to split a large pull request into multiple smaller pull requests. - - -## Style - -1. `this` pointer - -> All class attributes and member functions must be accessed using the this-> pointer. Here is an example. - -2. Underscore function parameters - -> All function parameters must start with an underscore. Here is an example. - -3. Do not cuddle braces - -> All braces must be on their own line. Here is an example. - -4. Multi-line code blocks - -> If a block of code spans multiple lines and is part of a flow control statement, such as an `if`, then it must be wrapped in braces. Here is an example - -5. `++` operator - -> This occurs mostly in for loops. Prefix the `++` operator, which is slightly more efficient than postfix in some cases. - -6. PIMPL/Opaque pointer - -> If you are writing a new class, it must use a private data pointer. Here is an example, and you can read more here. - -7. `const` functions - -> Any class function that does not change a member variable should be marked as `const`. Here is an example. - -8. `const` parameters - -> All parameters that are not modified by a function should be marked as `const`. This applies to parameters that are passed by reference, pointer, and value. Here is an example. - -9. Pointer and reference variables - -> Place the `*` and `&` next to the variable name, not next to the type. For example: `int &variable` is good, but `int&` variable is not. Here is an example. - -10. Camel case - -> In general, everything should use camel case. Exceptions include `SDF` element names, and `protobuf` variable names. Here is an example. - -11. Class function names - -> Class functions must start with a capital letter, and capitalize every word. -> -> `void MyFunction();` : Good -> -> `void myFunction();` : Bad -> -> `void my_function();` : Bad - -12. Variable names - -> Variables must start with a lower case letter, and capitalize every word thereafter. -> -> `int myVariable;` : Good -> -> `int myvariable;` : Bad -> -> `int my_variable;` : Bad - -13. No inline comments - -> `//` style comments may not be placed on the same line as code. -> -> `speed *= 0.44704; // miles per hour to meters per second` : Bad - -[gazebo-source](http://gazebosim.org/tutorials?tut=contrib_code&cat=development) - -## `git comit` message guidelines - -The seven rules of a great Git commit message - - Keep in mind: This has all been said before. - -1. Separate subject from body with a blank line -1. Limit the subject line to 50 characters -1. Capitalize the subject line -1. Do not end the subject line with a period -1. Use the imperative mood in the subject line -1. Wrap the body at 72 characters -1. Use the body to explain what and why vs. how - -[git-source](https://chris.beams.io/posts/git-commit/) diff --git a/Dockerfile b/Dockerfile index 960c4c077e..bc5005e53b 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,24 +1,19 @@ -FROM ubuntu:bionic +FROM cigroup/gazebo:gazebo10-revolve # Dependencies -RUN apt-get update -RUN apt-get install -y build-essential \ - libboost-all-dev \ +RUN apt-get update && apt-get upgrade -y && apt-get install -y \ + build-essential \ cmake \ - curl \ - cppcheck \ - doxygen \ git \ - gsl-bin libgsl0-dev \ - mercurial \ - pkg-config \ - python \ + libgsl0-dev \ python3-pip \ libyaml-cpp-dev \ - xsltproc \ - libcairo2-dev -RUN apt-get install -y libgazebo9-dev gazebo9 -RUN apt-get clean && rm -rf /var/lib/apt/lists/* + libcairo2-dev \ + graphviz \ + libeigen3-dev \ + libnlopt-dev && \ + apt-get clean && \ + rm -rf /var/lib/apt/lists/* ADD . /revolve RUN /revolve/docker/build_revolve.sh diff --git a/LICENSE b/LICENSE deleted file mode 100644 index 261eeb9e9f..0000000000 --- a/LICENSE +++ /dev/null @@ -1,201 +0,0 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. diff --git a/cpprevolve/CMakeLists.txt b/cpprevolve/CMakeLists.txt index bdc37effa1..d39c8565d7 100644 --- a/cpprevolve/CMakeLists.txt +++ b/cpprevolve/CMakeLists.txt @@ -1,236 +1,17 @@ # CMake Required Version -cmake_minimum_required (VERSION 2.8.12) +cmake_minimum_required (VERSION 3.7.0) # Project name project (Revolve) +set (CMAKE_CXX_STANDARD 11) -# Initial setups -# _____________________________________________________________________________ +# Include cmake subdirectories +add_subdirectory(revolve/brains) -# CMake flag to help local projects find the build dir -set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/../build/lib") -set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/../build/lib") -set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/../build") -set(HEADER_COPY_DIR "${CMAKE_CURRENT_SOURCE_DIR}/../build/include") - -# Copy header files to the output directory so they can be used -# by other projects in development. -file( - COPY ${CMAKE_CURRENT_SOURCE_DIR}/revolve - DESTINATION ${HEADER_COPY_DIR} - FILES_MATCHING PATTERN "*.h" -) -message("Using local build directory.") - -# Pass source dir to preprocessor -add_definitions(-DSOURCE_DIR=${CMAKE_SOURCE_DIR}) - -# Compiler options -# TODO This currently assumes GCC, add Windows support in due time -add_definitions(-pedantic -Wno-long-long -Wall -Wextra -Wformat=2 - -Wredundant-decls -Wwrite-strings -Wmissing-include-dirs - -Wswitch-enum -Wuninitialized - -Wswitch-default -Winit-self -Wfloat-equal -fPIC ) - -# Use C++11 (removed - the Gazebo flags below do this) -# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") - -# Debug Flags -set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -O0 -ggdb3 -DDEBUG") - -# Release flags -#set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -funroll-loops -finline-functions -fomit-frame-pointer -DNDEBUG") - -# MacOS X needed variables -if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin") - # adaptable according to individual needs - set(CMAKE_MACOSX_RPATH ON) - # set(CMAKE_SKIP_BUILD_RPATH FALSE) - # set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE) - # set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib") - # set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) -endif () - -# Finding dependencies -# _____________________________________________________________________________ - -# Find Boost -find_package(Boost REQUIRED COMPONENTS system) -include_directories(${Boost_INCLUDE_DIRS}) - -# Find GSL - GNU Scientific Library -find_package(GSL REQUIRED) -include_directories(${GSL_INCLUDE_DIRS}) - -find_package(yaml-cpp REQUIRED) -include_directories(${YAML_CPP_INCLUDE_DIR}) - -# Find Gazebo -# LOCAL_GAZEBO_DIR can be set to a path with a gazebo-config.cmake -if (LOCAL_GAZEBO_DIR) - find_package(gazebo 9 REQUIRED CONFIG - PATHS "${LOCAL_GAZEBO_DIR}" - NO_DEFAULT_PATH) - message(WARNING "Using local Gazebo @ ${gazebo_DIR}") -else() - find_package(gazebo 9 REQUIRED) +if (NOT BUILD_ONLY_BRAIN) + add_subdirectory(revolve/gazebo) endif() -include_directories(${GAZEBO_INCLUDE_DIRS}) -link_directories(${GAZEBO_LIBRARY_DIRS}) - -# Find Protobuf -# TODO: This part is currently a mess, and it should be handeled better -find_package(Protobuf REQUIRED) - -# Find the Protobuf import directory for Gazebo. Found in this -# tutorial: http://gazebosim.org/tutorials?tut=custom_messages&cat=transport -set(GAZEBO_PROTOBUF_DIR) -foreach(ITR ${GAZEBO_INCLUDE_DIRS}) - if(ITR MATCHES ".*gazebo-[0-9.]+$") - set(GAZEBO_PROTO_PATH "${ITR}/gazebo/msgs/proto") - set(GAZEBO_PROTO_INCLUDE "${ITR}/gazebo/msgs") - endif() -endforeach() -include_directories( - ${CMAKE_SOURCE_DIR} - ${PROTOBUF_INCLUDE_DIRS} - ${GAZEBO_PROTO_INCLUDE} -) - -# Add Gazebo C++ flags (this includes c++11) -list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}") - -# Directory where the .proto files reside within revolve -set(SPEC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/revolve/msgs") -# All protobuf files we need, including the Gazebo ones -file(GLOB_RECURSE REVOLVE_PROTOS ${SPEC_DIR}/*.proto) - -# Do the protobuf generation by hand for more flexibility. The files are -# generated in a subdirectory such that it can potentially be added to the -# include path for work-in-progress projects I co-develop with this. -# Copied most of this code from -# http://stackoverflow.com/questions/29346488/protobuf-generate-cpp-not-generating-src-and-header-files -# Also see -# https://github.com/Kitware/CMake/blob/master/Modules/FindProtobuf.cmake -set(PROTO_SRCS) -set(PROTO_HDRS) -if (HEADER_COPY_DIR) - set(PROTO_OUTPUT_BASE ${HEADER_COPY_DIR}) -else() - set(PROTO_OUTPUT_BASE ${CMAKE_CURRENT_BINARY_DIR}) +if (BUILD_RASPBERRY) + add_subdirectory(revolve/raspberry) endif() - -# Include the directory where the protobuf files will be placed -include_directories(${PROTO_OUTPUT_BASE}) - -file(MAKE_DIRECTORY ${PROTO_OUTPUT_BASE}/revolve/msgs) -foreach(RV_PROTO ${REVOLVE_PROTOS}) - get_filename_component(RV_ABS_PROTO ${RV_PROTO} ABSOLUTE) - get_filename_component(RV_NAME_PROTO ${RV_PROTO} NAME_WE) - get_filename_component(RV_DIR_PROTO ${RV_PROTO} DIRECTORY) - - list(APPEND PROTO_SRCS - "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.cc") - list(APPEND PROTO_HDRS - "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.h") - - add_custom_command( - OUTPUT "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.cc" - "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.h" - COMMAND ${PROTOBUF_PROTOC_EXECUTABLE} - ARGS -I ${RV_DIR_PROTO} - -I ${GAZEBO_PROTO_PATH} - --cpp_out ${PROTO_OUTPUT_BASE}/revolve/msgs ${RV_ABS_PROTO} - DEPENDS ${RV_ABS_PROTO} - COMMENT "Running C++ protocol buffer compiler on ${RV_PROTO}" - VERBATIM ) -endforeach() - -# Tell the compiler these files were generated -set_source_files_properties( - ${PROTO_SRCS} ${PROTO_HDRS} PROPERTIES GENERATED TRUE) - -# Source subdirectories -# _____________________________________________________________________________ - -# Plugin C++ files -file(GLOB_RECURSE - REVOLVE_GZ_SRC - revolve/gazebo/brains/*.cpp - revolve/gazebo/motors/*.cpp - revolve/gazebo/sensors/*.cpp - revolve/gazebo/util/*.cpp - revolve/gazebo/plugin/BodyAnalyzer.cpp - revolve/gazebo/plugin/RobotController.cpp - revolve/gazebo/plugin/WorldController.cpp -) - -# Generate -# _____________________________________________________________________________ -# Add the file that registers the body analyzer as a separate library that -# can be used as a world plugin directly. -# Create the library containing the Revolve API - -# Generate spec library with the messages -add_library( - revolve-proto STATIC - ${PROTO_SRCS} -) -set_target_properties(revolve-proto PROPERTIES LINKER_LANGUAGE CXX) -target_link_libraries( - revolve-proto - ${PROTOBUF_LIBRARIES} -) - -# Create Revolve bundle plugin -add_library( - revolve-gazebo - ${REVOLVE_GZ_SRC} -) -target_link_libraries( - revolve-gazebo - ${GAZEBO_LIBRARIES} - ${Boost_LIBRARIES} - ${GSL_LIBRARIES} - ${YAML_CPP_LIBRARIES} -) - -# Create World plugin -add_library( - WorldControlPlugin SHARED - revolve/gazebo/plugin/register_world_plugin.cpp -) -target_link_libraries( - WorldControlPlugin - revolve-gazebo - revolve-proto - ${GAZEBO_LIBRARIES} -) - -# Create Robot plugin -add_library( - RobotControlPlugin SHARED - revolve/gazebo/plugin/register_robot_plugin.cpp -) -target_link_libraries( - RobotControlPlugin - revolve-gazebo - revolve-proto - ${GAZEBO_LIBRARIES} -) - -# Install -# _____________________________________________________________________________ -# Install libraries into "lib", header files into "include" - -install( - TARGETS revolve-proto revolve-gazebo - DESTINATION lib -) - -install( - DIRECTORY revolve - DESTINATION include - FILES_MATCHING PATTERN "*.h" -) diff --git a/cpprevolve/revolve/brains/CMakeLists.txt b/cpprevolve/revolve/brains/CMakeLists.txt new file mode 100644 index 0000000000..8b7f614ff7 --- /dev/null +++ b/cpprevolve/revolve/brains/CMakeLists.txt @@ -0,0 +1,45 @@ +file(GLOB_RECURSE + CONTROLLER_SRCS + controller/*.cpp + controller/actuators/*.cpp + controller/sensors/*.cpp +) +file(GLOB_RECURSE + LEARNER_SRCS + learner/*.cpp +) + +# PKG-CONFIG +find_package(PkgConfig REQUIRED) + +# Find Boost +find_package(Boost REQUIRED COMPONENTS system) + +# Find Eigen3 - A lightweight C++ template library for vector and matrix math +find_package(Eigen3 REQUIRED) + +# Find NLOpt - Non Linear Optimization +pkg_check_modules(NLOpt REQUIRED nlopt>=2.4) + +# Find Limbo - LIbrary for Model-Based Optimization +set(LIMBO_DIR ${CMAKE_SOURCE_DIR}/thirdparty/limbo) +set(LIMBO_DEFINES USE_NLOPT) + +add_library(revolve-controllers SHARED ${CONTROLLER_SRCS}) +add_library(revolve-learners SHARED ${LEARNER_SRCS}) + +target_include_directories(revolve-controllers + PUBLIC ${EIGEN3_INCLUDE_DIR} + PUBLIC ${Boost_INCLUDE_DIRS}) + +target_include_directories(revolve-learners + PUBLIC ${Boost_INCLUDE_DIRS} + PUBLIC ${LIMBO_DIR}/src + PUBLIC ${NLOpt_INCLUDE_DIRS}) + +target_include_directories(revolve-learners + PUBLIC ${NLOpt_LIBRARY_DIRS}) + +install(TARGETS revolve-controllers revolve-learners + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib) \ No newline at end of file diff --git a/cpprevolve/revolve/brains/controller/Controller.h b/cpprevolve/revolve/brains/controller/Controller.h new file mode 100644 index 0000000000..1512af0d3a --- /dev/null +++ b/cpprevolve/revolve/brains/controller/Controller.h @@ -0,0 +1,36 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_CONTROLLER_H +#define REVOLVE_CONTROLLER_H + +#include "actuators/Actuator.h" +#include "sensors/Sensor.h" +#include +#include + +namespace revolve +{ + +class Controller +{ +public: + /// \brief Constructor + explicit Controller() {} + + /// \brief Deconstructor + virtual ~Controller() {} + + virtual void update( + const std::vector< std::unique_ptr< Actuator > > &_actuators, + const std::vector< std::unique_ptr< Sensor > > &_sensors, + const double _time, + const double _step + ) = 0; +}; + +} + + +#endif //REVOLVE_CONTROLLER_H diff --git a/cpprevolve/revolve/brains/controller/DifferentialCPG.cpp b/cpprevolve/revolve/brains/controller/DifferentialCPG.cpp new file mode 100644 index 0000000000..bba9ce77dc --- /dev/null +++ b/cpprevolve/revolve/brains/controller/DifferentialCPG.cpp @@ -0,0 +1,457 @@ +/* + * Copyright (C) 2015-2018 Vrije Universiteit Amsterdam + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + * Description: TODO: + * Author: Milan Jelisavcic & Maarten van Hooft + * Date: December 29, 2018 + * + */ + +#include "DifferentialCPG.h" + +// STL macros +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Project headers +#include "actuators/Actuator.h" + +#include "sensors/Sensor.h" + +// TODO: Resolve odd behaviour at the end of the validation procedure +// This behaviour is not present if you directly load a trained controller + +// Define namespaces +using namespace revolve; + +/** + * Constructor for DifferentialCPG class. + * + * @param _model + * @param robot_config + */ +DifferentialCPG::DifferentialCPG( + const DifferentialCPG::ControllerParams ¶ms, + const std::vector< std::unique_ptr< Actuator > > &actuators) + : next_state(nullptr) + , n_motors(actuators.size()) + , output(new double[actuators.size()]) +{ + // Controller parameters + this->reset_neuron_random = params.reset_neuron_random; + this->init_neuron_state = params.init_neuron_state; + this->range_lb = -params.range_ub; + this->range_ub = params.range_ub; + this->use_frame_of_reference = params.use_frame_of_reference; + this->signal_factor_all_ = params.signal_factor_all; + this->signal_factor_mid = params.signal_factor_mid; + this->signal_factor_left_right = params.signal_factor_left_right; + this->abs_output_bound = params.abs_output_bound; + + size_t j=0; + for (const std::unique_ptr &actuator: actuators) + { + // Pass coordinates + auto coord_x = actuator->coordinate_x(); + auto coord_y = actuator->coordinate_y(); + this->motor_coordinates[{coord_x, coord_y}] = j; + + // Set frame of reference + int frame_of_reference = 0; + // We are a left neuron + if (coord_x < 0) + { + frame_of_reference = -1; + } + // We are a right neuron + else if (coord_x > 0) + { + frame_of_reference = 1; + } + + // Save neurons: bias/gain/state. Make sure initial states are of different sign. + this->neurons[{coord_x, coord_y, 1}] = {0.f, 0.f, this->init_neuron_state, frame_of_reference}; //Neuron A + this->neurons[{coord_x, coord_y, -1}] = {0.f, 0.f, -this->init_neuron_state, frame_of_reference}; // Neuron B + j++; + } + + // Add connections between neighbouring neurons + int i = 0; + for (const std::unique_ptr &actuator: actuators) + { + // Get name and x,y-coordinates of all neurons. + double x = actuator->coordinate_x(); + double y = actuator->coordinate_y(); + + // Continue to next iteration in case there is already a connection between the 1 and -1 neuron. + // These checks feel a bit redundant. + // if A->B connection exists. + if (this->connections.count({x, y, 1, x, y, -1}) > 0) + { + continue; + } + // if B->A connection exists: + if (this->connections.count({x, y, -1, x, y, 1}) > 0) + { + continue; + } + + // Loop over all positions. We call it neighbours, but we still need to check if they are a neighbour. + for (const std::unique_ptr &neighbour: actuators) + { + // Get information of this neuron (that we call neighbour). + double near_x = neighbour->coordinate_x(); + double near_y = neighbour->coordinate_y(); + + // If there is a node that is a Moore neighbour, we set it to be a neighbour for their A-nodes. + // Thus the connections list only contains connections to the A-neighbourhood, and not the + // A->B and B->A for some node (which makes sense). + double dist_x = std::fabs(x - near_x); + double dist_y = std::fabs(y - near_y); + + // TODO: Verify for non-spiders + if (std::fabs(dist_x + dist_y - 2) < 0.01) + { + if(std::get<0>(this->connections[{x, y, 1, near_x, near_y, 1}]) != 1 or + std::get<0>(this->connections[{near_x, near_y, 1, x, y, 1}]) != 1) + { + this->connections[{x, y, 1, near_x, near_y, 1}] = std::make_tuple(1, i); + this->connections[{near_x, near_y, 1, x, y, 1}] = std::make_tuple(1, i); + i++; + } + } + } + } + + // Initialise array of neuron states for Update() method + this->next_state = new double[this->neurons.size()]; + this->n_weights = (int)(this->connections.size()/2) + this->n_motors; + + // Loading Brain + + // Save weights for brain + assert(params.weights.size() == this->n_weights); + this->sample.resize(this->n_weights); + for(size_t j = 0; j < this->n_weights; j++) + { + this->sample(j) = params.weights.at(j); + } + + // Set ODE matrix at initialization + this->set_ode_matrix(); + + std::cout << "Brain has been loaded." << std::endl; +} + +/** + * Destructor + */ +DifferentialCPG::~DifferentialCPG() +{ + delete[] this->next_state; + delete[] this->output; +} + +/** + * Callback function that defines the movement of the robot + * + * @param _motors + * @param _sensors + * @param _time + * @param _step + */ +void DifferentialCPG::update( + const std::vector< std::unique_ptr < Actuator > > &actuators, + const std::vector< std::unique_ptr < Sensor > > &sensors, + const double time, + const double step) +{ + // Send new signals to the motors + this->step(time, step); + + unsigned int p = 0; + for (const auto &actuator: actuators) + { + actuator->write(this->output + p, step); + p += actuator->n_outputs(); + } +} + +/** + * Make matrix of weights A as defined in dx/dt = Ax. + * Element (i,j) specifies weight from neuron i to neuron j in the system of ODEs + */ +void DifferentialCPG::set_ode_matrix(){ + // Initiate new matrix + std::vector> matrix; + + // Fill with zeroes + for(size_t i =0; i neurons.size(); i++) + { + // Initialize row in matrix with zeros + std::vector< double > row; + for (size_t j = 0; j < this->neurons.size(); j++) + { + row.push_back(0); + } + matrix.push_back(row); + } + + // Process A<->B connections + int index = 0; + for(size_t i =0; i neurons.size(); i++) + { + // Get correct index + int c = 0; + if (i%2 == 0){ + c = i + 1; + } + else{ + c = i - 1; + } + + // Add a/b connection weight + index = (int)(i/2); + auto w = this->sample(index) * + (this->range_ub - this->range_lb) + this->range_lb; + matrix[i][c] = w; + matrix[c][i] = -w; + } + + // A<->A connections + index++; + int k = 0; + std::vector connections_seen; + + for (auto const &connection : this->connections) + { + // Get connection information + int x1, y1, z1, x2, y2, z2; + std::tie(x1, y1, z1, x2, y2, z2) = connection.first; + + // Find location of the two neurons in this->neurons list + int l1 = -1; + int l2 = -1; + int c = 0; + for(auto const &neuron : this->neurons) + { + int x, y, z; + std::tie(x, y, z) = neuron.first; + if (x == x1 and y == y1 and z == z1) + { + l1 = c; + } + else if (x == x2 and y == y2 and z == z2) + { + l2 = c; + } + // Update counter + c++; + } + + // Add connection to seen connections + if(l1 > l2) + { + int l1_old = l1; + l1 = l2; + l2 = l1_old; + } + std::string connection_string = std::to_string(l1) + "-" + std::to_string(l2); + + // if not in list, add to list + auto connections_list = std::find(connections_seen.begin(), connections_seen.end(), connection_string); + if(connections_list == connections_seen.end()) + { + connections_seen.push_back(connection_string); + } + // else continue to next iteration + else{ + continue; + } + + // Get weight + auto w = this->sample(index + k) * + (this->range_ub - this->range_lb) + this->range_lb; + + // Set connection in weight matrix + matrix[l1][l2] = w; + matrix[l2][l1] = -w; + k++; + } + + // Update matrix + this->ode_matrix = matrix; + + // Reset neuron state + this->reset_neuron_state(); +} + + +/** + * Set states back to original value (that is on the unit circle) + */ +void DifferentialCPG::reset_neuron_state(){ + int c = 0; + for(auto const &neuron : this->neurons) + { + // Get neuron properties + int x, y, z, frame_of_reference; + double bias ,gain ,state; + std::tie(x, y, z) = neuron.first; + std::tie(bias, gain, state, frame_of_reference) = neuron.second; + + if (z == -1) + { + // Neuron B + if (this->reset_neuron_random) + { + this->neurons[{x, y, z}] = {0.f, + 0.f, + ((double) rand() / (RAND_MAX))*2*this->init_neuron_state - this->init_neuron_state, + frame_of_reference}; + } + else + { + this->neurons[{x, y, z}] = {0.f, 0.f, -this->init_neuron_state, frame_of_reference}; + } + } + else + { + // Neuron A + if (this->reset_neuron_random) + { + this->neurons[{x, y, z}] = {0.f, + 0.f, + ((double) rand() / (RAND_MAX))*2*this->init_neuron_state - this->init_neuron_state, + frame_of_reference}; + } + else + { + this->neurons[{x, y, z}] = {0.f, 0.f, +this->init_neuron_state, frame_of_reference}; + } + } + c++; + } +} + +/** + * Step function that is called from within Update() + * + * @param _time + * @param _output + */ +void DifferentialCPG::step( + const double time, + const double dt) +{ + int neuron_count = 0; + for (const auto &neuron : this->neurons) + { + // Neuron.second accesses the second 3-tuple of a neuron, containing the bias/gain/state. + double recipient_bias, recipient_gain, recipient_state; + int frame_of_reference; + std::tie(recipient_bias, recipient_gain, recipient_state, frame_of_reference) = neuron.second; + + // Save for ODE + this->next_state[neuron_count] = recipient_state; + neuron_count++; + } + + // Copy values from next_state into x for ODEINT + state_type x(this->neurons.size()); + for (size_t i = 0; i < this->neurons.size(); i++) + { + x[i] = this->next_state[i]; + } + + // Perform one step + stepper.do_step( + [this](const state_type &x, state_type &dxdt, double t) + { + for(size_t i = 0; i < this->neurons.size(); i++) + { + dxdt[i] = 0; + for(size_t j = 0; j < this->neurons.size(); j++) + { + dxdt[i] += x[j]*this->ode_matrix[j][i]; + } + } + }, + x, + time, + dt); + + // Copy values into nextstate + for (size_t i = 0; i < this->neurons.size(); i++) + { + this->next_state[i] = x[i]; + } + + // Loop over all neurons to actually update their states. Note that this is a new outer for loop + auto i = 0; auto j = 0; + for (auto &neuron : this->neurons) + { + // Get bias gain and state for this neuron. Note that we don't take the coordinates. + // However, they are implicit as their order did not change. + double bias, gain, state; + int frame_of_reference; + std::tie(bias, gain, state, frame_of_reference) = neuron.second; + double x, y, z; + std::tie(x, y, z) = neuron.first; + neuron.second = {bias, gain, this->next_state[i], frame_of_reference}; + j = this->motor_coordinates[{x,y}]; + // Should be one, as output should be based on +1 neurons, which are the A neurons + if (i % 2 == 1) + { + // TODO: Add Milan's function here as soon as things are working a bit + // f(a) = (w_ao*a - bias)*gain + + // Apply saturation formula + auto x = this->next_state[i]; + + // Use frame of reference + if(use_frame_of_reference) + { + + if (std::abs(frame_of_reference) == 1) + { + this->output[j] = this->signal_factor_left_right*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } + else if (frame_of_reference == 0) + { + this->output[j] = this->signal_factor_mid*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } + else + { + std::clog << "WARNING: frame_of_reference not in {-1,0,1}." << std::endl; + } + + } + // Don't use frame of reference + else + { + this->output[j] = this->signal_factor_all_*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } + } + i++; + } +} diff --git a/cpprevolve/revolve/brains/controller/DifferentialCPG.h b/cpprevolve/revolve/brains/controller/DifferentialCPG.h new file mode 100644 index 0000000000..d223f45d9a --- /dev/null +++ b/cpprevolve/revolve/brains/controller/DifferentialCPG.h @@ -0,0 +1,142 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_DIFFERENTIALCPG_H +#define REVOLVE_DIFFERENTIALCPG_H + +#include "Controller.h" +#include "actuators/Actuator.h" +#include "sensors/Sensor.h" +#include +#include +#include + +typedef std::vector< double > state_type; + +namespace revolve +{ +class DifferentialCPG + : public Controller +{ +public: + struct ControllerParams { + bool reset_neuron_random; + bool use_frame_of_reference; + double init_neuron_state; + double range_ub; + double signal_factor_all; + double signal_factor_mid; + double signal_factor_left_right; + double abs_output_bound; + std::vector< double > weights; + }; + + /// \brief Constructor + /// \param[in] _modelName Name of the robot + /// \param[in] _node The brain node + /// \param[in] _motors Reference to a motor list, it be reordered + /// \param[in] _sensors Reference to a sensor list, it might be reordered + DifferentialCPG( + const ControllerParams ¶ms, + const std::vector< std::unique_ptr < Actuator > > &_actuators); + + /// \brief Destructor + virtual ~DifferentialCPG(); + + /// \brief The default update method for the controller + /// \param[in] _motors Motor list + /// \param[in] _sensors Sensor list + /// \param[in] _time Current world time + /// \param[in] _step Current time step + virtual void update( + const std::vector< std::unique_ptr < Actuator > > &actuators, + const std::vector< std::unique_ptr < Sensor > > &sensors, + const double _time, + const double _step) override; + +protected: + + void step( + const double time, + const double step); + + void set_ode_matrix(); + +private: + /// \brief Function that resets neuron state + void reset_neuron_state(); + +public: + std::map< std::tuple< double, double >, size_t > motor_coordinates; + +protected: + /// \brief Register of motor IDs and their x,y-coordinates +// std::map< std::string, std::tuple< int, int > > positions; + + /// \brief Register of individual neurons in x,y,z-coordinates + /// \details x,y-coordinates define position of a robot's module and + // z-coordinate define A or B neuron (z=1 or -1 respectively). Stored + // values are a bias, gain, state and frame of reference of each neuron. + std::map< std::tuple< int, int, int >, std::tuple< double, double, double, int > > + neurons; + + /// \brief Register of connections between neighnouring neurons + /// \details Coordinate set of two neurons (x1, y1, z1) and (x2, y2, z2) + // define a connection. The second tuple contains 1: the connection value and + // 2: the weight index corresponding to this connection. + std::map< std::tuple< int, int, int, int, int, int >, std::tuple > + connections; + + /// \brief Runge-Kutta 45 stepper + boost::numeric::odeint::runge_kutta4< state_type > stepper; + + /// \brief Used for ODE-int + std::vector> ode_matrix; + +private: + /// \brief Used to determine the next state array + double *next_state; + + /// \brief Used to determine the output to the motors array + double *output; + + /// \brief Limbo optimizes in [0,1] + double range_lb; + + /// \brief Limbo optimizes in [0,1] + double range_ub; + + /// \brief Loaded sample + Eigen::VectorXd sample; + + /// \brief The number of weights to optimize + size_t n_weights; + + /// \brief Factor to multiply output signal with + double signal_factor_all_; + + /// \brief Factor to multiply output signal with + double signal_factor_mid; + + /// \brief Factor to multiply output signal with + double signal_factor_left_right; + + /// \brief When reset a neuron state,do it randomly: + bool reset_neuron_random; + + /// \brief Holds the number of motors in the robot + size_t n_motors; + + /// \brief Initial neuron state + double init_neuron_state; + + /// \brief Use frame of reference {-1,0,1} version or not + bool use_frame_of_reference; + + double abs_output_bound; +}; + +} + +#endif //REVOLVE_DIFFERENTIALCPG_H diff --git a/cpprevolve/revolve/brains/controller/actuators/Actuator.h b/cpprevolve/revolve/brains/controller/actuators/Actuator.h new file mode 100644 index 0000000000..e8bf932cec --- /dev/null +++ b/cpprevolve/revolve/brains/controller/actuators/Actuator.h @@ -0,0 +1,39 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_ACTUATOR_H +#define REVOLVE_ACTUATOR_H + +#include + +namespace revolve { + +class Actuator +{ +public: + explicit Actuator(unsigned int n_outputs, double x, double y, double z) + : Actuator(n_outputs, {x,y,z}) + {} + explicit Actuator(unsigned int n_outputs, const std::tuple coordinates) + : _n_outputs(n_outputs) + , coordinates(coordinates) + {} + + inline double coordinate_x() const { return std::get<0>(this->coordinates); } + inline double coordinate_y() const { return std::get<1>(this->coordinates); } + inline double coordinate_z() const { return std::get<2>(this->coordinates); } + + virtual void write(const double *output, double step) = 0; + + inline unsigned int n_outputs() const {return this->_n_outputs;} + +private: + const unsigned int _n_outputs; + const std::tuple coordinates; +}; + +} + + +#endif //REVOLVE_ACTUATOR_H diff --git a/cpprevolve/revolve/brains/controller/sensors/Sensor.h b/cpprevolve/revolve/brains/controller/sensors/Sensor.h new file mode 100644 index 0000000000..496e54bf5f --- /dev/null +++ b/cpprevolve/revolve/brains/controller/sensors/Sensor.h @@ -0,0 +1,30 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_SENSOR_H +#define REVOLVE_SENSOR_H + +namespace revolve { + +class Sensor +{ +public: + explicit Sensor(unsigned int n_inputs) + : _n_inputs(n_inputs) + {} + + /// \brief Read the value of the sensor into the + /// \param[in] _input: array. + /// \brief[in,out] _input Input value to write on + virtual void read(double *input) = 0; + + inline unsigned int n_inputs() const {return this->_n_inputs;} + +private: + const unsigned int _n_inputs; +}; + +} + +#endif //REVOLVE_SENSOR_H diff --git a/cpprevolve/revolve/brains/learner/BayesianOptimizer.cpp b/cpprevolve/revolve/brains/learner/BayesianOptimizer.cpp new file mode 100644 index 0000000000..a0615ea638 --- /dev/null +++ b/cpprevolve/revolve/brains/learner/BayesianOptimizer.cpp @@ -0,0 +1,5 @@ +// +// Created by matteo on 14/06/19. +// + +#include "BayesianOptimizer.h" diff --git a/cpprevolve/revolve/brains/learner/BayesianOptimizer.h b/cpprevolve/revolve/brains/learner/BayesianOptimizer.h new file mode 100644 index 0000000000..15fcaa2621 --- /dev/null +++ b/cpprevolve/revolve/brains/learner/BayesianOptimizer.h @@ -0,0 +1,14 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_BAYESIANOPTIMIZER_H +#define REVOLVE_BAYESIANOPTIMIZER_H + + +class BayesianOptimizer { + +}; + + +#endif //REVOLVE_BAYESIANOPTIMIZER_H diff --git a/cpprevolve/revolve/gazebo/CMakeLists.txt b/cpprevolve/revolve/gazebo/CMakeLists.txt new file mode 100644 index 0000000000..d55ef2abab --- /dev/null +++ b/cpprevolve/revolve/gazebo/CMakeLists.txt @@ -0,0 +1,277 @@ +# Initial setups +# _____________________________________________________________________________ + +# CMake flag to help local projects find the build dir +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_SOURCE_DIR}/build/lib") +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_SOURCE_DIR}/build/lib") +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_SOURCE_DIR}/build") + +include_directories(${CMAKE_SOURCE_DIR}/cpprevolve) + +# Pass source dir to preprocessor +add_definitions(-DSOURCE_DIR=${CMAKE_SOURCE_DIR}) + +# Compiler options +# TODO This currently assumes GCC, add Windows support in due time +add_definitions(-pedantic -Wno-long-long -Wall -Wextra -Wformat=2 + -Wredundant-decls -Wwrite-strings -Wmissing-include-dirs + -Wswitch-enum -Wuninitialized + -Wswitch-default -Winit-self -Wfloat-equal -fPIC ) + +set (CMAKE_CXX_STANDARD 11) + +# Debug Flags +set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -O0 -ggdb3 -DDEBUG") + +# Release flags +#set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -funroll-loops -finline-functions -fomit-frame-pointer -DNDEBUG") + +# MacOS X needed variables +if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin") + # adaptable according to individual needs + set(CMAKE_MACOSX_RPATH ON) + #set(CMAKE_SKIP_BUILD_RPATH FALSE) + #set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE) + #set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib") + #set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) +endif () + + +# Finding dependencies +# _____________________________________________________________________________ + + +# PKG-CONFIG +find_package(PkgConfig REQUIRED) + +# Find Boost +find_package(Boost REQUIRED COMPONENTS system) +include_directories(${Boost_INCLUDE_DIRS}) + +# Find Eigen3 - A lightweight C++ template library for vector and matrix math +find_package(Eigen3 REQUIRED) +include_directories(${EIGEN3_INCLUDE_DIR}) + +# Find NLOpt - Non Linear Optimization +pkg_check_modules(NLOpt REQUIRED nlopt>=2.4) +include_directories(${NLOpt_INCLUDE_DIRS}) +link_directories(${NLOpt_LIBRARY_DIRS}) + +# Find Limbo - LIbrary for Model-Based Optimization +set(LIMBO_DIR ${CMAKE_SOURCE_DIR}/thirdparty/limbo) +set(LIMBO_DEFINES USE_NLOPT) +include_directories(${LIMBO_DIR}/src) + +# Find GSL - GNU Scientific Library +find_package(GSL REQUIRED) +include_directories(${GSL_INCLUDE_DIRS}) + +# Find Yaml-cpp +find_package(yaml-cpp REQUIRED) +include_directories(${YAML_CPP_INCLUDE_DIR}) + +# Find Gazebo +# LOCAL_GAZEBO_DIR can be set to a path with a gazebo-config.cmake +if (LOCAL_GAZEBO_DIR) + find_package(gazebo 10 REQUIRED CONFIG + PATHS "${LOCAL_GAZEBO_DIR}" + NO_DEFAULT_PATH) + message(WARNING "Using local Gazebo @ ${gazebo_DIR}") +else() + find_package(gazebo 9 REQUIRED) +endif() +include_directories(${GAZEBO_INCLUDE_DIRS}) +link_directories(${GAZEBO_LIBRARY_DIRS}) + +# Gazebo dependencies +# Find avcodec +pkg_check_modules(libavcodec libavcodec) +if (NOT libavcodec_FOUND) + BUILD_WARNING ("libavcodec not found. Audio-video capabilities of gazebo are probably disabled.") +else() + include_directories(${libavcodec_INCLUDE_DIRS}) + link_directories(${libavcodec_LIBRARY_DIRS}) +endif () + +# Find Protobuf +# TODO: This part is currently a mess, and it should be handeled better +find_package(Protobuf REQUIRED) + +# Find the Protobuf import directory for Gazebo. Found in this +# tutorial: http://gazebosim.org/tutorials?tut=custom_messages&cat=transport +set(GAZEBO_PROTOBUF_DIR) +foreach(ITR ${GAZEBO_INCLUDE_DIRS}) + if(ITR MATCHES ".*gazebo-[0-9.]+$") + set(GAZEBO_PROTO_PATH "${ITR}/gazebo/msgs/proto") + set(GAZEBO_PROTO_INCLUDE "${ITR}/gazebo/msgs") + endif() +endforeach() +include_directories( + ${CMAKE_SOURCE_DIR} + ${PROTOBUF_INCLUDE_DIRS} + ${GAZEBO_PROTO_INCLUDE} +) + +# Add Gazebo C++ flags (this includes c++11) +list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}") + +# Directory where the .proto files reside within revolve +set(SPEC_DIR "msgs") + +# All protobuf files we need, including the Gazebo ones +file(GLOB_RECURSE REVOLVE_PROTOS ${SPEC_DIR}/*.proto) + +# Do the protobuf generation by hand for more flexibility. The files are +# generated in a subdirectory such that it can potentially be added to the +# include path for work-in-progress projects I co-develop with this. +# Copied most of this code from +# http://stackoverflow.com/questions/29346488/protobuf-generate-cpp-not-generating-src-and-header-files +# Also see +# https://github.com/Kitware/CMake/blob/master/Modules/FindProtobuf.cmake +set(PROTO_SRCS) +set(PROTO_HDRS) +set(PROTO_OUTPUT_BASE ${CMAKE_CURRENT_BINARY_DIR}) + + +# Include the directory where the protobuf files will be placed +include_directories(${PROTO_OUTPUT_BASE}) + +file(MAKE_DIRECTORY ${PROTO_OUTPUT_BASE}/revolve/msgs) +foreach(RV_PROTO ${REVOLVE_PROTOS}) + get_filename_component(RV_ABS_PROTO ${RV_PROTO} ABSOLUTE) + get_filename_component(RV_NAME_PROTO ${RV_PROTO} NAME_WE) + get_filename_component(RV_DIR_PROTO ${RV_PROTO} DIRECTORY) + + list(APPEND PROTO_SRCS + "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.cc") + list(APPEND PROTO_HDRS + "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.h") + + add_custom_command( + OUTPUT "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.cc" + "${PROTO_OUTPUT_BASE}/revolve/msgs/${RV_NAME_PROTO}.pb.h" + COMMAND ${PROTOBUF_PROTOC_EXECUTABLE} + ARGS -I ${RV_DIR_PROTO} + -I ${GAZEBO_PROTO_PATH} + --cpp_out ${PROTO_OUTPUT_BASE}/revolve/msgs ${RV_ABS_PROTO} + DEPENDS ${RV_ABS_PROTO} + COMMENT "Running C++ protocol buffer compiler on ${RV_PROTO}" + VERBATIM ) +endforeach() + +# Tell the compiler these files were generated +set_source_files_properties( + ${PROTO_SRCS} ${PROTO_HDRS} PROPERTIES GENERATED TRUE) + +# Source subdirectories +# _____________________________________________________________________________ + +# Plugin C++ files +file(GLOB_RECURSE + REVOLVE_GZ_SRC + brains/*.cpp + motors/*.cpp + sensors/*.cpp + util/*.cpp +) + +# Generate +# _____________________________________________________________________________ +# Add the file that registers the body analyzer as a separate library that +# can be used as a world plugin directly. +# Create the library containing the Revolve API + +# Generate spec library with the messages +add_library( + revolve-proto STATIC + ${PROTO_SRCS} ${PROTO_HDRS} +) +set_target_properties(revolve-proto PROPERTIES LINKER_LANGUAGE CXX) +target_link_libraries( + revolve-proto + ${PROTOBUF_LIBRARIES} +) + +# Create Revolve bundle plugin +add_library( + revolve-gazebo + ${REVOLVE_GZ_SRC} +) + +target_link_libraries( + revolve-gazebo + ${GAZEBO_LIBRARIES} + ${Boost_LIBRARIES} + ${GSL_LIBRARIES} + ${YAML_CPP_LIBRARIES} + ${NLOpt_LIBRARIES} +) + +target_compile_definitions( + revolve-gazebo + PUBLIC ${LIMBO_DEFINES} +) + +# Create World plugin +add_library( + WorldControlPlugin SHARED + plugin/WorldController.cpp + plugin/register_world_plugin.cpp +) +target_link_libraries( + WorldControlPlugin + revolve-gazebo + revolve-proto + ${GAZEBO_LIBRARIES} +) + +# Create Analyzer plugin +add_library( + AnalyzerPlugin SHARED + plugin/BodyAnalyzer.cpp + plugin/register_analyzer_plugin.cpp +) +target_link_libraries( + AnalyzerPlugin + revolve-gazebo + revolve-proto + ${GAZEBO_LIBRARIES} +) + +# Create Torus World plugin +add_library(TorusWorldPlugin SHARED + plugin/TorusWorld.cpp + plugin/register_torus_world_plugin.cpp +) +target_link_libraries(TorusWorldPlugin + revolve-gazebo + ${GAZEBO_LIBRARIES} +) + +# Create Robot plugin +add_library( + RobotControlPlugin SHARED + plugin/RobotController.cpp + plugin/register_robot_plugin.cpp +) +target_link_libraries( + RobotControlPlugin + revolve-gazebo + revolve-proto + ${GAZEBO_LIBRARIES} +) + +# Install +# _____________________________________________________________________________ +# Install libraries into "lib", header files into "include" + +install( + TARGETS revolve-proto revolve-gazebo + DESTINATION lib +) + +install( + DIRECTORY revolve + DESTINATION include + FILES_MATCHING PATTERN "*.h" +) diff --git a/cpprevolve/revolve/gazebo/brains/DifferentialCPG.cpp b/cpprevolve/revolve/gazebo/brains/DifferentialCPG.cpp index c65b6df72d..88d4a69bc1 100644 --- a/cpprevolve/revolve/gazebo/brains/DifferentialCPG.cpp +++ b/cpprevolve/revolve/gazebo/brains/DifferentialCPG.cpp @@ -14,190 +14,1177 @@ * limitations under the License. * * Description: TODO: - * Author: Milan Jelisavcic + * Author: Milan Jelisavcic & Maarten van Hooft * Date: December 29, 2018 * */ +// STL macros #include #include +#include +#include #include +#include +#include +#include +// Other libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Project headers #include "../motors/Motor.h" + #include "../sensors/Sensor.h" #include "DifferentialCPG.h" -namespace gz = gazebo; +#include "DifferentialCPG_BO.h" +// TODO: Resolve odd behaviour at the end of the validation procedure +// This behaviour is not present if you directly load a trained controller + +// Define namespaces +namespace gz = gazebo; using namespace revolve::gazebo; -///////////////////////////////////////////////// +// Copied from the limbo tutorial the BO implementation is based on +using Mean_t = limbo::mean::Data; +using Init_t = limbo::init::LHS; +using Kernel_t = limbo::kernel::MaternFiveHalves; +using GP_t = limbo::model::GP; + +/** + * Constructor for DifferentialCPG class. + * + * @param _model + * @param robot_config + */ DifferentialCPG::DifferentialCPG( const ::gazebo::physics::ModelPtr &_model, - const sdf::ElementPtr _settings, + const sdf::ElementPtr robot_config, const std::vector< revolve::gazebo::MotorPtr > &_motors, const std::vector< revolve::gazebo::SensorPtr > &_sensors) - : nextState_(nullptr) - , input_(new double[_sensors.size()]) - , output_(new double[_motors.size()]) + : next_state(nullptr) + , input(new double[_sensors.size()]) + , output(new double[_motors.size()]) { + + this->learner = robot_config->GetElement("rv:brain")->GetElement("rv:learner"); + + // Check for brain + if (not robot_config->HasElement("rv:brain")) + { + throw std::runtime_error("DifferentialCPG brain did not receive brain"); + } + auto brain = robot_config->GetElement("rv:brain"); + + // Check for learner + if (not brain->HasElement("rv:learner")) + { + throw std::runtime_error("DifferentialCPG brain did not receive learner"); + } + auto learner = brain->GetElement("rv:learner"); + + // Check for controller + if (not brain->HasElement("rv:controller")) + { + throw std::runtime_error("DifferentialCPG brain did not receive controller"); + } + auto controller = brain->GetElement("rv:controller"); + + // Check for actuators + if (not brain->HasElement("rv:actuators")) + { + throw std::runtime_error("DifferentialCPG brain did not receive actuators"); + } + auto actuators = brain->GetElement("rv:actuators"); + + // Controller parameters + this->reset_neuron_state_bool = std::stoi(controller->GetAttribute("reset_neuron_state_bool")->GetAsString()); + this->reset_neuron_random = std::stoi(controller->GetAttribute("reset_neuron_random")->GetAsString()); + this->init_neuron_state = std::stod(controller->GetAttribute("init_neuron_state")->GetAsString()); + this->range_lb = -std::stod(controller->GetAttribute("range_ub")->GetAsString()); + this->range_ub = std::stod(controller->GetAttribute("range_ub")->GetAsString()); + this->use_frame_of_reference = std::stoi(controller->GetAttribute("use_frame_of_reference")->GetAsString()); + this->signal_factor_all_ = std::stod(controller->GetAttribute("signal_factor_all")->GetAsString()); + this->signal_factor_mid = std::stod(controller->GetAttribute("signal_factor_mid")->GetAsString()); + this->signal_factor_left_right = std::stod(controller->GetAttribute("signal_factor_left_right")->GetAsString()); + + // Limbo BO Learner parameters + this->kernel_noise_ = std::stod(learner->GetAttribute("kernel_noise")->GetAsString()); + this->kernel_optimize_noise_ = std::stoi(learner->GetAttribute("kernel_optimize_noise")->GetAsString()); + this->kernel_sigma_sq_ = std::stod(learner->GetAttribute("kernel_sigma_sq")->GetAsString()); + this->kernel_l_ = std::stod(learner->GetAttribute("kernel_l")->GetAsString()); + this->kernel_squared_exp_ard_k_ = std::stoi(learner->GetAttribute("kernel_squared_exp_ard_k")->GetAsString()); + this->acqui_gpucb_delta_ = std::stod(learner->GetAttribute("acqui_gpucb_delta")->GetAsString()); + this->acqui_ucb_alpha_ = std::stod(learner->GetAttribute("acqui_ucb_alpha")->GetAsString()); + this->acqui_ei_jitter_ = std::stod(learner->GetAttribute("acqui_ei_jitter")->GetAsString()); + + // Non-limbo BO learner para + this->n_init_samples = std::stoi(learner->GetAttribute("n_init_samples")->GetAsString()); + this->n_learning_iterations = std::stoi(learner->GetAttribute("n_learning_iterations")->GetAsString()); + this->n_cooldown_iterations = std::stoi(learner->GetAttribute("n_cooldown_iterations")->GetAsString()); + this->init_method = learner->GetAttribute("init_method")->GetAsString(); + + // Meta parameters + this->startup_time = std::stoi(controller->GetAttribute("startup_time")->GetAsString()); + this->reset_robot_position = std::stoi(controller->GetAttribute("reset_robot_position")->GetAsString()); + this->run_analytics = std::stoi(controller->GetAttribute("run_analytics")->GetAsString()); + this->load_brain = controller->GetAttribute("load_brain")->GetAsString(); + this->evaluation_rate = std::stoi(learner->GetAttribute("evaluation_rate")->GetAsString()); + this->abs_output_bound = std::stoi(learner->GetAttribute("abs_output_bound")->GetAsString()); + this->verbose = std::stoi(controller->GetAttribute("verbose")->GetAsString()); + // Create transport node this->node_.reset(new gz::transport::Node()); this->node_->Init(); + // Get Robot + this->robot = _model; + this->n_motors = _motors.size(); auto name = _model->GetName(); - // Listen to network modification requests -// alterSub_ = node_->Subscribe( -// "~/" + name + "/modify_diff_cpg", &DifferentialCPG::Modify, -// this); - if (not _settings->HasElement("rv:brain")) + if(this->verbose) { - std::cerr << "No robot brain detected, this is probably an error." - << std::endl; - throw std::runtime_error("DifferentialCPG brain did not receive settings"); + std::cout << robot_config->GetDescription() << std::endl; } - - std::cout << _settings->GetDescription() << std::endl; - auto motor = _settings->HasElement("rv:motor") - ? _settings->GetElement("rv:motor") + auto motor = actuators->HasElement("rv:servomotor") + ? actuators->GetElement("rv:servomotor") : sdf::ElementPtr(); + auto j = 0; while(motor) { - if (not motor->HasAttribute("x") or not motor->HasAttribute("y")) + if (not motor->HasAttribute("coordinates")) { - std::cerr << "Missing required motor attributes (x- and/or y- coordinate)" - << std::endl; + std::cerr << "Missing required motor coordinates" << std::endl; throw std::runtime_error("Robot brain error"); } - auto motorId = motor->GetAttribute("part_id")->GetAsString(); - auto coordX = std::atoi(motor->GetAttribute("x")->GetAsString().c_str()); - auto coordY = std::atoi(motor->GetAttribute("y")->GetAsString().c_str()); - this->positions_[motorId] = {coordX, coordY}; - this->neurons_[{coordX, coordY, 1}] = {1.f, 0.f, 0.f}; - this->neurons_[{coordX, coordY, -1}] = {1.f, 0.f, 0.f}; + // Split string and get coordinates + auto coordinate_string = motor->GetAttribute("coordinates")->GetAsString(); + std::vector coordinates; + boost::split(coordinates, coordinate_string, boost::is_any_of(";")); + + // Check if we have exactly 2 coordinates + if (not coordinates.size() == 2) + { + throw std::runtime_error("Coordinates are not exactly of length two "); + } + + // Check if the coordinates are integers + try + { + for(auto coord : coordinates) + { + std::stoi(coord); + } + } + catch(std::invalid_argument e1) + { + std::cout << "Invalid argument: Cannot cast coordinates to integers " << std::endl; + }; + + // Pass coordinates + auto coord_x = std::stoi(coordinates[0]); + auto coord_y = std::stoi(coordinates[1]); + if (this->verbose) + { + std::cout << "coord_x,coord_y = " << coord_x << "," << coord_y << std::endl; + } + auto motor_id = motor->GetAttribute("part_id")->GetAsString(); + this->positions[motor_id] = {coord_x, coord_y}; + this->motor_coordinates[{coord_x, coord_y}] = j; + + // Set frame of reference + int frame_of_reference = 0; + // We are a left neuron + if (coord_x < 0) + { + frame_of_reference = -1; + } + // We are a right neuron + else if (coord_x > 0) + { + frame_of_reference = 1; + } -// TODO: Add check for duplicate coordinates + // Save neurons: bias/gain/state. Make sure initial states are of different sign. + this->neurons[{coord_x, coord_y, 1}] = {0.f, 0.f, this->init_neuron_state, frame_of_reference}; //Neuron A + this->neurons[{coord_x, coord_y, -1}] = {0.f, 0.f, -this->init_neuron_state, frame_of_reference}; // Neuron B - motor = motor->GetNextElement("rv:motor"); + // TODO: Add check for duplicate coordinates + motor = motor->GetNextElement("rv:servomotor"); + j++; } // Add connections between neighbouring neurons - for (const auto &position : this->positions_) + int i = 0; + for (const auto &position : this->positions) { + // Get name and x,y-coordinates of all neurons. auto name = position.first; int x, y; std::tie(x, y) = position.second; - if (this->connections_.count({x, y, 1, x, y, -1})) + // Continue to next iteration in case there is already a connection between the 1 and -1 neuron. + // These checks feel a bit redundant. + // if A->B connection exists. + if (this->connections.count({x, y, 1, x, y, -1})) { continue; } - if (this->connections_.count({x, y, -1, x, y, 1})) + // if B->A connection exists: + if (this->connections.count({x, y, -1, x, y, 1})) { continue; } - this->connections_[{x, y, 1, x, y, -1}] = 1.f; - this->connections_[{x, y, -1, x, y, 1}] = 1.f; - for (const auto &neighbour : this->positions_) + // Loop over all positions. We call it neighbours, but we still need to check if they are a neighbour. + for (const auto &neighbour : this->positions) { - int nearX, nearY; - std::tie(nearX, nearY) = neighbour.second; - if ((x+1) == nearX or (y+1) == nearY or (x-1) == nearX or (y-1) == nearY) + // Get information of this neuron (that we call neighbour). + int near_x, near_y; std::tie(near_x, near_y) = neighbour.second; + + // If there is a node that is a Moore neighbour, we set it to be a neighbour for their A-nodes. + // Thus the connections list only contains connections to the A-neighbourhood, and not the + // A->B and B->A for some node (which makes sense). + int dist_x = std::abs(x - near_x); + int dist_y = std::abs(y - near_y); + + // TODO: Verify for non-spiders + if (dist_x + dist_y == 2) { - this->connections_[{x, y, 1, nearX, nearY, 1}] = 1.f; - this->connections_[{nearX, nearY, 1, x, y, 1}] = 1.f; + if(std::get<0>(this->connections[{x, y, 1, near_x, near_y, 1}]) != 1 or + std::get<0>(this->connections[{near_x, near_y, 1, x, y, 1}]) != 1) + { + if(this->verbose) + { + std::cout << "New connection at index " << i << ": " << x << ", " << y << ", " << near_x << ", " << near_y << std::endl; + } + this->connections[{x, y, 1, near_x, near_y, 1}] = std::make_tuple(1, i); + this->connections[{near_x, near_y, 1, x, y, 1}] = std::make_tuple(1, i); + i++; + } } } } + // Create directory for output. + this->directory_name = controller->GetAttribute("output_directory")->GetAsString(); + if(this->directory_name.empty()) + { + this->directory_name = "output/cpg_bo/"; + this->directory_name += std::to_string(time(0)) + "/"; + } + + std::system(("mkdir -p " + this->directory_name).c_str()); + // Initialise array of neuron states for Update() method - this->nextState_ = new double[this->neurons_.size()]; + this->next_state = new double[this->neurons.size()]; + this->n_weights = (int)(this->connections.size()/2) + this->n_motors; + + // Check if we want to load a pre-trained brain + if(!this->load_brain.empty()) + { + // Get line + if(this->verbose) + { + std::cout << "I will load the following brain:" << std::endl; + } + std::ifstream brain_file(this->load_brain); + std::string line; + std::getline(brain_file, line); + + // Get weights in line + std::vector weights; + boost::split(weights, line, boost::is_any_of(",")); + + // Save weights for brain + Eigen::VectorXd loaded_brain(this->n_weights); + for(size_t j = 0; j < this->n_weights; j++) + { + loaded_brain(j) = std::stod(weights.at(j)); + if(this->verbose) + { + std::cout << loaded_brain(j) << ","; + } + } + if(this->verbose) + { + std::cout << std::endl; + } + + // Close brain + brain_file.close(); + + // Save these weights + this->samples.push_back(loaded_brain); + + // Set ODE matrix at initialization + this->set_ode_matrix(); + + // Go directly into cooldown phase: Note we do require that best_sample is filled. Check this + this->current_iteration = this->n_init_samples + this->n_learning_iterations; + + if(this->verbose) + { + std::cout << std::endl << "Brain has been loaded." << std::endl; + } + } + else + { + if (this->verbose) + { + std::cout << "Don't load existing brain" << std::endl; + } + + // Initialize BO + this->bo_init_sampling(); + } + + // Initiate the cpp Evaluator + this->evaluator.reset(new Evaluator(this->evaluation_rate)); + this->evaluator->directory_name = this->directory_name; } -///////////////////////////////////////////////// +/** + * Destructor + */ DifferentialCPG::~DifferentialCPG() { - delete[] this->nextState_; - delete[] this->input_; - delete[] this->output_; + delete[] this->next_state; + delete[] this->input; + delete[] this->output; } -///////////////////////////////////////////////// +/** + * Dummy function for limbo + */ +struct DifferentialCPG::evaluation_function{ + // Number of input dimension (samples.size()) + BO_PARAM(size_t, dim_in, 18); + + // number of dimensions of the fitness + BO_PARAM(size_t, dim_out, 1); + + Eigen::VectorXd operator()(const Eigen::VectorXd &x) const { + return limbo::tools::make_vector(0); + }; +}; + +/** + * Performs the initial random sampling for BO + */ +void DifferentialCPG::bo_init_sampling(){ + if(this->verbose) + { + // We only want to optimize the weights for now. + std::cout << "Number of weights = connections/2 + n_motors are " + << this->connections.size()/2 + << " + " + << this->n_motors + << std::endl; + + // Information purposes + std::cout << std::endl << "Sample method: " << this->init_method << ". Initial " + "samples are: " << std::endl; + } + + // Random sampling + if(this->init_method == "RS") + { + for (size_t i = 0; i < this->n_init_samples; i++) + { + // Working variable to hold a random number for each weight to be optimized + Eigen::VectorXd init_sample(this->n_weights); + + // For all weights + for (size_t j = 0; j < this->n_weights; j++) + { + // Generate a random number in [0, 1]. Transform later + double f = ((double) rand() / (RAND_MAX)); + + // Append f to vector + init_sample(j) = f; + } + + // Save vector in samples. + this->samples.push_back(init_sample); + } + } + // Latin Hypercube Sampling + else if(this->init_method == "LHS") + { + // Working variable + double my_range = 1.f/this->n_init_samples; + + // If we have n dimensions, create n such vectors that we will permute + std::vector> all_dimensions; + + // Fill vectors + for (size_t i=0; i < this->n_weights; i++) + { + std::vector one_dimension; + + // Prepare for vector permutation + for (size_t j = 0; j < this->n_init_samples; j++) + { + one_dimension.push_back(j); + } + + // Vector permutation + std::random_shuffle(one_dimension.begin(), one_dimension.end() ); + + // Save permuted vector + all_dimensions.push_back(one_dimension); + } + + // For all samples + for (size_t i = 0; i < this->n_init_samples; i++) + { + // Initialize Eigen::VectorXd here. + Eigen::VectorXd init_sample(this->n_weights); + + // For all dimensions + for (size_t j = 0; j < this->n_weights; j++) + { + // Take a LHS + init_sample(j) = all_dimensions.at(j).at(i)*my_range + ((double) rand() / (RAND_MAX))*my_range; + } + + // Append sample to samples + this->samples.push_back(init_sample); + } + } + else + { + std::cout << "Please provide a choice of init_method in {LHS, RS}" << std::endl; + } + + // Print samples + if(this->verbose) + { + for(auto init_sample :this->samples) + { + for (int h = 0; h < init_sample.size(); h++) + { + std::cout << init_sample(h) << ", "; + } + std::cout << std::endl; + } + } +} + +/** + * Function that obtains the current fitness by calling the evaluator and stores it + */ +void DifferentialCPG::save_fitness(){ + // Get fitness + double fitness = this->evaluator->Fitness(); + + // Save sample if it is the best seen so far + if(fitness >this->best_fitness) + { + this->best_fitness = fitness; + this->best_sample = this->samples.back(); + } + + if (this->verbose) + { + std::cout << "Iteration number " << this->current_iteration << " has fitness " << + fitness << ". Best fitness: " << this->best_fitness << std::endl; + } + + // Limbo requires fitness value to be of type Eigen::VectorXd + Eigen::VectorXd observation = Eigen::VectorXd(1); + observation(0) = fitness; + + // Save fitness to std::vector. This fitness corresponds to the solution of the previous iteration + this->observations.push_back(observation); + + // Write fitness to file + std::ofstream fitness_file; + fitness_file.open(this->directory_name + "fitnesses.txt", std::ios::app); + fitness_file << fitness << std::endl; + fitness_file.close(); +} + + + +/** + * Struct that holds the parameters on which BO is called. This is required + * by limbo. + */ +struct DifferentialCPG::Params{ + + struct bayes_opt_boptimizer : public limbo::defaults::bayes_opt_boptimizer { + }; + + // depending on which internal optimizer we use, we need to import different parameters +#ifdef USE_NLOPT + struct opt_nloptnograd : public limbo::defaults::opt_nloptnograd { + }; +#elif defined(USE_LIBCMAES) + struct opt_cmaes : public lm::defaults::opt_cmaes { + }; +#else +#error(NO SOLVER IS DEFINED) +#endif + struct kernel : public limbo::defaults::kernel { + BO_PARAM(double, noise, 0.001); + BO_PARAM(bool, optimize_noise, false); + }; + + struct bayes_opt_bobase : public limbo::defaults::bayes_opt_bobase { + // set stats_enabled to prevent creating all the directories + BO_PARAM(bool, stats_enabled, false); + BO_PARAM(bool, bounded, true); + }; + + // 1 Iteration as we will perform limbo step by steop + struct stop_maxiterations : public limbo::defaults::stop_maxiterations { + BO_PARAM(int, iterations, 1); + }; + + struct kernel_exp : public limbo::defaults::kernel_exp { + /// @ingroup kernel_defaults + BO_PARAM(double, sigma_sq, 0.1); + BO_PARAM(double, l, 0.1); // the width of the kernel. Note that it assumes equally sized ranges over dimensions + }; + + struct kernel_squared_exp_ard : public limbo::defaults::kernel_squared_exp_ard { + /// @ingroup kernel_defaults + BO_PARAM(int, k, 3); // k number of columns used to compute M + /// @ingroup kernel_defaults + BO_PARAM(double, sigma_sq, 0.1); //brochu2010tutorial p.9 without sigma_sq + }; + + struct kernel_maternfivehalves : public limbo::defaults::kernel_maternfivehalves + { + BO_DYN_PARAM(double, sigma_sq); //brochu2010tutorial p.9 without sigma_sq + BO_DYN_PARAM(double, l); //characteristic length scale + }; + + struct acqui_gpucb : public limbo::defaults::acqui_gpucb { + //UCB(x) = \mu(x) + \kappa \sigma(x). + BO_PARAM(double, delta, 0.1 );//acqui_gpucb_delta_); // default delta = 0.1, delta in (0,1) convergence guaranteed + }; + + struct acqui_ei : public limbo::defaults::acqui_ei{ + BO_PARAM(double, jitter, 0.5); + }; + + // This is just a placeholder to be able to use limbo with revolve + struct init_lhs : public limbo::defaults::init_lhs{ + BO_PARAM(int, samples, 0); + }; + + struct acqui_ucb : public limbo::defaults::acqui_ucb { + //constexpr double ra = acqui_ucb_alpha_; + //UCB(x) = \mu(x) + \alpha \sigma(x). high alpha have high exploration + //iterations is high, alpha can be low for high accuracy in enough iterations. + // In contrast, the lsow iterations should have high alpha for high + // searching in limited iterations, which guarantee to optimal. + // BO_PARAM(double, alpha, transform_double(acqui_ucb_alpha_)); // default alpha = 0.5 + BO_DYN_PARAM(double, alpha); // default alpha = 0.5 + + }; +}; + +BO_DECLARE_DYN_PARAM(double, DifferentialCPG::Params::acqui_ucb, alpha); +BO_DECLARE_DYN_PARAM(double, DifferentialCPG::Params::kernel_maternfivehalves, sigma_sq); +BO_DECLARE_DYN_PARAM(double, DifferentialCPG::Params::kernel_maternfivehalves, l); + +/** + * Wrapper function that makes calls to limbo to solve the current BO + * iteration and returns the best sample + */ +void DifferentialCPG::bo_step(){ + Params::acqui_ucb::set_alpha(this->acqui_ucb_alpha_); + Params::kernel_maternfivehalves::set_l(this->kernel_l_); + Params::kernel_maternfivehalves::set_sigma_sq(this->kernel_sigma_sq_); + + // Save all parameters once + if (this->current_iteration == 0) + { + // Save parameters + this->save_parameters(); + } + Eigen::VectorXd x; + + // In case we are done with the initial random sampling. + if (this->current_iteration >= this->n_init_samples) + { + // std::cout << "Acquisition function: " << this->acquisition_function << std::endl; + if(true) + { + + // Specify bayesian optimizer. TODO: Make attribute and initialize at bo_init + limbo::bayes_opt::BOptimizer, + limbo::modelfun, + limbo::acquifun>> boptimizer; + + // Optimize. Pass dummy evaluation function and observations . + boptimizer.optimize(DifferentialCPG::evaluation_function(), + this->samples, + this->observations); + x = boptimizer.last_sample(); + + // Write parametesr to verify thread-stability after the run + std::ofstream dyn_parameters_file; + dyn_parameters_file.open(this->directory_name + "dynamic_parameters.txt", std::ios::app); + dyn_parameters_file << Params::acqui_ucb::alpha() << ","; + dyn_parameters_file << Params::kernel_maternfivehalves::sigma_sq() << ","; + dyn_parameters_file << Params::kernel_maternfivehalves::l() << std::endl; + dyn_parameters_file.close(); + + + } + // else if(this->acquisition_function == "GP_UCB") + // { + // // Specify bayesian optimizer. TODO: Make attribute and initialize at bo_init + // limbo::bayes_opt::BOptimizer, + // limbo::modelfun, + // limbo::acquifun>> boptimizer; + // + // // Optimize. Pass dummy evaluation function and observations . + // boptimizer.optimize(DifferentialCPG::evaluation_function(), + // this->samples, + // this->observations); + // x = boptimizer.last_sample(); + // } + // else if(this->acquisition_function == "EI") + // { + // // Specify bayesian optimizer. TODO: Make attribute and initialize at bo_init + // limbo::bayes_opt::BOptimizer, + // limbo::modelfun, + // limbo::acquifun>> boptimizer; + // + // // Optimize. Pass dummy evaluation function and observations . + // boptimizer.optimize(DifferentialCPG::evaluation_function(), + // this->samples, + // this->observations); + // x = boptimizer.last_sample(); + // } + else + { + std::cout << "Specify correct acquisition function: {EI, UCB, GP_UCB}" << std::endl; + } + + // Save this x_hat_star + this->samples.push_back(x); + } +} + +/** + * Callback function that defines the movement of the robot + * + * @param _motors + * @param _sensors + * @param _time + * @param _step + */ void DifferentialCPG::Update( const std::vector< revolve::gazebo::MotorPtr > &_motors, const std::vector< revolve::gazebo::SensorPtr > &_sensors, const double _time, const double _step) { + // Prevent two threads from accessing the same resource at the same time boost::mutex::scoped_lock lock(this->networkMutex_); // Read sensor data and feed the neural network unsigned int p = 0; for (const auto &sensor : _sensors) { - sensor->Read(this->input_ + p); + sensor->Read(this->input + p); p += sensor->Inputs(); } - this->Step(_time, this->output_); + this->evaluator->Update(this->robot->WorldPose(), _time, _step); + + // Only start recording the fitness after the startup time each iteration + double elapsed_evaluation_time = _time - this->start_time; + if((std::fmod(elapsed_evaluation_time, (int)this->evaluation_rate) >= this->startup_time) & this->start_fitness_recording) + { + // Update position +// this->evaluator->Update(this->robot->WorldPose(), _time, _step); + this->start_fitness_recording = false; + } + // Evaluate policy on certain time limit, or if we just started + if ((elapsed_evaluation_time > this->evaluation_rate) or ((_time - _step) < 0.001)) + { + // Update position +// this->evaluator->Update(this->robot->WorldPose(), _time, _step); + this->start_fitness_recording = true; + + // Get and save fitness (but not at start) + if(not (_time - _step < 0.001 )) + { + this->save_fitness(); + } + + // Reset robot if opted to do + if(this->reset_robot_position) + { + //this->robot->Reset(); + this->robot->ResetPhysicsStates(); + auto start_pose = ::ignition::math::Pose3d(); + start_pose.Set(0.0, 0.0, 0.05, 0.0, 0.0, 0.0); + this->robot->SetWorldPose(start_pose); + this->robot->Update(); + } + + // Reset neuron state if opted to do + if(this->reset_neuron_state_bool) + { + this->reset_neuron_state(); + } + + // If we are still learning + if(this->current_iteration < this->n_init_samples + this->n_learning_iterations) + { + if(this->verbose) + { + if (this->current_iteration < this->n_init_samples) + { + std::cout << std::endl << "Evaluating initial random sample" << std::endl; + } + else + { + std::cout << std::endl << "I am learning " << std::endl; + } + } + // Get new sample (weights) and add sample + this->bo_step(); + + // Set new weights + this->set_ode_matrix(); + + // Update position +// this->evaluator->Update(this->robot->WorldPose(), _time, _step); + } + // If we are finished learning but are cooling down - reset once + else if((this->current_iteration >= (this->n_init_samples + + this->n_learning_iterations)) + and (this->current_iteration < (this->n_init_samples + + this->n_learning_iterations + + this->n_cooldown_iterations - 1))) + { + if(this->verbose) + { + std::cout << std::endl << "I am cooling down " << std::endl; + } + + // Update robot position +// this->evaluator->Update(this->robot->WorldPose(), _time, _step); + + // Use best sample in next iteration + this->samples.push_back(this->best_sample); + + // Set ODE matrix + this->set_ode_matrix(); + } + // Else we don't want to update anything, but construct plots from this run once. + else + { +// // Create plots +// if(this->run_analytics) +// { +// // Construct plots +// this->get_analytics(); +// } + + // Exit + if(this->verbose) + { + std::cout << std::endl << "I am finished " << std::endl; + } + std::exit(0); + } + + // Evaluation policy here + this->start_time = _time; + this->evaluator->Reset(); + this->current_iteration += 1; + } // Send new signals to the motors + this->step(_time, this->output); p = 0; for (const auto &motor: _motors) { - motor->Update(this->output_ + p, _step); + motor->Update(this->output + p, _step); p += motor->Outputs(); } } -void DifferentialCPG::Step( - const double _time, - double *_output) -{ - auto i = 0; - for (const auto &neuron : this->neurons_) +/** + * Make matrix of weights A as defined in dx/dt = Ax. + * Element (i,j) specifies weight from neuron i to neuron j in the system of ODEs + */ +void DifferentialCPG::set_ode_matrix(){ + // Initiate new matrix + std::vector> matrix; + + // Fill with zeroes + for(size_t i =0; i neurons.size(); i++) { - // The map key is representing x-, y-, and z-coordinates of a neuron and - // map value represents bias, gain, and current state of the neuron. - int x, y, z; - std::tie(x, y, z) = neuron.first; + // Initialize row in matrix with zeros + std::vector< double > row; + for (size_t j = 0; j < this->neurons.size(); j++) + { + row.push_back(0); + } + matrix.push_back(row); + } + + // Process A<->B connections + int index = 0; + for(size_t i =0; i neurons.size(); i++) + { + // Get correct index + int c = 0; + if (i%2 == 0){ + c = i + 1; + } + else{ + c = i - 1; + } + + // Add a/b connection weight + index = (int)(i/2); + auto w = this->samples.at(this->current_iteration)(index) * + (this->range_ub - this->range_lb) + this->range_lb; + matrix[i][c] = w; + matrix[c][i] = -w; + } - double biasA, gainA, stateA; - std::tie(biasA, gainA, stateA) = neuron.second; + // A<->A connections + index++; + int k = 0; + std::vector connections_seen; - auto inputA = 0.f; - for (auto const &connection : this->connections_) + for (auto const &connection : this->connections) + { + // Get connection information + int x1, y1, z1, x2, y2, z2; + std::tie(x1, y1, z1, x2, y2, z2) = connection.first; + + // Find location of the two neurons in this->neurons list + int l1, l2; + int c = 0; + for(auto const &neuron : this->neurons) + { + int x, y, z; + std::tie(x, y, z) = neuron.first; + if (x == x1 and y == y1 and z == z1) + { + l1 = c; + } + else if (x == x2 and y == y2 and z == z2) + { + l2 = c; + } + // Update counter + c++; + } + + // Add connection to seen connections + if(l1 > l2) { - int x1, y1, z1, x2, y2, z2; - std::tie(x1, y1, z1, x2, y2, z2) = connection.first; - auto weightBA = connection.second; + int l1_old = l1; + l1 = l2; + l2 = l1_old; + } + std::string connection_string = std::to_string(l1) + "-" + std::to_string(l2); + + // if not in list, add to list + auto connections_list = std::find(connections_seen.begin(), connections_seen.end(), connection_string); + if(connections_list == connections_seen.end()) + { + connections_seen.push_back(connection_string); + } + // else continue to next iteration + else{ + continue; + } + + // Get weight + auto w = this->samples.at(this->current_iteration)(index + k) * + (this->range_ub - this->range_lb) + this->range_lb; + + // Set connection in weight matrix + matrix[l1][l2] = w; + matrix[l2][l1] = -w; + k++; + } + + // Update matrix + this->ode_matrix = matrix; - if (x2 == x and y2 == y and z2 == z) + // Reset neuron state + this->reset_neuron_state(); + + // Save this sample to file + std::ofstream samples_file; + samples_file.open(this->directory_name + "samples.txt", std::ios::app); + auto sample = this->samples.at(this->current_iteration); + for(size_t j = 0; j < this->n_weights; j++) + { + samples_file << sample(j) << ", "; + } + samples_file << std::endl; + samples_file.close(); +} + + +/** + * Set states back to original value (that is on the unit circle) + */ +void DifferentialCPG::reset_neuron_state(){ + int c = 0; + for(auto const &neuron : this->neurons) + { + // Get neuron properties + int x, y, z, frame_of_reference; + double bias ,gain ,state; + std::tie(x, y, z) = neuron.first; + std::tie(bias, gain, state, frame_of_reference) = neuron.second; + + if (z == -1) + { + // Neuron B + if (this->reset_neuron_random) + { + this->neurons[{x, y, z}] = {0.f, + 0.f, + ((double) rand() / (RAND_MAX))*2*this->init_neuron_state - this->init_neuron_state, + frame_of_reference}; + } + else + { + this->neurons[{x, y, z}] = {0.f, 0.f, -this->init_neuron_state, frame_of_reference}; + } + } + else + { + // Neuron A + if (this->reset_neuron_random) + { + this->neurons[{x, y, z}] = {0.f, + 0.f, + ((double) rand() / (RAND_MAX))*2*this->init_neuron_state - this->init_neuron_state, + frame_of_reference}; + } + else { - auto input = std::get<2>(this->neurons_[{x1, y1, z1}]); - inputA += weightBA * input + biasA; + this->neurons[{x, y, z}] = {0.f, 0.f, +this->init_neuron_state, frame_of_reference}; } } + c++; + } +} + +/** + * Step function that is called from within Update() + * + * @param _time + * @param _output + */ +void DifferentialCPG::step( + const double _time, + double *_output) +{ + int neuron_count = 0; + for (const auto &neuron : this->neurons) + { + // Neuron.second accesses the second 3-tuple of a neuron, containing the bias/gain/state. + double recipient_bias, recipient_gain, recipient_state; + int frame_of_reference; + std::tie(recipient_bias, recipient_gain, recipient_state, frame_of_reference) = neuron.second; - this->nextState_[i] = stateA + (inputA * _time); - ++i; + // Save for ODE + this->next_state[neuron_count] = recipient_state; + neuron_count++; } - i = 0; auto j = 0; - for (auto &neuron : this->neurons_) + // Copy values from next_state into x for ODEINT + state_type x(this->neurons.size()); + for (size_t i = 0; i < this->neurons.size(); i++) { - double biasA, gainA, stateA; - std::tie(biasA, gainA, stateA) = neuron.second; + x[i] = this->next_state[i]; + } - neuron.second = {biasA, gainA, this->nextState_[i]}; - if (i % 2 == 0) + // Stepper. The result is saved in x. Begin time t, time step dt + double dt = (_time - this->previous_time); + this->previous_time = _time; + + // Perform one step + stepper.do_step( + [this](const state_type &x, state_type &dxdt, double t) + { + for(size_t i = 0; i < this->neurons.size(); i++) + { + dxdt[i] = 0; + for(size_t j = 0; j < this->neurons.size(); j++) + { + dxdt[i] += x[j]*this->ode_matrix[j][i]; + } + } + }, + x, + _time, + dt); + + // Copy values into nextstate + for (size_t i = 0; i < this->neurons.size(); i++) + { + this->next_state[i] = x[i]; + } + + // Loop over all neurons to actually update their states. Note that this is a new outer for loop + auto i = 0; auto j = 0; + for (auto &neuron : this->neurons) + { + // Get bias gain and state for this neuron. Note that we don't take the coordinates. + // However, they are implicit as their order did not change. + double bias, gain, state; + int frame_of_reference; + std::tie(bias, gain, state, frame_of_reference) = neuron.second; + double x, y, z; + std::tie(x, y, z) = neuron.first; + neuron.second = {bias, gain, this->next_state[i], frame_of_reference}; + j = this->motor_coordinates[{x,y}]; + // Should be one, as output should be based on +1 neurons, which are the A neurons + if (i % 2 == 1) { - _output[j] = this->nextState_[i]; - j++; + // TODO: Add Milan's function here as soon as things are working a bit + // f(a) = (w_ao*a - bias)*gain + + // Apply saturation formula + auto x = this->next_state[i]; + + // Use frame of reference + if(use_frame_of_reference) + { + + if (std::abs(frame_of_reference) == 1) + { + this->output[j] = this->signal_factor_left_right*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } + else if (frame_of_reference == 0) + { + this->output[j] = this->signal_factor_mid*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } + else + { + std::cout << "WARNING: frame_of_reference not in {-1,0,1}." << std::endl; + } + + } + // Don't use frame of reference + else{ + this->output[j] = this->signal_factor_all_*this->abs_output_bound*((2.0)/(1.0 + std::pow(2.718, -2.0*x/this->abs_output_bound)) -1); + } } - ++i; + i++; } + + // Comment to save disk space +// // Write state to file +// std::ofstream state_file; +// state_file.open(this->directory_name + "states.txt", std::ios::app); +// for(size_t i = 0; i < this->neurons.size(); i++) +// { +// state_file << this->next_state[i] << ","; +// } +// state_file << std::endl; +// state_file.close(); +// +// // Write signal to file +// std::ofstream signal_file; +// signal_file.open(this->directory_name + "signal.txt", std::ios::app); +// for(size_t i = 0; i < this->n_motors; i++) +// { +// signal_file << this->output[i] << ","; +// } +// signal_file << std::endl; +// signal_file.close(); +} + + +/** + * Save the parameters used in this run to a file. + */ +void DifferentialCPG::save_parameters(){ + // Write parameters to file + std::ofstream parameters_file; + parameters_file.open(this->directory_name + "parameters.txt"); + + // Various parameters + parameters_file << "Dimensions: " << this->n_weights << std::endl; + parameters_file << "n_init_samples: " << this->n_init_samples << std::endl; + parameters_file << "n_learning_iterations: " << this->n_learning_iterations << std::endl; + parameters_file << "n_cooldown_iterations: " << this->n_cooldown_iterations << std::endl; + parameters_file << "evaluation_rate: " << this->evaluation_rate << std::endl; + parameters_file << "abs_output_bound: " << this->abs_output_bound << std::endl; + parameters_file << "signal_factor_all: " << this->signal_factor_all_ << std::endl; + parameters_file << "range_lb: " << this->range_lb << std::endl; + parameters_file << "range_ub: " << this->range_ub << std::endl; + parameters_file << "run_analytics: " << this->run_analytics << std::endl; + parameters_file << "load_brain: " << this->load_brain << std::endl; + parameters_file << "reset_robot_position: " << this->reset_robot_position << std::endl; + parameters_file << "reset_neuron_state_bool: " << this->reset_neuron_state_bool << std::endl; + parameters_file << "reset_neuron_random: " << this->reset_neuron_random << std::endl; + parameters_file << "initial state value: " << this->init_neuron_state << std::endl; + + // BO hyper-parameters + parameters_file << std::endl << "Initialization method used: " << this->init_method << std::endl; + parameters_file << "Acqui. function used: " << this->acquisition_function << std::endl; + parameters_file << "EI jitter: " <directory_name + + " " + + std::to_string((int)this->n_init_samples) + + " " + + std::to_string((int)this->n_cooldown_iterations); + + // Execute python command + std::system(std::string("python3 " + plot_command).c_str()); } diff --git a/cpprevolve/revolve/gazebo/brains/DifferentialCPG.h b/cpprevolve/revolve/gazebo/brains/DifferentialCPG.h index 8bb850eb21..2595f83621 100644 --- a/cpprevolve/revolve/gazebo/brains/DifferentialCPG.h +++ b/cpprevolve/revolve/gazebo/brains/DifferentialCPG.h @@ -22,15 +22,39 @@ #ifndef REVOLVE_DIFFERENTIALCPG_H_ #define REVOLVE_DIFFERENTIALCPG_H_ +// Standard libraries #include #include +// External libraries +#include +#include + +// Project headers +#include "Evaluator.h" #include "Brain.h" +/// These numbers are quite arbitrary. It used to be in:13 out:8 for the +/// Arduino, but I upped them both to 20 to accommodate other scenarios. +/// Should really be enforced in the Python code, this implementation should +/// not be the limit. +#define MAX_INPUT_NEURONS 20 +#define MAX_OUTPUT_NEURONS 20 + +/// Arbitrary value +#define MAX_HIDDEN_NEURONS 30 + +/// Convenience +#define MAX_NON_INPUT_NEURONS (MAX_HIDDEN_NEURONS + MAX_OUTPUT_NEURONS) + +/// (bias, tau, gain) or (phase offset, period, gain) +#define MAX_NEURON_PARAMS 3 + +typedef std::vector< double > state_type; + namespace revolve { - namespace gazebo - { + namespace gazebo { class DifferentialCPG : public Brain { @@ -39,12 +63,15 @@ namespace revolve /// \param[in] _node The brain node /// \param[in] _motors Reference to a motor list, it be reordered /// \param[in] _sensors Reference to a sensor list, it might be reordered - public: DifferentialCPG( + public: + DifferentialCPG( const ::gazebo::physics::ModelPtr &_model, - const sdf::ElementPtr _settings, + const sdf::ElementPtr robot_config, const std::vector< MotorPtr > &_motors, const std::vector< SensorPtr > &_sensors); + public: void set_ode_matrix(); + /// \brief Destructor public: virtual ~DifferentialCPG(); @@ -53,41 +80,194 @@ namespace revolve /// \param[in] _sensors Sensor list /// \param[in] _time Current world time /// \param[in] _step Current time step - public: virtual void Update( + public: + virtual void Update( const std::vector< MotorPtr > &_motors, const std::vector< SensorPtr > &_sensors, const double _time, const double _step); - protected: void Step( + protected: + void step( const double _time, double *_output); /// \brief Register of motor IDs and their x,y-coordinates - protected: std::map< std::string, std::tuple< int, int > > - positions_; + protected: std::map< std::string, std::tuple< int, int > > positions; - /// \brief Register of individual neurons in x,y,z-coordinates + public: std::map< std::tuple< int, int>, int> motor_coordinates; + + + /// \brief Register of individual neurons in x,y,z-coordinates /// \details x,y-coordinates define position of a robot's module and // z-coordinate define A or B neuron (z=1 or -1 respectively). Stored - // values are a bias and a gain of each neuron. - protected: std::map< std::tuple< int, int, int >, - std::tuple< double, double, double > > neurons_; + // values are a bias, gain, state and frame of reference of each neuron. + protected: + std::map< std::tuple< int, int, int >, std::tuple< double, double, double, int > > + neurons; /// \brief Register of connections between neighnouring neurons /// \details Coordinate set of two neurons (x1, y1, z1) and (x2, y2, z2) - // define a connection. - protected: std::map< std::tuple< int, int, int, int, int, int >, - double > connections_; + // define a connection. The second tuple contains 1: the connection value and + // 2: the weight index corresponding to this connection. + protected: + std::map< std::tuple< int, int, int, int, int, int >, std::tuple > + connections; + + /// \brief Runge-Kutta 45 stepper + protected: boost::numeric::odeint::runge_kutta4< state_type > stepper; + + /// \brief Pointer to access parameters + private: sdf::ElementPtr learner; /// \brief Used to determine the next state array - private: double *nextState_; + private: double *next_state; + + /// \brief Used for ODE-int + protected: std::vector> ode_matrix; + protected: state_type x; /// \brief One input state for each input neuron - private: double *input_; + private: double *input; /// \brief Used to determine the output to the motors array - private: double *output_; + private: double *output; + + /// \brief Location where to save output + private: std::string directory_name; + + /// \brief Name of the robot + private: ::gazebo::physics::ModelPtr robot; + + /// \brief Init BO loop + public: void bo_init_sampling(); + + /// \brief Main BO loop + public: void bo_step(); + + /// \brief evaluation rate + private: double evaluation_rate; + + /// \brief Get fitness + private: void save_fitness(); + + /// \brief Pointer to the fitness evaluator + protected: EvaluatorPtr evaluator; + + /// \brief Holder for BO parameters + public: struct Params; + + /// \brief Save parameters + private: void save_parameters(); + + /// \brief Best fitness seen so far + private: double best_fitness = -10.0; + + /// \brief Sample corresponding to best fitness + private: Eigen::VectorXd best_sample; + + /// \brief Starting time + private: double start_time; + + /// \brief BO attributes + private: size_t current_iteration = 0; + + /// \brief Max number of iterations learning is allowed + private: size_t n_learning_iterations; + + /// \brief Number of initial samples + private: size_t n_init_samples; + + /// \brief Cool down period + private: size_t n_cooldown_iterations; + + /// \brief Limbo optimizes in [0,1] + private: double range_lb; + + /// \brief Limbo optimizes in [0,1] + private: double range_ub; + + /// \brief How to take initial random samples + private: std::string init_method; + + /// \brief All fitnesses seen so far. Called observations in limbo context + private: std::vector< Eigen::VectorXd > observations; + + /// \brief All samples seen so far. + private: std::vector< Eigen::VectorXd > samples; + + /// \brief The number of weights to optimize + private: size_t n_weights; + + /// \brief Dummy evaluation funtion to reduce changes to be made on the limbo package + public: struct evaluation_function; + + /// \brief Reset the robot to starting position each iteration. + private: bool reset_robot_position; + + /// \brief Reset neuron state at each iteration (also during validation) + private: bool reset_neuron_state_bool; + + /// \brief Factor to multiply output signal with + private: double signal_factor_all_; + + /// \brief Factor to multiply output signal with + private: double signal_factor_mid; + + /// \brief Factor to multiply output signal with + private: double signal_factor_left_right; + + /// \brief Function that resets neuron state + private: void reset_neuron_state(); + + /// \brief When reset a neuron state,do it randomly: + private: bool reset_neuron_random; + + /// \brief Boolean to enable/disable constructing plots + private: bool run_analytics; + + /// \brief Automatically generate plots + public: void get_analytics(); + + /// \brief Show output (1) or not (0) + public: int verbose; + + /// \brief Time to skip for fitness evaluation during training + public: int startup_time; + + /// \brief Helper for startup time + private: bool start_fitness_recording = true; + + /// \brief absolute bound on motor signal value + public: double abs_output_bound; + + /// \brief Holds the number of motors in the robot + private: size_t n_motors; + + /// \brief Helper for numerical integrator + private: double previous_time = 0; + + /// \brief Initial neuron state + private: double init_neuron_state; + + /// \brief Holder for loading a brain + private: std::string load_brain = ""; + + /// \brief Specifies the acquisition function used + public: std::string acquisition_function; + + /// \brief Use frame of reference {-1,0,1} version or not + private: bool use_frame_of_reference; + + // BO Learner parameters + private: double kernel_noise_; + private: bool kernel_optimize_noise_; + public: double kernel_sigma_sq_; + public: double kernel_l_; + private: int kernel_squared_exp_ard_k_; + private: double acqui_gpucb_delta_ ; + public: double acqui_ucb_alpha_; + private: double acqui_ei_jitter_; }; } } diff --git a/cpprevolve/revolve/gazebo/brains/DifferentialCPG_BO.h b/cpprevolve/revolve/gazebo/brains/DifferentialCPG_BO.h new file mode 100644 index 0000000000..c859415630 --- /dev/null +++ b/cpprevolve/revolve/gazebo/brains/DifferentialCPG_BO.h @@ -0,0 +1,195 @@ +// +// Created by maarten on 03/02/19. +// + +#ifndef REVOLVE_BOPTIMIZER_CPG_H +#define REVOLVE_BOPTIMIZER_CPG_H + +// Standard libraries +#include +#include +#include +#include + +// External libraries +#include +#include +#include +#include +#include +#include + +namespace limbo { + namespace defaults { + struct bayes_opt_boptimizer { + BO_PARAM(int, hp_period, -1); + }; + } + BOOST_PARAMETER_TEMPLATE_KEYWORD(acquiopt) + + namespace bayes_opt { + + using boptimizer_signature = boost::parameter::parameters, + boost::parameter::optional, + boost::parameter::optional, + boost::parameter::optional, + boost::parameter::optional, + boost::parameter::optional>; + + // clang-format off + /** + The classic Bayesian optimization algorithm. + + \rst + References: :cite:`brochu2010tutorial,Mockus2013` + \endrst + + This class takes the same template parameters as BoBase. It adds: + \rst + +---------------------+------------+----------+---------------+ + |type |typedef | argument | default | + +=====================+============+==========+===============+ + |acqui. optimizer |acquiopt_t | acquiopt | see below | + +---------------------+------------+----------+---------------+ + \endrst + + The default value of acqui_opt_t is: + - ``opt::NLOptNoGrad`` if NLOpt was found in `waf configure` + - ``opt::Cmaes`` if libcmaes was found but NLOpt was not found + - ``opt::GridSearch`` otherwise (please do not use this: the algorithm will not work as expected!) + */ + template + // clang-format on + class BOptimizer : public BoBase { + public: + // defaults + struct defaults { + using acquiopt_t = opt::NLOptNoGrad; + }; + + /// link to the corresponding BoBase (useful for typedefs) + using base_t = BoBase; + using model_t = typename base_t::model_t; + using acquisition_function_t = typename base_t::acquisition_function_t; + + // extract the types + using args = typename boptimizer_signature::bind::type; + using acqui_optimizer_t = typename boost::parameter::binding::type; + + /// The main function (run the Bayesian optimization algorithm) + template + void optimize(const StateFunction& sfun, std::vector all_samples, std::vector all_observations, const AggregatorFunction& afun = AggregatorFunction(), bool reset = true) + { + this->_init(sfun, afun, reset); //reset + + // Maarten: set observations and samples + this->_samples = all_samples; + this->_observations = all_observations; + + if (!this->_observations.empty()) { + _model.compute(this->_samples, this->_observations); + } + else { + std::cout << "OBSERVATION SET IS EMPTY \n"; + _model = model_t(StateFunction::dim_in(), StateFunction::dim_out()); + } + acqui_optimizer_t acqui_optimizer; + + struct timeval timeStart, timeEnd; + double timeDiff; + + while (!this->_stop(*this, afun)) { + + gettimeofday(&timeStart,NULL); + + acquisition_function_t acqui(_model, this->_current_iteration); + + auto acqui_optimization = + [&](const Eigen::VectorXd& x, bool g) { return acqui(x, afun, g); }; + Eigen::VectorXd starting_point = tools::random_vector(StateFunction::dim_in(), Params::bayes_opt_bobase::bounded()); + + // new samples are from the acquisition optimizer + Eigen::VectorXd new_sample = acqui_optimizer(acqui_optimization, starting_point, Params::bayes_opt_bobase::bounded()); + + ///Evaluate a sample and add the result to the 'database'(sample/observations vectors)--it does not update the model + this->eval_and_add(sfun, new_sample); + + this->_update_stats(*this, afun); + + _model.add_sample(this->_samples.back(), this->_observations.back()); + + if (Params::bayes_opt_boptimizer::hp_period() > 0 + && (this->_current_iteration + 1) % Params::bayes_opt_boptimizer::hp_period() == 0) + _model.optimize_hyperparams(); + + this->_current_iteration++; + this->_total_iterations++; + + gettimeofday(&timeEnd,NULL); + + timeDiff = 1000000 * (timeEnd.tv_sec - timeStart.tv_sec) + + timeEnd.tv_usec - timeStart.tv_usec; //tv_sec: value of second, tv_usec: value of microsecond + timeDiff/=1000; + + std::ofstream ctime; + ctime.open("../ctime.txt", std::ios::app); + ctime << std::fixed << timeDiff << std::endl; + } + } + + /// return the best observation so far (i.e. max(f(x))) + template + const Eigen::VectorXd& best_observation(const AggregatorFunction& afun = AggregatorFunction()) const + { + auto rewards = std::vector(this->_observations.size()); + std::transform(this->_observations.begin(), this->_observations.end(), rewards.begin(), afun); + auto max_e = std::max_element(rewards.begin(), rewards.end()); + return this->_observations[std::distance(rewards.begin(), max_e)]; + } + + /// return the best sample so far (i.e. the argmax(f(x))) + template + const Eigen::VectorXd& best_sample(const AggregatorFunction& afun = AggregatorFunction()) const + { + auto rewards = std::vector(this->_observations.size()); + std::transform(this->_observations.begin(), this->_observations.end(), rewards.begin(), afun); + auto max_e = std::max_element(rewards.begin(), rewards.end()); + return this->_samples[std::distance(rewards.begin(), max_e)]; + } + + /// Return a reference to the last sample. Used for implementation with revolve + const Eigen::VectorXd& last_sample(){ + return this->_samples.back(); + } + + const model_t& model() const { return _model; } + + protected: + model_t _model; + }; + + namespace _default_hp { + template + using model_t = model::GPOpt; + template + using acqui_t = acqui::UCB>; + } + + /// A shortcut for a BOptimizer with UCB + GPOpt + /// The acquisition function and the model CANNOT be tuned (use BOptimizer for this) + template + using BOptimizerHPOpt = BOptimizer>, acquifun<_default_hp::acqui_t>, A1, A2, A3, A4>; + } +} + +#endif //REVOLVE_BOPTIMIZER_CPG_H diff --git a/cpprevolve/revolve/gazebo/brains/Evaluator.cpp b/cpprevolve/revolve/gazebo/brains/Evaluator.cpp index 0213c662ec..e082cd1596 100644 --- a/cpprevolve/revolve/gazebo/brains/Evaluator.cpp +++ b/cpprevolve/revolve/gazebo/brains/Evaluator.cpp @@ -26,13 +26,29 @@ using namespace revolve::gazebo; ///////////////////////////////////////////////// -Evaluator::Evaluator(const double _evaluationRate) +double Evaluator::measure_distance( + const ignition::math::Pose3d &_pose1, + const ignition::math::Pose3d &_pose2) +{ + return std::sqrt(std::pow(_pose1.Pos().X() - _pose2.Pos().X(), 2) + + std::pow(_pose1.Pos().Y() - _pose2.Pos().Y(), 2)); +} + +///////////////////////////////////////////////// +Evaluator::Evaluator(const double _evaluationRate, + const double step_saving_rate) + : last_step_time(-1) + , step_saving_rate(step_saving_rate) + , step_poses(0) { assert(_evaluationRate > 0 and "`_evaluationRate` should be greater than 0"); - this->evaluationRate_ = _evaluationRate; + this->evaluation_rate_ = _evaluationRate; - this->currentPosition_.Reset(); - this->previousPosition_.Reset(); + this->current_position_.Reset(); + this->previous_position_.Reset(); + this->start_position_.Reset(); + this->locomotion_type = "directed"; // {directed, gait} + this->path_length = 0.0; } ///////////////////////////////////////////////// @@ -41,22 +57,141 @@ Evaluator::~Evaluator() = default; ///////////////////////////////////////////////// void Evaluator::Reset() { - this->previousPosition_ = this->currentPosition_; + this->step_poses.clear(); //cleared to null + this->path_length = 0.0; + this->last_step_time = 0.0; + this->start_position_ = this->current_position_; } ///////////////////////////////////////////////// double Evaluator::Fitness() { - auto dS = std::sqrt(std::pow(this->previousPosition_.Pos().X() - - this->currentPosition_.Pos().X(), 2) + - std::pow(this->previousPosition_.Pos().Y() - - this->currentPosition_.Pos().Y(), 2)); - this->previousPosition_ = this->currentPosition_; - return dS / this->evaluationRate_; + double fitness_value = 0.0; + if(this->locomotion_type == "gait") + { + double dS; + dS = std::sqrt(std::pow(this->previous_position_.Pos().X() - + this->current_position_.Pos().X(), 2) + + std::pow(this->previous_position_.Pos().Y() - + this->current_position_.Pos().Y(), 2)); + fitness_value = dS / this->evaluation_rate_; + } + else if (this->locomotion_type == "directed") + { + + this->step_poses.push_back(this->current_position_); + //step_poses: x y z roll pitch yaw + for (int i=1; i < this->step_poses.size(); i++) + { + const auto &pose_i_1 = this->step_poses[i-1]; + const auto &pose_i = this->step_poses[i]; + this->path_length += Evaluator::measure_distance(pose_i_1, pose_i); + //save coordinations to coordinates.txt + std::ofstream coordinates; + coordinates.open(this->directory_name + "/coordinates.txt",std::ios::app); + + if(i == 1) + { + coordinates << std::fixed << start_position_.Pos().X() << " " << start_position_.Pos().Y() << std::endl; + } + coordinates << std::fixed << pose_i.Pos().X() << " " << pose_i.Pos().Y() << std::endl; + } + + ////********** directed locomotion fitness function **********//// + //directions(forward) of heads are the orientation(+x axis) - 1.570796 + double beta0 = this->start_position_.Rot().Yaw()- M_PI/2.0; + if (beta0 < - M_PI) //always less than pi (beta0 + max(40degree) < pi) + { + beta0 = 2 * M_PI - std::abs(beta0); + } + + //save direction to coordinates.txt: This is used to make Figure 8 + std::ofstream coordinates; + coordinates.open(this->directory_name + "/coordinates.txt",std::ios::app); + coordinates << std::fixed << beta0 << std::endl; + + double beta1 = std::atan2( + this->current_position_.Pos().Y() - this->start_position_.Pos().Y(), + this->current_position_.Pos().X() - this->start_position_.Pos().X()); + + double alpha; + if (std::abs(beta1 - beta0) > M_PI) + { + alpha = 2 * M_PI - std::abs(beta1) - std::abs(beta0); + } else + { + alpha = std::abs(beta1 - beta0); + } + + double A = std::tan(beta0); + double B = this->start_position_.Pos().Y() + - A * this->start_position_.Pos().X(); + + double X_p = (A * (this->current_position_.Pos().Y() - B) + + this->current_position_.Pos().X()) / (A * A + 1); + double Y_p = A * X_p + B; + + //calculate the fitness_direction based on dist_projection, alpha, penalty + double dist_projection; + double dist_penalty; + double penalty; + double fitness_direction; + double ksi = 1.0; + if (alpha > 0.5 * M_PI) + { + dist_projection = -std::sqrt( + std::pow((this->start_position_.Pos().X() - X_p), 2.0) + + std::pow((this->start_position_.Pos().Y() - Y_p), 2.0)); + dist_penalty = std::sqrt( + std::pow((this->current_position_.Pos().X() - X_p), 2.0) + + std::pow((this->current_position_.Pos().Y() - Y_p), 2.0)); + penalty = 0.01 * dist_penalty; + } + else + { + dist_projection = std::sqrt( + std::pow((this->start_position_.Pos().X() - X_p), 2.0) + + std::pow((this->start_position_.Pos().Y() - Y_p), 2.0)); + dist_penalty = std::sqrt( + std::pow((this->current_position_.Pos().X() - X_p), 2.0) + + std::pow((this->current_position_.Pos().Y() - Y_p), 2.0)); + penalty = 0.01 * dist_penalty; + } + + //fitness_direction = dist_projection / (alpha + ksi) - penalty; + fitness_direction = std::abs(dist_projection) / path_length * + (dist_projection / (alpha + ksi) - penalty); + fitness_value = fitness_direction; + } + return fitness_value; } -///////////////////////////////////////////////// -void Evaluator::Update(const ignition::math::Pose3d &_pose) +// update is always running in the loop +void Evaluator::Update(const ignition::math::Pose3d &_pose, + const double time, + const double step) { - this->currentPosition_ = _pose; + // this->path_length += measure_distance(current_position_, _pose); + this->previous_position_ = current_position_; + this->current_position_ = _pose; + + //If `last_step_time` is not initialized, do the initialization now + if (this->last_step_time < 0) + { + this->last_step_time = time; // 0.005 + this->step_poses.push_back(_pose); + } + + //save the startPosition in the beginning of each iteration + if (this->last_step_time < 0.001) // 0.001 < 0.005 + { + this->step_poses.push_back(_pose); + this->last_step_time = time; + } + //update information each step + if ((time - this->last_step_time) > this->evaluation_rate_ * this->step_saving_rate) + { + this->step_poses.push_back(_pose); + this->last_step_time = time; + }; } diff --git a/cpprevolve/revolve/gazebo/brains/Evaluator.h b/cpprevolve/revolve/gazebo/brains/Evaluator.h index c57d48a41a..357634da57 100644 --- a/cpprevolve/revolve/gazebo/brains/Evaluator.h +++ b/cpprevolve/revolve/gazebo/brains/Evaluator.h @@ -31,7 +31,8 @@ namespace revolve class Evaluator { /// \brief Constructor - public: Evaluator(const double _evaluationRate); + public: Evaluator(const double _evaluationRate, + const double step_saving_rate = 0.1); /// \brief Destructor public: ~Evaluator(); @@ -43,18 +44,38 @@ namespace revolve /// \return A fitness value according to a given formula public: double Fitness(); + public: double measure_distance( + const ignition::math::Pose3d &_pose1, + const ignition::math::Pose3d &_pose2); + + /// brief Specifies locomotion type + public: std::string locomotion_type; + /// \brief Update the position /// \param[in] _pose Current position of a robot - public: void Update(const ignition::math::Pose3d &_pose); + public: void Update(const ignition::math::Pose3d &_pose, + const double time, + const double step); + + /// \brief start position of a robot + protected: ignition::math::Pose3d start_position_; /// \brief Previous position of a robot - private: ignition::math::Pose3d previousPosition_; + protected: ignition::math::Pose3d previous_position_; /// \brief Current position of a robot - private: ignition::math::Pose3d currentPosition_; + protected: ignition::math::Pose3d current_position_; /// \brief - private: double evaluationRate_; + protected: double evaluation_rate_; + + protected: double path_length = 0.0; + + protected: double last_step_time; + protected: double step_saving_rate; + protected: std::vector step_poses; + // public: double current_dist_pro = 0.0; + public: std::string directory_name = ""; }; } } diff --git a/cpprevolve/revolve/gazebo/brains/NeuralNetwork.cpp b/cpprevolve/revolve/gazebo/brains/NeuralNetwork.cpp index 7a9b406287..94fd84f372 100644 --- a/cpprevolve/revolve/gazebo/brains/NeuralNetwork.cpp +++ b/cpprevolve/revolve/gazebo/brains/NeuralNetwork.cpp @@ -60,23 +60,15 @@ NeuralNetwork::NeuralNetwork( , nHidden_(0) , nNonInputs_(0) { - // Create transport node - this->node_.reset(new gz::transport::Node()); - this->node_->Init(); +// // Create transport node +// this->node_.reset(new gz::transport::Node()); +// this->node_->Init(); - auto name = _model->GetName(); - // Listen to network modification requests - this->alterSub_ = this->node_->Subscribe( - "~/" + name + "/modify_neural_network", &NeuralNetwork::Modify, - this); - - // Initialize weights, input and states to zero by default - std::memset(this->inputWeights_, 0, sizeof(this->inputWeights_)); - std::memset(this->outputWeights_, 0, sizeof(this->outputWeights_)); - std::memset(this->hiddenWeights_, 0, sizeof(this->hiddenWeights_)); - std::memset(this->state1_, 0, sizeof(this->state1_)); - std::memset(this->state2_, 0, sizeof(this->state2_)); - std::memset(this->input_, 0, sizeof(this->input_)); +// auto name = _model->GetName(); +// // Listen to network modification requests +// this->alterSub_ = this->node_->Subscribe( +// "~/" + name + "/modify_neural_network", &NeuralNetwork::Modify, +// this); // We now setup the neural network and its parameters. The end result // of this operation should be that we can iterate/update all sensors in @@ -132,43 +124,18 @@ NeuralNetwork::NeuralNetwork( // INPUT LAYER if ("input" == layer) { - if (this->nInputs_ >= MAX_INPUT_NEURONS) - { - std::cerr << "The number of input neurons(" << (nInputs_ + 1) - << ") is greater than the maximum allowed one (" - << MAX_INPUT_NEURONS << ")" << std::endl; - throw std::runtime_error("Robot brain error"); - } - toProcess.insert(neuronId); ++(this->nInputs_); } // OUTPUT LAYER else if ("output" == layer) { - if (this->nOutputs_ >= MAX_OUTPUT_NEURONS) - { - std::cerr << "The number of output neurons(" << (nOutputs_ + 1) - << ") is greater than the maximum allowed (" - << MAX_OUTPUT_NEURONS << ")"<< std::endl; - throw std::runtime_error("Robot brain error"); - } - toProcess.insert(neuronId); ++(this->nOutputs_); } // HIDDEN LAYER else if ("hidden" == layer) { - if (hiddenNeurons.size() >= MAX_HIDDEN_NEURONS) - { - std::cerr << "The number of hidden neurons(" - << (hiddenNeurons.size() + 1) - << ") is greater than the maximum allowed one (" - << MAX_HIDDEN_NEURONS << ")" << std::endl; - throw std::runtime_error("Robot brain error"); - } - hiddenNeurons.push_back(neuronId); ++(this->nHidden_); } @@ -181,6 +148,16 @@ NeuralNetwork::NeuralNetwork( neuron = neuron->GetNextElement("rv:neuron"); } + // Initialize weights, input and states to zero by default + this->inputWeights_.resize(this->nInputs_ * (this->nOutputs_ + this->nHidden_), 0); + this->outputWeights_.resize(this->nOutputs_ * (this->nOutputs_ + this->nHidden_), 0); + this->hiddenWeights_.resize(this->nHidden_ * (this->nOutputs_ + this->nHidden_), 0); + this->types_.resize(this->nOutputs_ + this->nHidden_, 0); + this->params_.resize(MAX_NEURON_PARAMS * (this->nOutputs_ + this->nHidden_), 0); + this->state1_.resize(this->nOutputs_ + this->nHidden_, 0); + this->state2_.resize(this->nOutputs_ + this->nHidden_, 0); + this->input_.resize(this->nInputs_, 0); + // Create motor output neurons at the correct position // We iterate a part's motors and just assign every // neuron we find in order. @@ -213,8 +190,8 @@ NeuralNetwork::NeuralNetwork( } std::string neuronId = (*neuron_iter)->GetAttribute("id")->GetAsString(); - neuronHelper(&this->params_[outputsIndex * MAX_NEURON_PARAMS], - &this->types_[outputsIndex], + neuronHelper(&this->params_.at(outputsIndex * MAX_NEURON_PARAMS), + &this->types_.at(outputsIndex), *neuron_iter); this->positionMap_[neuronId] = outputsIndex; toProcess.erase(neuronId); @@ -288,8 +265,8 @@ NeuralNetwork::NeuralNetwork( // Offset with output neurons within params / types auto pos = this->nOutputs_ + outputsIndex; - neuronHelper(&this->params_[pos * MAX_NEURON_PARAMS], - &this->types_[pos], + neuronHelper(&this->params_.at(pos * MAX_NEURON_PARAMS), + &this->types_.at(pos), neuronMap[neuronId]); ++outputsIndex; } @@ -336,20 +313,20 @@ void NeuralNetwork::Step(const double _time) return; } - double *curState, *nextState; + std::vector *curState, *nextState; if (this->flipState_) { - curState = this->state2_; - nextState = this->state1_; + curState = &this->state2_; + nextState = &this->state1_; } else { - curState = this->state1_; - nextState = this->state2_; + curState = &this->state1_; + nextState = &this->state2_; } - unsigned int maxNonInputs = MAX_HIDDEN_NEURONS + MAX_OUTPUT_NEURONS; + unsigned int maxNonInputs = this->nHidden_ + this->nOutputs_; for (i = 0; i < this->nNonInputs_; ++i) { double curNeuronActivation = 0; @@ -365,29 +342,29 @@ void NeuralNetwork::Step(const double _time) for (j = 0; j < this->nOutputs_; ++j) { curNeuronActivation += this->outputWeights_[maxNonInputs * j + i] - * curState[j]; + * curState->at(j); } // Add hidden neuron values for (j = 0; j < this->nHidden_; ++j) { curNeuronActivation += this->hiddenWeights_[maxNonInputs * j + i] - * curState[this->nOutputs_ + j]; + * curState->at(this->nOutputs_ + j); } unsigned int base = MAX_NEURON_PARAMS * i; - switch (this->types_[i]) + switch (this->types_.at(i)) { case SIGMOID: /* params are bias, gain */ curNeuronActivation -= this->params_[base]; - nextState[i] = + nextState->at(i) = 1.0 / (1.0 + exp(-(this->params_[base + 1]) * curNeuronActivation)); break; case SIMPLE: /* linear, params are bias, gain */ curNeuronActivation -= this->params_[base]; - nextState[i] = this->params_[base + 1] * curNeuronActivation; + nextState->at(i) = this->params_[base + 1] * curNeuronActivation; break; case OSCILLATOR: { // Use the block to prevent "crosses initialization" error @@ -397,11 +374,11 @@ void NeuralNetwork::Step(const double _time) double gain = this->params_[base + 2]; /* Value in [0, 1] */ - nextState[i] = ((sin((2.0 * M_PI / period) * + nextState->at(i) = ((sin((2.0 * M_PI / period) * (_time - period * phaseOffset))) + 1.0) / 2.0; /* set output to be in [0.5 - gain/2, 0.5 + gain/2] */ - nextState[i] = (0.5 - (gain / 2.0) + nextState[i] * gain); + nextState->at(i) = (0.5 - (gain / 2.0) + nextState->at(i) * gain); } break; default: @@ -422,13 +399,13 @@ void NeuralNetwork::Update( const double _time, const double _step) { - boost::mutex::scoped_lock lock(this->networkMutex_); +// boost::mutex::scoped_lock lock(this->networkMutex_); // Read sensor data and feed the neural network unsigned int p = 0; for (const auto &sensor : _sensors) { - sensor->Read(&this->input_[p]); + sensor->Read(this->input_.data()+p); p += sensor->Inputs(); } @@ -436,213 +413,213 @@ void NeuralNetwork::Update( // Since the output neurons are the first in the state // array we can just use it to update the motors directly. - auto output = this->flipState_ ? &this->state2_[0] : &this->state1_[0]; + const std::vector &output = this->flipState_ ? this->state2_ : this->state1_; // Send new signals to the motors p = 0; for (const auto &motor: _motors) { - motor->Update(&output[p], _step); + motor->Update(output.data()+p, _step); p += motor->Outputs(); } } ///////////////////////////////////////////////// -void NeuralNetwork::Modify(ConstModifyNeuralNetworkPtr &_request) -{ - boost::mutex::scoped_lock lock(this->networkMutex_); - - unsigned int i, j; - for (i = 0; i < (unsigned int)_request->remove_hidden_size(); ++i) - { - // Find the neuron + position - auto id = _request->remove_hidden(i); - if (not this->positionMap_.count(id)) - { - std::cerr << "Unknown neuron ID `" << id << "`" << std::endl; - throw std::runtime_error("Robot brain error"); - } - - if ("hidden" not_eq this->layerMap_[id]) - { - std::cerr - << "Cannot remove neuron ID `" - << id - << "`, it is not a hidden neuron." - << std::endl; - throw std::runtime_error("Robot brain error"); - } - - auto pos = this->positionMap_[id]; - this->positionMap_.erase(id); - this->layerMap_.erase(id); - - // Shift types - auto s = sizeof(this->types_[0]); - std::memmove( - // Position shifted one type to the left - this->types_ + (pos + this->nOutputs_) * s, - - // Position of next neuron type - this->types_ + (pos + this->nOutputs_ + 1) * s, - - // # of hidden neurons beyond this one - s * (this->nHidden_ - pos - 1)); - - // Shift parameters - s = sizeof(this->params_[0]); - std::memmove( - // Position of item to remove - this->params_ + (pos + this->nOutputs_) * MAX_NEURON_PARAMS * s, - - // Position of next neuron type - this->params_ + (pos + this->nOutputs_ + 1) * MAX_NEURON_PARAMS * s, - - // # of hidden neurons beyond this one - (this->nHidden_ - pos - 1) * MAX_NEURON_PARAMS * s); - - // Reposition items in weight arrays. We start with the weights of - // connections pointing *to* the neuron to be removed. For each entry in - // each of the three weights arrays we have to move all hidden connection - // weights down, then zero out the last entry - s = sizeof(this->inputWeights_[0]); - double *weightArrays[] = { - this->inputWeights_, - this->outputWeights_, - this->hiddenWeights_ - }; - unsigned int sizes[] = { - this->nInputs_, - this->nOutputs_, - this->nHidden_ - }; - - for (size_t k = 0; k < 3; ++k) - { - auto weights = weightArrays[k]; - auto size = sizes[k]; - - for (j = 0; j < size; ++j) - { - std::memmove( - // Position of item to remove - weights + (this->nOutputs_ + pos) * s, - - // Position of next item - weights + (this->nOutputs_ + pos + 1) * s, - - // # of possible hidden neurons beyond this one - (MAX_HIDDEN_NEURONS - pos - 1) * s); - - // Zero out the last item in case a connection that corresponds to it - // is ever added. - weights[this->nOutputs_ + pos] = 0; - } - } - - // Now the weights where the removed neuron is the source. The block of - // weights corresponding to the neuron that is being removed needs to be - // removed by shifting down all items beyond it. - std::memmove( - // Position of the item to remove - this->hiddenWeights_ + pos * MAX_NON_INPUT_NEURONS * s, - - // Position of the next item - this->hiddenWeights_ + (pos + 1) * MAX_NON_INPUT_NEURONS * s, - - // Remaining number of memory items - (MAX_HIDDEN_NEURONS - pos - 1) * MAX_NON_INPUT_NEURONS * s); - - // Zero the remaining entries at the end - std::memset(this->hiddenWeights_ + (MAX_HIDDEN_NEURONS - 1) * s, - 0, - MAX_NON_INPUT_NEURONS * s); - - // Decrement the entry in the `positionMap` for all hidden neurons above - // this one. - for (auto iter = this->positionMap_.begin(); - iter not_eq this->positionMap_.end(); ++iter) - { - auto layer = this->layerMap_[iter->first]; - if ("hidden" == layer and this->positionMap_[iter->first] > pos) - { - --(this->positionMap_[iter->first]); - } - } - - --(this->nHidden_); - --(this->nNonInputs_); - } - - // Add new requested hidden neurons - for (i = 0; i < (unsigned int)_request->add_hidden_size(); ++i) - { - if (this->nHidden_ >= MAX_HIDDEN_NEURONS) - { - std::cerr - << "Cannot add hidden neuron; the max (" - << MAX_HIDDEN_NEURONS - << ") is already reached." - << std::endl; - throw std::runtime_error("Robot brain error"); - } - - auto neuron = _request->add_hidden(i); - const auto id = neuron.id(); - if (this->layerMap_.count(id)) - { - std::cerr << "Adding duplicate neuron ID `" << id << "`" << std::endl; - throw std::runtime_error("Robot brain error"); - } - - this->positionMap_[id] = this->nHidden_; - this->layerMap_[id] = "hidden"; - - unsigned int pos = this->nOutputs_ + this->nHidden_; - neuronHelper( - &this->params_[pos * MAX_NEURON_PARAMS], - &this->types_[pos], - neuron); - - ++(this->nHidden_); - ++(this->nNonInputs_); - } - - // Update parameters of existing neurons - for (i = 0; i < (unsigned int)_request->set_parameters_size(); ++i) - { - auto neuron = _request->set_parameters(i); - const auto id = neuron.id(); - if (not this->positionMap_.count(id)) - { - std::cerr << "Unknown neuron ID `" << id << "`" << std::endl; - throw std::runtime_error("Robot brain error"); - } - - auto pos = this->positionMap_[id]; - auto layer = this->layerMap_[id]; - - if ("input" == layer) - { - std::cerr << "Input neurons cannot be modified." << std::endl; - throw std::runtime_error("Robot brain error"); - } - - neuronHelper( - &this->params_[pos * MAX_NEURON_PARAMS], - &this->types_[pos], - neuron); - } - - // Set weights of new or existing connections - for (i = 0; i < (unsigned int)_request->set_weights_size(); ++i) - { - auto conn = _request->set_weights(i); - const auto src = conn.src(); - const auto dst = conn.dst(); - this->ConnectionHelper(src, dst, conn.weight()); - } -} +//void NeuralNetwork::Modify(ConstModifyNeuralNetworkPtr &_request) +//{ +// boost::mutex::scoped_lock lock(this->networkMutex_); +// +// unsigned int i, j; +// for (i = 0; i < (unsigned int)_request->remove_hidden_size(); ++i) +// { +// // Find the neuron + position +// auto id = _request->remove_hidden(i); +// if (not this->positionMap_.count(id)) +// { +// std::cerr << "Unknown neuron ID `" << id << "`" << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// if ("hidden" not_eq this->layerMap_[id]) +// { +// std::cerr +// << "Cannot remove neuron ID `" +// << id +// << "`, it is not a hidden neuron." +// << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// auto pos = this->positionMap_[id]; +// this->positionMap_.erase(id); +// this->layerMap_.erase(id); +// +// // Shift types +// auto s = sizeof(this->types_[0]); +// std::memmove( +// // Position shifted one type to the left +// this->types_ + (pos + this->nOutputs_) * s, +// +// // Position of next neuron type +// this->types_ + (pos + this->nOutputs_ + 1) * s, +// +// // # of hidden neurons beyond this one +// s * (this->nHidden_ - pos - 1)); +// +// // Shift parameters +// s = sizeof(this->params_[0]); +// std::memmove( +// // Position of item to remove +// this->params_ + (pos + this->nOutputs_) * MAX_NEURON_PARAMS * s, +// +// // Position of next neuron type +// this->params_ + (pos + this->nOutputs_ + 1) * MAX_NEURON_PARAMS * s, +// +// // # of hidden neurons beyond this one +// (this->nHidden_ - pos - 1) * MAX_NEURON_PARAMS * s); +// +// // Reposition items in weight arrays. We start with the weights of +// // connections pointing *to* the neuron to be removed. For each entry in +// // each of the three weights arrays we have to move all hidden connection +// // weights down, then zero out the last entry +// s = sizeof(this->inputWeights_[0]); +// double *weightArrays[] = { +// this->inputWeights_, +// this->outputWeights_, +// this->hiddenWeights_ +// }; +// unsigned int sizes[] = { +// this->nInputs_, +// this->nOutputs_, +// this->nHidden_ +// }; +// +// for (size_t k = 0; k < 3; ++k) +// { +// auto weights = weightArrays[k]; +// auto size = sizes[k]; +// +// for (j = 0; j < size; ++j) +// { +// std::memmove( +// // Position of item to remove +// weights + (this->nOutputs_ + pos) * s, +// +// // Position of next item +// weights + (this->nOutputs_ + pos + 1) * s, +// +// // # of possible hidden neurons beyond this one +// (MAX_HIDDEN_NEURONS - pos - 1) * s); +// +// // Zero out the last item in case a connection that corresponds to it +// // is ever added. +// weights[this->nOutputs_ + pos] = 0; +// } +// } +// +// // Now the weights where the removed neuron is the source. The block of +// // weights corresponding to the neuron that is being removed needs to be +// // removed by shifting down all items beyond it. +// std::memmove( +// // Position of the item to remove +// this->hiddenWeights_ + pos * MAX_NON_INPUT_NEURONS * s, +// +// // Position of the next item +// this->hiddenWeights_ + (pos + 1) * MAX_NON_INPUT_NEURONS * s, +// +// // Remaining number of memory items +// (MAX_HIDDEN_NEURONS - pos - 1) * MAX_NON_INPUT_NEURONS * s); +// +// // Zero the remaining entries at the end +// std::memset(this->hiddenWeights_ + (MAX_HIDDEN_NEURONS - 1) * s, +// 0, +// MAX_NON_INPUT_NEURONS * s); +// +// // Decrement the entry in the `positionMap` for all hidden neurons above +// // this one. +// for (auto iter = this->positionMap_.begin(); +// iter not_eq this->positionMap_.end(); ++iter) +// { +// auto layer = this->layerMap_[iter->first]; +// if ("hidden" == layer and this->positionMap_[iter->first] > pos) +// { +// --(this->positionMap_[iter->first]); +// } +// } +// +// --(this->nHidden_); +// --(this->nNonInputs_); +// } +// +// // Add new requested hidden neurons +// for (i = 0; i < (unsigned int)_request->add_hidden_size(); ++i) +// { +// if (this->nHidden_ >= MAX_HIDDEN_NEURONS) +// { +// std::cerr +// << "Cannot add hidden neuron; the max (" +// << MAX_HIDDEN_NEURONS +// << ") is already reached." +// << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// auto neuron = _request->add_hidden(i); +// const auto id = neuron.id(); +// if (this->layerMap_.count(id)) +// { +// std::cerr << "Adding duplicate neuron ID `" << id << "`" << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// this->positionMap_[id] = this->nHidden_; +// this->layerMap_[id] = "hidden"; +// +// unsigned int pos = this->nOutputs_ + this->nHidden_; +// neuronHelper( +// &this->params_[pos * MAX_NEURON_PARAMS], +// &this->types_[pos], +// neuron); +// +// ++(this->nHidden_); +// ++(this->nNonInputs_); +// } +// +// // Update parameters of existing neurons +// for (i = 0; i < (unsigned int)_request->set_parameters_size(); ++i) +// { +// auto neuron = _request->set_parameters(i); +// const auto id = neuron.id(); +// if (not this->positionMap_.count(id)) +// { +// std::cerr << "Unknown neuron ID `" << id << "`" << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// auto pos = this->positionMap_[id]; +// auto layer = this->layerMap_[id]; +// +// if ("input" == layer) +// { +// std::cerr << "Input neurons cannot be modified." << std::endl; +// throw std::runtime_error("Robot brain error"); +// } +// +// neuronHelper( +// &this->params_[pos * MAX_NEURON_PARAMS], +// &this->types_[pos], +// neuron); +// } +// +// // Set weights of new or existing connections +// for (i = 0; i < (unsigned int)_request->set_weights_size(); ++i) +// { +// auto conn = _request->set_weights(i); +// const auto src = conn.src(); +// const auto dst = conn.dst(); +// this->ConnectionHelper(src, dst, conn.weight()); +// } +//} ///////////////////////////////////////////////// void NeuralNetwork::ConnectionHelper( @@ -684,7 +661,7 @@ void NeuralNetwork::ConnectionHelper( } // Determine the index of the weight. - unsigned int idx = (srcNeuronPos * MAX_NON_INPUT_NEURONS) + dstNeuronPos; + unsigned int idx = (srcNeuronPos * this->nNonInputs_) + dstNeuronPos; if ("input" == srcLayer) { this->inputWeights_[idx] = _weight; diff --git a/cpprevolve/revolve/gazebo/brains/NeuralNetwork.h b/cpprevolve/revolve/gazebo/brains/NeuralNetwork.h index 19505d8a55..a1147f6663 100644 --- a/cpprevolve/revolve/gazebo/brains/NeuralNetwork.h +++ b/cpprevolve/revolve/gazebo/brains/NeuralNetwork.h @@ -32,19 +32,6 @@ #include "Brain.h" -/// These numbers are quite arbitrary. It used to be in:13 out:8 for the -/// Arduino, but I upped them both to 20 to accommodate other scenarios. -/// Should really be enforced in the Python code, this implementation should -/// not be the limit. -#define MAX_INPUT_NEURONS 20 -#define MAX_OUTPUT_NEURONS 20 - -/// Arbitrary value -#define MAX_HIDDEN_NEURONS 30 - -/// Convenience -#define MAX_NON_INPUT_NEURONS (MAX_HIDDEN_NEURONS + MAX_OUTPUT_NEURONS) - /// (bias, tau, gain) or (phase offset, period, gain) #define MAX_NEURON_PARAMS 3 @@ -52,8 +39,8 @@ namespace revolve { namespace gazebo { - typedef const boost::shared_ptr< revolve::msgs::ModifyNeuralNetwork const > - ConstModifyNeuralNetworkPtr; +// typedef const boost::shared_ptr< revolve::msgs::ModifyNeuralNetwork const > +// ConstModifyNeuralNetworkPtr; /// Copied from NeuronRepresentation.h enum neuronType @@ -97,8 +84,8 @@ namespace revolve /// \brief Steps the neural network protected: void Step(const double _time); - /// \brief Request handler to modify the neural network - protected: void Modify(ConstModifyNeuralNetworkPtr &_request); +// /// \brief Request handler to modify the neural network +// protected: void Modify(ConstModifyNeuralNetworkPtr &_request); /// \brief Network modification subscriber protected: ::gazebo::transport::SubscriberPtr alterSub_; @@ -109,36 +96,32 @@ namespace revolve /// entries for the maximum possible number of connections. This makes /// restructuring the weights arrays when a hidden neuron is removed /// slightly less cumbersome. - protected: double inputWeights_[ - MAX_INPUT_NEURONS * (MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS)]; + protected: std::vector inputWeights_; /// \brief output weights - protected: double outputWeights_[ - MAX_OUTPUT_NEURONS * (MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS)]; + protected: std::vector outputWeights_; /// \brief hidden weights - protected: double hiddenWeights_[ - MAX_HIDDEN_NEURONS * (MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS)]; + protected: std::vector hiddenWeights_; /// \brief Type of each non-input neuron /// \details Unlike weights, types, params and current states are stored /// without gaps, meaning the first `m` entries are for output neurons, /// followed by `n` entries for hidden neurons. If a hidden neuron is /// removed, the items beyond it are moved back. - protected: unsigned int types_[(MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS)]; + protected: std::vector types_; /// \brief Params for hidden and output neurons, quantity depends on /// the type of neuron - protected: double params_[ - MAX_NEURON_PARAMS * (MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS)]; + protected: std::vector params_; /// \brief Output states arrays for the current state and the next state. - protected: double state1_[MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS]; + protected: std::vector state1_; - protected: double state2_[MAX_OUTPUT_NEURONS + MAX_HIDDEN_NEURONS]; + protected: std::vector state2_; /// \brief One input state for each input neuron - protected: double input_[MAX_INPUT_NEURONS]; + protected: std::vector input_; /// \brief Used to determine the current state array. /// \example false := state1, true := state2. diff --git a/cpprevolve/revolve/gazebo/brains/RLPower.cpp b/cpprevolve/revolve/gazebo/brains/RLPower.cpp index 5a58448b2b..527ced5c72 100644 --- a/cpprevolve/revolve/gazebo/brains/RLPower.cpp +++ b/cpprevolve/revolve/gazebo/brains/RLPower.cpp @@ -39,25 +39,25 @@ using namespace revolve::gazebo; ///////////////////////////////////////////////// RLPower::RLPower( const ::gazebo::physics::ModelPtr &_model, - const sdf::ElementPtr &_node, + const sdf::ElementPtr &_settings, const std::vector< MotorPtr > &_motors, const std::vector< SensorPtr > &_sensors) : generationCounter_(0) , cycleStartTime_(-1) , startTime_(-1) + , evaluationRate_(30.0) // default { // Create transport node this->node_.reset(new gz::transport::Node()); this->node_->Init(); -// // Listen to network modification requests -// this->alterSub_ = this->node_->Subscribe( -// "~/" + _modelName + "/modify_spline_policy", &RLPower::Modify, -// this); + auto learner_settings = _settings->GetElement("rv:learner"); this->robot_ = _model; this->algorithmType_ = "D"; - this->evaluationRate_ = 30.0; + try { + this->evaluationRate_ = std::stod(learner_settings->GetAttribute("evaluation_rate")->GetAsString()); + } catch (const std::exception &e) {} this->numInterpolationPoints_ = 100; this->maxEvaluations_ = 1000; this->maxRankedPolicies_ = 10; @@ -119,7 +119,7 @@ void RLPower::Update( } auto currPosition = this->robot_->WorldPose(); - this->evaluator_->Update(currPosition); + this->evaluator_->Update(currPosition, _time, _step); delete[] output; } @@ -260,7 +260,7 @@ void RLPower::UpdatePolicy(const size_t _numSplines) } // Increase spline points if it is a time - if (this->generationCounter_ % this->stepRate_ == 0) + if (this->sourceYSize_ <= 5 and this->generationCounter_ % this->stepRate_ == 0) { this->IncreaseSplinePoints(_numSplines); } diff --git a/cpprevolve/revolve/gazebo/brains/RLPower.h b/cpprevolve/revolve/gazebo/brains/RLPower.h index 18d30f3976..2e49c0e9c7 100644 --- a/cpprevolve/revolve/gazebo/brains/RLPower.h +++ b/cpprevolve/revolve/gazebo/brains/RLPower.h @@ -69,7 +69,7 @@ namespace revolve /// \return pointer to the RLPower class object public: RLPower( const ::gazebo::physics::ModelPtr &_model, - const sdf::ElementPtr &_node, + const sdf::ElementPtr &_settings, const std::vector< MotorPtr > &_motors, const std::vector< SensorPtr > &_sensors); @@ -185,7 +185,7 @@ namespace revolve /// \brief Maximal number of stored ranked policies private: size_t maxRankedPolicies_; - /// \brief Maximal number of evaluations + /// \brief Maximal numberEvaluator of evaluations private: size_t maxEvaluations_; /// \brief The size of a spline before beeing increased diff --git a/cpprevolve/revolve/gazebo/motors/Motor.h b/cpprevolve/revolve/gazebo/motors/Motor.h index 7c10155c07..3441f61beb 100644 --- a/cpprevolve/revolve/gazebo/motors/Motor.h +++ b/cpprevolve/revolve/gazebo/motors/Motor.h @@ -55,7 +55,7 @@ namespace revolve /// values if it specifies `n` outputs. /// \param[in] step Actuation time in seconds public: virtual void Update( - double *_output, + const double *_output, double _step) = 0; /// \brief Retrieve the ID diff --git a/cpprevolve/revolve/gazebo/motors/PositionMotor.cpp b/cpprevolve/revolve/gazebo/motors/PositionMotor.cpp index 16a86b613f..63a33724fe 100644 --- a/cpprevolve/revolve/gazebo/motors/PositionMotor.cpp +++ b/cpprevolve/revolve/gazebo/motors/PositionMotor.cpp @@ -77,7 +77,7 @@ PositionMotor::~PositionMotor() = default; ///////////////////////////////////////////////// void PositionMotor::Update( - double *outputs, + const double *outputs, double /*step*/) { // Just one network output, which is the first diff --git a/cpprevolve/revolve/gazebo/motors/PositionMotor.h b/cpprevolve/revolve/gazebo/motors/PositionMotor.h index 75031070e3..7f07c831a5 100644 --- a/cpprevolve/revolve/gazebo/motors/PositionMotor.h +++ b/cpprevolve/revolve/gazebo/motors/PositionMotor.h @@ -51,7 +51,7 @@ namespace revolve /// \brief public: virtual void Update( - double *_outputs, + const double *_outputs, double _step) override; /// \brief World update event function diff --git a/cpprevolve/revolve/gazebo/motors/VelocityMotor.cpp b/cpprevolve/revolve/gazebo/motors/VelocityMotor.cpp index dcc45aeca1..9a45596621 100644 --- a/cpprevolve/revolve/gazebo/motors/VelocityMotor.cpp +++ b/cpprevolve/revolve/gazebo/motors/VelocityMotor.cpp @@ -67,7 +67,7 @@ VelocityMotor::~VelocityMotor() } void VelocityMotor::Update( - double *outputs, + const double *outputs, double /*step*/) { // Just one network output, which is the first diff --git a/cpprevolve/revolve/gazebo/motors/VelocityMotor.h b/cpprevolve/revolve/gazebo/motors/VelocityMotor.h index d70f641b49..3a978c4922 100644 --- a/cpprevolve/revolve/gazebo/motors/VelocityMotor.h +++ b/cpprevolve/revolve/gazebo/motors/VelocityMotor.h @@ -56,7 +56,7 @@ namespace revolve /// \param[in,out] outputs /// \param[in] step virtual void Update( - double *outputs, + const double *outputs, double step); /// \brief World update event function diff --git a/cpprevolve/revolve/msgs/body.proto b/cpprevolve/revolve/gazebo/msgs/body.proto similarity index 100% rename from cpprevolve/revolve/msgs/body.proto rename to cpprevolve/revolve/gazebo/msgs/body.proto diff --git a/cpprevolve/revolve/msgs/model_inserted.proto b/cpprevolve/revolve/gazebo/msgs/model_inserted.proto similarity index 100% rename from cpprevolve/revolve/msgs/model_inserted.proto rename to cpprevolve/revolve/gazebo/msgs/model_inserted.proto diff --git a/cpprevolve/revolve/msgs/neural_net.proto b/cpprevolve/revolve/gazebo/msgs/neural_net.proto similarity index 100% rename from cpprevolve/revolve/msgs/neural_net.proto rename to cpprevolve/revolve/gazebo/msgs/neural_net.proto diff --git a/cpprevolve/revolve/msgs/parameter.proto b/cpprevolve/revolve/gazebo/msgs/parameter.proto similarity index 100% rename from cpprevolve/revolve/msgs/parameter.proto rename to cpprevolve/revolve/gazebo/msgs/parameter.proto diff --git a/cpprevolve/revolve/msgs/robot.proto b/cpprevolve/revolve/gazebo/msgs/robot.proto similarity index 100% rename from cpprevolve/revolve/msgs/robot.proto rename to cpprevolve/revolve/gazebo/msgs/robot.proto diff --git a/cpprevolve/revolve/msgs/robot_states.proto b/cpprevolve/revolve/gazebo/msgs/robot_states.proto similarity index 92% rename from cpprevolve/revolve/msgs/robot_states.proto rename to cpprevolve/revolve/gazebo/msgs/robot_states.proto index 2003b743e2..60f77dce0f 100644 --- a/cpprevolve/revolve/msgs/robot_states.proto +++ b/cpprevolve/revolve/gazebo/msgs/robot_states.proto @@ -7,6 +7,7 @@ message RobotState { required uint32 id = 1; required string name = 2; required gazebo.msgs.Pose pose = 3; + optional bool dead = 4; } message RobotStates { diff --git a/cpprevolve/revolve/msgs/sdf_body_analyze.proto b/cpprevolve/revolve/gazebo/msgs/sdf_body_analyze.proto similarity index 100% rename from cpprevolve/revolve/msgs/sdf_body_analyze.proto rename to cpprevolve/revolve/gazebo/msgs/sdf_body_analyze.proto diff --git a/cpprevolve/revolve/msgs/spline_policy.proto b/cpprevolve/revolve/gazebo/msgs/spline_policy.proto similarity index 100% rename from cpprevolve/revolve/msgs/spline_policy.proto rename to cpprevolve/revolve/gazebo/msgs/spline_policy.proto diff --git a/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.cpp b/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.cpp new file mode 100644 index 0000000000..41ea335fcc --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.cpp @@ -0,0 +1,301 @@ +/* +* Copyright (C) 2017 Vrije Universiteit Amsterdam +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +* +* Author: Elte Hupkes +* +*/ + +#include +#include + +#include +#include +#include +#include + +#include "BodyAnalyzer.h" + +namespace gz = gazebo; + +using namespace revolve::gazebo; + +void BodyAnalyzer::Load( + gz::physics::WorldPtr world, + sdf::ElementPtr /*_sdf*/) +{ + // Store pointer to the world + world_ = world; + + // Pause the world if it is not already paused + world->SetPaused(true); + + // Set initial state values + processing_ = false; + counter_ = 0; + currentRequest_ = -1; + + // Create a new transport node for advertising / subscribing + node_.reset(new gz::transport::Node()); + node_->Init(); + + // Subscribe to the contacts message. Note that the contact manager does + // not generate data without at least one subscriber, so there is no use + // in bypassing the messaging mechanism. + contactsSub_ = node_->Subscribe( + "~/physics/contacts", + &BodyAnalyzer::OnContacts, + this); + + // Subscribe to analysis request messages + requestSub_ = node_->Subscribe( + "~/request", + &BodyAnalyzer::AnalyzeRequest, + this); + + // Since models are added asynchronously, we need some way of detecting + // our model add. We do this using a model info subscriber. + modelSub_ = node_->Subscribe( + "~/model/info", + &BodyAnalyzer::OnModel, + this); + + // Publisher for the results + responsePub_ = node_->Advertise< gz::msgs::Response >("~/response"); + + // Subscribe to model delete events + deleteSub_ = node_->Subscribe( + "~/response", + &BodyAnalyzer::OnModelDelete, + this); + + // Hello world! + std::cout << "Body analyzer ready" << std::endl; +} + +void BodyAnalyzer::OnModel(ConstModelPtr &msg) +{ + std::string expectedName = + "analyze_bot_" + boost::lexical_cast< std::string >(counter_); + if (msg->name() not_eq expectedName) + { + throw std::runtime_error( + "INTERNAL ERROR: Expecting model with name '" + expectedName + + "', created model was '" + msg->name() + "'."); + } + + if (world_->Models().size() > 1) + { + throw std::runtime_error( + "INTERNAL ERROR: Too many models in analyzer."); + } + + // Unpause the world so contacts will be handled + world_->SetPaused(false); +} + +void BodyAnalyzer::OnModelDelete(ConstResponsePtr &msg) +{ + if (msg->request() == "entity_delete") + { + // This might have cleared the world + this->ProcessQueue(); + } +} + +void BodyAnalyzer::Advance() +{ + processingMutex_.lock(); + + // Clear current request to indicate nothing is being + // processed, and move on to the next item if there is one. + counter_++; + processing_ = false; + currentRequest_ = -1; + + // ProcessQueue needs the processing mutex, release it + processingMutex_.unlock(); + this->ProcessQueue(); +} + +void BodyAnalyzer::OnContacts(ConstContactsPtr &msg) +{ + // Pause the world so no new contacts will come in + world_->SetPaused(true); + + boost::mutex::scoped_lock plock(processingMutex_); + if (not processing_) + { + return; + } + plock.unlock(); + + if (world_->ModelCount() > 1) + { + std::cerr << "WARNING: Too many models in the world." << std::endl; + } + + // Create a response + msgs::BodyAnalysisResponse response; + gz::msgs::Response wrapper; + wrapper.set_id(currentRequest_); + wrapper.set_request("analyze_body"); + + // Add contact info + for (const auto &contact : msg->contact()) + { + auto msgContact = response.add_contact(); + msgContact->set_collision1(contact.collision1()); + msgContact->set_collision2(contact.collision2()); + } + + auto name = "analyze_bot_" + boost::lexical_cast< std::string >(counter_); + auto model = world_->ModelByName(name); + + if (not model) + { + std::cerr << "------------------------------------" << std::endl; + std::cerr << "INTERNAL ERROR, contact model not found: " << name + << std::endl; + std::cerr << "Please retry this request." << std::endl; + std::cerr << "------------------------------------" << std::endl; + wrapper.set_response("error"); + response.SerializeToString(wrapper.mutable_serialized_data()); + responsePub_->Publish(wrapper); + + // Advance manually + this->Advance(); + return; + } + + // Add the bounding box to the message + // Model collision bounding box is currently broken in Gazebo: + // https://bitbucket.org/osrf/gazebo/issue/1325/getboundingbox-returns-the-models-last + // My suggested fixes are present in the gazebo6-revolve branch + auto bbox = model->BoundingBox(); + auto box = response.mutable_boundingbox(); + gz::msgs::Set(box->mutable_min(), bbox.Min()); + gz::msgs::Set(box->mutable_max(), bbox.Max()); + + // Publish the message, serializing the response message in the wrapper + // data + response.SerializeToString(wrapper.mutable_serialized_data()); + wrapper.set_response("success"); + responsePub_->Publish(wrapper); + std::cout << "Response for request " << currentRequest_ + << " sent." << std::endl; + + // Remove all models from the world and advance + world_->Clear(); + this->Advance(); +} + +void BodyAnalyzer::AnalyzeRequest(ConstRequestPtr &request) +{ + auto request_title = request->request(); + + if (request_title not_eq "analyze_body") + { + // Request is not meant for us + return; + } + + if (not request->has_data()) + { + std::cerr << "An `analyze_body` request should have data." << std::endl; + return; + } + + // Create the request pair before locking the mutex - this seems + // to prevent threading and "unknown message type" problems. + std::pair< int, std::string > req(request->id(), request->data()); + std::cout << "Received request " << request->id() << std::endl; + + boost::mutex::scoped_lock lock(queueMutex_); + + if (requests_.size() >= MAX_QUEUE_SIZE) + { + std::cerr << "Ignoring request " << request->id() + << ": maximum queue size (" << MAX_QUEUE_SIZE << ") reached." + << std::endl; + return; + } + + // This actually copies the message, but since everything is const + // we don't really have a choice in that regard. This shouldn't + // be the performance bottleneck anyway. + requests_.push(req); + + // Release the lock explicitly to prevent deadlock in ProcessQueue + lock.unlock(); + + this->ProcessQueue(); +} + +void BodyAnalyzer::ProcessQueue() +{ + // Acquire mutex on queue + boost::mutex::scoped_lock lock(queueMutex_); + + if (requests_.empty()) + { + // No requests to handle + return; + } + + boost::mutex::scoped_lock plock(processingMutex_); + if (processing_) + { + // Another item is being processed, wait for it + return; + } + + if (world_->ModelCount() > 0) + { + // There are still some items in the world, wait until + // `Clear()` has done its job. + return; + } + + processing_ = true; + + // Pop one request off the queue and set the + // currently processed ID on the class + auto request = requests_.front(); + requests_.pop(); + + currentRequest_ = request.first; + std::cout << "Now handling request: " << currentRequest_ << std::endl; + + // Create model SDF + sdf::SDF robotSDF; + robotSDF.SetFromString(request.second); + + // Force the model name to something we know + std::string name = + "analyze_bot_" + boost::lexical_cast< std::string >(counter_); + robotSDF.Root()->GetElement("model") + ->GetAttribute("name")->SetFromString(name); + + // Insert the model into the world. For clarity we use + // `InsertModelString` directly, this is actually also what + // `InsertModelSdf` does. + world_->InsertModelString(robotSDF.ToString()); + + // The contents of the SDF element are *not* cleared automatically + // when robotSDF goes out of scope. + // https://bitbucket.org/osrf/sdformat/issues/104/memory-leak-in-element + robotSDF.Root()->Reset(); + + // Analysis will proceed once the model insertion message comes through +} diff --git a/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.h b/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.h new file mode 100644 index 0000000000..a25ec7bdb7 --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/BodyAnalyzer.h @@ -0,0 +1,126 @@ +/* +* Copyright (C) 2017 Vrije Universiteit Amsterdam +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +* +* Description: The body analyzer can be used to gather some statistics about +* robot bodies before actually using them. This analyzer does +* the following: +* +* - It listens to incoming analyze messages TODO: message type +* - It publishes a message with robot statistics, currently all +* registered contacts (which is used to identify intersecting +* body parts) and the robot model's bounding box. +* Author: Elte Hupkes +* +*/ + +#ifndef REVOLVE_BODYANALYZER_H +#define REVOLVE_BODYANALYZER_H + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include + +namespace revolve { +namespace gazebo { + +class BodyAnalyzer: public ::gazebo::WorldPlugin +{ +public: + void Load( + ::gazebo::physics::WorldPtr _parent, + sdf::ElementPtr _sdf); + + // Maximum size of request queue, if more requests come in they are + // discarded + static const int MAX_QUEUE_SIZE = 100; +private: + // HACK: Use this as an ID "prefix" to make sure we don't + // erroneously identify other response messages as our + // delete requests. + static const int DELETE_BASE = 8888888; + + // Processes the items in the queue if possible + void ProcessQueue(); + + /// Callback for contact messages from the physics engine. + void OnContacts(ConstContactsPtr &_msg); + + // Callback for model insertion + void OnModel(ConstModelPtr &_msg); + + // Callback for model insertion + void OnModelDelete(ConstResponsePtr &_msg); + + // Listener for analysis requests + void AnalyzeRequest(ConstRequestPtr &request); + + // Advances the request queue + void Advance(); + + /** + * Analyze request queue. + */ + std::queue< std::pair< int, std::string>> requests_; + + // In case message handling is fully threaded (I'm not 100% certain + // at this point) no two threads should be allowed to modify the + // queue at the same time, so we protect methods doing this with + // a mutex. + boost::mutex queueMutex_; + + // We add another mutex that is only released once a next item + // can be processed. + bool processing_ = false; + boost::mutex processingMutex_; + + // Internal counter for the number of analyzed models + int counter_ = 0; + + // ID of the current request being evaluated + int currentRequest_; + + // Pointer to the world + ::gazebo::physics::WorldPtr world_; + + // Transport nodes for the contact messages + ::gazebo::transport::NodePtr node_; + + // Subscriber for analysis request messages + ::gazebo::transport::SubscriberPtr requestSub_; + + // Subscriber for contacts messages + ::gazebo::transport::SubscriberPtr contactsSub_; + + // Subscriber for model insertion + ::gazebo::transport::SubscriberPtr modelSub_; + + // Publisher for the responses + ::gazebo::transport::PublisherPtr responsePub_; + + // Listen to delete responses + ::gazebo::transport::SubscriberPtr deleteSub_; +}; +} +} + +#endif // REVOLVE_BODYANALYZER_H \ No newline at end of file diff --git a/cpprevolve/revolve/gazebo/plugin/RobotController.cpp b/cpprevolve/revolve/gazebo/plugin/RobotController.cpp index 05116c23e3..a02aac322c 100644 --- a/cpprevolve/revolve/gazebo/plugin/RobotController.cpp +++ b/cpprevolve/revolve/gazebo/plugin/RobotController.cpp @@ -203,7 +203,7 @@ void RobotController::LoadBrain(const sdf::ElementPtr _sdf) auto brain = _sdf->GetElement("rv:brain"); auto controller = brain->GetElement("rv:controller")->GetAttribute("type")->GetAsString(); auto learner = brain->GetElement("rv:learner")->GetAttribute("type")->GetAsString(); - std::cout << "Loading controller " << controller << " and learner " << learner; + std::cout << "Loading controller " << controller << " and learner " << learner << std::endl; if ("offline" == learner and "ann" == controller) { @@ -211,9 +211,11 @@ void RobotController::LoadBrain(const sdf::ElementPtr _sdf) } else if ("rlpower" == learner and "spline" == controller) { - brain_.reset(new RLPower(this->model_, brain, motors_, sensors_)); + if (not motors_.empty()) { + brain_.reset(new RLPower(this->model_, brain, motors_, sensors_)); + } } - else if ("diff_cpg" == learner) + else if ("bo" == learner and "cpg" == controller) { brain_.reset(new DifferentialCPG(this->model_, _sdf, motors_, sensors_)); } @@ -251,7 +253,8 @@ void RobotController::DoUpdate(const ::gazebo::common::UpdateInfo _info) { auto currentTime = _info.simTime.Double() - initTime_; - brain_->Update(motors_, sensors_, currentTime, actuationTime_); + if (brain_) + brain_->Update(motors_, sensors_, currentTime, actuationTime_); } ///////////////////////////////////////////////// diff --git a/cpprevolve/revolve/gazebo/plugin/TorusWorld.cpp b/cpprevolve/revolve/gazebo/plugin/TorusWorld.cpp new file mode 100644 index 0000000000..aea9cd773c --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/TorusWorld.cpp @@ -0,0 +1,27 @@ +// +// Created by matteo on 6/19/19. +// + +#include "TorusWorld.h" + +using namespace revolve::gazebo; + +TorusWorld::TorusWorld() +{ + +} + +TorusWorld::~TorusWorld() +{ + +} + +void TorusWorld::Load(::gazebo::physics::WorldPtr _parent, sdf::ElementPtr _sdf) +{ + +} + +void TorusWorld::OnUpdate(const ::gazebo::common::UpdateInfo &_info) +{ + +} diff --git a/cpprevolve/revolve/gazebo/plugin/TorusWorld.h b/cpprevolve/revolve/gazebo/plugin/TorusWorld.h new file mode 100644 index 0000000000..8556a58732 --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/TorusWorld.h @@ -0,0 +1,39 @@ +// +// Created by matteo on 6/19/19. +// + +#ifndef REVOLVE_TORUSWORLD_H +#define REVOLVE_TORUSWORLD_H + +#include +#include +#include +#include + + +namespace revolve { +namespace gazebo { + +class TorusWorld : public ::gazebo::WorldPlugin { +public: + TorusWorld(); + ~TorusWorld() override; + + virtual void Load( + ::gazebo::physics::WorldPtr _parent, + sdf::ElementPtr _sdf) override; + + virtual void OnUpdate(const ::gazebo::common::UpdateInfo &_info); + +private: + + // Pointer to the update event connection + ::gazebo::event::ConnectionPtr onBeginUpdateConnection; + ::gazebo::event::ConnectionPtr onEndUpdateConnection; +}; + +} +} + + +#endif //REVOLVE_TORUSWORLD_H diff --git a/cpprevolve/revolve/gazebo/plugin/WorldController.cpp b/cpprevolve/revolve/gazebo/plugin/WorldController.cpp index 102dd91505..ea491681d7 100644 --- a/cpprevolve/revolve/gazebo/plugin/WorldController.cpp +++ b/cpprevolve/revolve/gazebo/plugin/WorldController.cpp @@ -27,16 +27,47 @@ using namespace revolve::gazebo; ///////////////////////////////////////////////// WorldController::WorldController() - : robotStatesPubFreq_(0) + : delete_robot_queue() + , robotStatesPubFreq_(5) , lastRobotStatesUpdateTime_(0) { } +void unsubscribe(gz::transport::SubscriberPtr &subscription) +{ + if (subscription) + subscription->Unsubscribe(); +} + +void fini(gz::transport::PublisherPtr &publisher) +{ + if (publisher) + publisher->Fini(); +} + +WorldController::~WorldController() +{ + unsubscribe(this->requestSub_); + unsubscribe(this->responseSub_); + unsubscribe(this->modelSub_); + fini(this->requestPub_); + fini(this->responsePub_); + fini(this->robotStatesPub_); +} + ///////////////////////////////////////////////// void WorldController::Load( gz::physics::WorldPtr world, sdf::ElementPtr /*_sdf*/) { + gz::physics::PhysicsEnginePtr physicsEngine = world->Physics(); + assert(physicsEngine != nullptr); + + // Turn on threading + physicsEngine->SetParam("thread_position_correction", true); + physicsEngine->SetParam("island_threads", 8); + + std::cout << "World plugin loaded." << std::endl; // Store the world @@ -74,56 +105,161 @@ void WorldController::Load( this); // Bind to the world update event to perform some logic - this->updateConnection_ = gz::event::Events::ConnectWorldUpdateBegin( - boost::bind(&WorldController::OnUpdate, this, _1)); + this->onBeginUpdateConnection = gz::event::Events::ConnectWorldUpdateBegin( + [this] (const ::gazebo::common::UpdateInfo &_info) {this->OnBeginUpdate(_info);}); + + // Bind to the world update event to perform some logic + this->onEndUpdateConnection = gz::event::Events::ConnectWorldUpdateEnd( + [this] () {this->OnEndUpdate();}); // Robot pose publisher this->robotStatesPub_ = this->node_->Advertise< revolve::msgs::RobotStates >( - "~/revolve/robot_states", 50); + "~/revolve/robot_states", 500); } -///////////////////////////////////////////////// -void WorldController::OnUpdate(const ::gazebo::common::UpdateInfo &_info) +void WorldController::Reset() { - if (not this->robotStatesPubFreq_) - { - return; - } + this->lastRobotStatesUpdateTime_ = 0; //this->world_->SimTime().Double(); +} - auto secs = 1.0 / this->robotStatesPubFreq_; - auto time = _info.simTime.Double(); - if ((time - this->lastRobotStatesUpdateTime_) >= secs) - { - // Send robot info update message, this only sends the - // main pose of the robot (which is all we need for now) - msgs::RobotStates msg; - gz::msgs::Set(msg.mutable_time(), _info.simTime); +///////////////////////////////////////////////// +void WorldController::OnBeginUpdate(const ::gazebo::common::UpdateInfo &_info) { + if (not this->robotStatesPubFreq_) { + return; + } - for (const auto &model : this->world_->Models()) - { - if (model->IsStatic()) - { - // Ignore static models such as the ground and obstacles - continue; - } - - auto stateMsg = msg.add_robot_state(); - stateMsg->set_name(model->GetScopedName()); - stateMsg->set_id(model->GetId()); - - auto poseMsg = stateMsg->mutable_pose(); - auto relativePose = model->RelativePose(); - gz::msgs::Set(poseMsg, relativePose); + auto secs = 1.0 / this->robotStatesPubFreq_; + auto time = _info.simTime.Double(); + if ((time - this->lastRobotStatesUpdateTime_) >= secs) { + // Send robot info update message, this only sends the + // main pose of the robot (which is all we need for now) + msgs::RobotStates msg; + gz::msgs::Set(msg.mutable_time(), _info.simTime); + + { + boost::recursive_mutex::scoped_lock lock_physics(*this->world_->Physics()->GetPhysicsUpdateMutex()); + for (const auto &model : this->world_->Models()) { + if (model->IsStatic()) { + // Ignore static models such as the ground and obstacles + continue; + } + + revolve::msgs::RobotState *stateMsg = msg.add_robot_state(); + const std::string scoped_name = model->GetScopedName(); + stateMsg->set_name(scoped_name); + stateMsg->set_id(model->GetId()); + + auto poseMsg = stateMsg->mutable_pose(); + auto relativePose = model->RelativePose(); + + gz::msgs::Set(poseMsg, relativePose); + + // Death sentence check + const std::string name = model->GetName(); + bool death_sentence = false; + double death_sentence_value = 0; + { + boost::mutex::scoped_lock lock_death(death_sentences_mutex_); + death_sentence = death_sentences_.count(name) > 0; + if (death_sentence) + death_sentence_value = death_sentences_[name]; + } + + if (death_sentence) { + if (death_sentence_value < 0) { + // Initialize death sentence + death_sentences_[name] = time - death_sentence_value; + stateMsg->set_dead(false); + } else { + bool alive = death_sentence_value > time; + stateMsg->set_dead(not alive); + + if (not alive) { + boost::mutex::scoped_lock lock(this->death_sentences_mutex_); + this->death_sentences_.erase(model->GetName()); + + this->models_to_remove.emplace_back(model); + } + } + } + } + } + + if (msg.robot_state_size() > 0) { + this->robotStatesPub_->Publish(msg); + this->lastRobotStatesUpdateTime_ = time; + } } - if (msg.robot_state_size() > 0) - { - this->robotStatesPub_->Publish(msg); - this->lastRobotStatesUpdateTime_ = time; + +// if (world_insert_remove_mutex.try_lock()) { + for (const auto &model: this->models_to_remove) { + std::cout << "Removing " << model->GetScopedName() << std::endl; +// this->world_->RemoveModel(model); +// gz::msgs::Request deleteReq; +// auto id = gz::physics::getUniqueId(); +// deleteReq.set_id(id); +// deleteReq.set_request("entity_delete"); +// deleteReq.set_data(model->GetScopedName()); +// this->requestPub_->Publish(deleteReq); + gz::transport::requestNoReply(this->world_->Name(), "entity_delete", model->GetScopedName()); + std::cout << "Removed " << model->GetScopedName() << std::endl; + + } + this->models_to_remove.clear(); +// this->world_insert_remove_mutex.unlock(); +// } +} + +void WorldController::OnEndUpdate() +{ + { // check if there are robots to delete + std::tuple< ::gazebo::physics::ModelPtr, int> delete_robot; + { + boost::mutex::scoped_lock lock(this->deleteMutex_); + if (not this->delete_robot_queue.empty()) { + delete_robot = this->delete_robot_queue.front(); + this->delete_robot_queue.pop(); + } + } + auto model = std::get<0>(delete_robot); + auto request_id = std::get<1>(delete_robot); + if (model) + { + { +// boost::recursive_mutex::scoped_lock lock_physics(*this->world_->Physics()->GetPhysicsUpdateMutex()); + this->world_->RemoveModel(model); + } + + gz::msgs::Response resp; + resp.set_id(request_id); + resp.set_request("delete_robot"); + resp.set_response("success"); + this->responsePub_->Publish(resp); + } + } + + { // check if there are robots to insert + boost::mutex::scoped_lock lock(this->insertMutex_); + for (auto &iterator: this->insertMap_) + { + bool &insert_operation_pending = std::get<2>(iterator.second); + //std::cout << "trying to insert " << iterator.first << " - " << insert_operation_pending << std::endl; +// if (insert_operation_pending and this->world_insert_remove_mutex.try_lock()) + if (insert_operation_pending) + { + // Start insert operation! +// boost::recursive_mutex::scoped_lock lock_physics(*this->world_->Physics()->GetPhysicsUpdateMutex()); + const std::string &robotSDF = std::get<1>(iterator.second); + this->world_->InsertModelString(robotSDF); + insert_operation_pending = false; + break; + } + } } - } } + ///////////////////////////////////////////////// // Process insert and delete requests void WorldController::HandleRequest(ConstRequestPtr &request) @@ -134,31 +270,36 @@ void WorldController::HandleRequest(ConstRequestPtr &request) std::cout << "Processing request `" << request->id() << "` to delete robot `" << name << "`" << std::endl; - auto model = this->world_->ModelByName(name); - if (model) - { - // Tell the world to remove the model - // Using `World::RemoveModel()` from here crashes the transport - // library, the cause of which I've yet to figure out - it has - // something to do with race conditions where the model is used by - // the world while it is being updated. Fixing this completely - // appears to be a rather involved process, instead, we'll use an - // `entity_delete` request, which will make sure deleting the model - // happens on the world thread. - gz::msgs::Request deleteReq; - auto id = gz::physics::getUniqueId(); - deleteReq.set_id(id); - deleteReq.set_request("entity_delete"); - deleteReq.set_data(model->GetScopedName()); - - this->deleteMutex_.lock(); - this->deleteMap_[id] = request->id(); - this->deleteMutex_.unlock(); - - this->requestPub_->Publish(deleteReq); - } - else - { +// auto model = this->world_->ModelByName(name); +// if (model) +// { +// // Tell the world to remove the model +// // Using `World::RemoveModel()` from here crashes the transport +// // library, the cause of which I've yet to figure out - it has +// // something to do with race conditions where the model is used by +// // the world while it is being updated. Fixing this completely +// // appears to be a rather involved process, instead, we'll use an +// // `entity_delete` request, which will make sure deleting the model +// // happens on the world thread. +// gz::msgs::Request deleteReq; +// auto id = gz::physics::getUniqueId(); +// deleteReq.set_id(id); +// deleteReq.set_request("entity_delete"); +// deleteReq.set_data(model->GetScopedName()); +// +// { +// boost::mutex::scoped_lock lock(this->deleteMutex_); +// this->delete_robot_queue.emplace(std::make_tuple(model, request->id())); +// } +// { +// boost::mutex::scoped_lock lock(this->death_sentences_mutex_); +// this->death_sentences_.erase(model->GetName()); +// } +// +// this->requestPub_->Publish(deleteReq); +// } +// else +// { std::cerr << "Model `" << name << "` could not be found in the world." << std::endl; gz::msgs::Response resp; @@ -166,7 +307,7 @@ void WorldController::HandleRequest(ConstRequestPtr &request) resp.set_request("delete_robot"); resp.set_response("error"); this->responsePub_->Publish(resp); - } +// } } else if (request->request() == "insert_sdf") { @@ -174,16 +315,27 @@ void WorldController::HandleRequest(ConstRequestPtr &request) << std::endl; sdf::SDF robotSDF; robotSDF.SetFromString(request->data()); + double lifespan_timeout = request->dbl_data(); // Get the model name, store in the expected map auto name = robotSDF.Root()->GetElement("model")->GetAttribute("name") ->GetAsString(); - this->insertMutex_.lock(); - this->insertMap_[name] = request->id(); - this->insertMutex_.unlock(); + if (lifespan_timeout > 0) + { + boost::mutex::scoped_lock lock(death_sentences_mutex_); + // Initializes the death sentence negative because I don't dare to take the + // simulation time from this thread. + death_sentences_[name] = -lifespan_timeout; + } + + { + boost::mutex::scoped_lock lock(this->insertMutex_); + this->insertMap_[name] = std::make_tuple(request->id(), robotSDF.ToString(), true); + } - this->world_->InsertModelString(robotSDF.ToString()); + //TODO insert here, it's better + //this->world_->InsertModelString(robotSDF.ToString()); // Don't leak memory // https://bitbucket.org/osrf/sdformat/issues/104/memory-leak-in-element @@ -209,60 +361,77 @@ void WorldController::HandleRequest(ConstRequestPtr &request) ///////////////////////////////////////////////// void WorldController::OnModel(ConstModelPtr &msg) { - auto name = msg->name(); + auto name = msg->name(); + std::cout << "WorldController::OnModel(" << name << ')' << std::endl; - int id; - { - boost::mutex::scoped_lock lock(this->insertMutex_); - if (this->insertMap_.count(name) <= 0) + + int id; + bool insert_operation_pending; { - // Insert was not requested here, ignore it - return; + boost::mutex::scoped_lock lock(this->insertMutex_); + if (this->insertMap_.count(name) <= 0) + { + // Insert was not requested here, ignore it + return; + } + const std::tuple &entry = this->insertMap_[name]; + id = std::get<0>(entry); + insert_operation_pending = std::get<2>(entry); + if (insert_operation_pending) + { + // Insert operation has not been done yet + // (but you should never be here, because we are in the "OnModel" function + return; + } + this->insertMap_.erase(name); } - id = this->insertMap_[name]; - this->insertMap_.erase(name); - } - // Respond with the inserted model - gz::msgs::Response resp; - resp.set_request("insert_sdf"); - resp.set_response("success"); - resp.set_id(id); + // Respond with the inserted model + gz::msgs::Response resp; + resp.set_request("insert_sdf"); + resp.set_response("success"); + resp.set_id(id); - msgs::ModelInserted inserted; - inserted.mutable_model()->CopyFrom(*msg); - gz::msgs::Set(inserted.mutable_time(), this->world_->SimTime()); - inserted.SerializeToString(resp.mutable_serialized_data()); + msgs::ModelInserted inserted; + inserted.mutable_model()->CopyFrom(*msg); + gz::msgs::Set(inserted.mutable_time(), this->world_->SimTime()); + inserted.SerializeToString(resp.mutable_serialized_data()); - this->responsePub_->Publish(resp); + this->responsePub_->Publish(resp); - std::cout << "Model `" << name << "` inserted, world now contains " - << this->world_->ModelCount() << " models." << std::endl; +// this->world_insert_remove_mutex.unlock(); + + std::cout << "Model `" << name << "` inserted, world now contains " + << this->world_->ModelCount() << " models." << std::endl; } ///////////////////////////////////////////////// void WorldController::HandleResponse(ConstResponsePtr &response) { - if (response->request() not_eq "entity_delete") - { - return; - } +// std::cout << "WorldController::HandleResponse(" << response->request() << ')' << std::endl; - int id; - { - boost::mutex::scoped_lock lock(this->deleteMutex_); - if (this->deleteMap_.count(response->id()) <= 0) + if (response->request() not_eq "entity_delete") { - return; + return; } - id = this->deleteMap_[response->id()]; - this->deleteMap_.erase(id); - } - - gz::msgs::Response resp; - resp.set_id(id); - resp.set_request("delete_robot"); - resp.set_response("success"); - this->responsePub_->Publish(resp); +// int id; +// { +// boost::mutex::scoped_lock lock(this->deleteMutex_); +// if (this->deleteMap_.count(response->id()) <= 0) +// { +// return; +// } +// +// id = this->deleteMap_[response->id()]; +// this->deleteMap_.erase(id); +// } + +// this->world_insert_remove_mutex.unlock(); + +// gz::msgs::Response resp; +// resp.set_id(id); +// resp.set_request("delete_robot"); +// resp.set_response("success"); +// this->responsePub_->Publish(resp); } diff --git a/cpprevolve/revolve/gazebo/plugin/WorldController.h b/cpprevolve/revolve/gazebo/plugin/WorldController.h index d4826a5f93..359badbd96 100644 --- a/cpprevolve/revolve/gazebo/plugin/WorldController.h +++ b/cpprevolve/revolve/gazebo/plugin/WorldController.h @@ -26,6 +26,7 @@ #include #include +#include #include @@ -37,80 +38,99 @@ #include #include -namespace revolve +namespace revolve { +namespace gazebo { + +class WorldController: public ::gazebo::WorldPlugin { - namespace gazebo - { - class WorldController - : public ::gazebo::WorldPlugin - { - public: - WorldController(); +public: + WorldController(); + + virtual ~WorldController(); + + virtual void Load( + ::gazebo::physics::WorldPtr _parent, + sdf::ElementPtr _sdf) override; + + virtual void Reset() override; + +protected: + // Listener for analysis requests + virtual void HandleRequest(ConstRequestPtr &request); + + // Listener for entity delete responses + virtual void HandleResponse(ConstResponsePtr &request); + + // Callback for model insertion + virtual void OnModel(ConstModelPtr &msg); + + // Method called + virtual void OnBeginUpdate(const ::gazebo::common::UpdateInfo &_info); + + virtual void OnEndUpdate(); - virtual void Load( - ::gazebo::physics::WorldPtr _parent, - sdf::ElementPtr _sdf); + // Maps model names to insert request IDs + // model_name -> request_id, SDF, insert_operation_pending + std::map > insertMap_; - protected: - // Listener for analysis requests - virtual void HandleRequest(ConstRequestPtr &request); + // Queue of `delete_robot` requests + std::queue> delete_robot_queue; - // Listener for entity delete responses - virtual void HandleResponse(ConstResponsePtr &request); + // Stores the world + ::gazebo::physics::WorldPtr world_; - // Callback for model insertion - virtual void OnModel(ConstModelPtr &msg); + // Transport node + ::gazebo::transport::NodePtr node_; - // Method called - virtual void OnUpdate(const ::gazebo::common::UpdateInfo &_info); + // Mutex for the insertMap_ + boost::mutex insertMutex_; - // Maps model names to insert request IDs - std::map< std::string, int > insertMap_; + // Mutex for the deleteMap_ + boost::mutex deleteMutex_; - // Maps `entity_delete` IDs to `delete_robot` ids - std::map< int, int > deleteMap_; + // Request subscriber + ::gazebo::transport::SubscriberPtr requestSub_; - // Stores the world - ::gazebo::physics::WorldPtr world_; + // Request publisher + ::gazebo::transport::PublisherPtr requestPub_; - // Transport node - ::gazebo::transport::NodePtr node_; + // Response subscriber + ::gazebo::transport::SubscriberPtr responseSub_; - // Mutex for the insertMap_ - boost::mutex insertMutex_; + // Response publisher + ::gazebo::transport::PublisherPtr responsePub_; - // Mutex for the deleteMap_ - boost::mutex deleteMutex_; + // Subscriber for actual model insertion + ::gazebo::transport::SubscriberPtr modelSub_; - // Request subscriber - ::gazebo::transport::SubscriberPtr requestSub_; + // Publisher for periodic robot poses + ::gazebo::transport::PublisherPtr robotStatesPub_; - // Request publisher - ::gazebo::transport::PublisherPtr requestPub_; + // Frequency at which robot info is published + // Defaults to 0, which means no update at all + unsigned int robotStatesPubFreq_; - // Response subscriber - ::gazebo::transport::SubscriberPtr responseSub_; + // Pointer to the update event connection + ::gazebo::event::ConnectionPtr onBeginUpdateConnection; + ::gazebo::event::ConnectionPtr onEndUpdateConnection; - // Response publisher - ::gazebo::transport::PublisherPtr responsePub_; + // Last (simulation) time robot info was sent + double lastRobotStatesUpdateTime_; - // Subscriber for actual model insertion - ::gazebo::transport::SubscriberPtr modelSub_; + // Death sentence list. It collects all the end time for all robots that have + // a death sentence + // NEGATIVE DEATH SENTENCES mean total lifetime, death sentence not yet initialized. + std::map death_sentences_; - // Publisher for periodic robot poses - ::gazebo::transport::PublisherPtr robotStatesPub_; + // Mutex for the deleteMap_ + boost::mutex death_sentences_mutex_; - // Frequency at which robot info is published - // Defaults to 0, which means no update at all - unsigned int robotStatesPubFreq_; +// boost::mutex world_insert_remove_mutex; - // Pointer to the update event connection - ::gazebo::event::ConnectionPtr updateConnection_; + ::gazebo::physics::Model_V models_to_remove; +}; - // Last (simulation) time robot info was sent - double lastRobotStatesUpdateTime_; - }; - } // namespace gazebo +} // namespace gazebo } // namespace revolve #endif // REVOLVE_WORLDCONTROLLER_H diff --git a/cpprevolve/revolve/gazebo/plugin/register_analyzer_plugin.cpp b/cpprevolve/revolve/gazebo/plugin/register_analyzer_plugin.cpp new file mode 100644 index 0000000000..e354002e8e --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/register_analyzer_plugin.cpp @@ -0,0 +1,23 @@ +/* +* Copyright (C) 2017 Vrije Universiteit Amsterdam +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +* +* Author: Elte Hupkes +* +*/ + +#include +#include + +using namespace gazebo; +GZ_REGISTER_WORLD_PLUGIN(::revolve::gazebo::BodyAnalyzer) diff --git a/cpprevolve/revolve/gazebo/plugin/register_torus_world_plugin.cpp b/cpprevolve/revolve/gazebo/plugin/register_torus_world_plugin.cpp new file mode 100644 index 0000000000..71aaf3cc3f --- /dev/null +++ b/cpprevolve/revolve/gazebo/plugin/register_torus_world_plugin.cpp @@ -0,0 +1,9 @@ +// +// Created by matteo on 6/19/19. +// + +#include +#include "TorusWorld.h" + +using namespace gazebo; +GZ_REGISTER_WORLD_PLUGIN(revolve::gazebo::TorusWorld) diff --git a/cpprevolve/revolve/raspberry/CMakeLists.txt b/cpprevolve/revolve/raspberry/CMakeLists.txt new file mode 100644 index 0000000000..20101930cf --- /dev/null +++ b/cpprevolve/revolve/raspberry/CMakeLists.txt @@ -0,0 +1,24 @@ +message(WARNING "Building Raspberry code") + +# Find Yaml-cpp +find_package(yaml-cpp REQUIRED) +include_directories(${YAML_CPP_INCLUDE_DIR}) + +file(GLOB_RECURSE + RASPBERRY_SRCS + *.cpp + ) + +add_executable(revolve-raspberry ${RASPBERRY_SRCS}) + +target_link_libraries(revolve-raspberry + PUBLIC revolve-controllers + PUBLIC pigpio_if2 + ${YAML_CPP_LIBRARIES} +) + +include_directories(${PIGPIO_HEADER_DIR}) + +install(TARGETS revolve-raspberry + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib) diff --git a/cpprevolve/revolve/raspberry/PIGPIOConnection.h b/cpprevolve/revolve/raspberry/PIGPIOConnection.h new file mode 100644 index 0000000000..f0239d0272 --- /dev/null +++ b/cpprevolve/revolve/raspberry/PIGPIOConnection.h @@ -0,0 +1,50 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_PIGPIOCONNECTION_H +#define REVOLVE_PIGPIOCONNECTION_H + +extern "C" { +#include "pigpiod_if2.h" +} + +#include +#include +#include + +class PIGPIOConnection { +public: + explicit PIGPIOConnection( + const std::string &address = PI_DEFAULT_SOCKET_ADDR_STR, + unsigned short port = PI_DEFAULT_SOCKET_PORT) + { + std::stringstream port_str; port_str << port; + this->connection = pigpio_start(address.c_str(), port_str.str().c_str()); + if (this->connection < 0) { + throw std::runtime_error("connection unsuccessful"); + } + } + + ~PIGPIOConnection() { + pigpio_stop(connection); + } + + int set_pwm_frequency(unsigned user_gpio, unsigned frequency) { + return set_PWM_frequency(connection, user_gpio, frequency); + } + + int set_pwm_range(unsigned user_gpio, unsigned range) { + return set_PWM_range(connection, user_gpio, range); + } + + int set_pwm_dutycycle(unsigned user_gpio, unsigned dutycycle) { + return set_PWM_dutycycle(connection, user_gpio, dutycycle); + } + +private: + int connection; +}; + + +#endif //REVOLVE_PIGPIOCONNECTION_H diff --git a/cpprevolve/revolve/raspberry/RaspController.cpp b/cpprevolve/revolve/raspberry/RaspController.cpp new file mode 100644 index 0000000000..1a424b2fc0 --- /dev/null +++ b/cpprevolve/revolve/raspberry/RaspController.cpp @@ -0,0 +1,71 @@ +// +// Created by matteo on 14/06/19. +// + +#include "RaspController.h" +#include "../brains/controller/DifferentialCPG.h" +#include + +using namespace revolve; + +RaspController::RaspController( + std::vector > actuators, + std::vector > sensors, + const YAML::Node &conf) + : revolve_controller(nullptr) + , actuators(std::move(actuators)) + , sensors(std::move(sensors)) +{ + this->set_new_controller(conf); +} + +RaspController::~RaspController() = default; + +#include +#include + +void RaspController::update() +{ + double step = this->timer.step(); + double time = this->timer.elapsed(); + if (step == 0) + return; + this->revolve_controller->update( + this->actuators, + this->sensors, + time, + step + ); +// std::this_thread::sleep_for(std::chrono::milliseconds(125)); +} + +void RaspController::set_new_controller(const YAML::Node &conf) +{ + std::string type = conf["type"].as(""); + if (type.empty()) { + throw std::runtime_error("Controller type not set"); + } else if (type == "differential-cpg") { + + DifferentialCPG::ControllerParams params; + params.reset_neuron_random = false; + params.use_frame_of_reference = false; + params.init_neuron_state = 0.707; + params.range_ub = 1.0; + params.signal_factor_all = 1.0; + params.signal_factor_mid = 2.5; + params.signal_factor_left_right = 2.5; + params.abs_output_bound = 1.0; + + YAML::Node yaml_weights = conf["weights"]; + for(const YAML::Node &weight: yaml_weights) { + params.weights.emplace_back(weight.as()); + } + + revolve_controller.reset( + new DifferentialCPG(params,this->actuators) + ); + } else { + throw std::runtime_error("Controller " + type + " not supported (yet)"); + } +} + diff --git a/cpprevolve/revolve/raspberry/RaspController.h b/cpprevolve/revolve/raspberry/RaspController.h new file mode 100644 index 0000000000..00ba47996e --- /dev/null +++ b/cpprevolve/revolve/raspberry/RaspController.h @@ -0,0 +1,39 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_RASPCONTROLLER_H +#define REVOLVE_RASPCONTROLLER_H + +#include +#include +#include "../brains/controller/Controller.h" +#include "Timer.h" + +namespace revolve { + +class RaspController +{ +public: + explicit RaspController( + std::vector > actuators, + std::vector > sensors, + const YAML::Node &conf); + + ~RaspController(); + + void update(); + + void set_new_controller(const YAML::Node &conf); + +private: + std::unique_ptr revolve_controller; + Timer timer; + std::vector< std::unique_ptr< revolve::Actuator > > actuators; + std::vector< std::unique_ptr< revolve::Sensor > > sensors; +}; + +} + + +#endif //REVOLVE_RASPCONTROLLER_H diff --git a/cpprevolve/revolve/raspberry/Servo.cpp b/cpprevolve/revolve/raspberry/Servo.cpp new file mode 100644 index 0000000000..2f221c0c23 --- /dev/null +++ b/cpprevolve/revolve/raspberry/Servo.cpp @@ -0,0 +1,62 @@ +// +// Created by matteo on 14/06/19. +// + +#include "Servo.h" +#include "PIGPIOConnection.h" + +using namespace revolve; + +#define POSITION_OFF 0 +#define POSITION_BEGIN 40 +#define POSITION_MIDDLE 75 +#define POSITION_END 110 + +Servo::Servo(double coordinate_x, double coordinate_y, double coordinate_z, PIGPIOConnection *connection, unsigned short pin, unsigned int frequency, int range, bool inverse) + : Actuator(1, coordinate_x, coordinate_y, coordinate_z) + , pin(pin) + , pigpio(connection) + , frequency(frequency) + , range(range) + , inverse(inverse) +{ + pigpio->set_pwm_frequency(pin, frequency); + pigpio->set_pwm_range(pin, range); + + if (inverse) { + minPWM = POSITION_END; + maxPWM = POSITION_BEGIN; + } else { + minPWM = POSITION_BEGIN; + maxPWM = POSITION_END; + } +} + +void Servo::move_to_position(double position) +{ + if (position < -1.0) + position = -1.0; + else if (position > 1.0) + position = 1.0; + + position *= 0.7; + + position = this->minPWM + (1 + position) * (this->maxPWM - this->minPWM) / 2; + + this->pigpio->set_pwm_dutycycle(this->pin, static_cast(position)); +} + +void Servo::off() +{ + this->pigpio->set_pwm_dutycycle(this->pin, POSITION_OFF); +} + +void Servo::write(const double *output_vector, double step) +{ + double output = output_vector[0]; + this->move_to_position(output); +} + +std::ostream &operator<<(std::ostream &os, Servo const &s) { + return s.print(os); +} diff --git a/cpprevolve/revolve/raspberry/Servo.h b/cpprevolve/revolve/raspberry/Servo.h new file mode 100644 index 0000000000..6c2ee1ef3c --- /dev/null +++ b/cpprevolve/revolve/raspberry/Servo.h @@ -0,0 +1,70 @@ +// +// Created by matteo on 14/06/19. +// + +#ifndef REVOLVE_SERVO_H +#define REVOLVE_SERVO_H + +#include "PIGPIOConnection.h" +#include "../brains/controller/actuators/Actuator.h" +#include + +namespace revolve { + +class Servo: public revolve::Actuator +{ +public: + explicit Servo( + double coordinate_x, + double coordinate_y, + double coordinate_z, + PIGPIOConnection *connection, + unsigned short pin, + unsigned int frequency=50, + int range=1000, + bool inverse=false + ); + + ~Servo() { + this->off(); + } + + /*** + * Sends signal to the engine to move to a specified position. + * Position should be in range [-1, 1] with 0 being the middle. + * @param position + */ + void move_to_position(double position); + + void center() { move_to_position(0); } + + void off(); + + virtual void write(const double *output, double step) override; + + std::ostream &print(std::ostream &os) const + { + os << "Servo pin:\t" << this->pin << std::endl; + os << "\tcoordinates [" << this->coordinate_x() << ',' << this->coordinate_y() << ',' << this->coordinate_z() << ']' << std::endl; + os << "\tfrequency:\t" << this->frequency << std::endl; + os << "\trange: \t" << this->range << std::endl; + os << "\tinverse: \t" << this->inverse; + + return os; + } + +private: + unsigned short pin; + PIGPIOConnection *pigpio; + unsigned int frequency; + int range; + bool inverse; + float minPWM; + float maxPWM; +}; + +} + +std::ostream &operator<<(std::ostream &os, revolve::Servo const &s); + +#endif //REVOLVE_SERVO_H diff --git a/cpprevolve/revolve/raspberry/Timer.h b/cpprevolve/revolve/raspberry/Timer.h new file mode 100644 index 0000000000..16d0c17cfc --- /dev/null +++ b/cpprevolve/revolve/raspberry/Timer.h @@ -0,0 +1,39 @@ +// +// Created by matteo on 17/06/19. +// + +#ifndef REVOLVE_TIMER_H +#define REVOLVE_TIMER_H +#include +#include + +class Timer +{ +public: + Timer() + : beg_(clock_::now()) + , last_step_(beg_) + {} + void reset() { beg_ = clock_::now(); } + double step() { + std::chrono::time_point prev = last_step_; + last_step_ = clock_::now(); + return time_difference(prev, last_step_); + } + double elapsed() const { return time_difference(beg_, last_step_); } + double elapsed_now() const { return time_difference(beg_, clock_::now()); } + +private: + typedef std::chrono::high_resolution_clock clock_; + typedef std::chrono::duration > second_; + std::chrono::time_point beg_; + std::chrono::time_point last_step_; + + static double time_difference(const std::chrono::time_point start, const std::chrono::time_point end) + { + return std::chrono::duration_cast + (end - start).count(); + } +}; + +#endif //REVOLVE_TIMER_H diff --git a/cpprevolve/revolve/raspberry/rasp_main.cpp b/cpprevolve/revolve/raspberry/rasp_main.cpp new file mode 100644 index 0000000000..5f7681b4a3 --- /dev/null +++ b/cpprevolve/revolve/raspberry/rasp_main.cpp @@ -0,0 +1,203 @@ +// +// Created by matteo on 14/06/19. +// + +#include "RaspController.h" +#include "Servo.h" +#include +#include +#include + +typedef std::unique_ptr Servo_p; + +std::vector read_conf(PIGPIOConnection &pigpio, const YAML::Node &yaml_servos); +void reset(std::vector &servos); +void center(std::vector &servos); +void control(std::vector &servos, const YAML::Node &controller_conf); +void learner(std::vector &servos, const YAML::Node &controller_conf); +void move_to(std::vector &servos, double value); +void test(std::vector &servos); + + +int main( int argc, const char* argv[] ) +{ + try { + YAML::Node config = YAML::LoadFile("robot_conf.yaml"); + + std::string ip = PI_DEFAULT_SOCKET_ADDR_STR; + unsigned short port = PI_DEFAULT_SOCKET_PORT; + + try { + YAML::Node pigpio_address = config["robot_address"]; + ip = pigpio_address["ip"].as(PI_DEFAULT_SOCKET_ADDR_STR); + port = pigpio_address["port"].as(PI_DEFAULT_SOCKET_PORT); + } catch (const YAML::RepresentationException &e) { + // pass + } + std::cout << "Connecting to PIGPIO " << ip << ':' << port << std::endl; + PIGPIOConnection pigpio(ip, port); + YAML::Node yaml_servos = config["servos"]; + std::vector servos = read_conf(pigpio, yaml_servos); + + + if (argc >= 2) { + std::string command = std::string(argv[1]); + if (command == "reset") + reset(servos); + else if (command == "center") + center(servos); + else if (command == "controller") + control(servos, config["controller"]); + else if (command == "learner") + learner(servos, config["controllers"]); + else if (command == "test") + test(servos); + else if (command == "set" && argc >= 3) + move_to(servos, atof(argv[2])); + else + std::clog << "Command \"" << command << "\" not recognized" << std::endl; + } else { + control(servos, config["controller"]); + } + } catch (const std::exception &e) { + std::cerr<<"Exception occurred"<< std::endl; + std::cerr< read_conf(PIGPIOConnection &pigpio, const YAML::Node &yaml_servos) +{ + std::vector servos; + for (const YAML::Node &yaml_servo: yaml_servos) { + unsigned short pin; + try { + pin = yaml_servo["pin"].as(); + } catch (const YAML::InvalidNode &e) { + std::clog << "Error, pin not setted for one servo" << std::endl; + std::exit(2); + } + + double x = 0.0; + double y = 0.0; + double z = 0.0; + try { + YAML::Node coordinates = yaml_servo["coordinates"]; + x = coordinates[0].as(0.0); + y = coordinates[1].as(0.0); + z = coordinates[2].as(0.0); + } catch (const YAML::InvalidNode &e) { + // keep default [0,0,0] + } + auto frequency = yaml_servo["frequency"].as(50); + auto range = yaml_servo["range"] .as(1000); + auto inverse = yaml_servo["inverse"] .as(false); + servos.emplace_back(new revolve::Servo( + x, + y, + z, + &pigpio, + pin, + frequency, + range, + inverse + )); + std::cout << *servos.back() << std::endl; + } + + return servos; +} + +void control(std::vector &servos, const YAML::Node &controller_conf) +{ + std::cout << "Staring controller" << std::endl; + std::vector> sensors; + std::vector> actuators; + actuators.reserve(servos.size()); + for (Servo_p &servo: servos) { + actuators.emplace_back(std::move(servo)); + } + + revolve::RaspController controller( + std::move(actuators), + std::move(sensors), + controller_conf + ); + + while (true) { + controller.update(); + } +} + +void learner(std::vector &servos, const YAML::Node &controllers_conf) +{ + std::cout << "Staring controller" << std::endl; + std::vector> sensors; + std::vector> actuators; + actuators.reserve(servos.size()); + for (Servo_p &servo: servos) { + actuators.emplace_back(std::move(servo)); + } + + revolve::RaspController controller( + std::move(actuators), + std::move(sensors), + controllers_conf[0] + ); + + Timer timer; + unsigned short counter = 0; + for (const YAML::Node &controller_conf: controllers_conf) { + std::cout << "Loading controller[" << ++counter << "] fitness: " << controller_conf["fitness"].as(-1) << std::endl; + controller.set_new_controller(controller_conf); + timer.reset(); + while (timer.elapsed_now() < 30.0) { + controller.update(); + } + } + + std::cout << "Evaluation finished, keeping best controller" << std::endl; + while (true) { + controller.update(); + } +} + +void reset(std::vector &servos) +{ + std::cout << "Shutting off servos" << std::endl; + for (const Servo_p &servo: servos) + servo->off(); +} + +void center(std::vector &servos) +{ + std::cout << "Setting servos to center" << std::endl; + for (const Servo_p &servo: servos) + servo->center(); + + std::cout << "Press enter to continue" << std::endl; + std::string something; + std::cin >> something; +} + +void move_to(std::vector &servos, double value) +{ + std::cout << "Setting servos to " << value << std::endl; + for (const Servo_p &servo: servos) + servo->move_to_position(value); + std::cout << "Press enter to continue" << std::endl; + std::string something; + std::cin >> something; +} + +void test(std::vector &servos) +{ + std::cout << "Testing servos" << std::endl; + + move_to(servos, -1); + move_to(servos, -.5); + move_to(servos, 0); + move_to(servos, 0.5); + move_to(servos, 1); +} \ No newline at end of file diff --git a/cpprevolve/revolve/raspberry/robot_conf.yaml b/cpprevolve/revolve/raspberry/robot_conf.yaml new file mode 100644 index 0000000000..e139ac18e2 --- /dev/null +++ b/cpprevolve/revolve/raspberry/robot_conf.yaml @@ -0,0 +1,64 @@ +robot_name: "spider9" +robot_id: 1, +robot_address: + ip: "192.168.1.25" + #port: 8888 + +#"servo_pins": [17,18,27,22,23,10,9,25], +servos: + - pin: 27 #S + coordinates: [-1, 0] + frequency: 50 + range: 1000 + inverse: True + - pin: 17 #SNN + coordinates: [-3, 0] + inverse: True + - pin: 9 #N + coordinates: [1, 0] + inverse: True + - pin: 25 #NNN + coordinates: [3, 0] + - pin: 22 #E + coordinates: [0, 1] + inverse: True + - pin: 18 #ENN + coordinates: [0, 3] + inverse: True + - pin: 23 #W + coordinates: [0, -1] + inverse: True + - pin: 10 #WNN + coordinates: [0, -3] + inverse: True + +rgb_pins: [15,14,4] + +#controller: + # spider weights + #type: "differential-cpg" + #weights: [0.545275, 0.48118, 0.677335, 0.834078, 0.331732, 0.479091, 0.87384, 0.527239, 0.0148421, 0.131508, 0.711216, 0.672872, 0.648163, 0.204883, 0.788699, 0.38614, 0.483561, 0.0777244] + +controllers: + # baby+1 learning weights, crescendo + - type: "differential-cpg" + weights: [0.395516, 0.83811, 0.463123, 0.702373, 0.936804, 0.166412, 0.631632, 0.287821, 0.799552, 0.218267, 0.0623519, 0.799128] + fitness: 0.000503405 + - type: "differential-cpg" + weights: [0.871967, 0.441235, 0.684449, 0.58511, 0.899357, 0.497721, 0.342563, 0.164466, 0.676871, 0.475722, 0.405172, 0.370701] + fitness: 0.202879 + - type: "differential-cpg" + weights: [0.223283, 0.912134, 0.374909, 0.931379, 0.733706, 0.283053, 0.0923915, 0.0706944, 0.0915673, 0.53245, 0.962511, 0.512361] + fitness: 0.403299 + - type: "differential-cpg" + weights: [0.302763, 0.913937, 0.376248, 0.911346, 0.712692, 0.298535, 0.0272732, 0.0706944, 0.095008, 0.46318, 0.990895, 0.564726] + fitness: 0.600739 + - type: "differential-cpg" + weights: [0.319842, 0.848368, 0.415024, 0.946114, 0.665586, 0.26537, 0.0609814, 0.0757356, 0.100649, 0.461241, 0.972517, 0.485218] + fitness: 0.801518 + - type: "differential-cpg" + weights: [0.698179, 0.828084, 0.381213, 0.974549, 0.663302, 0.22419, 0.163161, 0.0362292, 0.0558966, 0.357249, 0.960544, 0.512658] + fitness: 1.00555 + - type: "differential-cpg" + weights: [0.65835, 0.723842, 0.431859, 0.919208, 0.721147, 0.160043, 0.138266, 0.0751595, 0.0335994, 0.395186, 0.88612, 0.601392] + fitness: 1.27441 diff --git a/docker/build_revolve.sh b/docker/build_revolve.sh index 9019b73334..953e270d87 100755 --- a/docker/build_revolve.sh +++ b/docker/build_revolve.sh @@ -3,6 +3,10 @@ set -e # Build Revolve cd /revolve + +# use version 10 +sed -i 's/ find_package(gazebo 9 REQUIRED)/ find_package(gazebo 10 REQUIRED)/g' cpprevolve/revolve/gazebo/CMakeLists.txt + mkdir -p build && cd build cmake .. -DCMAKE_BUILD_TYPE="Release" make -j4 diff --git a/experiments/.gitignore b/experiments/.gitignore new file mode 100644 index 0000000000..52bd2c92d4 --- /dev/null +++ b/experiments/.gitignore @@ -0,0 +1,2 @@ +/default_experiment +/*/data \ No newline at end of file diff --git a/experiments/bo_learner/3DPlot.py b/experiments/bo_learner/3DPlot.py new file mode 100644 index 0000000000..bf23c6edb9 --- /dev/null +++ b/experiments/bo_learner/3DPlot.py @@ -0,0 +1,113 @@ +import matplotlib +from sys import platform +if platform == "darwin": + matplotlib.use("TkAgg") +import matplotlib.pyplot as plt +from glob import glob +import pandas as pd +from mpl_toolkits import mplot3d +import numpy as np +import os +import plotly.offline as py +import plotly.graph_objs as go + +# Parameters +path = "/home/maarten/CLionProjects/revolve/output/cpg_bo/main_1557701167/" +var1 = "range_ub" +var2 = "signal_factor" +parameter_file = "parameters.txt" + +# Set matplotlib font +font = {'size' : 13} +matplotlib.rc('font', **font) + +# Get all sub-directories +path_list = glob(path + "*") +path_list = [path_ for path_ in path_list if os.path.isdir(path_)] +n_dirs = len(path_list) + +# Holder +results = np.empty((n_dirs, 3)) + +# Check if it's numeric: +for ix, path_ in enumerate(path_list): + try: + int(path_.split("/")[-1] ) + except: + continue + + # Cope with unsorted issue + path_ = "/".join(path_.split("/")[:-1]) + "/" + str(ix) + print(path_, ix) # All fine till here + + # Get parameters for this file + subfolder_list = glob(path_ + "/*/") + parameters = [] + + # Get some parameter file (so no empty list anymore) + c = 0 + while parameters == []: + parameters = [(line.rstrip('\n')) for line in open(path_ + "/" + subfolder_list[c].split("/")[-2] + "/" + parameter_file)] + c += 1 + + for param in parameters: + if(var1 in param): + results[ix, 0] = float(param.split(":")[-1]) + if(var2 in param): + results[ix, 1] = float(param.split(":")[-1]) + + # Get Fitness. This is an average file in path_ + fitness = ".".join(glob(path_ + "/*.png")[0].split("/")[-1].split(".")[:-1]) + #fitness = ".".join(glob(path_ + "/*d.png")[0].split("/")[-1].split(".")[:-1]) + results[ix, 2] = fitness[:-1] + +# Combine results +df = pd.DataFrame(results) +results = df.sort_values(by = [0,1]).to_numpy() + +# Prepare for 3D plot +my_size_x = 11 +my_size_y = 13 +X =results[:,0].reshape((my_size_x, my_size_y)) +Y =results[:,1].reshape((my_size_x, my_size_y)) +Z =results[:,2].reshape((my_size_x, my_size_y)) + +# Construct 3D plot +fig = plt.figure(figsize=(10,10)) +ax = plt.axes(projection='3d') +ax.plot_surface(X, Y, Z, rstride=1, cstride=1, + cmap='viridis', edgecolor='none') +ax.set_xlabel(var1) +ax.set_ylabel(var2) +ax.set_zlabel("fitness") +plt.savefig(path + "3Dplot.png") + + +# Get data for plotly +data = [ + go.Surface( + x = X, + y = Y, + z = Z + ) +] + +# Layout +layout = go.Layout( + title = path, + scene = dict( + xaxis=dict(title=var1), + yaxis=dict(title=var2), + zaxis=dict(title="fitness"), + ), +) + +# Construct ploty +fig = go.Figure(data=data, layout = layout) +py.plot(fig, filename=path + "interactive_3d") + +# Save XYZ +np.savetxt(path + "X.txt", np.matrix(X), fmt='%f', delimiter = ",") +np.savetxt(path + "Y.txt", np.matrix(Y), fmt='%f', delimiter = ",") +np.savetxt(path + "Z.txt", np.matrix(Z), fmt='%f', delimiter = ",") + diff --git a/experiments/bo_learner/AggregateGridSearches.py b/experiments/bo_learner/AggregateGridSearches.py new file mode 100644 index 0000000000..51c1b65693 --- /dev/null +++ b/experiments/bo_learner/AggregateGridSearches.py @@ -0,0 +1,44 @@ +import matplotlib +from sys import platform +if platform == "darwin": + matplotlib.use("TkAgg") +import matplotlib.pyplot as plt +from glob import glob +import numpy as np + + +# Parameters +path = "/home/maarten/Thesis_output/cpg_tuning/" +my_size_x = 11 +my_size_y = 13 +var1 = "range_ub" +var2 = "signal_factor" + +paths = glob(path + "*/") +Z1 = np.loadtxt(paths[0] + "Z.txt", delimiter=",") +Z2 = np.loadtxt(paths[1] + "Z.txt", delimiter=",") +Z3 = np.loadtxt(paths[2] + "Z.txt", delimiter=",") +Z4 = np.loadtxt(paths[3] + "Z.txt", delimiter=",") +Z5 = np.loadtxt(paths[4] + "Z.txt", delimiter=",") +Z6 = np.loadtxt(paths[5] + "Z.txt", delimiter=",") +Z7 = np.loadtxt(paths[6] + "Z.txt", delimiter=",") +Z8 = np.loadtxt(paths[7] + "Z.txt", delimiter=",") +Z9 = np.loadtxt(paths[7] + "Z.txt", delimiter=",") +Z = (Z1 + Z2 + Z3 + Z4 + Z5 + Z6 + Z7 + Z8 + Z9)/9.0 + +X = np.loadtxt(paths[0] + "X.txt", delimiter=",") +Y = np.loadtxt(paths[0] + "Y.txt", delimiter=",") + +# Create plot +fig, ax = plt.subplots() +cs = plt.contourf(X.tolist(),Y.tolist(),Z.tolist(),extend = "both", cmap = "hot_r", levels = 15) +cs.changed() +fig.colorbar(cs) +plt.xlabel(var1) +plt.ylabel(var2) +plt.savefig(path + "cpg_combined.png") + +# Save XYZ +np.savetxt(path + "X.txt", np.matrix(X), fmt='%f', delimiter = ",") +np.savetxt(path + "Y.txt", np.matrix(Y), fmt='%f', delimiter = ",") +np.savetxt(path + "Z.txt", np.matrix(Z), fmt='%f', delimiter = ",") diff --git a/experiments/bo_learner/BOTuningAnalysis.py b/experiments/bo_learner/BOTuningAnalysis.py new file mode 100644 index 0000000000..0136decf65 --- /dev/null +++ b/experiments/bo_learner/BOTuningAnalysis.py @@ -0,0 +1,115 @@ +import numpy as np +import os +from glob import glob +import matplotlib.pyplot as plt +import matplotlib as mpl + + +path = "/home/gongjinlan/BO_tuning_results/main_1560002003-BO-spider9-finished/" +dirs = glob(path + "*/") + +# Base settings for alph, sigma_sq, l +base_names = ["Sampling method", "UCB alpha", "Kernel sigma_sq", "Kernel l"] +base_setting = ["LHS", "0.5", "1", "0.1"] +parameter_file = "dynamic_parameters.txt" +max_dirs = 20 +model_name = "Spider9" + +# Set matplotlib font +font = {'font.size' : 60} + +# Initiate groups with base +zero = ["/".join(x.split("/")[:-2]) + "/" for x in dirs][0] + "0/" +groups = [] +for k in range(len(base_setting)): + groups += [[[zero, base_setting]]] + +for ix, my_dir in enumerate(dirs): + my_sub_dirs = [float(path.split("/")[-2]) for path in glob(my_dir + "*/")] + my_sub_dirs.sort() + my_sub_dirs = [str(x) for x in my_sub_dirs] + + # Save all fitnesses in a list. This can help you to later construct the + sd_list = [] + for sd in my_sub_dirs: + if os.path.isfile(my_dir + sd + "/" + parameter_file): + sd_list += [sd] + + # Get dynamic parameters + params_all = [(line.rstrip('\n')).split(",") for line in open(my_dir + sd_list[0] + "/" + parameter_file)] + params = params_all[0] + real_param = params_all[0] + + # Check dynamic parameters for thread-safety: + for sd in sd_list: + temp_param = [(line.rstrip('\n')).split(",") for line in open(my_dir + sd + "/" + parameter_file)] + if not all(x == real_param for x in temp_param): + differ = [x for x in temp_param if not x == real_param] + differ = [d for d in differ if len(d) != 3] + if len(differ) > 0: + None + #print(f"WARNING: DYNAMIC PARAMETERS DIFFER FOR {sd}") + for d in differ: + print(d) + + # Group folders together based on which param they differ in from + equality = [0]*len(base_setting) + c= 0 + for k in range(len(base_setting)): + if not base_setting[k] == params[k]: + groups[k] += [[my_dir, params]] + print(f"Added {my_dir} to group {k} with params {params}") + c += 1 + if c == 0: + print(f"Didn't add {my_dir}") + + +for ix, group in enumerate(groups): + print("\n\n") + # Sort group + group = sorted(group, key=lambda x: x[1][ix]) + labels = [] + fitnesses_list_mean = [] + fitnesses_list_error = [] + + for i, e in enumerate(group): + print(e) + labels += [e[1][ix]] + + # Get fitnesses that are generated by gridsearchanalysis + fitnesses = np.loadtxt(e[0] + "experiment_fitnesses.txt", delimiter =",") + print(f"{ix}, {i} uses {len(fitnesses)} runs") + + fitnesses = fitnesses[:,0] + error = 1.96*np.std(fitnesses)/np.sqrt(len(fitnesses)) + mean = np.mean(fitnesses) + fitnesses_list_mean += [mean] + fitnesses_list_error += [error] + + f, ax = plt.subplots(1,1,figsize=(10,7.5)) + plt.rcParams["font.size"] = "32" + plt.xlabel(base_names[ix], fontsize=34) + plt.ylabel("fitness", fontsize=34) + plt.title(model_name) + plt.xlim((-0.5, len(group) -0.5)) + plt.errorbar([i for i in range(len(group))], + fitnesses_list_mean, + yerr = fitnesses_list_error, + linewidth =3.5, + capsize = 6, + capthick = 3.0, + marker="o", + ms = 10, + ls ="none") + ax.set_xticks([i for i in range(len(group))]) + ax.set_xticklabels(labels) + ax.tick_params(labelsize=34) + + plt.tight_layout() + plt.savefig(path + model_name + "-" + str(ix) + ".pdf") + plt.clf() + #plt.show() + + + + diff --git a/experiments/bo_learner/DeletePNGs.py b/experiments/bo_learner/DeletePNGs.py new file mode 100644 index 0000000000..535a5664f5 --- /dev/null +++ b/experiments/bo_learner/DeletePNGs.py @@ -0,0 +1,11 @@ +from glob import glob +import os + +path = "/home/gongjinlan/projects/revolve/output/cpg_bo/main_1559644358-BO-gecko7/" +print(path) + +paths = glob(path + "*/*.png") +print(len(paths)) + +for path in paths: + os.remove(path) diff --git a/experiments/bo_learner/GridSearch manual.md b/experiments/bo_learner/GridSearch manual.md new file mode 100644 index 0000000000..257f5b4d60 --- /dev/null +++ b/experiments/bo_learner/GridSearch manual.md @@ -0,0 +1,35 @@ + +# Documentation + +This GridSearch.py-file can be used to perform a grid search over some set of parameters. One can just call the file without arguments, i.e. from the revolve directory:: + +`python3 experiments/bo_learner/GridSearch.py` + +# Parameters +After the imports, one can select parameters, e.g.: +``` +# Parameters +n_runs = 2 +n_jobs = 4 +my_yaml_path = "experiments/bo_learner/yaml/" +base_model = "spider.yaml" +manager = "experiments/bo_learner/manager.py" +python_interpreter = "~/projects/revolve-simulator/revolve/.venv36/bin/python3.6" +search_space = { +'init_method': ["RS", "LHS"], +'signal_factor': [1.5,1.7, 1.9, 2.1, 2.3], +} +``` + +What happens is that all the parameters in the yaml-file (my_yaml_path + base_model) are used as default for the manager, unless changed here. So, at `search_space` we declare that we want to iterate over the `init_method` and `signal_factor` parameters corresponding to the yaml-file. Note that this yaml-file will also contain what brain to use (from which it inherits the parameters). + +Search space parameters always need to be entered in a list (as we iterate over elements). From the search_space provided, we take every combination, and perform experiments for it. In this exapmle, we therefore have len(init_method)*len(signal_fator) = 10 experiments. Each experiment is repeated n_runs = 10 number of times, resulting in 200 runs (and with that 200 gzserver instances) to be performed. + +The parameter n_jobs specifies the number of threads to be used. E.g. on the ripper we have 64 threads, so we can set n_jobs = 63 (advisable to not set the maximum). This is equivalanet to setting n_jobs = -2. + + +The output is written to `output/cpg_bo/main_ min_lines: + runs_succesful[str(e.split("/")[-2])] += 1 + + to_run = {} + for key, val in runs_succesful.items(): + to_run[key] = n_runs - val + to_run = {k: v for k, v in to_run.items() if v > 0} + + # If the experiment list is empty + if not bool(to_run): + finished = True + else: + print(f"To finish {sum(to_run.values())} runs") + + # Empty experiments list + experiments = [] + + # Use spare computing capacity + while sum(to_run.values()) < n_jobs - len(to_run): + print(to_run) + + for key, value in to_run.items(): + to_run[key] += 1 + + # Construct new experiment list + for key, val in to_run.items(): + for i in range(val): + entry = unique_experiments[int(key)] + experiments.append(entry) + + # START ANALYSIS HERE + print("I will now perform analysis") + + # Do analysis + fitness_list = [] + for i in range(n_unique_experiments): + path = output_path + str(i) + "/*/" + path_list = glob(path) + path_list = [my_path for my_path in path_list if os.path.exists(my_path + "fitnesses.txt")] + n_rows = len([(line.rstrip('\n')) for line in open(path_list[0] + "fitnesses.txt")]) + n_subruns = len(path_list) + + # Working variables + fitnesses = np.empty((n_rows,n_subruns)) + fitnesses_mon = np.empty((n_rows,n_subruns)) + + # Create plot + plt.figure() + plt.title("Monotonic - Param setting " + str(i)) + plt.xlabel("Iteration") + plt.ylabel("Fitness") + plt.grid() + + # Get sub-runs for this setup + for ix, e in enumerate(path_list): + # Read fitness + my_fitness = [float((line.rstrip('\n'))) for line in open(e + "fitnesses.txt")] + + # Transfer fitness to monotonic sequence and save + my_fitness_mon = [e if e >= max(my_fitness[:ix+1]) else max(my_fitness[:ix+1]) for ix, e in enumerate(my_fitness)] + + # Save fitness + fitnesses_mon[:,ix] = np.array(my_fitness_mon) + fitnesses[:,ix] = np.array(my_fitness) + + # Plot the avg fitness + plt.plot(fitnesses_mon[:, ix], linewidth = 1, color = "blue") + + # Take average value over the n_runs + avg_fitness = np.mean(fitnesses, axis=1) + avg_fitness_mon = np.mean(fitnesses_mon, axis=1) + + # Save plot + plt.plot(avg_fitness_mon, linestyle="dashed", linewidth=2.5, color="black") + plt.tight_layout() + plt.savefig(output_path + str(i) + "/" + str(round(avg_fitness_mon[-1], 7)) + ".png") + + # Save fitness + fitness_list += [[round(avg_fitness_mon[-1], 5), i]] + + # Get fitness stats + fitness_list.sort(key=lambda x: x[0]) + fitness_list.reverse() + fitness_list + + print("Fitnesses are:") + for e in fitness_list: + print(e) + e = [str(e_) for e_ in e] + # Write to file in main directory + with open(output_path + '/results.txt', 'a') as avg_fitness_file: + avg_fitness_file.write(",".join(e) + "\n") + + print("Contents written to ", output_path) + + # Delete the yaml's + yaml_temp = my_yaml_path + my_sub_directory + yaml_files = glob(yaml_temp + "*") + for f in yaml_files: + os.remove(f) + + # Write the parameters + params_string =[] + for key, value in iter(search_space.items()): + params_string += [str(key) + ": " + str(value)] + write_file(output_path + "search_space.txt", params_string) diff --git a/experiments/bo_learner/GridSearchAnalysis.py b/experiments/bo_learner/GridSearchAnalysis.py new file mode 100644 index 0000000000..3309518ac6 --- /dev/null +++ b/experiments/bo_learner/GridSearchAnalysis.py @@ -0,0 +1,148 @@ +from sys import platform +import matplotlib +import numpy as np +import os +from glob import glob +if platform == "darwin": + matplotlib.use("TkAgg") +import matplotlib.pyplot as plt +import time + +# Parameters +path = "/home/gongjinlan/projects/revolve/output/cpg_bo/main_1559644358-BO-gecko7/" +fitness_file = "fitnesses.txt" +yaml_temp_path = "/home/gongjinlan/projects/revolve/experiments/bo_learner/yaml/yaml_temp/" + +# Get all sub-directories +path_list = glob(path + "*") +path_list = [path_ for path_ in path_list if os.path.isdir(path_)] +n_dirs = len(path_list) +max_dirs = 20 +n_rows_max = 1500 +n_rows_min = 1450 + +# Holder +results = np.empty((n_dirs, 3)) + +# Check if it's numeric: +fitness_list = [] +subrun_numbers = [] +for i, path_ in enumerate(path_list): + try: + int(path_.split("/")[-1] ) + except: + continue + + # Cope with unsorted issue + path_ = "/".join(path_.split("/")[:-1]) + "/" + str(i) + + # Do fitness analysis + subfolder_list = glob(path_ + "/*/") + subfolder_list = [d for d in subfolder_list if os.path.isfile(d + fitness_file)] + try: + n_rows = len([(line.rstrip('\n')) for line in open(subfolder_list[0] + "/" + fitness_file)]) + except: + None + + # Remove all rows with a small number of values + subfolder_list_temp = [] + for j_, subfolder_ in enumerate(subfolder_list): + # Get fitness file + my_fitness_ = [(line.rstrip('\n')) for line in open(subfolder_ + "/" + fitness_file)] + if len(my_fitness_) >= n_rows_min: + subfolder_list_temp += [subfolder_] + else: + print("Exclude ", subfolder_, "length", len(my_fitness_)) + + # Save thisnumber of subruns + n_subruns = len(subfolder_list_temp) + subrun_numbers += [[n_subruns, i]] + + # Working variables + fitnesses = np.empty((n_rows_max,n_subruns)) + fitnesses_mon = np.empty((n_rows_max,n_subruns)) + + # Create plot + plt.figure() + plt.title("Monotonic - Param setting " + str(i)) + plt.xlabel("Iteration") + plt.ylabel("Fitness") + plt.grid() + + # Clean file + open(path_ + "/experiment_fitnesses.txt", 'w').close() + kx = 0 + + # For all n_runs + for j, subfolder in enumerate(subfolder_list_temp): + # print( subfolder) + # Get fitness file + my_fitness = [float((line.rstrip('\n'))) for line in open(subfolder + "/" + fitness_file)] + # Take maximum n_rows_max + my_fitness = my_fitness[:n_rows_max] + + # Take minimum n_rows_max + c_ = 0 + while(len(my_fitness) < n_rows_max): + my_fitness += [my_fitness[-1]] + c_ += 1 + + if c_ >0: + print(f"Added {c_} fitnesses for {subfolder}") + + # Transfer fitness to monotonic sequence and save + my_fitness_mon = [e if e >= max(my_fitness[:ix+1]) else max(my_fitness[:ix+1]) for ix, e in enumerate(my_fitness)] + + # Save fitness + fitnesses_mon[:,j] = np.array(my_fitness_mon) + fitnesses[:,j] = np.array(my_fitness) + + # Save the fitnesses of all runs + with open(path_ + "/experiment_fitnesses.txt", 'a') as experiment_fitness_file: + if kx < max_dirs: + experiment_fitness_file.write(",".join([str(my_fitness_mon[-1]), subfolder.split("/")[-2]]) + "\n") + kx += 1 + + # Plot the avg fitness + plt.plot(fitnesses_mon[:, j], linewidth = 1, color = "blue") + + # Take average value over the n_runs + avg_fitness = np.mean(fitnesses, axis=1) + avg_fitness_mon = np.mean(fitnesses_mon, axis=1) + + # Save plot + plt.plot(avg_fitness_mon, linestyle="dashed", linewidth=2.5, color="black") + plt.tight_layout() + plt.savefig(path_ + "/" + str(round(avg_fitness_mon[-1], 7)) + ".png") + fig = plt.gcf() + plt.close(fig) + + # Save fitness + fitness_list += [[round(avg_fitness_mon[-1], 5), i]] + +# Get fitness stats +fitness_list.sort(key=lambda x: x[0]) +fitness_list.reverse() +fitness_list + + +# TODO: Results.txt has wrong order (3D plot not affected by this). +print("Fitnesses are:") +for e in fitness_list: + print(e) + e = [str(e_) for e_ in e] + # Write to file in main directory + with open(path + '/results.txt', 'a') as avg_fitness_file: + avg_fitness_file.write(",".join(e) + "\n") + +print("Number of succesful runs:") +for l in range(len(subrun_numbers)): + print(subrun_numbers[l]) + +print("Contents written to ", path) + +# Delete the yaml's +yaml_files = glob(yaml_temp_path + "*") +for f in yaml_files: + os.remove(f) + diff --git a/experiments/bo_learner/RunAnalysisBO.py b/experiments/bo_learner/RunAnalysisBO.py new file mode 100755 index 0000000000..6a80d519d1 --- /dev/null +++ b/experiments/bo_learner/RunAnalysisBO.py @@ -0,0 +1,99 @@ +#!usr/bin/env python3 +""" +This script can be called to create plots of the fitness function. I use it after a run of BO. +It creates both a monotonic (increasing) fitness plot, as well as a fitness plot with all the +separate fitness points over time. It's written to the directory given. + +Params: +arg1: The directory name that contains the fitness data fitnesses.txt +arg2: The number of initial samples drawn for BO +arg3: The number of iterations to test the best controller in the end +""" + +import numpy as np +import sys +import matplotlib +from sys import platform + +# Enable different backend for OSX +if platform == "darwin": + matplotlib.use("TkAgg") +import matplotlib.pyplot as plt + +# Set matplotlib font +font = {'size' : 20} +matplotlib.rc('font', **font) + +# Obtain arguments +try: + root_directory = str(sys.argv[1]) + n_initial_samples = int(sys.argv[2]) + n_no_learning_iterations = int(sys.argv[3]) +except IndexError: + print("Please check the arguments of the directory/n_initial_samples/n_no_learning_iterations") + +def fitness_per_iteration_plot(my_directory, my_data, n_initial_samples, n_no_learning_iterations): + # Set up plot + plt.figure(figsize=(14, 14)) + plt.xlabel("#Evaluations") + plt.ylabel("Fitness") + plt.title("CPG + BO") + plt.axvline(x=n_initial_samples, color="green", linestyle="dashed") + plt.axvline(x=len(my_data) - n_no_learning_iterations, color="red", linestyle="dashed") + plt.grid() + plt.plot(my_data[:-(n_no_learning_iterations + 1)]) + # Save plots + plt.savefig(my_directory + "/fitness.png") + + +def max_fitness_plot(my_directory, my_data, n_initial_samples, n_no_learning_iterations): + # Create monotonic sequence + my_data = [e if e >= max(my_data[:ix+1]) else max(my_data[:ix+1]) for ix, e in enumerate(my_data)] + + # Set up plot + plt.figure(figsize=(14, 14)) + plt.xlabel("#Evaluations") + plt.ylabel("Fitness") + plt.title("CPG + BO") + plt.axvline(x=n_initial_samples, color="green", linestyle="dashed") + plt.grid() + plt.plot(my_data[:-(n_no_learning_iterations + 1)]) + print(my_data[-1]) + + # Save plots + plt.savefig(my_directory + "/fitness_monotonic.png") + + +def get_data(my_directory, filename): + # Read data + filename = my_directory + filename + my_data = [float(line.rstrip('\n')) for line in open(filename)] + + # Return data + return my_data + + +def save_best_brain(path): + my_fitness = [float(line.rstrip('\n')) for line in open(path + "fitnesses.txt")] + my_samples = [line.rstrip('\n') for line in open(path + "samples.txt")] + ix_best = np.argmax(my_fitness) + # Exclude last comma while saving brain + np.savetxt(path + "/best_brain.txt", [my_samples[ix_best][:-2]], delimiter=",", fmt="%s") + + +# Get and process data +fitness_data = get_data(root_directory, "fitnesses.txt") + +fitness_per_iteration_plot(root_directory, + fitness_data, + n_initial_samples, + n_no_learning_iterations) + +max_fitness_plot(root_directory, + fitness_data, + n_initial_samples, + n_no_learning_iterations) + +print("root directory is ", root_directory) +save_best_brain(root_directory) +print("Plots are constructed at ", root_directory) diff --git a/experiments/bo_learner/manager.py b/experiments/bo_learner/manager.py new file mode 100755 index 0000000000..bb095cd1d8 --- /dev/null +++ b/experiments/bo_learner/manager.py @@ -0,0 +1,72 @@ +#!/usr/bin/env python3 +import os +import sys +import asyncio + +# Add `..` folder in search path +current_dir = os.path.dirname(os.path.abspath(__file__)) +newpath = os.path.join(current_dir, '..', '..') +sys.path.append(newpath) + +from pygazebo.pygazebo import DisconnectError + +from pyrevolve import revolve_bot +from pyrevolve import parser +from pyrevolve.SDF.math import Vector3 +from pyrevolve.tol.manage import World + + +async def run(): + """ + The main coroutine, which is started below. + """ + # Parse command line / file input arguments + settings = parser.parse_args() + + # Load a robot from yaml + robot = revolve_bot.RevolveBot() + if settings.robot_yaml is None: + robot.load_file("experiments/bo_learner/yaml/spider.yaml") + else: + robot.load_file(settings.robot_yaml) + robot.update_substrate() + + # Connect to the simulator and pause + world = await World.create(settings) + await world.pause(True) + + await world.delete_model(robot.id) + await asyncio.sleep(2.5) + + # Insert the robot in the simulator + robot_manager = await world.insert_robot(robot, Vector3(0, 0, 0.025)) + + # Resume simulation + await world.pause(False) + + # Start a run loop to do some stuff + while True: + await asyncio.sleep(5.0) + + +def main(): + def handler(loop, context): + exc = context['exception'] + if isinstance(exc, DisconnectError) \ + or isinstance(exc, ConnectionResetError): + print("Got disconnect / connection reset - shutting down.") + sys.exit(0) + raise context['exception'] + + try: + loop = asyncio.get_event_loop() + loop.set_exception_handler(handler) + loop.run_until_complete(run()) + except KeyboardInterrupt: + print("Got CtrlC, shutting down.") + + +if __name__ == '__main__': + print("STARTING") + main() + print("FINISHED") diff --git a/experiments/bo_learner/run_get_analytics.py b/experiments/bo_learner/run_get_analytics.py new file mode 100644 index 0000000000..c48c90fa6e --- /dev/null +++ b/experiments/bo_learner/run_get_analytics.py @@ -0,0 +1,16 @@ +from glob import glob +import os + +python_interpreter = "/home/maarten/CLionProjects/revolve/venv/bin/python" +path = "/home/maarten/CLionProjects/revolve/output/cpg_bo/main_1557477606/47/" + + +paths = glob(path + "*/") +print(len(paths)) +paths = [p for p in paths if os.path.isfile(p + "fitnesses.txt")] +print(len(paths)) + +for path in paths: + # Call the experiment + py_command = python_interpreter + " experiments/bo_learner/RunAnalysisBO.py " + path + "/ 50 1" + os.system(py_command) \ No newline at end of file diff --git a/experiments/bo_learner/yaml/babyA.yaml b/experiments/bo_learner/yaml/babyA.yaml new file mode 100644 index 0000000000..6ee67bdc64 --- /dev/null +++ b/experiments/bo_learner/yaml/babyA.yaml @@ -0,0 +1,190 @@ +--- +id: example_babyA +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg021Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg02 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/babyB.yaml b/experiments/bo_learner/yaml/babyB.yaml new file mode 100644 index 0000000000..1144e9f64f --- /dev/null +++ b/experiments/bo_learner/yaml/babyB.yaml @@ -0,0 +1,222 @@ +--- +id: example_babyB +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 0: + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 1: + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 2: + id : Leg20Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 3: + id : Leg30Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/babyC.yaml b/experiments/bo_learner/yaml/babyC.yaml new file mode 100644 index 0000000000..07b15884af --- /dev/null +++ b/experiments/bo_learner/yaml/babyC.yaml @@ -0,0 +1,336 @@ +--- +id: example_babyC +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg002Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg002 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg012Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg012 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + slot : 0 + id : BodyJoint2 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : BodyJoint3 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Body3 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg102Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg102 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg112Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : -90 + children : + 1: + id : Leg112 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/gecko12.yaml b/experiments/bo_learner/yaml/gecko12.yaml new file mode 100644 index 0000000000..bb6dfaaeab --- /dev/null +++ b/experiments/bo_learner/yaml/gecko12.yaml @@ -0,0 +1,253 @@ +--- +id: example_gecko12 +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : BodyJoint2 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg111 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/gecko17.yaml b/experiments/bo_learner/yaml/gecko17.yaml new file mode 100644 index 0000000000..1c32cf0ede --- /dev/null +++ b/experiments/bo_learner/yaml/gecko17.yaml @@ -0,0 +1,345 @@ +--- +id: example_gecko17 +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg002Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg002 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg012Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg012 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + slot : 0 + id : BodyJoint2 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : BodyJoint3 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Body3 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg102Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg102 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg111 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg112Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg112 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/gecko7.yaml b/experiments/bo_learner/yaml/gecko7.yaml new file mode 100644 index 0000000000..00b3eee25e --- /dev/null +++ b/experiments/bo_learner/yaml/gecko7.yaml @@ -0,0 +1,162 @@ +--- +id: example_gecko7 +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/spider13.yaml b/experiments/bo_learner/yaml/spider13.yaml new file mode 100644 index 0000000000..5fed980f4e --- /dev/null +++ b/experiments/bo_learner/yaml/spider13.yaml @@ -0,0 +1,258 @@ +--- +id: example_spider13 +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 0: + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 1: + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg12Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg12 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 2: + id : Leg20Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + 3: + id : Leg30Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 26 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/spider17.yaml b/experiments/bo_learner/yaml/spider17.yaml new file mode 100644 index 0000000000..2cdae21c26 --- /dev/null +++ b/experiments/bo_learner/yaml/spider17.yaml @@ -0,0 +1,330 @@ +--- +id: example_spider17 +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 0: + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg03Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg03 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg12Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg12 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg13Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg13 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 2: + id : Leg20Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg23Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg23 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + id : Leg30Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg33Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 0 + children : + 1: + id : Leg33 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 34 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/bo_learner/yaml/spider9.yaml b/experiments/bo_learner/yaml/spider9.yaml new file mode 100644 index 0000000000..7e153dceef --- /dev/null +++ b/experiments/bo_learner/yaml/spider9.yaml @@ -0,0 +1,182 @@ +--- +id: example_spider +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 0: + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 2: + id : Leg20Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg21 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + id : Leg30Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg31 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg + controller: + use_frame_of_reference: 0 + load_brain: "" + reset_neuron_state_bool: "true" + reset_neuron_random: "false" + abs_output_bound: 1.0 + signal_factor_all: 4.0 + signal_factor_mid: 2.5 + signal_factor_left_right: 2.5 + range_lb: -1.0 + range_ub: 1.5 + init_neuron_state: 0.707 + learner: + n_init_samples: 50 + init_method: "LHS" + kernel_noise: 0.00000001 + kernel_optimize_noise: "false" + kernel_sigma_sq: 0.222 + kernel_l: 0.55 + kernel_squared_exp_ard_k: 4 + acqui_gpucb_delta: 0.5 + acqui_ucb_alpha: 0.44 + acqui_ei_jitter: 0 + acquisition_function: "UCB" + meta: + robot_size: 18 + run_analytics: "true" + n_learning_iterations: 1450 + n_cooldown_iterations: 1 + reset_robot_position: "false" + evaluation_rate: 60 + output_directory: "" + verbose: 0 + startup_time: 0 diff --git a/experiments/examples/consolidate_experiments.py b/experiments/examples/consolidate_experiments.py new file mode 100644 index 0000000000..b512d681e0 --- /dev/null +++ b/experiments/examples/consolidate_experiments.py @@ -0,0 +1,90 @@ +import os + +# set these variables according to your experiments # +dirpath = 'data' +experiments_type = [ + 'default_experiment' + ] +runs = 1 +# set these variables according to your experiments # + + +def build_headers(path): + + print(path + "/all_measures.txt") + file_summary = open(path + "/all_measures.tsv", "w+") + file_summary.write('robot_id\t') + + behavior_headers = [] + with open(path + '/data_fullevolution/descriptors/behavior_desc_robot_1.txt') as file: + for line in file: + measure, value = line.strip().split(' ') + behavior_headers.append(measure) + file_summary.write(measure+'\t') + + phenotype_headers = [] + with open(path + '/data_fullevolution/descriptors/phenotype_desc_robot_1.txt') as file: + for line in file: + measure, value = line.strip().split(' ') + phenotype_headers.append(measure) + file_summary.write(measure+'\t') + file_summary.write('fitness\n') + file_summary.close() + + file_summary = open(path + "/snapshots_ids.tsv", "w+") + file_summary.write('generation\trobot_id\n') + file_summary.close() + + return behavior_headers, phenotype_headers + + +for exp in experiments_type: + for run in range(1, runs+1): + + print(exp, run) + path = os.path.join(dirpath, str(exp), str(run)) + behavior_headers, phenotype_headers = build_headers(path) + + file_summary = open(path + "/all_measures.tsv", "a") + for r, d, f in os.walk(path+'/data_fullevolution/fitness'): + for file in f: + + robot_id = file.split('.')[0].split('_')[-1] + file_summary.write(robot_id+'\t') + + bh_file = path+'/data_fullevolution/descriptors/behavior_desc_robot_'+robot_id+'.txt' + if os.path.isfile(bh_file): + with open(bh_file) as file: + for line in file: + measure, value = line.strip().split(' ') + file_summary.write(value+'\t') + else: + for h in behavior_headers: + file_summary.write('None'+'\t') + + pt_file = path+'/data_fullevolution/descriptors/phenotype_desc_robot_'+robot_id+'.txt' + if os.path.isfile(pt_file): + with open(pt_file) as file: + for line in file: + measure, value = line.strip().split(' ') + file_summary.write(value+'\t') + else: + for h in phenotype_headers: + file_summary.write('None'+'\t') + + file = open(path+'/data_fullevolution/fitness/fitness_robot_'+robot_id+'.txt', 'r') + fitness = file.read() + file_summary.write(fitness + '\n') + file_summary.close() + + file_summary = open(path + "/snapshots_ids.tsv", "a") + for r, d, f in os.walk(path): + for dir in d: + if 'selectedpop' in dir: + gen = dir.split('_')[1] + for r2, d2, f2 in os.walk(path + '/selectedpop_' + str(gen)): + for file in f2: + if 'body' in file: + id = file.split('.')[0].split('_')[-1] + file_summary.write(gen+'\t'+id+'\n') + file_summary.close() diff --git a/experiments/examples/manager.py b/experiments/examples/manager.py index 3dacc321c2..9f74a7083e 100755 --- a/experiments/examples/manager.py +++ b/experiments/examples/manager.py @@ -27,17 +27,17 @@ async def run(): robot = revolve_bot.RevolveBot() robot.load_file("experiments/examples/yaml/spider.yaml") robot.update_substrate() + # robot._brain = BrainRLPowerSplines() # Connect to the simulator and pause world = await World.create(settings) await world.pause(True) - await (await world.delete_model(robot.id)) + await world.delete_model(robot.id) await asyncio.sleep(2.5) # Insert the robot in the simulator - insert_future = await world.insert_robot(robot, Vector3(0, 0, 0.25)) - robot_manager = await insert_future + robot_manager = await world.insert_robot(robot, Vector3(0, 0, 0.25)) # Resume simulation await world.pause(False) diff --git a/experiments/examples/manager_multi.py b/experiments/examples/manager_multi.py new file mode 100755 index 0000000000..e625839401 --- /dev/null +++ b/experiments/examples/manager_multi.py @@ -0,0 +1,240 @@ +#!/usr/bin/env python3 +import os +import sys +import asyncio +import time + +# Add `..` folder in search path +current_dir = os.path.dirname(os.path.abspath(__file__)) +newpath = os.path.join(current_dir, '..', '..') +relative = os.path.join(current_dir,__file__) +sys.path.append(newpath) + +from pygazebo.pygazebo import DisconnectError + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.SDF.math import Vector3 +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.tol.manage import World +from pyrevolve.util.supervisor.supervisor_multi import DynamicSimSupervisor +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.custom_logging.logger import logger + + +class ExperimentConfig: + def __init__(self): + + self.num_generations = 100 + + self.genotype_conf = PlasticodingConfig( + max_structural_modules=20, + ) + self.mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=self.genotype_conf, + ) + + self.crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + + self.population_conf = PopulationConfig( + population_size=100, + genotype_constructor=random_initialization, + genotype_conf=self.genotype_conf, + fitness_function=fitness.online_old_revolve, + mutation_operator=standard_mutation, + mutation_conf=self.mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=self.crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=30, + offspring_size=20, + ) + + +class SimulatorQueue: + def __init__(self, n_cores: int, settings): + assert (n_cores > 0) + self._settings = settings + self._n_cores = n_cores + self._supervisors = [] + self._connections = [] + self._robot_queue = asyncio.Queue() + self._free_simulator = [True for _ in range(n_cores)] + self._workers = [] + + async def start(self): + future_launches = [] + future_connections = [] + for i in range(self._n_cores): + simulator_supervisor = DynamicSimSupervisor( + world_file=newpath + "/" + self._settings.world, + simulator_cmd=self._settings.simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join(newpath, 'build', 'lib'), + models_dir_path=os.path.join(newpath, 'models'), + simulator_name='gazebo_{}'.format(i) + ) + simulator_future_launch = simulator_supervisor.launch_simulator(port=11345+i) + + future_launches.append(simulator_future_launch) + self._supervisors.append(simulator_supervisor) + + for i, future_launch in enumerate(future_launches): + await future_launch + connection_future = World.create(self._settings, world_address=("127.0.0.1", 11345+i)) + future_connections.append(connection_future) + + for i, future_conn in enumerate(future_connections): + self._connections.append(await future_conn) + self._workers.append(asyncio.create_task(self._simulator_queue_worker(i))) + + def test_robot(self, robot, conf: PopulationConfig): + """ + :param robot: robot phenotype + :param conf: configuration of the experiment + :return: + """ + future = asyncio.Future() + self._robot_queue.put_nowait((robot, future, conf)) + return future + + async def _restart_simulator(self, i): + # restart simulator + logger.error("Restarting simulator") + self._connections[i].disconnect() + await (await self._supervisors[i].relaunch(5)) + await asyncio.sleep(5) + self._connections[i] = await World.create(self._settings, world_address=("127.0.0.1", 11345+i)) + + async def _simulator_queue_worker(self, i): + self._free_simulator[i] = True + while True: + logger.info(f"simulator {i} waiting for robot") + (robot, future, conf) = await self._robot_queue.get() + logger.info(f"Picking up robot {robot.id} into simulator {i}") + self._free_simulator[i] = False + + start = time.time() + evaluation_future = asyncio.create_task(self._evaluate_robot(self._connections[i], robot, conf)) + broken = False + while not evaluation_future.done(): + elapsed = time.time()-start + if elapsed > 5: + await self._robot_queue.put((robot, future, conf)) + await self._restart_simulator(i) + broken = True + break + await asyncio.sleep(0.1) + + if not broken: + await evaluation_future + robot_fitness = evaluation_future.result() + + future.set_result(robot_fitness) + + self._robot_queue.task_done() + self._free_simulator[i] = True + logger.info(f"simulator {i} finished robot {robot.id}") + + @staticmethod + async def _evaluate_robot(simulator_connection, robot, conf): + await simulator_connection.pause(True) + robot_manager = await simulator_connection.insert_robot(robot, Vector3(0, 0, 0.25)) + await simulator_connection.pause(False) + start = time.time() + # Start a run loop to do some stuff + max_age = conf.evaluation_time + while robot_manager.age() < max_age: + await asyncio.sleep(1.0 / 5) # 5= state_update_frequency + end = time.time() + elapsed = end-start + logger.info(f'Time taken: {elapsed}') + + robot_fitness = conf.fitness_function(robot_manager) + await simulator_connection.pause(True) + delete_future = await simulator_connection.delete_all_robots() # robot_manager + await delete_future + return robot_fitness + + async def _joint(self): + await self._robot_queue.join() + + +async def run(): + """ + The main coroutine, which is started below. + """ + + n_cores = 1 + + experiment_conf = ExperimentConfig() + settings = parser.parse_args() + queue = SimulatorQueue(n_cores, settings) + await queue.start() + + population = Population(experiment_conf.population_conf) + await population.init_pop(queue) + # population.simulator_connection.disconnect() + + # await simulator_supervisor.relaunch() + + gen_num = 0 + while gen_num < experiment_conf.num_generations: + population = await population.next_gen(gen_num+1, queue) + # simulator_connection.disconnect() + # simulator_supervisor.relaunch() + # population.simulator_connection = await World.create(settings) + gen_num += 1 + + # output result after completing all generations... + # simulator_supervisor.stop() + + +def main(): + import traceback + + def handler(_loop, context): + try: + exc = context['exception'] + except KeyError: + print(context['message']) + return + + if isinstance(exc, DisconnectError) \ + or isinstance(exc, ConnectionResetError): + print("Got disconnect / connection reset - shutting down.") + # sys.exit(0) + + if isinstance(exc, OSError) and exc.errno == 9: + print(exc) + traceback.print_exc() + return + + traceback.print_exc() + raise exc + + try: + loop = asyncio.get_event_loop() + loop.set_exception_handler(handler) + loop.run_until_complete(run()) + except KeyboardInterrupt: + print("Got CtrlC, shutting down.") + + +if __name__ == '__main__': + print("STARTING") + main() + print("FINISHED") diff --git a/experiments/examples/manager_pop.py b/experiments/examples/manager_pop.py new file mode 100755 index 0000000000..ed42adced8 --- /dev/null +++ b/experiments/examples/manager_pop.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 +import asyncio + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.experiment_management import ExperimentManagement +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.util.supervisor.analyzer_queue import AnalyzerQueue +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +from pyrevolve.custom_logging.logger import logger + + +async def run(): + """ + The main coroutine, which is started below. + """ + + # experiment params # + num_generations = 100 + population_size = 100 + offspring_size = 50 + + genotype_conf = PlasticodingConfig( + max_structural_modules=100, + ) + + mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=genotype_conf, + ) + + crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + # experiment params # + + # Parse command line / file input arguments + settings = parser.parse_args() + experiment_management = ExperimentManagement(settings) + do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new() + + logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name) + + if do_recovery: + gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size, offspring_size) + + if gen_num == num_generations-1: + logger.info('Experiment is already complete.') + return + else: + gen_num = 0 + next_robot_id = 1 + + population_conf = PopulationConfig( + population_size=population_size, + genotype_constructor=random_initialization, + genotype_conf=genotype_conf, + fitness_function=fitness.displacement_velocity, + mutation_operator=standard_mutation, + mutation_conf=mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=settings.evaluation_time, + offspring_size=offspring_size, + experiment_name=settings.experiment_name, + experiment_management=experiment_management, + ) + + n_cores = settings.n_cores + + settings = parser.parse_args() + simulator_queue = SimulatorQueue(n_cores, settings, settings.port_start) + await simulator_queue.start() + + analyzer_queue = AnalyzerQueue(1, settings, settings.port_start+n_cores) + await analyzer_queue.start() + + population = Population(population_conf, simulator_queue, analyzer_queue, next_robot_id) + + if do_recovery: + # loading a previous state of the experiment + await population.load_snapshot(gen_num) + if gen_num >= 0: + logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals') + if has_offspring: + individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id) + gen_num += 1 + logger.info('Recovered unfinished offspring '+str(gen_num)) + + if gen_num == 0: + await population.init_pop(individuals) + else: + population = await population.next_gen(gen_num, individuals) + + experiment_management.export_snapshots(population.individuals, gen_num) + else: + # starting a new experiment + experiment_management.create_exp_folders() + await population.init_pop() + experiment_management.export_snapshots(population.individuals, gen_num) + + while gen_num < num_generations-1: + gen_num += 1 + population = await population.next_gen(gen_num) + experiment_management.export_snapshots(population.individuals, gen_num) + + # output result after completing all generations... diff --git a/experiments/examples/only_gazebo.py b/experiments/examples/only_gazebo.py new file mode 100644 index 0000000000..271b874b71 --- /dev/null +++ b/experiments/examples/only_gazebo.py @@ -0,0 +1,32 @@ +#!/usr/bin/env python3 +import asyncio +import os + +from pyrevolve import parser +from pyrevolve.tol.manage import World +from pyrevolve.util.supervisor.supervisor_multi import DynamicSimSupervisor + + +async def run(): + # Parse command line / file input arguments + settings = parser.parse_args() + + # Start Simulator + if settings.simulator_cmd != 'debug': + simulator_supervisor = DynamicSimSupervisor( + world_file=settings.world, + simulator_cmd=settings.simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name='gazebo' + ) + await simulator_supervisor.launch_simulator(port=settings.port_start) + # let there be some time to sync all initial output of the simulator + await asyncio.sleep(5) + + # Connect to the simulator and pause + connection = await World.create(settings, world_address=('127.0.0.1', settings.port_start)) + await asyncio.sleep(1) + await connection.disconnect() + print("SIMULATOR STARTED") diff --git a/experiments/examples/run-experiments b/experiments/examples/run-experiments new file mode 100755 index 0000000000..fcbcc5e2b3 --- /dev/null +++ b/experiments/examples/run-experiments @@ -0,0 +1,9 @@ +#!/bin/bash +while true + do + + for i in {1..10}; do + ./revolve.py --experiment-name default_experiment_$i --run $i --manager experiments/examples/manager_pop.py --n-cores 5; + sleep 5s + done +done \ No newline at end of file diff --git a/experiments/examples/stuck-experiments_watchman.py b/experiments/examples/stuck-experiments_watchman.py new file mode 100644 index 0000000000..6b0a2a4fc7 --- /dev/null +++ b/experiments/examples/stuck-experiments_watchman.py @@ -0,0 +1,46 @@ +from datetime import datetime, timedelta +import os + +# set these variables according to your experiments # +dir_path = '../' +experiments_names = ['default_experiment' + ] +runs = 1 +limit_of_minutes = 10 +# set these variables according to your experiments # + +some_has_been_updated = False + +while 1: + + # 10 minutes (do update this according to limit_of_minutes! + os.system(" sleep 600s") + + youngest = [] + for exp in experiments_names: + for run in range(0, runs): + + path = dir_path + "/" + exp +'_'+str(run+1) + "/data_fullevolution/fitness" + time_now = datetime.now() + time_ago = time_now - timedelta(minutes=limit_of_minutes) + + if os.path.isdir(path): + files = [] + for r, d, f in os.walk(path): + for file in f: + filetime = datetime.fromtimestamp(os.path.getctime(path+'/'+file)) + files.append(filetime) + files.sort() + youngest.append(files[-1]) + + if files[-1] > time_ago: + some_has_been_updated = True + + if not some_has_been_updated: + youngest.sort() + print(str(time_now) + ': youngest file from ' + str(youngest[-1])) + os.system(" kill $( ps aux | grep 'gzserver' | awk '{print $2}')") + os.system(" kill $( ps aux | grep 'revolve.py' | awk '{print $2}')") + print(' killled gzserver and revolve.py to force an error!') + + some_has_been_updated = False \ No newline at end of file diff --git a/experiments/examples/summary_measures.R b/experiments/examples/summary_measures.R new file mode 100644 index 0000000000..184eea80d9 --- /dev/null +++ b/experiments/examples/summary_measures.R @@ -0,0 +1,384 @@ +library(ggplot2) +library(sqldf) +library(plyr) +library(dplyr) +library(trend) + +base_directory <- paste('../', sep='') + +output_directory = base_directory + +experiments_type = c( + 'default_experiment' + ) + + +initials = c('d') + +experiments_labels = c('default_experiment') + + +runs = c(1,2,3,4,5,6,7,8,9,10) +gens = 100 +pop = 100 +sig = 0.05 +line_size = 30 +show_markers = TRUE +show_legends = TRUE +experiments_type_colors = c( '#009900', '#FF8000', '#BA1616', '#000099') # DARK:green, orange, red, blue + +measures_names = c( + 'displacement_velocity_hill', + 'head_balance', + 'contacts', + 'displacement_velocity', + 'branching', + 'branching_modules_count', + 'limbs', + 'extremities', + 'length_of_limbs', + 'extensiveness', + 'coverage', + 'joints', + 'hinge_count', + 'active_hinges_count', + 'brick_count', + 'touch_sensor_count', + 'brick_sensor_count', + 'proportion', + 'width', + 'height', + 'absolute_size', + 'sensors', + 'symmetry', + 'avg_period', + 'dev_period', + 'avg_phase_offset', + 'dev_phase_offset', + 'avg_amplitude', + 'dev_amplitude', + 'avg_intra_dev_params', + 'avg_inter_dev_params', + 'sensors_reach', + 'recurrence', + 'synaptic_reception', + 'fitness' +) + +# add proper labels soon... +measures_labels = c( + 'Speed', + 'Balance', + 'Contacts', + 'displacement_velocity', + 'branching', + 'branching_modules_count', + 'limbs', + 'extremities', + 'length_of_limbs', + 'extensiveness', + 'coverage', + 'joints', + 'hinge_count', + 'active_hinges_count', + 'brick_count', + 'touch_sensor_count', + 'brick_sensor_count', + 'proportion', + 'width', + 'height', + 'absolute_size', + 'sensors', + 'symmetry', + 'avg_period', + 'dev_period', + 'avg_phase_offset', + 'dev_phase_offset', + 'avg_amplitude', + 'dev_amplitude', + 'avg_intra_dev_params', + 'avg_inter_dev_params', + 'sensors_reach', + 'recurrence', + 'synaptic_reception', + 'Fitness' +) + + +measures_snapshots_all = NULL + +for (exp in 1:length(experiments_type)) +{ + for(run in runs) + { + input_directory <- paste(base_directory, '/', experiments_type[exp], '_', run, sep='') + measures = read.table(paste(input_directory,"/all_measures.tsv", sep=''), header = TRUE) + for( m in 1:length(measures_names)) + { + measures[measures_names[m]] = as.numeric(as.character(measures[[measures_names[m]]])) + } + + snapshots = read.table(paste(input_directory,"/snapshots_ids.tsv", sep=''), header = TRUE) + measures_snapshots = sqldf('select * from snapshots inner join measures using(robot_id) order by generation') + + measures_snapshots$run = run + measures_snapshots$run = as.factor(measures_snapshots$run) + measures_snapshots$method = experiments_type[exp] + + if ( is.null(measures_snapshots_all)){ + measures_snapshots_all = measures_snapshots + }else{ + measures_snapshots_all = rbind(measures_snapshots_all, measures_snapshots) + } + } +} + + + +measures_snapshots_all = sqldf("select * from measures_snapshots_all where fitness IS NOT NULL") + +fail_test = sqldf(paste("select method,run,generation,count(*) as c from measures_snapshots_all group by 1,2,3 having c<",gens," order by 4")) + + +measures_averages_gens_1 = list() +measures_averages_gens_2 = list() + +measures_ini = list() +measures_fin = list() + +for (exp in 1:length(experiments_type)) +{ + + query ='select run, generation' + for (i in 1:length(measures_names)) + { + query = paste(query,', avg(',measures_names[i],') as ',experiments_type[exp],'_',measures_names[i],'_avg', sep='') + } + query = paste(query,' from measures_snapshots_all + where method="',experiments_type[exp],'" group by run, generation', sep='') + + + measures_averages_gens_1[[exp]] = sqldf(query) + + temp = measures_averages_gens_1[[exp]] + + measures_ini[[exp]] = sqldf(paste("select * from temp where generation=1")) + measures_fin[[exp]] = sqldf(paste("select * from temp where generation=",gens-1)) + query = 'select generation' + for (i in 1:length(measures_names)) + { + query = paste(query,', avg(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_avg', sep='') + query = paste(query,', max(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_max', sep='') + query = paste(query,', stdev(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_stdev', sep='') + query = paste(query,', median(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_median', sep='') + } + query = paste(query,' from temp group by generation', sep="") + + measures_averages_gens_2[[exp]] = sqldf(query) + + measures_averages_gens_2[[exp]]$generation = as.numeric(measures_averages_gens_2[[exp]]$generation) + +} + + +for (exp in 1:length(experiments_type)) +{ + if(exp==1){ + measures_averages_gens = measures_averages_gens_2[[1]] + }else{ + measures_averages_gens = merge(measures_averages_gens, measures_averages_gens_2[[exp]], by = "generation") + } +} + + + +file <-file(paste(output_directory,'/trends.txt',sep=''), open="w") + +#tests trends in curves and difference between ini and fin generations + + +# ini VS fin +array_wilcoxon = list() +array_wilcoxon2 = list() + +# curve +array_mann = list() + + +for (m in 1:length(experiments_type)) +{ + + array_wilcoxon[[m]] = list() + array_mann[[m]] = list() + + for (i in 1:length(measures_names)) + { + + writeLines(paste(experiments_type[m],measures_names[i],'ini avg ',as.character( + mean(c(array(measures_ini[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + + writeLines(paste(experiments_type[m],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + array_wilcoxon[[m]][[i]] = wilcox.test(c(array(measures_ini[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] , + c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] + ) + + writeLines(c( + paste(experiments_type[m],'iniVSfin',measures_names[i],'wilcox p: ',as.character(round(array_wilcoxon[[m]][[i]]$p.value,4)), sep=' ') + ,paste(experiments_type[m],'iniVSfin',measures_names[i],'wilcox est: ',as.character(round(array_wilcoxon[[m]][[i]]$statistic,4)), sep=' ') + + ), file) + + + #tests trends + array_mann[[m]][[i]] = mk.test(c(array(measures_averages_gens_2[[m]][paste(experiments_type[m],"_",measures_names[i],'_median',sep='')]) )[[1]], + continuity = TRUE) + + + writeLines(c( + paste(experiments_type[m],measures_names[i], ' Mann-Kendall median p', as.character(round(array_mann[[m]][[i]]$p.value,4)),sep=' '), + paste(experiments_type[m],measures_names[i], ' Mann-Kendall median s', as.character(round(array_mann[[m]][[i]]$statistic,4)),sep=' ') + ), file) + + } + +} + + + +# tests final generation among experiments_type + +aux_m = length(experiments_type) + +if (aux_m>1) +{ + + # fins + array_wilcoxon2[[1]] = list() + array_wilcoxon2[[2]] = list() + +aux_m = aux_m -1 +count_pairs = 0 +for(m in 1:aux_m) +{ + aux = m+1 + for(m2 in aux:length(experiments_type)) + { + + count_pairs = count_pairs+1 + array_wilcoxon2[[1]][[count_pairs]] = list() + + for (i in 1:length(measures_names)) + { + + writeLines(paste(experiments_type[m],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + writeLines(paste(experiments_type[m2],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m2]][paste(experiments_type[m2],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + array_wilcoxon2[[1]][[count_pairs]][[i]] = wilcox.test(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] , + c(array(measures_fin[[m2]][paste(experiments_type[m2],"_",measures_names[i],"_avg",sep='')]))[[1]] + ) + + writeLines(c( + paste(experiments_type[m],'VS',experiments_type[m2],measures_names[i],'fin avg wilcox p: ',as.character(round(array_wilcoxon2[[1]][[count_pairs]][[i]]$p.value,4)), sep=' ') + ,paste(experiments_type[m],'VS',experiments_type[m2],measures_names[i],'fin avg wilcox est: ',as.character(round(array_wilcoxon2[[1]][[count_pairs]][[i]]$statistic,4)), sep=' ') + + ), file) + + } + + + array_wilcoxon2[[2]][[count_pairs]] = paste(initials[m],initials[m2],sep='') + + } +} + +} + +close(file) + +# plots measures + +for (i in 1:length(measures_names)) +{ + tests1 = '' + tests2 = '' + tests3 = '' + break_aux = 0 + + graph <- ggplot(data=measures_averages_gens, aes(x=generation)) + for(m in 1:length(experiments_type)) + { + graph = graph + geom_errorbar(aes_string(ymin=paste(experiments_type[m],'_',measures_names[i],'_avg','-',experiments_type[m],'_',measures_names[i],'_stdev',sep=''), + ymax=paste(experiments_type[m],'_',measures_names[i],'_avg','+',experiments_type[m],'_',measures_names[i],'_stdev',sep='') ), + color=experiments_type_colors[m], + alpha=0.35,size=0.5,width=0.001) + } + + for(m in 1:length(experiments_type)) + { + if(show_legends == TRUE){ + graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_avg',sep=''), colour=shQuote(experiments_labels[m]) ), size=2) + }else{ + graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_avg',sep='') ),size=2, color = experiments_type_colors[m]) + } + # graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_median',sep='') ),size=2, color = colors_median[m]) + + if(!is.na(array_mann[[m]][[i]]$p.value)) + { + if(array_mann[[m]][[i]]$p.value<=sig) + { + if(array_mann[[m]][[i]]$statistic>0){ direction = "/ "} else { direction = "\\ "} + tests1 = paste(tests1, initials[m],direction,sep="") + } + } + } + for(m in 1:length(experiments_type)) + { + if(!is.na(array_wilcoxon[[m]][[i]]$p.value)) + { + if(array_wilcoxon[[m]][[i]]$p.value<=sig) + { + tests2 = paste(tests2, initials[m],'C ', sep='') + } + } + } + + if (length(array_wilcoxon2)>0) + { + + for(p in 1:length(array_wilcoxon2[[1]])) + { + if(!is.na(array_wilcoxon2[[1]][[p]][[i]]$p.value)) + { + if(array_wilcoxon2[[1]][[p]][[i]]$p.value<=sig) + { + if(nchar(tests3)>line_size && break_aux == 0){ + tests3 = paste(tests3, '\n') + break_aux = 1 + } + tests3 = paste(tests3, array_wilcoxon2[[2]][[p]],'D ',sep='') + } + } + + } + + } + + graph = graph + + #coord_cartesian(ylim = c(0, 1))+ + labs( y=measures_labels[i], x="Generation") + if(show_markers == TRUE){ + graph = graph + labs( y=measures_labels[i], x="Generation", subtitle = paste(tests1,'\n', tests2, '\n', tests3, sep='')) + } + graph = graph + theme(legend.position="bottom" , legend.text=element_text(size=20), axis.text=element_text(size=30),axis.title=element_text(size=39), + plot.subtitle=element_text(size=25 )) + + ggsave(paste( output_directory,'/' ,measures_names[i],'_generations.pdf', sep=''), graph , device='pdf', height = 8, width = 8) +} + + diff --git a/experiments/examples/tutorial3.py b/experiments/examples/tutorial3.py index a4da82853a..1bf62848c4 100755 --- a/experiments/examples/tutorial3.py +++ b/experiments/examples/tutorial3.py @@ -32,8 +32,7 @@ async def run(): await world.pause(True) # Insert the robot in the simulator - insert_future = await world.insert_robot(robot, Vector3(0, 0, 0.05)) - robot_manager = await insert_future + robot_manager = await world.insert_robot(robot, Vector3(0, 0, 0.05)) # Resume simulation await world.pause(False) diff --git a/experiments/examples/watch_best_robots.py b/experiments/examples/watch_best_robots.py new file mode 100755 index 0000000000..935751dfaa --- /dev/null +++ b/experiments/examples/watch_best_robots.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 +import asyncio +from pygazebo.pygazebo import DisconnectError + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.experiment_management import ExperimentManagement +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +import numpy as np + + +async def run(): + """ + The main coroutine, which is started below. + """ + # Parse command line / file input arguments + + + genotype_conf = PlasticodingConfig( + max_structural_modules=100, + ) + + mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=genotype_conf, + ) + + crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + + settings = parser.parse_args() + experiment_management = ExperimentManagement(settings) + + population_conf = PopulationConfig( + population_size=100, + genotype_constructor=random_initialization, + genotype_conf=genotype_conf, + fitness_function=fitness.displacement_velocity_hill, + mutation_operator=standard_mutation, + mutation_conf=mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=settings.evaluation_time, + offspring_size=50, + experiment_name=settings.experiment_name, + experiment_management=experiment_management, + ) + + settings = parser.parse_args() + simulator_queue = SimulatorQueue(settings.n_cores, settings, settings.port_start) + await simulator_queue.start() + + population = Population(population_conf, simulator_queue, 0) + + # choose a snapshot here. and the maximum best individuals you wish to watch + generation = 100 + max_best = 10 + await population.load_snapshot(generation) + + fitnesses = [] + for ind in population.individuals: + fitnesses.append(ind.fitness) + fitnesses = np.array(fitnesses) + + ini = len(population.individuals)-max_best + fin = len(population.individuals) + population.individuals = np.array(population.individuals) + population.individuals = population.individuals[np.argsort(fitnesses)[ini:fin]] + + await population.evaluate(population.individuals, generation) diff --git a/experiments/examples/yaml/babyA.yaml b/experiments/examples/yaml/babyA.yaml new file mode 100644 index 0000000000..f239e42ac0 --- /dev/null +++ b/experiments/examples/yaml/babyA.yaml @@ -0,0 +1,89 @@ +--- +body: + id : Core + type : Core + children : + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + orientation : 0 + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg021Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg02 + type : FixedBrick + orientation : 0 diff --git a/experiments/examples/yaml/babyB.yaml b/experiments/examples/yaml/babyB.yaml new file mode 100644 index 0000000000..4508b9944a --- /dev/null +++ b/experiments/examples/yaml/babyB.yaml @@ -0,0 +1,101 @@ +--- +body: + id : Core + type : Core + children : + 0: + id : Leg00Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + orientation : -90 + 1: + id : Leg10Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + orientation : -90 + 2: + id : Leg20Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + orientation : -90 + 3: + id : Leg30Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + orientation : -90 \ No newline at end of file diff --git a/experiments/examples/yaml/babyC.yaml b/experiments/examples/yaml/babyC.yaml new file mode 100644 index 0000000000..6424c6e8b9 --- /dev/null +++ b/experiments/examples/yaml/babyC.yaml @@ -0,0 +1,171 @@ +--- +body: + id : Core + type : Core + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg002Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg002 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg012Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg012 + type : FixedBrick + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + orientation : 0 + children : + 1: + slot : 0 + id : BodyJoint2 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + orientation : -90 + children : + 1: + id : BodyJoint3 + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Body3 + type : FixedBrick + orientation : 0 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg102Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg102 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg112Joint + type : ActiveHinge + orientation : -90 + children : + 1: + id : Leg112 + type : FixedBrick + orientation : 0 diff --git a/experiments/examples/yaml/gecko12.yaml b/experiments/examples/yaml/gecko12.yaml new file mode 100644 index 0000000000..9c138ad0f4 --- /dev/null +++ b/experiments/examples/yaml/gecko12.yaml @@ -0,0 +1,124 @@ +--- +body: + id : Core + type : Core + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + orientation : -90 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + orientation : -90 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + orientation : 0 + children : + 1: + id : BodyJoint2 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + orientation : -90 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg111 + type : FixedBrick + orientation : -90 \ No newline at end of file diff --git a/experiments/examples/yaml/gecko17.yaml b/experiments/examples/yaml/gecko17.yaml new file mode 100644 index 0000000000..5e11c4f3ae --- /dev/null +++ b/experiments/examples/yaml/gecko17.yaml @@ -0,0 +1,176 @@ +--- +body: + id : Core + type : Core + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg001Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg001 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg002Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg002 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg011Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg011 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg012Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg012 + type : FixedBrick + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + orientation : 0 + children : + 1: + slot : 0 + id : BodyJoint2 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body2 + type : FixedBrick + orientation : -90 + children : + 1: + id : BodyJoint3 + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Body3 + type : FixedBrick + orientation : 0 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg101Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg101 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg102Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg102 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg111Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg111 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg112Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg112 + type : FixedBrick + orientation : 0 \ No newline at end of file diff --git a/experiments/examples/yaml/gecko7.yaml b/experiments/examples/yaml/gecko7.yaml new file mode 100644 index 0000000000..806b73605c --- /dev/null +++ b/experiments/examples/yaml/gecko7.yaml @@ -0,0 +1,73 @@ +--- +body: + id : Core + type : Core + children : + 2: + slot : 0 + id : Leg00Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg00 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg01 + type : FixedBrick + orientation : 0 + 1: + slot : 0 + id : BodyJoint0 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body0 + type : FixedBrick + orientation : -90 + children : + 1: + slot : 0 + id : BodyJoint1 + type : ActiveHinge + orientation : 90 + children : + 1: + slot : 0 + id : Body1 + type : FixedBrick + orientation : -90 + children: + 2: + slot : 0 + id : Leg10Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg10 + type : FixedBrick + orientation : 0 + 3: + slot : 0 + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + slot : 0 + id : Leg11 + type : FixedBrick + orientation : 0 \ No newline at end of file diff --git a/experiments/examples/yaml/robot_5.yaml b/experiments/examples/yaml/robot_5.yaml new file mode 100644 index 0000000000..0234e991fc --- /dev/null +++ b/experiments/examples/yaml/robot_5.yaml @@ -0,0 +1,151 @@ +id: 1 +body: + params: + blue: 0 + green: 1 + red: 1 + type : CoreComponent + id : module0 + children : + 3: + slot : 0 + orientation : 90 + params: + blue: 0 + green: 0 + red: 0.7 + type : ActiveHinge + id : module1 + children : + 1: + slot : 0 + orientation : 270 + params: + blue: 0.58 + green: 0.08 + red: 1 + type : ActiveHinge + id : module2 + children : + 1: + slot : 0 + orientation : 0 + params: + blue: 1 + green: 0 + red: 0 + type : FixedBrick + id : module3 + children : + 2: + slot : 0 + orientation : 0 + params: + blue: 0.7 + green: 0.7 + red: 0.7 + type : FixedBrickSensor + id : module3sensor-r + 3: + slot : 0 + orientation : 0 + params: + blue: 1 + green: 0 + red: 0 + type : FixedBrick + id : module4 + children : + 1: + slot : 0 + orientation : 0 + params: + blue: 0.7 + green: 0.7 + red: 0.7 + type : FixedBrickSensor + id : module4sensor-f +brain: + neurons: + node1: + id: node1 + layer: output + part_id: module1 + type: Oscillator + node2: + id: node2 + layer: output + part_id: module2 + type: Oscillator + node3: + id: node3 + layer: input + part_id: module3sensor-r + type: Input + node4: + id: node4 + layer: input + part_id: module4sensor-f + type: Input + node3-2: + id: node3-2 + layer: input + part_id: module3sensor-r + type: Input + node4-2: + id: node4-2 + layer: input + part_id: module4sensor-f + type: Input + node-core1: + id: node-core1 + layer: input + part_id: module0 + type: Input + node-core2: + id: node-core2 + layer: input + part_id: module0 + type: Input + node-core3: + id: node-core3 + layer: input + part_id: module0 + type: Input + node-core4: + id: node-core4 + layer: input + part_id: module0 + type: Input + node-core5: + id: node-core5 + layer: input + part_id: module0 + type: Input + node-core6: + id: node-core6 + layer: input + part_id: module0 + type: Input + connections: + - dst: node1 + src: node3 + weight: 0.741018 + - dst: node2 + src: node3 + weight: 0.501063 + - dst: node1 + src: node4 + weight: 0.186485 + - dst: node2 + src: node4 + weight: 0.585072 + params: + node1: + period: 7.95243 + phase_offset: 2.75448 + amplitude: 9.7974 + node2: + period: 1 + phase_offset: 7.39968 + amplitude: 8.01294 diff --git a/experiments/examples/yaml/spider.sdf.xml b/experiments/examples/yaml/spider.sdf.xml new file mode 100644 index 0000000000..7414578c06 --- /dev/null +++ b/experiments/examples/yaml/spider.sdf.xml @@ -0,0 +1,1609 @@ + + + + 0.000000e+00 0.000000e+00 2.500000e-01 0.000000e+00 -0.000000e+00 0.000000e+00 + + -9.430986e-18 3.110825e-02 -1.755849e-17 1.570796e+00 -3.330669e-16 -1.570796e+00 + Core + S_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + -1.300223e-17 2.747656e-02 -1.539957e-17 -9.420555e-16 -6.280370e-16 -1.570796e+00 + S_Leg + SNN_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + -8.717806e-18 -3.110825e-02 1.048457e-17 1.570796e+00 3.330669e-16 1.570796e+00 + Core + N_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + 1.194569e-17 -2.747656e-02 1.294222e-17 -4.710277e-16 4.710277e-16 1.570796e+00 + N_Leg + NNN_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + -3.110825e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 -0.000000e+00 + Core + E_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + -2.747656e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + E_Leg + ENN_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + 3.110825e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 3.141593e+00 + Core + W_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + 2.747656e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + W_Leg + WNN_Leg + + 0.000000e+00 1.000000e+00 0.000000e+00 + 0 + + -7.853982e-01 + 7.853982e-01 + 1.765800e-01 + 5.235988e+00 + + + + + 1.400054e-19 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -1.400054e-19 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + + -1.400054e-19 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/CoreComponent.dae + + + + + -1.400054e-19 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 8.900000e-02 8.900000e-02 4.500000e-02 + + + + + 2.302485e-18 -5.550000e-02 6.106227e-19 1.570796e+00 -5.551115e-17 -1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 2.302485e-18 -5.550000e-02 6.106227e-19 1.570796e+00 -5.551115e-17 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 2.302485e-18 5.550000e-02 -6.106227e-19 1.570796e+00 5.551115e-17 1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 2.302485e-18 5.550000e-02 -6.106227e-19 1.570796e+00 5.551115e-17 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 5.550000e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 -0.000000e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 5.550000e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 -0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + -5.550000e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 3.141593e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + -5.550000e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 9.680000e-02 + + 8.595755208333334e-05 + 0.0 + 0.0 + 8.595755208333334e-05 + 1.4866158073075413e-22 + 0.00014009163333333333 + + + + + 1.332232e-17 -9.125825e-02 1.946807e-17 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -6.599917e-18 2.260825e-02 -1.472742e-17 1.570796e+00 -3.330669e-16 -1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + -5.808883e-18 2.023325e-02 -1.393639e-17 1.570796e+00 -3.330669e-16 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + -1.451258e-18 8.483254e-03 1.000000e-03 1.570796e+00 -3.330669e-16 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + 3.017390e-18 -1.101675e-02 7.019074e-18 8.881784e-16 -6.661338e-16 -3.141593e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + 3.017390e-18 -1.101675e-02 7.019074e-18 8.881784e-16 -6.661338e-16 -3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 1.264857e-17 -4.101675e-02 3.166642e-17 -7.065416e-16 -7.065416e-16 -1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 1.264857e-17 -4.101675e-02 3.166642e-17 -7.065416e-16 -7.065416e-16 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 2.090000e-02 + + 1.1312736847089305e-05 + 2.1648188582986934e-21 + -1.3720940220056711e-25 + 3.36133489583333e-06 + 6.012418896988902e-21 + 1.1508719659589309e-05 + + + + + 4.103813e-17 -1.644016e-01 6.952509e-17 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -9.227468e-18 1.897656e-02 -1.006126e-17 -9.420555e-16 -6.280370e-16 -1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + -8.172756e-18 1.660156e-02 -8.569672e-18 -9.420555e-16 -6.280370e-16 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + 1.000000e-03 4.851562e-03 -2.132293e-18 -9.420555e-16 -6.280370e-16 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + 7.211255e-18 -1.464844e-02 7.561476e-18 4.440892e-16 -9.420555e-16 -3.141593e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + 7.211255e-18 -1.464844e-02 7.561476e-18 4.440892e-16 -9.420555e-16 -3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 1.920000e-02 + + 7.788189453124997e-06 + 2.2776669243582927e-21 + 6.46423747472484e-22 + 3.1661093749999973e-06 + 2.745796473977747e-21 + 8.474373828125e-06 + + + + + 1.260914e-17 9.125825e-02 -1.239415e-17 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -5.886737e-18 -2.260825e-02 7.653500e-18 1.570796e+00 3.330669e-16 1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + -5.095703e-18 -2.023325e-02 6.862466e-18 1.570796e+00 3.330669e-16 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + -1.626256e-18 -8.483254e-03 1.000000e-03 1.570796e+00 3.330669e-16 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + 3.245202e-18 1.101675e-02 -3.545875e-18 -3.330669e-16 -6.661338e-16 -2.242545e-16 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + 3.245202e-18 1.101675e-02 -3.545875e-18 -3.330669e-16 -6.661338e-16 -2.242545e-16 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 7.506038e-18 4.101675e-02 -1.505545e-17 -4.710277e-16 4.710277e-16 1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 7.506038e-18 4.101675e-02 -1.505545e-17 -4.710277e-16 4.710277e-16 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 2.090000e-02 + + 1.1312736847089317e-05 + -1.751924061738799e-21 + 3.944263415324837e-23 + 3.361334895833333e-06 + 2.9643788204362183e-21 + 1.1508719659589315e-05 + + + + + 6.504156e-18 1.644016e-01 -4.258211e-17 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + 8.170927e-18 -1.897656e-02 8.938487e-18 -4.710277e-16 4.710277e-16 1.570796e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + 7.116215e-18 -1.660156e-02 7.819796e-18 -4.710277e-16 4.710277e-16 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + -1.000000e-03 -4.851562e-03 1.814193e-18 -4.710277e-16 4.710277e-16 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + -6.279013e-18 1.464844e-02 -6.899820e-18 -4.710277e-16 -4.440892e-16 4.186913e-16 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + -6.279013e-18 1.464844e-02 -6.899820e-18 -4.710277e-16 -4.440892e-16 4.186913e-16 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 1.920000e-02 + + 7.788189453125e-06 + 1.9805146602050528e-21 + -3.135776460162391e-22 + 3.166109375e-06 + 2.500339795965217e-21 + 8.474373828125e-06 + + + + + 9.125825e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -2.260825e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 -0.000000e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + -2.023325e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 -0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + -8.483254e-03 0.000000e+00 1.000000e-03 1.570796e+00 -0.000000e+00 -0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + 1.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -1.570796e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + 1.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 4.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + 4.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 2.090000e-02 + + 3.361334895833333e-06 + 0.0 + 0.0 + 1.1312736847089317e-05 + 0.0 + 1.1508719659589315e-05 + + + + + 1.644016e-01 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + -1.897656e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + -1.660156e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + -4.851562e-03 1.000000e-03 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + 1.464844e-02 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -1.570796e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + 1.464844e-02 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 1.920000e-02 + + 3.166109375e-06 + 0.0 + 0.0 + 7.788189453125e-06 + 0.0 + 8.474373828125e-06 + + + + + -9.125825e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + 2.260825e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 3.141593e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + 2.023325e-02 0.000000e+00 0.000000e+00 1.570796e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + 8.483254e-03 0.000000e+00 1.000000e-03 1.570796e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + -1.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 1.570796e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + -1.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + -4.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveHinge_Frame.dae + + + + + -4.101675e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.200000e-02 3.575000e-02 1.000000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 2.090000e-02 + + 3.3613348958333334e-06 + 0.0 + 0.0 + 1.1312736847089317e-05 + 0.0 + 1.1508719659589315e-05 + + + + + -1.644016e-01 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + True + + 1.897656e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + + 0.98 0.98 0.98 1.0 + 0.98 0.98 0.98 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/ActiveCardanHinge_Servo_Holder.dae + + + + + 1.660156e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 2.450000e-02 2.575000e-02 1.500000e-02 + + + + + 4.851562e-03 -1.000000e-03 0.000000e+00 0.000000e+00 -0.000000e+00 3.141593e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 1.000000e-03 3.400000e-02 3.400000e-02 + + + + + -1.464844e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 1.570796e+00 + + 0.04 0.26 0.72 1.0 + 0.04 0.26 0.72 1.0 + 0.1 0.1 0.1 1.0 + + + + model://rg_robot/meshes/FixedBrick.dae + + + + + -1.464844e-02 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 1.570796e+00 + + + + 3.333333e+06 + 9.000000e+04 + + + + + 1.000000e+00 + 1.000000e+00 + 1.000000e-02 + 1.000000e-02 + + + 1.000000e+00 + 1.000000e+00 + + + + + + 4.100000e-02 4.100000e-02 3.550000e-02 + + + + + 0.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 -0.000000e+00 0.000000e+00 + 1.920000e-02 + + 3.1661093750000003e-06 + 0.0 + 0.0 + 7.788189453125001e-06 + 0.0 + 8.474373828125e-06 + + + + + + 8.000000e+00 + + + + + + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + 9.000000e-01 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + 0.000000e+00 + + + + + + + + diff --git a/experiments/examples/yaml/spider13.yaml b/experiments/examples/yaml/spider13.yaml new file mode 100644 index 0000000000..bf48b74c6f --- /dev/null +++ b/experiments/examples/yaml/spider13.yaml @@ -0,0 +1,123 @@ +--- +body: + id : Core + type : Core + children : + 0: + id : Leg00Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + orientation : -90 + 1: + id : Leg10Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg11 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg12Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg12 + type : FixedBrick + orientation : -90 + 2: + id : Leg20Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + orientation : -90 + 3: + id : Leg30Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + orientation : -90 +brain: + type: bo-cpg \ No newline at end of file diff --git a/experiments/examples/yaml/spider17.yaml b/experiments/examples/yaml/spider17.yaml new file mode 100644 index 0000000000..8def37bcfe --- /dev/null +++ b/experiments/examples/yaml/spider17.yaml @@ -0,0 +1,161 @@ +--- +body: + id : Core + type : Core + children : + 0: + id : Leg00Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg01 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg02Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg02 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg03Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg03 + type : FixedBrick + orientation : 0 + 1: + id : Leg10Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg11 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg12Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg12 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg13Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg13 + type : FixedBrick + orientation : 0 + 2: + id : Leg20Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg21 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg22Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg22 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg23Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg23 + type : FixedBrick + orientation : 0 + 3: + id : Leg30Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg31 + type : FixedBrick + orientation : 0 + children : + 1: + id : Leg32Joint + type : ActiveHinge + orientation : 90 + children : + 1: + id : Leg32 + type : FixedBrick + orientation : -90 + children : + 1: + id : Leg33Joint + type : ActiveHinge + orientation : 0 + children : + 1: + id : Leg33 + type : FixedBrick + orientation : 0 \ No newline at end of file diff --git a/experiments/examples/yaml/spider9.yaml b/experiments/examples/yaml/spider9.yaml new file mode 100644 index 0000000000..d52c547299 --- /dev/null +++ b/experiments/examples/yaml/spider9.yaml @@ -0,0 +1,148 @@ +--- +id: example_spider +body: + id : Core + type : Core + params: + red: 0.04 + green: 0.26 + blue: 0.72 + children : + 0: + id : Leg00Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg00 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg01Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg01 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 1: + id : Leg10Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg10 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg11Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg11 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 2: + id : Leg20Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg20 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg21Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg21 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 + 3: + id : Leg30Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + orientation : 90 + children : + 1: + id : Leg30 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : -90 + children : + 1: + id : Leg31Joint + type : ActiveHinge + params: + red: 0.98 + green: 0.98 + blue: 0.98 + children : + 1: + id : Leg31 + type : FixedBrick + params: + red: 0.04 + green: 0.26 + blue: 0.72 + orientation : 0 +brain: + type: bo-cpg diff --git a/experiments/karines_experiments/consolidate_experiments.py b/experiments/karines_experiments/consolidate_experiments.py new file mode 100644 index 0000000000..e7d713d137 --- /dev/null +++ b/experiments/karines_experiments/consolidate_experiments.py @@ -0,0 +1,92 @@ +import os + + +# set these variables according to your experiments # +dirpath = 'data' +experiments_type = [ + 'plane', + 'lava' + ] +runs = 10 +# set these variables according to your experiments # + + +def build_headers(path): + + print(path + "/all_measures.txt") + file_summary = open(path + "/all_measures.tsv", "w+") + file_summary.write('robot_id\t') + + behavior_headers = [] + with open(path + '/data_fullevolution/descriptors/behavior_desc_robot_1.txt') as file: + for line in file: + measure, value = line.strip().split(' ') + behavior_headers.append(measure) + file_summary.write(measure+'\t') + + phenotype_headers = [] + with open(path + '/data_fullevolution/descriptors/phenotype_desc_robot_1.txt') as file: + for line in file: + measure, value = line.strip().split(' ') + phenotype_headers.append(measure) + file_summary.write(measure+'\t') + file_summary.write('fitness\n') + file_summary.close() + + file_summary = open(path + "/snapshots_ids.tsv", "w+") + file_summary.write('generation\trobot_id\n') + file_summary.close() + + return behavior_headers, phenotype_headers + + +for exp in experiments_type: + for run in range(1, runs+1): + + print(exp, run) + path = os.path.join(dirpath, str(exp), str(run)) + behavior_headers, phenotype_headers = build_headers(path) + + file_summary = open(path + "/all_measures.tsv", "a") + for r, d, f in os.walk(path+'/data_fullevolution/fitness'): + for file in f: + + robot_id = file.split('.')[0].split('_')[-1] + file_summary.write(robot_id+'\t') + + bh_file = path+'/data_fullevolution/descriptors/behavior_desc_robot_'+robot_id+'.txt' + if os.path.isfile(bh_file): + with open(bh_file) as file: + for line in file: + measure, value = line.strip().split(' ') + file_summary.write(value+'\t') + else: + for h in behavior_headers: + file_summary.write('None'+'\t') + + pt_file = path+'/data_fullevolution/descriptors/phenotype_desc_robot_'+robot_id+'.txt' + if os.path.isfile(pt_file): + with open(pt_file) as file: + for line in file: + measure, value = line.strip().split(' ') + file_summary.write(value+'\t') + else: + for h in phenotype_headers: + file_summary.write('None'+'\t') + + file = open(path+'/data_fullevolution/fitness/fitness_robot_'+robot_id+'.txt', 'r') + fitness = file.read() + file_summary.write(fitness + '\n') + file_summary.close() + + file_summary = open(path + "/snapshots_ids.tsv", "a") + for r, d, f in os.walk(path): + for dir in d: + if 'selectedpop' in dir: + gen = dir.split('_')[1] + for r2, d2, f2 in os.walk(path + '/selectedpop_' + str(gen)): + for file in f2: + if 'body' in file: + id = file.split('.')[0].split('_')[-1] + file_summary.write(gen+'\t'+id+'\n') + file_summary.close() \ No newline at end of file diff --git a/experiments/karines_experiments/manager_pop.py b/experiments/karines_experiments/manager_pop.py new file mode 100755 index 0000000000..2c82914acd --- /dev/null +++ b/experiments/karines_experiments/manager_pop.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 +import asyncio + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.experiment_management import ExperimentManagement +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.tol.manage import measures +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +from pyrevolve.custom_logging.logger import logger + + +async def run(): + """ + The main coroutine, which is started below. + """ + + # experiment params # + num_generations = 100 + population_size = 100 + offspring_size = 50 + + genotype_conf = PlasticodingConfig( + max_structural_modules=100, + ) + + mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=genotype_conf, + ) + + crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + # experiment params # + + # Parse command line / file input arguments + settings = parser.parse_args() + experiment_management = ExperimentManagement(settings) + do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new() + + logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name) + + if do_recovery: + gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size, offspring_size) + + if gen_num == num_generations-1: + logger.info('Experiment is already complete.') + return + else: + gen_num = 0 + next_robot_id = 1 + + def fitness_function(robot_manager, robot): + contacts = measures.contacts(robot_manager, robot) + assert(contacts != 0) + return fitness.displacement_velocity_hill(robot_manager, robot) + + population_conf = PopulationConfig( + population_size=population_size, + genotype_constructor=random_initialization, + genotype_conf=genotype_conf, + fitness_function=fitness_function, + mutation_operator=standard_mutation, + mutation_conf=mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=settings.evaluation_time, + offspring_size=offspring_size, + experiment_name=settings.experiment_name, + experiment_management=experiment_management, + ) + + settings = parser.parse_args() + simulator_queue = SimulatorQueue(settings.n_cores, settings, settings.port_start) + await simulator_queue.start() + + population = Population(population_conf, simulator_queue, next_robot_id) + + if do_recovery: + # loading a previous state of the experiment + await population.load_snapshot(gen_num) + if gen_num >= 0: + logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals') + if has_offspring: + individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id) + gen_num += 1 + logger.info('Recovered unfinished offspring '+str(gen_num)) + + if gen_num == 0: + await population.init_pop(individuals) + else: + population = await population.next_gen(gen_num, individuals) + + experiment_management.export_snapshots(population.individuals, gen_num) + else: + # starting a new experiment + experiment_management.create_exp_folders() + await population.init_pop() + experiment_management.export_snapshots(population.individuals, gen_num) + + while gen_num < num_generations-1: + gen_num += 1 + population = await population.next_gen(gen_num) + experiment_management.export_snapshots(population.individuals, gen_num) + + # output result after completing all generations... diff --git a/experiments/karines_experiments/manager_pop_lava.py b/experiments/karines_experiments/manager_pop_lava.py new file mode 100755 index 0000000000..0d5ab20a5b --- /dev/null +++ b/experiments/karines_experiments/manager_pop_lava.py @@ -0,0 +1,119 @@ +#!/usr/bin/env python3 +import asyncio + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.experiment_management import ExperimentManagement +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.tol.manage import measures +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +from pyrevolve.custom_logging.logger import logger + + +async def run(): + """ + The main coroutine, which is started below. + """ + + # experiment params # + num_generations = 100 + population_size = 100 + offspring_size = 50 + + genotype_conf = PlasticodingConfig( + max_structural_modules=100, + ) + + mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=genotype_conf, + ) + + crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + # experiment params # + + # Parse command line / file input arguments + settings = parser.parse_args() + experiment_management = ExperimentManagement(settings) + do_recovery = settings.recovery_enabled and not experiment_management.experiment_is_new() + + logger.info('Activated run '+settings.run+' of experiment '+settings.experiment_name) + + if do_recovery: + gen_num, has_offspring, next_robot_id = experiment_management.read_recovery_state(population_size, offspring_size) + + if gen_num == num_generations-1: + logger.info('Experiment is already complete.') + return + else: + gen_num = 0 + next_robot_id = 1 + + def fitness_function(robot_manager, robot): + contacts = measures.contacts(robot_manager, robot) + assert(contacts != 0) + return fitness.floor_is_lava(robot_manager, robot) + + population_conf = PopulationConfig( + population_size=population_size, + genotype_constructor=random_initialization, + genotype_conf=genotype_conf, + fitness_function=fitness_function, + mutation_operator=standard_mutation, + mutation_conf=mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=settings.evaluation_time, + offspring_size=offspring_size, + experiment_name=settings.experiment_name, + experiment_management=experiment_management, + ) + + settings = parser.parse_args() + simulator_queue = SimulatorQueue(settings.n_cores, settings, settings.port_start) + await simulator_queue.start() + + population = Population(population_conf, simulator_queue, next_robot_id) + + if do_recovery: + # loading a previous state of the experiment + await population.load_snapshot(gen_num) + if gen_num >= 0: + logger.info('Recovered snapshot '+str(gen_num)+', pop with ' + str(len(population.individuals))+' individuals') + if has_offspring: + individuals = await population.load_offspring(gen_num, population_size, offspring_size, next_robot_id) + gen_num += 1 + logger.info('Recovered unfinished offspring '+str(gen_num)) + + if gen_num == 0: + await population.init_pop(individuals) + else: + population = await population.next_gen(gen_num, individuals) + + experiment_management.export_snapshots(population.individuals, gen_num) + else: + # starting a new experiment + experiment_management.create_exp_folders() + await population.init_pop() + experiment_management.export_snapshots(population.individuals, gen_num) + + while gen_num < num_generations-1: + gen_num += 1 + population = await population.next_gen(gen_num) + experiment_management.export_snapshots(population.individuals, gen_num) + + # output result after completing all generations... diff --git a/experiments/karines_experiments/run-experiments b/experiments/karines_experiments/run-experiments new file mode 100755 index 0000000000..2499bbd4cc --- /dev/null +++ b/experiments/karines_experiments/run-experiments @@ -0,0 +1,10 @@ +#!/bin/bash +while true + do + for i in {1..10}; do + ./revolve.py --experiment_name karines_experiments/data/lava_$i --run $i --manager experiments/karines_experiments/manager_pop_lava.py --n-cores 5; + sleep 5s + ./revolve.py --experiment_name karines_experiments/data/plane_$i --run $i --manager experiments/karines_experiments/manager_pop.py --n-cores 5; + sleep 5s + done +done \ No newline at end of file diff --git a/experiments/karines_experiments/stuck-experiments_watchman.py b/experiments/karines_experiments/stuck-experiments_watchman.py new file mode 100644 index 0000000000..272d59a67a --- /dev/null +++ b/experiments/karines_experiments/stuck-experiments_watchman.py @@ -0,0 +1,52 @@ +from datetime import datetime, timedelta +import os + +# set these variables according to your experiments # +dir_path = 'data' +experiments_names = ['plane', + 'lava' + ] +runs = 10 +limit_of_minutes = 10 +# set these variables according to your experiments # + +some_has_been_updated = False + +while 1: + + # 10 minutes (do update this according to limit_of_minutes! + os.system(" sleep 600s") + + youngest = [] + for exp in experiments_names: + for run in range(0, runs): + + path = os.path.join(dir_path, exp, str(run+1), 'data_fullevolution', 'fitness') + time_now = datetime.now() + time_ago = time_now - timedelta(minutes=limit_of_minutes) + + if os.path.isdir(path): + files = [] + for r, d, f in os.walk(path): + for file in f: + filetime = datetime.fromtimestamp(os.path.getctime(path+'/'+file)) + files.append(filetime) + files.sort() + youngest.append(files[-1]) + + if files[-1] > time_ago: + some_has_been_updated = True + + if not some_has_been_updated: + youngest.sort() + print(str(time_now) + ': youngest file from ' + str(youngest[-1])) + os.system(" kill $( ps aux | grep 'gzserver' | awk '{print $2}')") + os.system(" kill $( ps aux | grep 'revolve.py' | awk '{print $2}')") + print(' killled gzserver and revolve.py to force an error!') + + some_has_been_updated = False + + + + + diff --git a/experiments/karines_experiments/summary_measures.R b/experiments/karines_experiments/summary_measures.R new file mode 100644 index 0000000000..b9a396edee --- /dev/null +++ b/experiments/karines_experiments/summary_measures.R @@ -0,0 +1,383 @@ +library(ggplot2) +library(sqldf) +library(plyr) +library(dplyr) +library(trend) + +base_directory <- paste('projects/revolve/experiments/karines_experiments/data', sep='') + +output_directory = base_directory + +experiments_type = c( + 'plane', + 'lava' + ) + +initials = c('p', 'l') + +experiments_labels = c('Plane', 'Floor is lava') + +runs = c(1,2,3,4,5,6,7,8,9,10) +gens = 100 +pop = 100 +sig = 0.05 +line_size = 30 +show_markers = TRUE +show_legends = TRUE +experiments_type_colors = c( '#009900', '#FF8000', '#BA1616', '#000099') # DARK:green, orange, red, blue + +measures_names = c( + 'displacement_velocity_hill', + 'head_balance', + 'contacts', + 'displacement_velocity', + 'branching', + 'branching_modules_count', + 'limbs', + 'extremities', + 'length_of_limbs', + 'extensiveness', + 'coverage', + 'joints', + 'hinge_count', + 'active_hinges_count', + 'brick_count', + 'touch_sensor_count', + 'brick_sensor_count', + 'proportion', + 'width', + 'height', + 'absolute_size', + 'sensors', + 'symmetry', + 'avg_period', + 'dev_period', + 'avg_phase_offset', + 'dev_phase_offset', + 'avg_amplitude', + 'dev_amplitude', + 'avg_intra_dev_params', + 'avg_inter_dev_params', + 'sensors_reach', + 'recurrence', + 'synaptic_reception', + 'fitness' +) + +# add proper labels soon... +measures_labels = c( + 'Speed', + 'Balance', + 'Contacts', + 'displacement_velocity', + 'branching', + 'branching_modules_count', + 'limbs', + 'extremities', + 'length_of_limbs', + 'extensiveness', + 'coverage', + 'joints', + 'hinge_count', + 'active_hinges_count', + 'brick_count', + 'touch_sensor_count', + 'brick_sensor_count', + 'proportion', + 'width', + 'height', + 'absolute_size', + 'sensors', + 'symmetry', + 'avg_period', + 'dev_period', + 'avg_phase_offset', + 'dev_phase_offset', + 'avg_amplitude', + 'dev_amplitude', + 'avg_intra_dev_params', + 'avg_inter_dev_params', + 'sensors_reach', + 'recurrence', + 'synaptic_reception', + 'Fitness' +) + + +measures_snapshots_all = NULL + +for (exp in 1:length(experiments_type)) +{ + for(run in runs) + { + input_directory <- paste(base_directory, '/', experiments_type[exp], '_', run, sep='') + measures = read.table(paste(input_directory,"/all_measures.tsv", sep=''), header = TRUE) + for( m in 1:length(measures_names)) + { + measures[measures_names[m]] = as.numeric(as.character(measures[[measures_names[m]]])) + } + + snapshots = read.table(paste(input_directory,"/snapshots_ids.tsv", sep=''), header = TRUE) + measures_snapshots = sqldf('select * from snapshots inner join measures using(robot_id) order by generation') + + measures_snapshots$run = run + measures_snapshots$run = as.factor(measures_snapshots$run) + measures_snapshots$method = experiments_type[exp] + + if ( is.null(measures_snapshots_all)){ + measures_snapshots_all = measures_snapshots + }else{ + measures_snapshots_all = rbind(measures_snapshots_all, measures_snapshots) + } + } +} + + + +measures_snapshots_all = sqldf("select * from measures_snapshots_all where fitness IS NOT NULL") + +fail_test = sqldf(paste("select method,run,generation,count(*) as c from measures_snapshots_all group by 1,2,3 having c<",gens," order by 4")) + + +measures_averages_gens_1 = list() +measures_averages_gens_2 = list() + +measures_ini = list() +measures_fin = list() + +for (exp in 1:length(experiments_type)) +{ + + query ='select run, generation' + for (i in 1:length(measures_names)) + { + query = paste(query,', avg(',measures_names[i],') as ',experiments_type[exp],'_',measures_names[i],'_avg', sep='') + } + query = paste(query,' from measures_snapshots_all + where method="',experiments_type[exp],'" group by run, generation', sep='') + + + measures_averages_gens_1[[exp]] = sqldf(query) + + temp = measures_averages_gens_1[[exp]] + + measures_ini[[exp]] = sqldf(paste("select * from temp where generation=1")) + measures_fin[[exp]] = sqldf(paste("select * from temp where generation=",gens-1)) + query = 'select generation' + for (i in 1:length(measures_names)) + { + query = paste(query,', avg(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_avg', sep='') + query = paste(query,', max(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_max', sep='') + query = paste(query,', stdev(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_stdev', sep='') + query = paste(query,', median(',experiments_type[exp],'_',measures_names[i],'_avg) as ',experiments_type[exp],'_',measures_names[i],'_median', sep='') + } + query = paste(query,' from temp group by generation', sep="") + + measures_averages_gens_2[[exp]] = sqldf(query) + + measures_averages_gens_2[[exp]]$generation = as.numeric(measures_averages_gens_2[[exp]]$generation) + +} + + +for (exp in 1:length(experiments_type)) +{ + if(exp==1){ + measures_averages_gens = measures_averages_gens_2[[1]] + }else{ + measures_averages_gens = merge(measures_averages_gens, measures_averages_gens_2[[exp]], by = "generation") + } +} + + + +file <-file(paste(output_directory,'/trends.txt',sep=''), open="w") + +#tests trends in curves and difference between ini and fin generations + + +# ini VS fin +array_wilcoxon = list() +array_wilcoxon2 = list() + +# curve +array_mann = list() + + +for (m in 1:length(experiments_type)) +{ + + array_wilcoxon[[m]] = list() + array_mann[[m]] = list() + + for (i in 1:length(measures_names)) + { + + writeLines(paste(experiments_type[m],measures_names[i],'ini avg ',as.character( + mean(c(array(measures_ini[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + + writeLines(paste(experiments_type[m],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + array_wilcoxon[[m]][[i]] = wilcox.test(c(array(measures_ini[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] , + c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] + ) + + writeLines(c( + paste(experiments_type[m],'iniVSfin',measures_names[i],'wilcox p: ',as.character(round(array_wilcoxon[[m]][[i]]$p.value,4)), sep=' ') + ,paste(experiments_type[m],'iniVSfin',measures_names[i],'wilcox est: ',as.character(round(array_wilcoxon[[m]][[i]]$statistic,4)), sep=' ') + + ), file) + + + #tests trends + array_mann[[m]][[i]] = mk.test(c(array(measures_averages_gens_2[[m]][paste(experiments_type[m],"_",measures_names[i],'_median',sep='')]) )[[1]], + continuity = TRUE) + + + writeLines(c( + paste(experiments_type[m],measures_names[i], ' Mann-Kendall median p', as.character(round(array_mann[[m]][[i]]$p.value,4)),sep=' '), + paste(experiments_type[m],measures_names[i], ' Mann-Kendall median s', as.character(round(array_mann[[m]][[i]]$statistic,4)),sep=' ') + ), file) + + } + +} + + + +# tests final generation among experiments_type + +aux_m = length(experiments_type) + +if (aux_m>1) +{ + + # fins + array_wilcoxon2[[1]] = list() + array_wilcoxon2[[2]] = list() + +aux_m = aux_m -1 +count_pairs = 0 +for(m in 1:aux_m) +{ + aux = m+1 + for(m2 in aux:length(experiments_type)) + { + + count_pairs = count_pairs+1 + array_wilcoxon2[[1]][[count_pairs]] = list() + + for (i in 1:length(measures_names)) + { + + writeLines(paste(experiments_type[m],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + writeLines(paste(experiments_type[m2],measures_names[i],'fin avg ',as.character( + mean(c(array(measures_fin[[m2]][paste(experiments_type[m2],"_",measures_names[i],"_avg",sep='')]) )[[1]]) ) ,sep=" "), file ) + + array_wilcoxon2[[1]][[count_pairs]][[i]] = wilcox.test(c(array(measures_fin[[m]][paste(experiments_type[m],"_",measures_names[i],"_avg",sep='')]))[[1]] , + c(array(measures_fin[[m2]][paste(experiments_type[m2],"_",measures_names[i],"_avg",sep='')]))[[1]] + ) + + writeLines(c( + paste(experiments_type[m],'VS',experiments_type[m2],measures_names[i],'fin avg wilcox p: ',as.character(round(array_wilcoxon2[[1]][[count_pairs]][[i]]$p.value,4)), sep=' ') + ,paste(experiments_type[m],'VS',experiments_type[m2],measures_names[i],'fin avg wilcox est: ',as.character(round(array_wilcoxon2[[1]][[count_pairs]][[i]]$statistic,4)), sep=' ') + + ), file) + + } + + + array_wilcoxon2[[2]][[count_pairs]] = paste(initials[m],initials[m2],sep='') + + } +} + +} + +close(file) + +# plots measures + +for (i in 1:length(measures_names)) +{ + tests1 = '' + tests2 = '' + tests3 = '' + break_aux = 0 + + graph <- ggplot(data=measures_averages_gens, aes(x=generation)) + for(m in 1:length(experiments_type)) + { + graph = graph + geom_errorbar(aes_string(ymin=paste(experiments_type[m],'_',measures_names[i],'_avg','-',experiments_type[m],'_',measures_names[i],'_stdev',sep=''), + ymax=paste(experiments_type[m],'_',measures_names[i],'_avg','+',experiments_type[m],'_',measures_names[i],'_stdev',sep='') ), + color=experiments_type_colors[m], + alpha=0.35,size=0.5,width=0.001) + } + + for(m in 1:length(experiments_type)) + { + if(show_legends == TRUE){ + graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_avg',sep=''), colour=shQuote(experiments_labels[m]) ), size=2) + }else{ + graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_avg',sep='') ),size=2, color = experiments_type_colors[m]) + } + # graph = graph + geom_line(aes_string(y=paste(experiments_type[m],'_',measures_names[i],'_median',sep='') ),size=2, color = colors_median[m]) + + if(!is.na(array_mann[[m]][[i]]$p.value)) + { + if(array_mann[[m]][[i]]$p.value<=sig) + { + if(array_mann[[m]][[i]]$statistic>0){ direction = "/ "} else { direction = "\\ "} + tests1 = paste(tests1, initials[m],direction,sep="") + } + } + } + for(m in 1:length(experiments_type)) + { + if(!is.na(array_wilcoxon[[m]][[i]]$p.value)) + { + if(array_wilcoxon[[m]][[i]]$p.value<=sig) + { + tests2 = paste(tests2, initials[m],'C ', sep='') + } + } + } + + if (length(array_wilcoxon2)>0) + { + + for(p in 1:length(array_wilcoxon2[[1]])) + { + if(!is.na(array_wilcoxon2[[1]][[p]][[i]]$p.value)) + { + if(array_wilcoxon2[[1]][[p]][[i]]$p.value<=sig) + { + if(nchar(tests3)>line_size && break_aux == 0){ + tests3 = paste(tests3, '\n') + break_aux = 1 + } + tests3 = paste(tests3, array_wilcoxon2[[2]][[p]],'D ',sep='') + } + } + + } + + } + + graph = graph + + #coord_cartesian(ylim = c(0, 1))+ + labs( y=measures_labels[i], x="Generation") + if(show_markers == TRUE){ + graph = graph + labs( y=measures_labels[i], x="Generation", subtitle = paste(tests1,'\n', tests2, '\n', tests3, sep='')) + } + graph = graph + theme(legend.position="bottom" , legend.text=element_text(size=20), axis.text=element_text(size=30),axis.title=element_text(size=39), + plot.subtitle=element_text(size=25 )) + + ggsave(paste( output_directory,'/' ,measures_names[i],'_generations.pdf', sep=''), graph , device='pdf', height = 8, width = 8) +} + + diff --git a/experiments/karines_experiments/watch_best_robots.py b/experiments/karines_experiments/watch_best_robots.py new file mode 100755 index 0000000000..5f84e81562 --- /dev/null +++ b/experiments/karines_experiments/watch_best_robots.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +import asyncio + +from pyrevolve import parser +from pyrevolve.evolution import fitness +from pyrevolve.evolution.selection import multiple_selection, tournament_selection +from pyrevolve.evolution.population import Population, PopulationConfig +from pyrevolve.evolution.pop_management.steady_state import steady_state_population_management +from pyrevolve.experiment_management import ExperimentManagement +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +import numpy as np + + +async def run(): + """ + The main coroutine, which is started below. + """ + # Parse command line / file input arguments + + + genotype_conf = PlasticodingConfig( + max_structural_modules=100, + ) + + mutation_conf = MutationConfig( + mutation_prob=0.8, + genotype_conf=genotype_conf, + ) + + crossover_conf = CrossoverConfig( + crossover_prob=0.8, + ) + + settings = parser.parse_args() + experiment_management = ExperimentManagement(settings) + + population_conf = PopulationConfig( + population_size=100, + genotype_constructor=random_initialization, + genotype_conf=genotype_conf, + fitness_function=fitness.displacement_velocity_hill, + mutation_operator=standard_mutation, + mutation_conf=mutation_conf, + crossover_operator=standard_crossover, + crossover_conf=crossover_conf, + selection=lambda individuals: tournament_selection(individuals, 2), + parent_selection=lambda individuals: multiple_selection(individuals, 2, tournament_selection), + population_management=steady_state_population_management, + population_management_selector=tournament_selection, + evaluation_time=settings.evaluation_time, + offspring_size=50, + experiment_name=settings.experiment_name, + experiment_management=experiment_management, + ) + + settings = parser.parse_args() + simulator_queue = SimulatorQueue(settings.n_cores, settings, settings.port_start) + await simulator_queue.start() + + population = Population(population_conf, simulator_queue, 0) + + # choose a snapshot here. and the maximum best individuals you wish to watch + generation = 99 + max_best = 10 + await population.load_snapshot(generation) + + values = [] + for ind in population.individuals: + # define a criteria here + #values.append(ind.fitness) + values.append(ind.phenotype._behavioural_measurements.contacts) + values = np.array(values) + + ini = len(population.individuals)-max_best + fin = len(population.individuals) + + population.individuals = np.array(population.individuals) + population.individuals = population.individuals[np.argsort(values)[ini:fin]] + + for ind in population.individuals: + print(ind.phenotype.id) + print('contacts', ind.phenotype._behavioural_measurements.contacts) + + await population.evaluate(population.individuals, generation, 'watch') diff --git a/experiments/unmanaged/.gitignore b/experiments/unmanaged/.gitignore new file mode 100644 index 0000000000..2c8bd16fa9 --- /dev/null +++ b/experiments/unmanaged/.gitignore @@ -0,0 +1 @@ +/[0-9]*/ \ No newline at end of file diff --git a/experiments/unmanaged/create_charts.py b/experiments/unmanaged/create_charts.py new file mode 100755 index 0000000000..ea6b23a835 --- /dev/null +++ b/experiments/unmanaged/create_charts.py @@ -0,0 +1,280 @@ +#!/usr/bin/env python3 +import os +import sys +import dateutil.parser +import yaml +import matplotlib +import matplotlib.pyplot as plt +import numpy as np + +from pyrevolve.SDF.math import Vector3 +from pyrevolve.revolve_bot import RevolveBot + + +def parse_vec3(source: str): + # example source: Vector3(2.394427e+00, 3.195821e-01, 2.244915e-02) + assert (source[:8] == 'Vector3(') + assert (source[-1:] == ')') + source = source[8:-1] + try: + x, y, z = [float(n) for n in source.split(', ')] + except ValueError: + print(f'could not parse vector3 for "{source}"') + return Vector3() + return Vector3(x, y, z) + + +def read_robot(file: str): + bot = RevolveBot() + bot.load_file(file) + return bot + + +def read_log(filename: str): + with open(filename) as file: + log = file.readlines() + + class LogLine: + def __init__(self, line): + self.time = dateutil.parser.parse(line[1:24]) + self.type = line[37:41] + self.text = line[46:] + self.event_type = 'NEW' if self.text[0:3] == 'LOW' else 'MATE' + + def __repr__(self): + return f'{self.time} {self.type}\t{self.event_type}' + + def parseline(line): + return LogLine(line.strip()) + + return [parseline(line) for line in log] + + +def read_robots(folder_name: str): + robots = {} + phenotype_folder = os.path.join(folder_name, 'phenotypes') + + class RobotLog: + def __init__(self, pheno_filename): + self.robot = RevolveBot() + self.robot.load_file(os.path.join(phenotype_folder, pheno_filename)) + assert(f'{self.robot.id}.yaml' == pheno_filename) + with open(os.path.join(folder_name, f'life_{pheno_filename}')) as life_file: + self.life = yaml.safe_load(life_file) + birth = self.life['starting_time'] + age = self.life['age'] + self.life['death'] = None if age == 0 else birth + age + del self.life['avg_orientation'] + del self.life['avg_pos'] + del self.life['charge'] + self.life['birth_reason'] = 'MATE' + + def __repr__(self): + return f'{self.robot}:{self.life}' + + for pheno_file in os.listdir(phenotype_folder): + r = RobotLog(pheno_file) + robots[r.robot.id] = r + + return robots + + +def read_data(folder_name: str): + assert(os.path.isdir(folder_name)) + assert(os.path.exists(os.path.join(folder_name, 'experiment_manager.log'))) + + return { + 'log': read_log(os.path.join(folder_name, 'experiment_manager.log')), + 'robots': read_robots(folder_name), + } + + +def speed(robot_life): + start_position = parse_vec3(robot_life['start_pos']) + last_position = parse_vec3(robot_life['last_pos']) + return (last_position - start_position).magnitude() + + +def draw_chart(folder_name: str, ax): + data = read_data(folder_name) + robots = data['robots'] + # print(f'{data}') + for logline in data['log']: + # print(f'{logline}') + if logline.event_type == 'NEW': + robot_id = logline.text[41:].split('(')[0] + robot_id = robot_id[11:] + if robot_id != '': + robots[robot_id].life['birth_reason'] = 'NEW' + # print(f'{logline.event_type} => {robot_id}') + + robot_points = [] + robot_points_new = [] + robot_points_mate = [] + robot_points_death = [] + robot_points_new_pop = [] + robot_points_mate_pop = [] + robot_points_death_pop = [] + robot_speed = [] + + for robot_id in data['robots']: + robot_log = data['robots'][robot_id] + # print(f'{robot_log}') + life = robot_log.life + birth = life['starting_time'] + age = life['age'] + if life['birth_reason'] == 'NEW': + robot_points.append(('NEW', birth)) + else: + robot_points.append(('MATE', birth)) + if life['death'] is not None: + robot_points.append(('DEATH', life['death'], speed(life))) + + print(f"Drawing {len(data['robots'])} robots, global time TODO") + + robot_points.sort(key=lambda e: e[1]) + pop_size = 0 + for robot_point in robot_points: + event = robot_point[0] + time = robot_point[1] + if event == 'NEW': + pop_size += 1 + robot_points_new.append(time) + robot_points_new_pop.append(pop_size) + elif event == 'MATE': + pop_size += 1 + robot_points_mate.append(time) + robot_points_mate_pop.append(pop_size) + elif event == 'DEATH': + pop_size -= 1 + robot_points_death.append(time) + robot_points_death_pop.append(pop_size) + robot_speed.append(robot_point[2]) + else: + raise RuntimeError("WAT?") + + return robot_points_new, robot_points_new_pop, \ + robot_points_mate, robot_points_mate_pop, \ + robot_points_death, robot_points_death_pop, \ + robot_speed + + +def my_min(*args): + try: + return min(*args) + except ValueError: + return 0 + + +def my_max(*args): + try: + return max(*args) + except ValueError: + return 0 + + +def calculate_min_max_len(data): + _min = my_min([my_min(x) for x in data]) + _max = my_max([my_max(x) for x in data]) + _len = _max - _min + return _min, _max, _len + + +if __name__ == '__main__': + folder_name = sys.argv[1] + live_update = False + save_png = False + if len(sys.argv) > 2: + if sys.argv[2] == 'live': + live_update = True + elif sys.argv[2] == 'png': + save_png = True + else: + print(f'Command {sys.argv[2]} not recognized') + sys.exit(1) + + if not save_png: + matplotlib.use('Qt5Agg') + # matplotlib.use('GTK3Cairo') # live update is bugged + # matplotlib.use('GTK3Agg') + fig, ax = plt.subplots() + if live_update: + plt.ion() + + robot_points_new, robot_points_new_pop, \ + robot_points_mate, robot_points_mate_pop, \ + robot_points_death, robot_points_death_pop, \ + robot_speed = draw_chart(folder_name, ax) + + new_scatter, = ax.plot(robot_points_new, robot_points_new_pop, label='new', ms=10, marker='*', ls='') + mate_scatter, = ax.plot(robot_points_mate, robot_points_mate_pop, label='mate', ms=10, marker='+', ls='') + death_scatter, = ax.plot(robot_points_death, robot_points_death_pop, label='death', ms=10, marker='x', ls='') + ax.legend() + if save_png: + plt.savefig(os.path.join(folder_name, 'population.png'), bbox_inches='tight') + + fig2, ax2 = plt.subplots() + speed_scatter, = ax2.plot(robot_points_death, robot_speed, label='speed', ms=10, marker='.', ls='') + if save_png: + plt.savefig(os.path.join(folder_name, 'population-speed.png'), bbox_inches='tight') + + if not live_update and not save_png: + plt.show() + elif not save_png: + plt.draw() + plt.pause(0.01) + + def update_data(dataset, points, points_pop): + assert(len(points) == len(points_pop)) + if len(points) == 0: + return + X = points + Y = points_pop + dataset.set_data(X, Y) + return min(X), max(X), min(Y), max(Y) + + while True: + robot_points_new, robot_points_new_pop, \ + robot_points_mate, robot_points_mate_pop, \ + robot_points_death, robot_points_death_pop, \ + robot_speed = draw_chart(folder_name, ax) + + update_data(new_scatter, robot_points_new, robot_points_new_pop) + update_data(mate_scatter, robot_points_mate, robot_points_mate_pop) + update_data(death_scatter, robot_points_death, robot_points_death_pop) + update_data(speed_scatter, robot_points_death, robot_speed) + + minx, maxx, x_len = calculate_min_max_len( + [robot_points_new, robot_points_mate, robot_points_death]) + miny, maxy, y_len = calculate_min_max_len( + [robot_points_new_pop, robot_points_mate_pop, robot_points_death_pop]) + + speed_minx, speed_maxx, speedx_len = calculate_min_max_len([robot_points_death]) + speed_miny, speed_maxy, speedy_len = calculate_min_max_len([robot_speed]) + + half_border_ratio = 0.01 + + ax.set_xlim(minx - half_border_ratio * x_len, maxx + half_border_ratio * x_len) + ax.set_ylim(miny - half_border_ratio * y_len, maxy + half_border_ratio * y_len) + + ax2.set_xlim(speed_minx - half_border_ratio * speedx_len, speed_maxx + half_border_ratio * speedx_len) + ax2.set_ylim(speed_miny - half_border_ratio * speedy_len, speed_maxy + half_border_ratio * speedy_len) + + plt.draw() + plt.pause(2) + + # + # # Example: loops monitoring events forever. + # # + # import pyinotify + # + # # Instanciate a new WatchManager (will be used to store watches). + # wm = pyinotify.WatchManager() + # # Associate this WatchManager with a Notifier (will be used to report and + # # process events). + # notifier = pyinotify.Notifier(wm) + # # Add a new watch on /tmp for ALL_EVENTS. + # wm.add_watch(os.path.join(folder_name, 'experiment_manager.log'), pyinotify.ALL_EVENTS) + # # Loop forever and handle events. + # notifier.loop() + # diff --git a/experiments/unmanaged/manager.py b/experiments/unmanaged/manager.py new file mode 100644 index 0000000000..da2095ec52 --- /dev/null +++ b/experiments/unmanaged/manager.py @@ -0,0 +1,626 @@ +#!/usr/bin/env python3 +import asyncio +import os +import sys +import random +import logging +import yaml +import enum +import time +import shutil +import pickle + +from pyrevolve.custom_logging import logger +from pyrevolve import parser +from pyrevolve.SDF.math import Vector3 +from pyrevolve.tol.manage import World +from pyrevolve.tol.manage import measures +from pyrevolve.evolution import fitness +from pyrevolve.evolution.individual import Individual +from pyrevolve.genotype.plasticoding.crossover.crossover import CrossoverConfig +from pyrevolve.genotype.plasticoding.crossover.standard_crossover import standard_crossover +from pyrevolve.genotype.plasticoding.initialization import random_initialization +from pyrevolve.genotype.plasticoding.mutation.mutation import MutationConfig +from pyrevolve.genotype.plasticoding.mutation.standard_mutation import standard_mutation +from pyrevolve.genotype.plasticoding.plasticoding import PlasticodingConfig +from pyrevolve.revolve_bot.brain import BrainRLPowerSplines +from pyrevolve.util.supervisor.supervisor_multi import DynamicSimSupervisor + +ROBOT_BATTERY = 5000 +ROBOT_STOP = 5050 +ROBOT_SELF_COLLIDE = False +REPRODUCE_LOCALLY = True +REPRODUCE_LOCALLY_RADIUS = 2 +INDIVIDUAL_MAX_AGE = 60 * 2 # 2 minutes +INDIVIDUAL_MAX_AGE_SIGMA = 1.0 +SEED_POPULATION_START = 50 +MIN_POP = 20 +MAX_POP = 50 +Z_SPAWN_DISTANCE = 0.2 +LIMIT_X = 3 +LIMIT_Y = 3 +MATURE_AGE = 5 +MATE_DISTANCE = 0.6 +MATING_COOLDOWN = 0.1 +COUPLE_MATING_LIMIT = 1 +MATING_INCREASE_RATE = 1.0 +SNAPSHOT_TIME = 60 * 10 # 10 minutes +RECENT_CHILDREN_DELTA_TIME = 30 + +PLASTICODING_CONF = PlasticodingConfig( + max_structural_modules=20 +) +CROSSOVER_CONF = CrossoverConfig(crossover_prob=1.0) +MUTATION_CONF = MutationConfig(mutation_prob=0.8, genotype_conf=PLASTICODING_CONF) + +# FOLDER WHERE TO SAVE THE EXPERIMENT +# {current_folder}/data/{arguments.experiment_name} +# example ~/projects/revolve/experiments/unmanaged/data/default_experiment +DATA_FOLDER_BASE = os.path.join( + os.path.dirname(os.path.realpath(__file__)), + 'data', +) + + +def make_folders(base_dirpath): + if os.path.exists(base_dirpath): + assert(os.path.isdir(base_dirpath)) + else: + os.makedirs(base_dirpath) + + counter = 0 + while True: + dirpath = os.path.join(base_dirpath, str(counter)) + if not os.path.exists(dirpath): + break + counter += 1 + + print(f"CHOSEN EXPERIMENT FOLDER {dirpath}") + + # if os.path.exists(dirpath): + # shutil.rmtree(dirpath) + os.mkdir(dirpath) + os.mkdir(os.path.join(dirpath, 'genotypes')) + os.mkdir(os.path.join(dirpath, 'phenotypes')) + os.mkdir(os.path.join(dirpath, 'descriptors')) + + return dirpath + + +class OnlineIndividual(Individual): + class BirthType(enum.Enum): + NEW = 0 + MATE = 1 + + def __init__(self, genotype, max_age=None, parents=None): + super().__init__(genotype) + self.parents = parents + if self.parents is None: + self.birth_type = OnlineIndividual.BirthType.NEW + else: + self.birth_type = OnlineIndividual.BirthType.MATE + self.children = [] + self.manager = None + self.max_age = random.gauss(INDIVIDUAL_MAX_AGE, INDIVIDUAL_MAX_AGE_SIGMA) if max_age is None else max_age + + @staticmethod + def clone_from(other): + self = OnlineIndividual(other.genotype, other.max_age) + self.phenotype = other.phenotype + self.manager = other.manager + self.fitness = other.fitness + self.parents = other.parents + + def develop(self): + super().develop() + # self.phenotype._brain = BrainRLPowerSplines(evaluation_rate=10.0) + + def age(self): + if self.manager is not None: + return self.manager.age() + else: + return 0.0 + + def charge(self): + if self.manager is not None: + return self.manager.charge() + else: + return 0.0 + + def pos(self): + if self.manager is not None: + return self.manager.last_position + else: + return None + + def alive(self): + if self.manager is not None: + return not self.manager.dead + else: + return None + + def starting_position(self): + if self.manager is not None: + return self.manager.starting_position + else: + return None + + @property + def name(self): + return self.id + + def distance_to(self, other, planar: bool = True): + """ + Calculates the Euclidean distance from this robot to + the given vector position. + :param other: Target for measuring distance + :type other: Vector3|OnlineIndividual + :param planar: If true, only x/y coordinates are considered. + :return: distance to other + :rtype: float + """ + my_pos = self.pos() + other_pos = other if isinstance(other, Vector3) else other.pos() + + diff = my_pos - other_pos + if planar: + diff.z = 0 + + return diff.norm() + + def mature(self): + return self.age() > MATURE_AGE + + def _wants_to_mate(self, other, mating_multiplier): + if not self.mature(): + return False + + if self.distance_to(other) > MATE_DISTANCE * mating_multiplier: + return False + + if self.manager.last_mate is not None and \ + float(self.manager.last_update - self.manager.last_mate) < MATING_COOLDOWN: + return False + + mate_count = self.manager.mated_with.get(other.manager.name, 0) + if mate_count > COUPLE_MATING_LIMIT: + return False + + return True + + def mate(self, other, mating_distance_multiplier: float): + """ + Will try to mate with other + :param other: potential mate + :type other: OnlineIndividual + :param mating_distance_multiplier: multiplier for mating distance, default should be 1 + :return: Genotype generated by the mating process, None if no mating happened + :rtype: Genotype|None + """ + if not (self._wants_to_mate(other, mating_distance_multiplier) + and other._wants_to_mate(self, mating_distance_multiplier)): + return None + + # save the mating + self.manager.last_mate = self.manager.last_update + if other.manager.name in self.manager.mated_with: + self.manager.mated_with[other.manager.name] += 1 + else: + self.manager.mated_with[other.manager.name] = 1 + + genotype = standard_crossover([self, other], PLASTICODING_CONF, CROSSOVER_CONF) + genotype = standard_mutation(genotype, MUTATION_CONF) + + child = OnlineIndividual(genotype) + + self.children.append(child) + other.children.append(child) + return child + + def export_life_data(self, folder): + life_measures = { + 'distance': str(measures.displacement(self.manager)[0]), + 'distance_magnitude': str(measures.displacement(self.manager)[0].magnitude()), + 'velocity': str(measures.velocity(self.manager)), + 'displacement_velocity': str(measures.displacement_velocity(self.manager)), + 'path_length': str(measures.path_length(self.manager)), + } + + life = { + 'starting_time': float(self.manager.starting_time), + 'age': float(self.age()), + 'charge': self.charge(), + 'start_pos': str(self.starting_position()), + 'last_pos': str(self.pos()), + 'avg_orientation': str(Vector3(self.manager.avg_roll, self.manager.avg_pitch, self.manager.avg_yaw)), + 'avg_pos': str(Vector3(self.manager.avg_x, self.manager.avg_y, self.manager.avg_z)), + 'last_mate': str(self.manager.last_mate), + 'alive': str(self.alive()), + 'birth': str(self.birth_type), + 'parents': [parent.name for parent in self.parents] if self.parents is not None else 'None', + 'children': [child.name for child in self.children], + 'measures': life_measures, + } + + with open(os.path.join(folder, f'life_{self.id}.yaml'), 'w') as f: + f.write(str(yaml.dump(life))) + + def snapshot_data(self): + return { + 'genotype': self.genotype, + 'parents': self.parents, + 'children': self.children, + 'birth': self.birth_type, + 'last_mate': self.manager.last_mate, + 'start_pos': self.starting_position(), + 'starting_time': self.manager.starting_time + } + + def export(self, folder): + self.export_genotype(folder) + self.export_phenotype(folder) + self.export_life_data(folder) + + def __repr__(self): + return f'Individual_{self.id}({self.age()}, {self.charge()}, {self.pos()})' + + +def random_spawn_pos(): + return Vector3( + random.uniform(-LIMIT_X, LIMIT_X), + random.uniform(-LIMIT_Y, LIMIT_Y), + Z_SPAWN_DISTANCE + ) + + +def random_uniform_unit_vec(): + return Vector3( + random.uniform(-1, 1), + random.uniform(-1, 1), + Z_SPAWN_DISTANCE + ).normalized() + + +class Finish(Exception): + pass + + +class Population(object): + def __init__(self, log, data_folder, connection): + self._log = log + self._data_folder = data_folder + self._connection = connection + self._robots = [] + self._robot_id_counter = 0 + self._mating_multiplier = 1.0 + self._mating_increase_rate = MATING_INCREASE_RATE + self._recent_children = [] + self._recent_children_start_time = -1.0 + self._recent_children_delta_time = RECENT_CHILDREN_DELTA_TIME + + def __len__(self): + return len(self._robots) + + async def _insert_robot(self, robot, pos: Vector3, life_duration: float): + robot.update_substrate() + robot.self_collide = ROBOT_SELF_COLLIDE + robot.battery_level = ROBOT_BATTERY + + # Insert the robot in the simulator + robot_manager = await asyncio.wait_for(self._connection.insert_robot(robot, pos, life_duration), 5) + return robot_manager + + async def _insert_individual(self, individual: OnlineIndividual, pos: Vector3): + individual.develop() + individual.manager = await self._insert_robot(individual.phenotype, pos, individual.max_age) + individual.export(self._data_folder) + return individual + + async def _remove_individual(self, individual: OnlineIndividual): + self._robots.remove(individual) + individual.export(self._data_folder) + + self._connection.unregister_robot(individual.manager) + # await self._connection.delete_robot(individual.manager) + if individual.id == f'robot_{ROBOT_STOP}': + raise Finish() + + def _is_pos_occupied(self, pos, distance): + for robot in self._robots: + if robot.distance_to(pos) < distance: + return True + return False + + class NoPositionFound(Exception): + def __str__(self): + return "NoPositionFound" + + def _free_random_spawn_pos(self, distance=MATE_DISTANCE + 0.1, n_tries=100): + pos = random_spawn_pos() + i = 1 + while self._is_pos_occupied(pos, distance): + i += 1 + if i > n_tries: + raise self.NoPositionFound() + pos = random_spawn_pos() + return pos + + def _free_random_spawn_pos_area(self, center: Vector3, radius: float=REPRODUCE_LOCALLY_RADIUS, distance=MATE_DISTANCE + 0.1, n_tries=100): + pos = center + (random_uniform_unit_vec() * random.uniform(0,radius)) + i = 1 + while self._is_pos_occupied(pos, distance): + i += 1 + if i > n_tries: + raise self.NoPositionFound() + pos = center + (random_uniform_unit_vec() * random.uniform(0,radius)) + return pos + + async def _generate_insert_random_robot(self, _id: int): + # Load a robot from yaml + genotype = random_initialization(PLASTICODING_CONF, _id) + individual = OnlineIndividual(genotype) + return await self._insert_individual(individual, self._free_random_spawn_pos()) + + async def seed_initial_population(self, pause_while_inserting: bool): + """ + Seed a new population + """ + if pause_while_inserting: + await self.pause(True) + await self._connection.reset(rall=True, time_only=True, model_only=False) + await self.immigration_season(SEED_POPULATION_START) + if pause_while_inserting: + await self.pause(False) + + def print_population(self): + for individual in self._robots: + self._log.info(f"{individual} " + f"battery {individual.manager.charge()} " + f"age {individual.manager.age()} " + f"fitness is {fitness.online_old_revolve(individual.manager)}") + + async def death_season(self): + """ + Checks for age in the all population and if it's their time of that (currently based on age) + """ + for individual in self._robots: + # alive can be None or boolean + alive = individual.alive() + if alive is False or individual.age() > individual.max_age: + self._log.debug(f"Attempting ROBOT DIES OF OLD AGE: {individual} - total_population: {len(self._robots)}") + await self._remove_individual(individual) + self._log.info(f"ROBOT DIES OF OLD AGE: {individual} - total_population: {len(self._robots)}") + + async def immigration_season(self, population_minimum=MIN_POP): + """ + Generates new random individual that are inserted in our population if the population size is too little + """ + while len(self._robots) < population_minimum: + self._robot_id_counter += 1 + self._log.debug(f"Attempting LOW REACHED") + try: + individual = await self._generate_insert_random_robot(self._robot_id_counter) + self._log.info(f"LOW REACHED: inserting new random robot: {individual}") + self._robots.append(individual) + except (Population.NoPositionFound, asyncio.TimeoutError) as e: + self._log.error(f"LOW REACHED failed: {e}") + + def adjust_mating_multiplier(self, time): + if self._recent_children_start_time < 0: + self._recent_children_start_time = time + return + + if time - self._recent_children_start_time > self._recent_children_delta_time: + # Time to update the multiplier! + self._recent_children_start_time = time + n = len(self._recent_children) + if n < 3: + self._mating_multiplier *= self._mating_increase_rate + self._log.info(f'NOT ENOUGH CHILDREN, increasing the range to {MATE_DISTANCE * self._mating_multiplier}' + f' (multiplier: {self._mating_multiplier})') + elif n > 10: + self._mating_multiplier /= self._mating_increase_rate + self._log.info(f'TOO MANY CHILDREN, decreasing the range to {MATE_DISTANCE * self._mating_multiplier}' + f' (multiplier: {self._mating_multiplier})') + + self._recent_children.clear() + + async def mating_season(self): + """ + Checks if mating condition are met for all couple of robots. If so, it produces a new robot from crossover. + That robot is inserted into the population. + """ + + class BreakIt(Exception): + pass + + try: + if len(self._robots) > MAX_POP: + raise BreakIt + for individual1 in self._robots: + if not individual1.mature(): + continue + for individual2 in self._robots: + if len(self._robots) > MAX_POP: + raise BreakIt + if individual1 is individual2: + continue + + individual3 = individual1.mate(individual2, mating_distance_multiplier=self._mating_multiplier) + if individual3 is None: + continue + + self._recent_children.append(individual3) + + self._robot_id_counter += 1 + individual3.genotype.id = self._robot_id_counter + + # pos3 = (individual1.pos() + individual2.pos())/2 + # pos3.z = Z_SPAWN_DISTANCE + try: + if REPRODUCE_LOCALLY: + pos3 = (individual1.pos() + individual2.pos())/2 + pos3 = self._free_random_spawn_pos_area(pos3) + else: + pos3 = self._free_random_spawn_pos() + self._log.debug( + f'Attempting mate between {individual1} and {individual2} generated {individual3} POP({len(self._robots)})') + await self._insert_individual(individual3, pos3) + self._log.info( + f'MATE!!!! between {individual1} and {individual2} generated {individual3} POP({len(self._robots)})') + except Population.NoPositionFound: + self._log.info('Space is too crowded! Cannot insert the new individual, giving up.') + except asyncio.TimeoutError: + self._log.info( + f'MATE failed!!!! between {individual1} and {individual2} generated {individual3} POP({len(self._robots)})') + else: + self._robots.append(individual3) + + except BreakIt: + pass + + async def pause(self, pause, how_many_times=20): + counter = 0 + while True: + try: + await asyncio.wait_for(self._connection.pause(pause), 0.2) + return + except asyncio.TimeoutError: + counter += 1 + if counter > how_many_times: + raise + + async def create_snapshot(self): + await self.pause(True) + await asyncio.sleep(0.05) + snapshot_folder = await self._connection.create_snapshot(pause_when_saving=False) + + population_snapshot_data = { + # 'log': self._log, + 'data_folder': self._data_folder, + # 'connection': self._connection, + 'robots': [], + 'robot_id_counter': self._robot_id_counter, + 'mating_multiplier': self._mating_multiplier, + 'mating_increase_rate': self._mating_increase_rate, + 'recent_children': [r.name for r in self._recent_children], + 'recent_children_start_time': self._recent_children_start_time, + 'recent_children_delta_time': self._recent_children_delta_time, + } + + for robot in self._robots: + population_snapshot_data['robots'].append(robot.snapshot_data()) + + sys.setrecursionlimit(10000) + with open(os.path.join(snapshot_folder, 'online_population.pickle'), 'wb') as f: + pickle.dump(population_snapshot_data, f, protocol=-1) + + await self.pause(False) + + +async def run(): + # Parse command line / file input arguments + settings = parser.parse_args() + + # create ata folder and logger + data_folder = os.path.join(DATA_FOLDER_BASE, settings.experiment_name) + data_folder = make_folders(data_folder) + log = logger.create_logger('experiment', handlers=[ + logging.StreamHandler(sys.stdout), + logging.FileHandler(os.path.join(data_folder, 'experiment_manager.log'), mode='w') + ]) + + # Set debug level to DEBUG + log.setLevel(logging.DEBUG) + + # Save settings + experimental_settings = { + 'START': { + 'human': time.strftime("%a, %d %b %Y %H:%M:%S"), + 'seconds': time.time(), + }, + 'ROBOT_BATTERY': ROBOT_BATTERY, + 'ROBOT_STOP': ROBOT_STOP, + 'ROBOT_SELF_COLLIDE': ROBOT_SELF_COLLIDE, + 'REPRODUCE_LOCALLY_RADIUS': REPRODUCE_LOCALLY_RADIUS, + 'INDIVIDUAL_MAX_AGE': INDIVIDUAL_MAX_AGE, + 'INDIVIDUAL_MAX_AGE_SIGMA': INDIVIDUAL_MAX_AGE_SIGMA, + 'SEED_POPULATION_START': SEED_POPULATION_START, + 'MIN_POP': MIN_POP, + 'MAX_POP': MAX_POP, + 'Z_SPAWN_DISTANCE': Z_SPAWN_DISTANCE, + 'LIMIT_X': LIMIT_X, + 'LIMIT_Y': LIMIT_Y, + 'MATURE_AGE': MATURE_AGE, + 'MATE_DISTANCE': MATE_DISTANCE, + 'MATING_COOLDOWN': MATING_COOLDOWN, + 'COUPLE_MATING_LIMIT': COUPLE_MATING_LIMIT, + 'MATING_INCREASE_RATE': MATING_INCREASE_RATE, + 'RECENT_CHILDREN_DELTA_TIME': RECENT_CHILDREN_DELTA_TIME, + + 'PLASTICODING_CONF.max_structural_modules': PLASTICODING_CONF.max_structural_modules, + 'CROSSOVER_PROBABILITY': CROSSOVER_CONF.crossover_prob, + 'MUTATION_PROBABILITY': MUTATION_CONF.mutation_prob, + + # FOLDER WHERE TO SAVE THE EXPERIMENT + # {current_folder}/data/{arguments.experiment_name} + # example ~/projects/revolve/experiments/unmanaged/data/default_experiment + 'DATA_FOLDER_BASE': DATA_FOLDER_BASE, + } + with open(os.path.join(data_folder, 'experimental_settings.yaml'), 'w') as f: + f.write(str(yaml.dump(experimental_settings))) + + # Start Simulator + if settings.simulator_cmd != 'debug': + def simulator_dead(_process, ret_code): + log.error("SIMULATOR DIED BEFORE THE END OF THE EXPERIMENT") + sys.exit(ret_code) + + simulator_supervisor = DynamicSimSupervisor( + world_file=settings.world, + simulator_cmd=settings.simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name='gazebo', + process_terminated_callback=simulator_dead, + ) + await simulator_supervisor.launch_simulator(port=settings.port_start) + # let there be some time to sync all initial output of the simulator + await asyncio.sleep(5) + + # Connect to the simulator and pause + connection = await World.create(settings, world_address=('127.0.0.1', settings.port_start)) + connection.output_directory = os.path.join(data_folder, 'snapshots') + await asyncio.sleep(1) + + robot_population = Population(log, data_folder, connection) + + log.info("SEEDING POPULATION STARTED") + await robot_population.seed_initial_population(pause_while_inserting=False) + log.info("SEEDING POPULATION FINISHED") + + # Start the main life loop + try: + last_snapshot = connection.last_time + + log.info("creating initial snapshot") + success = await robot_population.create_snapshot() + + while True: + world_time = connection.last_time + if float(world_time - last_snapshot) > SNAPSHOT_TIME: + log.info(f"Creating snapshot at {world_time}") + last_snapshot = world_time + success = await robot_population.create_snapshot() + await robot_population.death_season() + await robot_population.mating_season() + await robot_population.immigration_season() + robot_population.adjust_mating_multiplier(connection.age()) + + await asyncio.sleep(0.05) + except Finish: + await asyncio.wait_for(connection.disconnect(), 10) + if settings.simulator_cmd != 'debug': + await asyncio.wait_for(simulator_supervisor.stop(), 10) + log.info("EVOLUTION finished successfully") diff --git a/grid.py b/grid.py deleted file mode 100644 index 7cde9dae96..0000000000 --- a/grid.py +++ /dev/null @@ -1,149 +0,0 @@ -class Grid: - # Current position of last drawn element - x_pos = 0 - y_pos = 0 - - # Orientation of robot - orientation = 1 - - # Direction of last movement - previous_move = -1 - - # Coordinates and orientation of movements - movement_stack = [[0,0,1]] - - # Coordinates of visited positions - visited_coordinates = [] - - def get_position(self): - """Return current position on x and y axis""" - return [Grid.x_pos, Grid.y_pos] - - def set_position(self, x, y): - """Set position of x and y axis""" - Grid.x_pos = x - Grid.y_pos = y - - def set_orientation(self, orientation): - """Set new orientation on grid""" - if orientation in [0, 1, 2, 3]: - Grid.orientation = orientation - else: - return False - - def calculate_orientation(self): - """Set orientation by previous move and orientation""" - if (Grid.previous_move == -1 or - (Grid.previous_move == 1 and Grid.orientation == 1) or - (Grid.previous_move == 2 and Grid.orientation == 3) or - (Grid.previous_move == 3 and Grid.orientation == 2) or - (Grid.previous_move == 0 and Grid.orientation == 0)): - self.set_orientation(1) - elif ((Grid.previous_move == 2 and Grid.orientation == 1) or - (Grid.previous_move == 0 and Grid.orientation == 3) or - (Grid.previous_move == 1 and Grid.orientation == 2) or - (Grid.previous_move == 3 and Grid.orientation == 0)): - self.set_orientation(2) - elif ((Grid.previous_move == 0 and Grid.orientation == 1) or - (Grid.previous_move == 3 and Grid.orientation == 3) or - (Grid.previous_move == 2 and Grid.orientation == 2) or - (Grid.previous_move == 1 and Grid.orientation == 0)): - self.set_orientation(0) - elif ((Grid.previous_move == 3 and Grid.orientation == 1) or - (Grid.previous_move == 1 and Grid.orientation == 3) or - (Grid.previous_move == 0 and Grid.orientation == 2) or - (Grid.previous_move == 2 and Grid.orientation == 0)): - self.set_orientation(3) - - def move_by_slot(self, slot): - """Move in direction by slot id""" - if slot == 0: - self.move_down() - elif slot == 1: - self.move_up() - elif slot == 2: - self.move_right() - elif slot == 3: - self.move_left() - - def move_right(self): - """Set position one to the right in correct orientation""" - if Grid.orientation == 1: - Grid.x_pos += 1 - elif Grid.orientation == 2: - Grid.y_pos += 1 - elif Grid.orientation == 0: - Grid.x_pos -= 1 - elif Grid.orientation == 3: - Grid.y_pos -= 1 - Grid.previous_move = 2 - - def move_left(self): - """Set position one to the left""" - if Grid.orientation == 1: - Grid.x_pos -= 1 - elif Grid.orientation == 2: - Grid.y_pos -= 1 - elif Grid.orientation == 0: - Grid.x_pos += 1 - elif Grid.orientation == 3: - Grid.y_pos += 1 - Grid.previous_move = 3 - - def move_up(self): - """Set position one upwards""" - if Grid.orientation == 1: - Grid.y_pos -= 1 - elif Grid.orientation == 2: - Grid.x_pos += 1 - elif Grid.orientation == 0: - Grid.y_pos += 1 - elif Grid.orientation == 3: - Grid.x_pos -= 1 - Grid.previous_move = 1 - - def move_down(self): - """Set position one downwards""" - if Grid.orientation == 1: - Grid.y_pos += 1 - elif Grid.orientation == 2: - Grid.x_pos -= 1 - elif Grid.orientation == 0: - Grid.y_pos -= 1 - elif Grid.orientation == 3: - Grid.x_pos += 1 - Grid.previous_move = 0 - - def move_back(self): - if len(Grid.movement_stack) > 1: - Grid.movement_stack.pop() - last_movement = Grid.movement_stack[-1] - Grid.x_pos = last_movement[0] - Grid.y_pos = last_movement[1] - Grid.orientation = last_movement[2] - - def add_to_visited(self): - """Add current position to visited coordinates list""" - self.calculate_orientation() - Grid.visited_coordinates.append([Grid.x_pos, Grid.y_pos]) - Grid.movement_stack.append([Grid.x_pos, Grid.y_pos, Grid.orientation]) - - def calculate_grid_dimensions(self): - min_x = 0 - max_x = 0 - min_y = 0 - max_y = 0 - for coorinate in Grid.visited_coordinates: - min_x = coorinate[0] if coorinate[0] < min_x else min_x - max_x = coorinate[0] if coorinate[0] > max_x else max_x - min_y = coorinate[1] if coorinate[1] < min_y else min_y - max_y = coorinate[1] if coorinate[1] > max_y else max_y - return [min_x, max_x, min_y, max_y] - - def reset_grid(self): - Grid.x_pos = 0 - Grid.y_pos = 0 - Grid.orientation = 1 - Grid.previous_move = -1 - Grid.movement_stack = [[0,0,1]] - Grid.visited_coordinates = [] \ No newline at end of file diff --git a/models/tilted10/_DS_Store b/models/tilted10/_DS_Store new file mode 100644 index 0000000000..bcd77eecca Binary files /dev/null and b/models/tilted10/_DS_Store differ diff --git a/models/tilted10/meshes/_DS_Store b/models/tilted10/meshes/_DS_Store new file mode 100644 index 0000000000..5008ddfcf5 Binary files /dev/null and b/models/tilted10/meshes/_DS_Store differ diff --git a/models/tilted10/meshes/tilted10.dae b/models/tilted10/meshes/tilted10.dae new file mode 100644 index 0000000000..d4dcc52856 --- /dev/null +++ b/models/tilted10/meshes/tilted10.dae @@ -0,0 +1,60 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9 + + 2019-02-15T17:26:03 + 2019-02-15T17:26:03 + + Z_UP + + + + + + + -1 -1 0 1 -1 0 -1 1 0 1 1 0 + + + + + + + + + + 0 0 1 + + + + + + + + + + + + + + +

1 0 2 0 0 0 1 0 3 0 2 0

+
+
+
+
+ + + + + 11.4651 0 0 -1.166869 0 7.966063 -0.1736482 0 0 1.404632 0.9848077 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/models/tilted10/model.config b/models/tilted10/model.config new file mode 100644 index 0000000000..9c8d506a9c --- /dev/null +++ b/models/tilted10/model.config @@ -0,0 +1,16 @@ + + + + Ground Plane + 1.0 + model.sdf + + + Nate Koenig + nate@osrfoundation.org + + + + A simple ground plane. + + diff --git a/models/tilted15/_DS_Store b/models/tilted15/_DS_Store new file mode 100644 index 0000000000..ccee22c72b Binary files /dev/null and b/models/tilted15/_DS_Store differ diff --git a/models/tilted15/meshes/tilted15.dae b/models/tilted15/meshes/tilted15.dae new file mode 100644 index 0000000000..a86e715a4d --- /dev/null +++ b/models/tilted15/meshes/tilted15.dae @@ -0,0 +1,60 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9 + + 2018-12-15T14:44:07 + 2018-12-15T14:44:07 + + Z_UP + + + + + + + -1 -1 0 1 -1 0 -1 1 0 1 1 0 + + + + + + + + + + 0 0 1 + + + + + + + + + + + + + + +

1 0 2 0 0 0 1 0 3 0 2 0

+
+
+
+
+ + + + + 8.902934 0 0 -0.4008482 0 7.533279 -0.258819 0.02747059 0 2.018536 0.9659258 0.03747463 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/models/tilted15/model.config b/models/tilted15/model.config new file mode 100644 index 0000000000..9c8d506a9c --- /dev/null +++ b/models/tilted15/model.config @@ -0,0 +1,16 @@ + + + + Ground Plane + 1.0 + model.sdf + + + Nate Koenig + nate@osrfoundation.org + + + + A simple ground plane. + + diff --git a/models/tilted5/_DS_Store b/models/tilted5/_DS_Store new file mode 100644 index 0000000000..3e2ee46b7a Binary files /dev/null and b/models/tilted5/_DS_Store differ diff --git a/models/tilted5/meshes/_DS_Store b/models/tilted5/meshes/_DS_Store new file mode 100644 index 0000000000..5008ddfcf5 Binary files /dev/null and b/models/tilted5/meshes/_DS_Store differ diff --git a/models/tilted5/meshes/tilted5.dae b/models/tilted5/meshes/tilted5.dae new file mode 100644 index 0000000000..cfd6e5d22a --- /dev/null +++ b/models/tilted5/meshes/tilted5.dae @@ -0,0 +1,60 @@ + + + + + Blender User + Blender 2.79.0 commit date:2018-03-22, commit time:14:10, hash:f4dc9f9 + + 2019-02-15T17:30:33 + 2019-02-15T17:30:33 + + Z_UP + + + + + + + -1 -1 0 1 -1 0 -1 1 0 1 1 0 + + + + + + + + + + 0 0 1 + + + + + + + + + + + + + + +

1 0 2 0 0 0 1 0 3 0 2 0

+
+
+
+
+ + + + + 11.96257 0 0 -0.3712567 0 8.040138 -0.08715573 0 0 0.7034209 0.9961947 0 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/models/tilted5/model.config b/models/tilted5/model.config new file mode 100644 index 0000000000..9c8d506a9c --- /dev/null +++ b/models/tilted5/model.config @@ -0,0 +1,16 @@ + + + + Ground Plane + 1.0 + model.sdf + + + Nate Koenig + nate@osrfoundation.org + + + + A simple ground plane. + + diff --git a/pyrevolve/SDF/joint.py b/pyrevolve/SDF/joint.py index c3ae7d574e..220ebec0f5 100644 --- a/pyrevolve/SDF/joint.py +++ b/pyrevolve/SDF/joint.py @@ -19,7 +19,7 @@ def __init__(self, super().__init__( 'joint', { - 'id': _id, + # 'id': _id, 'name': name, 'type': 'revolute' }, diff --git a/pyrevolve/SDF/link.py b/pyrevolve/SDF/link.py index fa58a71413..e1f9a3e78d 100644 --- a/pyrevolve/SDF/link.py +++ b/pyrevolve/SDF/link.py @@ -3,6 +3,7 @@ from pyrevolve import SDF from pyrevolve.SDF.inertial import transform_inertia_tensor +from ..custom_logging.logger import logger class Link(SDF.Posable): @@ -78,7 +79,7 @@ def calculate_inertial(self): raise RuntimeError("Inertial for this link already existing") if not np.allclose(self.get_center_of_mass().norm(), 0): - print("WARNING: calculating inertial for link with nonzero center of mass.", file=sys.stderr) + logger.warning("calculating inertial for link with nonzero center of mass.", file=sys.stderr) i_final = np.zeros((3, 3)) total_mass = 0.0 diff --git a/pyrevolve/SDF/pose.py b/pyrevolve/SDF/pose.py index 2c41726364..46c4d40beb 100644 --- a/pyrevolve/SDF/pose.py +++ b/pyrevolve/SDF/pose.py @@ -3,6 +3,7 @@ from pyrevolve import SDF import pyrevolve.SDF.math +from ..custom_logging.logger import logger class Pose(xml.etree.ElementTree.Element): @@ -237,13 +238,13 @@ def align(self, my_parent_normal = self.to_parent_direction(my.normal) at_parent_normal = of.to_parent_direction(-at.normal) if not my_parent_normal.parallel_to(at_parent_normal): - print("Vector angle: %f" % my_parent_normal.angle(at_parent_normal), file=sys.stderr) + logger.info("Vector angle: %f" % my_parent_normal.angle(at_parent_normal), file=sys.stderr) raise AssertionError("Normal vectors failed to align!") parent_tangent = self.to_parent_direction(my.tangent) at_parent_tangent = of.to_parent_direction(at.tangent) if not parent_tangent.parallel_to(at_parent_tangent): - print("Vector angle: %f" % parent_tangent.angle(at_parent_tangent), file=sys.stderr) + logger.info("Vector angle: %f" % parent_tangent.angle(at_parent_tangent), file=sys.stderr) raise AssertionError("Tangent vectors failed to align!") # Finally, translate so that `my` lands at `at` diff --git a/pyrevolve/SDF/revolve_bot_sdf_builder.py b/pyrevolve/SDF/revolve_bot_sdf_builder.py index bc972d90b8..a577f5f02a 100644 --- a/pyrevolve/SDF/revolve_bot_sdf_builder.py +++ b/pyrevolve/SDF/revolve_bot_sdf_builder.py @@ -5,7 +5,7 @@ from pyrevolve.revolve_bot.revolve_module import ActiveHingeModule, Orientation, BoxSlot -def revolve_bot_to_sdf(robot, robot_pose, nice_format): +def revolve_bot_to_sdf(robot, robot_pose, nice_format, self_collide=True): from xml.etree import ElementTree from pyrevolve import SDF @@ -19,13 +19,14 @@ def revolve_bot_to_sdf(robot, robot_pose, nice_format): pose_elem = SDF.Pose(robot_pose) model.append(pose_elem) - core_link = SDF.Link('Core') + core_link = SDF.Link('Core', self_collide=self_collide) core_visual, core_collision, imu_core_sensor = robot._body.to_sdf('', core_link) links = [core_link] joints = [] actuators = [] sensors = [imu_core_sensor] + collisions = [core_collision] core_link.append(core_visual) core_link.append(core_collision) @@ -38,15 +39,18 @@ def revolve_bot_to_sdf(robot, robot_pose, nice_format): children_links, \ children_joints, \ - children_sensors = _module_to_sdf(child_module, - core_link, - core_slot, - core_collision, - slot_chain) + children_sensors, \ + children_collisions = _module_to_sdf(child_module, + core_link, + core_slot, + core_collision, + slot_chain, + self_collide) links.extend(children_links) joints.extend(children_joints) sensors.extend(children_sensors) + collisions.extend(children_collisions) for joint in joints: model.append(joint) @@ -117,7 +121,7 @@ def _sdf_attach_module(module_slot, module_orientation: float, collision.translate(collision.to_parent_direction(old_translation)) -def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, slot_chain=''): +def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, slot_chain, self_collide): """ Recursive function that takes a module and returns a list of SDF links and joints that that module and his children have generated. @@ -132,13 +136,14 @@ def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, links = [] joints = [] sensors = [] + collisions = [] my_link = parent_link my_collision = None # ACTIVE HINGE if type(module) is ActiveHingeModule: - child_link = SDF.Link('{}_Leg'.format(slot_chain)) + child_link = SDF.Link('{}_Leg'.format(slot_chain), self_collide=self_collide) visual_frame, collisions_frame, \ visual_servo, collisions_servo, \ @@ -165,6 +170,7 @@ def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, parent_link.append(visual_frame) for i, collision_frame in enumerate(collisions_frame): parent_link.append(collision_frame) + collisions.append(collision_frame) if i != 0: old_pos = collision_frame.get_position() collision_frame.set_rotation(visual_frame.get_rotation()) @@ -175,6 +181,7 @@ def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, child_link.append(visual_servo) for i, collision_servo in enumerate(collisions_servo): child_link.append(collision_servo) + collisions.append(collision_servo) if i != 0: old_pos = collision_servo.get_position() collision_servo.set_position(collisions_servo[0].get_position()) @@ -201,6 +208,7 @@ def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, parent_link.append(visual) parent_link.append(collision) + collisions.append(collision) my_collision = collision @@ -213,20 +221,22 @@ def _module_to_sdf(module, parent_link, parent_slot: BoxSlot, parent_collision, continue my_slot = module.boxslot(Orientation(my_slot)) - slot_chain = '{}{}'.format(slot_chain, my_slot.orientation.short_repr()) + child_slot_chain = '{}{}'.format(slot_chain, my_slot.orientation.short_repr()) children_links, \ children_joints, \ - children_sensors = _module_to_sdf(child_module, - my_link, - my_slot, - my_collision, - slot_chain) + children_sensors, \ + children_collisions = _module_to_sdf(child_module, + my_link, + my_slot, + my_collision, + child_slot_chain, self_collide) links.extend(children_links) joints.extend(children_joints) sensors.extend(children_sensors) + collisions.extend(children_collisions) - return links, joints, sensors + return links, joints, sensors, collisions def _sdf_brain_plugin_conf( @@ -252,10 +262,11 @@ def _sdf_brain_plugin_conf( attrib={ 'name': 'robot_controller', 'filename': controller_plugin, - 'xmlns:rv': 'https://github.com/ci-group/revolve', }) - config = xml.etree.ElementTree.SubElement(plugin, 'rv:robot_config') + config = xml.etree.ElementTree.SubElement(plugin, 'rv:robot_config', { + 'xmlns:rv': 'https://github.com/ci-group/revolve', + }) # update rate SDF.sub_element_text(config, 'rv:update_rate', update_rate) diff --git a/pyrevolve/angle/manage/robotmanager.py b/pyrevolve/angle/manage/robotmanager.py index b58b0dccba..678fa50bfc 100644 --- a/pyrevolve/angle/manage/robotmanager.py +++ b/pyrevolve/angle/manage/robotmanager.py @@ -4,8 +4,10 @@ import numpy as np from collections import deque -from pyrevolve.SDF.math import Vector3 +from pyrevolve.SDF.math import Vector3, Quaternion from pyrevolve.util import Time +import math +import os class RobotManager(object): @@ -20,7 +22,7 @@ def __init__( time, battery_level=0.0, speed_window=60, - warmup_time=0, + warmup_time=0.0, ): """ :param speed_window: @@ -33,6 +35,7 @@ def __init__( :type battery_level: float :return: """ + self.dead = False self.warmup_time = warmup_time self.speed_window = speed_window self.robot = robot @@ -47,15 +50,23 @@ def __init__( self._ds = deque(maxlen=speed_window) self._dt = deque(maxlen=speed_window) self._positions = deque(maxlen=speed_window) + self._orientations = deque(maxlen=speed_window) + self._contacts = deque(maxlen=speed_window) + self._seconds = deque(maxlen=speed_window) self._times = deque(maxlen=speed_window) - self._positions.append(position) - self._times.append(time) - self._dist = 0 self._time = 0 self._idx = 0 self._count = 0 + self.second = 1 + self.count_group = 1 + self.avg_roll = 0 + self.avg_pitch = 0 + self.avg_yaw = 0 + self.avg_x = 0 + self.avg_y = 0 + self.avg_z = 0 @property def name(self): @@ -74,9 +85,19 @@ def update_state(self, world, time, state, poses_file): :type poses_file: csv.writer :return: """ + dead = state.dead if state.dead is not None else False + self.dead = dead or self.dead + pos = state.pose.position position = Vector3(pos.x, pos.y, pos.z) + rot = state.pose.orientation + qua = Quaternion(rot.w, rot.x, rot.y, rot.z) + euler = qua.get_rpy() + euler = np.array([euler[0], euler[1], euler[2]]) # roll / pitch / yaw + + age = world.age() + if self.starting_time is None: self.starting_time = time self.last_update = time @@ -121,44 +142,16 @@ def update_state(self, world, time, state, poses_file): self._times.append(time) self._ds.append(ds) self._dt.append(dt) + self._orientations.append(euler) + self._seconds.append(age.sec) - def velocity(self): - """ - Returns the velocity over the maintained window - :return: - """ - return self._dist / self._time if self._time > 0 else 0 - - def displacement(self): - """ - Returns a tuple of the displacement in both time and space - between the first and last registered element in the speed - window. - :return: Tuple where the first item is a displacement vector - and the second a `Time` instance. - :rtype: tuple(Vector3, Time) - """ - if self.last_position is None: - return Vector3(0, 0, 0), Time() - - return ( - self._positions[-1] - self._positions[0], - self._times[-1] - self._times[0] - ) + def update_contacts(self, world, module_contacts): - def displacement_velocity(self): - """ - Returns the displacement velocity, i.e. the velocity - between the first and last recorded position of the - robot in the speed window over a straight line, - ignoring the path that was taken. - :return: - """ - dist, time = self.displacement() - if time.is_zero(): - return 0.0 + number_contacts = 0 + for position in module_contacts.position: + number_contacts += 1 - return np.sqrt(dist.x**2 + dist.y**2) / float(time) + self._contacts.append(number_contacts) def age(self): """ diff --git a/pyrevolve/angle/manage/world.py b/pyrevolve/angle/manage/world.py index 6a09bdc274..31c8fd9a9b 100644 --- a/pyrevolve/angle/manage/world.py +++ b/pyrevolve/angle/manage/world.py @@ -11,6 +11,7 @@ from asyncio import Future from datetime import datetime from pygazebo.msg import gz_string_pb2 +from pygazebo.msg.contacts_pb2 import Contacts from pyrevolve.SDF.math import Vector3 from pyrevolve.spec.msgs import BoundingBox @@ -19,9 +20,9 @@ from .robotmanager import RobotManager from ...gazebo import manage from ...gazebo import RequestHandler -from ...logging import logger from ...util import multi_future from ...util import Time +from ...custom_logging.logger import logger class WorldManager(manage.WorldManager): @@ -54,8 +55,8 @@ def __init__( :return: """ super(WorldManager, self).__init__( - _private=_private, - world_address=world_address, + _private=_private, + world_address=world_address, ) self.battery_handler = None @@ -86,15 +87,16 @@ def __init__( self.do_restore = None - if output_directory: + # Sorry Matteo + if False: #output_directory: if not restore: - restore = datetime.now()\ + restore = datetime.now() \ .strftime(datetime.now().strftime('%Y%m%d%H%M%S')) self.output_directory = os.path.join(output_directory, restore) if not os.path.exists(self.output_directory): - os.mkdir(self.output_directory) + os.makedirs(self.output_directory) self.snapshot_filename = \ os.path.join(self.output_directory, 'snapshot.pickle') @@ -105,8 +107,7 @@ def __init__( self.do_restore = pickle.load(snapshot_file) except Exception as e: traceback.print_exc() - print("Cannot restore snapshot, shutting down. " - "Exception: {}.".format(str(e))) + logger.exception("Cannot restore snapshot, shutting down.") sys.exit(23) self.world_snapshot_filename = \ @@ -174,9 +175,9 @@ async def create( :return: """ self = cls( - _private=cls._PRIVATE, - world_address=world_address, - state_update_frequency=pose_update_frequency + _private=cls._PRIVATE, + world_address=world_address, + state_update_frequency=pose_update_frequency ) await self._init(builder=None, generator=None) return self @@ -201,74 +202,100 @@ async def _init(self): await (super(WorldManager, self)._init()) # Subscribe to pose updates - self.pose_subscriber = self.manager.subscribe( + self.pose_subscriber = await self.manager.subscribe( '/gazebo/default/revolve/robot_states', 'revolve.msgs.RobotStates', self._update_states ) - await (self.set_state_update_frequency( - freq=self.state_update_frequency - )) + self.contact_subscriber = await self.manager.subscribe( + '/gazebo/default/physics/contacts', + 'gazebo.msgs.Contacts', + self._update_contacts + ) - self.battery_handler = await (RequestHandler.create( - manager=self.manager, - advertise='/gazebo/default/battery_level/request', - subscribe='/gazebo/default/battery_level/response', - # There will not be robots yet, so don't wait for this - wait_for_publisher=False, - wait_for_subscriber=False - )) + # Awaiting this immediately will lock the program + update_state_future = self.set_state_update_frequency( + freq=self.state_update_frequency + ) + + self.battery_handler = await RequestHandler.create( + manager=self.manager, + advertise='/gazebo/default/battery_level/request', + subscribe='/gazebo/default/battery_level/response', + # There will not be robots yet, so don't wait for this + wait_for_publisher=False, + wait_for_subscriber=False + ) # Wait for connections - await (self.pose_subscriber.wait_for_connection()) + await self.pose_subscriber.wait_for_connection() + await self.contact_subscriber.wait_for_connection() + await update_state_future if self.do_restore: await (self.restore_snapshot(self.do_restore)) - async def create_snapshot(self): + async def disconnect(self): + await super().disconnect() + await self.pose_subscriber.remove() + await self.contact_subscriber.remove() + await self.battery_handler.stop() + + async def create_snapshot(self, pause_when_saving=True): """ Creates a snapshot of the world in the output directory. This pauses the world. - :return: + :return: the folder of the snapshot """ if not self.output_directory: logger.warning("No output directory - no snapshot will be created.") - return False + return None # Pause the world - await (self.pause()) + if pause_when_saving: + await self.pause(True) # Obtain a copy of the current world SDF from Gazebo and write it to # file - response = await (self.request_handler.do_gazebo_request( - request="world_sdf" - )) + response = await self.request_handler.do_gazebo_request( + request="world_sdf" + ) if response.response == "error": logger.warning("WARNING: requesting world state resulted in " "error. Snapshot failed.") - return False - - msg = gz_string_pb2.GzString() - msg.ParseFromString(response.serialized_data) - with open(self.world_snapshot_filename, 'wb') as f: - f.write(msg.data) - - # Get the snapshot data and pickle to file - data = await (self.get_snapshot_data()) - - # It seems pickling causes some issues with the default recursion - # limit, up it - sys.setrecursionlimit(10000) - with open(self.snapshot_filename, 'wb') as f: - pickle.dump(data, f, protocol=-1) - - # Flush statistic files and copy them - self.poses_file.flush() - self.robots_file.flush() - shutil.copy(self.poses_filename, self.poses_filename+'.snapshot') - shutil.copy(self.robots_filename, self.robots_filename+'.snapshot') - return True + await self.pause(False) + return None + + try: + snapshot_folder = os.path.join(self.output_directory, str(self.last_time)) + os.makedirs(snapshot_folder) + + msg = gz_string_pb2.GzString() + msg.ParseFromString(response.serialized_data) + with open(os.path.join(snapshot_folder, 'snapshot.sdf'), 'wb') as f: + f.write(msg.data.encode()) + + # Get the snapshot data and pickle to file + data = self.get_snapshot_data() + + # It seems pickling causes some issues with the default recursion + # limit, up it + sys.setrecursionlimit(10000) + with open(os.path.join(snapshot_folder, 'snapshot.pickle'), 'wb') as f: + pickle.dump(data, f, protocol=-1) + + # # WHAT IS THIS? + # # Flush statistic files and copy them + # self.poses_file.flush() + # self.robots_file.flush() + # shutil.copy(self.poses_filename, self.poses_filename+'.snapshot') + # shutil.copy(self.robots_filename, self.robots_filename+'.snapshot') + finally: + if pause_when_saving: + await self.pause(False) + + return snapshot_folder async def restore_snapshot(self, data): """ @@ -283,7 +310,7 @@ async def restore_snapshot(self, data): self.start_time = data['start_time'] self.last_time = data['last_time'] - async def get_snapshot_data(self): + def get_snapshot_data(self): """ Returns a data object to be pickled into a snapshot file. This should contain @@ -303,12 +330,12 @@ async def set_state_update_frequency(self, freq): :type freq: int :return: """ - future = await (self.request_handler.do_gazebo_request( - request="set_robot_state_update_frequency", - data=str(freq) - )) + result = await self.request_handler.do_gazebo_request( + request="set_robot_state_update_frequency", + data=str(freq) + ) self.state_update_frequency = freq - return future + return result def get_robot_id(self): """ @@ -384,6 +411,7 @@ async def insert_robot( self, revolve_bot, pose=Vector3(0, 0, 0.05), + life_timeout=None, ): """ Inserts a robot into the world. This consists of two steps: @@ -401,27 +429,31 @@ async def insert_robot( :type revolve_bot: RevolveBot :param pose: Insertion pose of a robot :type pose: Pose|Vector3 + :param life_timeout: Life span of the robot + :type life_timeout: float|None :return: A future that resolves with the created `Robot` object. """ + + # if the ID is digit, when removing the robot, the simulation will try to remove random stuff from the + # environment and give weird crash errors + assert(not str(revolve_bot.id).isdigit()) + sdf_bot = revolve_bot.to_sdf(pose) - if self.output_directory: - robot_file_path = os.path.join( - self.output_directory, - 'robot_{}.sdf'.format(revolve_bot.id) - ) - with open(robot_file_path, 'w') as f: - f.write(sdf_bot) - - future = Future() - insert_future = await self.insert_model(sdf_bot) - # TODO: Unhandled error in exception handler. Fix this. - insert_future.add_done_callback(lambda fut: self._robot_inserted( + # if self.output_directory: + # robot_file_path = os.path.join( + # self.output_directory, + # 'robot_{}.sdf'.format(revolve_bot.id) + # ) + # with open(robot_file_path, 'w') as f: + # f.write(sdf_bot) + + response = await self.insert_model(sdf_bot, life_timeout) + robot_manager = self._robot_inserted( robot=revolve_bot, - msg=fut.result(), - return_future=future - )) - return future + msg=response + ) + return robot_manager def to_sdfbot( self, @@ -439,7 +471,7 @@ def to_sdfbot( :rtype: SDF """ raise NotImplementedError( - "Implement in subclass if you want to use this method.") + "Implement in subclass if you want to use this method.") async def delete_robot(self, robot): """ @@ -450,8 +482,7 @@ async def delete_robot(self, robot): # Immediately unregister the robot so no it won't be used # for anything else while it is being deleted. self.unregister_robot(robot) - future = await (self.delete_model(robot.name, req="delete_robot")) - return future + return await self.delete_model(robot.name, req="delete_robot") async def delete_all_robots(self): """ @@ -461,7 +492,7 @@ async def delete_all_robots(self): """ futures = [] for bot in list(self.robot_managers.values()): - future = await (self.delete_robot(bot)) + future = self.delete_robot(bot) futures.append(future) return multi_future(futures) @@ -469,8 +500,7 @@ async def delete_all_robots(self): def _robot_inserted( self, robot, - msg, - return_future + msg ): """ Registers a newly inserted robot and marks the insertion @@ -479,8 +509,6 @@ def _robot_inserted( :param robot: RevolveBot :param msg: :type msg: pygazebo.msgs.response_pb2.Response - :param return_future: Future to resolve with the created robot object. - :type return_future: Future :return: """ inserted = ModelInserted() @@ -491,12 +519,12 @@ def _robot_inserted( position = Vector3(p.x, p.y, p.z) robot_manager = self.create_robot_manager( - robot, - position, - time + robot, + position, + time ) self.register_robot(robot_manager) - return_future.set_result(robot_manager) + return robot_manager def create_robot_manager( self, @@ -512,9 +540,9 @@ def create_robot_manager( :rtype: RobotManager """ return RobotManager( - robot=robot, - position=position, - time=time, + robot=robot, + position=position, + time=time, ) def register_robot(self, robot_manager): @@ -522,9 +550,8 @@ def register_robot(self, robot_manager): Registers a robot with its Gazebo ID in the local array. :param robot_manager: :type robot_manager: RobotManager - :return: """ - logger.debug("Registering robot {}.".format(robot_manager.name)) + logger.info("Registering robot {}.".format(robot_manager.name)) if robot_manager.name in self.robot_managers: raise ValueError("Duplicate robot: {}".format(robot_manager.name)) @@ -537,9 +564,8 @@ def unregister_robot(self, robot_manager): it is deleted. :param robot_manager: :type robot_manager: RobotManager - :return: """ - logger.debug("Unregistering robot {}.".format(robot_manager.name)) + logger.info("Unregistering robot {}.".format(robot_manager.name)) del self.robot_managers[robot_manager.name] async def reset(self, **kwargs): @@ -559,12 +585,11 @@ async def update_battery_level(self, robot): :param robot: :return: """ - future = await (self.battery_handler.do_gazebo_request( - request="set_battery_level", - data=robot.name, - dbl_data=robot.get_battery_level() - )) - return future + return await self.battery_handler.do_gazebo_request( + request="set_battery_level", + data=robot.name, + dbl_data=robot.get_battery_level() + ) async def update_battery_levels(self): """ @@ -573,7 +598,7 @@ async def update_battery_levels(self): """ futures = [] for robot in self.robot_list(): - fut = await (self.update_battery_level(robot)) + fut = self.update_battery_level(robot) futures.append(fut) if futures: @@ -599,22 +624,49 @@ def _update_states(self, msg): """ states = RobotStates() states.ParseFromString(msg) - self.last_time = t = Time(msg=states.time) if self.start_time is None or t < self.start_time: # A lower start time may indicate a world reset, which # we should copy. self.start_time = t + touched = {} + # mark all as dead and make alive only the robots that received data + for _name, robot_manager in self.robot_managers.items(): + touched[robot_manager] = False + + # mark robots alive and receive their states for state in states.robot_state: robot_manager = self.robot_managers.get(state.name, None) if not robot_manager: continue - + touched[robot_manager] = True robot_manager.update_state(self, t, state, self.write_poses) + for robot_manager, touch in touched.items(): + if not touch: + robot_manager.dead = True + self.call_update_triggers() + def _update_contacts(self, msg): + """ + Handles the contacts with the ground info message by updating robot contacts. + :param msg: + :return: + """ + contacts = Contacts() + contacts.ParseFromString(msg) + # if there was any contact in that instant + if contacts.contact: + # fetches one or more contact points for each module that has contacts + for module_contacts in contacts.contact: + robot_name = module_contacts.collision1.split('::')[0] + robot_manager = self.robot_managers.get(robot_name, None) + if not robot_manager: + continue + robot_manager.update_contacts(self, module_contacts) + def add_update_trigger(self, callback): """ Adds an update trigger, a function called every time the local diff --git a/pyrevolve/config.py b/pyrevolve/config.py index a58ed52131..2f22e1bd56 100644 --- a/pyrevolve/config.py +++ b/pyrevolve/config.py @@ -1,5 +1,3 @@ -from __future__ import absolute_import - import argparse @@ -8,6 +6,7 @@ class CustomParser(argparse.ArgumentParser): Extends argument parser to add some simple file reading / writing functionality. """ + def convert_arg_line_to_args(self, arg_line): """ Simple arg line converter that returns `--my-argument value` from @@ -23,7 +22,7 @@ def convert_arg_line_to_args(self, arg_line): if split < 0: return [arg_line] - k, v = "--"+arg_line[:split].replace("_", "-"), arg_line[1+split:] + k, v = "--" + arg_line[:split].replace("_", "-"), arg_line[1 + split:] # Try to determine if this key is a store constant action, if so # return only the key. @@ -65,177 +64,93 @@ def str_to_address(v): parser = CustomParser(fromfile_prefix_chars='@') -parser.add_argument( - '--sensor-update-rate', - default=8, type=int, - help='The rate at which Gazebo sensors are set to update their values.' -) - -parser.add_argument( - '--controller-update-rate', - default=8, type=int, - help='The rate at which the `RobotController` is requested to update.' -) - -parser.add_argument( - '--visualize-sensors', - default=False, type=bool, - help='Visualize sensors (helpful for debugging purposes)' -) parser.add_argument( - '--pose-update-frequency', - default=5, type=int, - help="The frequency at which the world is requested to send robot pose" - " updates (in number of times per *simulation* second)." -) - -parser.add_argument( - '--evaluation-time', - default=12, type=float, - help="The size of the `speed window` for each robot, i.e. the number of " - "past (simulation) seconds over which its speed is evaluated. In " - "offline evolution, this determines the length of the experiment run." -) - -parser.add_argument( - '--min-parts', - default=3, type=int, - help="Minimum number of parts in a robot." -) - -parser.add_argument( - '--max-parts', - default=30, type=int, - help="Maximum number of parts in a robot." -) - -parser.add_argument( - '--initial-parts-mu', - default=12, type=int, - help="Mean part count of generated robots." -) - -parser.add_argument( - '--initial-parts-sigma', - default=5, type=int, - help="Standard deviation of part count in generated robots." -) - -parser.add_argument( - '--max-inputs', - default=10, type=int, - help="Maximum number of inputs (i.e. sensors) in a robot." -) - -parser.add_argument( - '--max-outputs', - default=10, type=int, - help="Maximum number of outputs (i.e. motors) in a robot." -) - -parser.add_argument( - '--enforce-planarity', - default=True, type=str_to_bool, - help="Force bricks to be in default orientation and disable parametric " - "bar joint rotation." -) - -parser.add_argument( - '--body-mutation-epsilon', - default=0.05, type=float, - help="Mutation epsilon for robot body parameters." -) - -parser.add_argument( - '--brain-mutation-epsilon', - default=0.1, type=float, - help="Mutation epsilon for robot neural net parameters." -) - -parser.add_argument( - '--p-duplicate-subtree', - default=0.1, type=float, - help="Probability of duplicating a subtree." + '--manager', + default=None, + type=str, + help="Determine which manager to use. Defaults to no manager." ) parser.add_argument( - '--p-connect-neurons', - default=0.1, type=float, - help="Initial connection probability." + '--experiment-name', + default='default_experiment', type=str, + help="Name of current experiment. A folder with this name will be created. Default to \"default_experiment\"." ) parser.add_argument( - '--p-swap-subtree', - default=0.05, type=float, - help="Probability of swapping two subtrees." + '--run', + default='1', type=str, + help="Run of repetition of an experiment. Default to \"1\"." ) parser.add_argument( - '--p-delete-subtree', - default=0.05, type=float, - help="Probability of deleting a subtree." + '--test-robot', + default=None, type=str, + help="Alternative to --manager. Start a simulation with a single robot instead of running evolution." + "Loads a yaml robot." ) parser.add_argument( - '--p-remove-brain-connection', - default=0.05, type=float, - help="Probability of removing a neural network connection." + '--test-robot-collision', + default=None, type=str, + help="Alternative to --manager. Tests the collision of a single robot. " + "Loads a yaml robot." ) parser.add_argument( - '--p-delete-hidden-neuron', - default=0.05, type=float, - help="Probability of deleting a random hidden neuron." + '--simulator-cmd', + default='gzserver', type=str, + help="Determine whether to use gzserver or gazebo. Default to \"gzserver\"." ) parser.add_argument( - '--world-address', - default="127.0.0.1:11345", type=str, - help="Host:port of the simulator." + '--n-cores', + default=1, type=int, + help="Number of simulators to use at the same time. Default to \"1\"." ) parser.add_argument( - '--simulator-cmd', - default='gzserver', type=str, - help="Determine wether to use gzserver or gazebo." + '--port-start', + default=11345, type=int, + help="Gazebo ports [start_port, start_port + n_cores + n_analyzers]. Default to \"11345\"." ) parser.add_argument( '--world', - default='worlds/gait-learning.world', type=str, - help="Determine which world to use." -) - -parser.add_argument( - '--manager', - # default='experiments/examples/manager.py', - type=str, - help="Determine which manager to use." + default='worlds/plane.world', type=str, + help="Determine which world gazebo should use." + "Usefull not only to change the environment, but also the physical properties of the world " + "and the simulation/real time ratio (you can use the dedicated real time worlds). " + "Defaults to \"worlds/plane.world\"." ) parser.add_argument( - '--robot-name', - default="spider", type=str, - help="Name of robot." + '--z-start', + default=0.03, type=float, + help="Position in the z axis where the robot is placed at the beginning of the simulation. " + "Default \"0.03\"." ) parser.add_argument( - '--experiment-round', - default="1", type=str, - help="Round of robot experiment." + '--evaluation-time', + default=30, type=float, + help="In offline evolution, this determines the length of the experiment run." + # For old_online_fitness: + # "The size of the `speed window` for each robot, i.e. the number of " + # "past (simulation) seconds over which its speed is evaluated." ) parser.add_argument( - '--brain-conf-path', - default="rlpower.cfg", type=str, - help="Path to brain configuration." + '--recovery-enabled', + default=True, type=str_to_bool, + help="Whether the recovery is enabled (save and load the recovery both). Default \"True\"." ) parser.add_argument( - '--load-controller', - default=None, type=str, - help="Path to controller data." + '--export-phenotype', + default=True, type=str_to_bool, + help="Exports yamls with the phenotypes. Default \"True\"." ) # Directory where robot information will be written. The system writes @@ -255,115 +170,33 @@ def str_to_address(v): parser.add_argument( '--output-directory', default="output", type=str, - help="Directory where robot statistics are written." + help="OLD. Directory where robot statistics are written. Default \"output\"." ) parser.add_argument( '--restore-directory', default="restore", type=str, - help="Explicit subdirectory of the output directory, if a world " - "state is present in this directory it will be restored." -) - -parser.add_argument( - '--disable-sensors', - default=False, type=str_to_bool, - help="Disables all sensors - overriding specific sensor settings." - "In practice this means that the core component is created without " - "an IMU sensor, whereas the other sensor parts are not enabled at all." -) - -parser.add_argument( - '--enable-touch-sensor', - default=True, type=str_to_bool, - help="Enable / disable the touch sensor in robots." -) - -parser.add_argument( - '--enable-light-sensor', - default=False, type=str_to_bool, - help="Enable / disable the light sensor in robots." -) - -parser.add_argument( - '--warmup-time', - default=0, type=float, - help="The number of seconds the robot is initially ignored, allows it to " - "e.g. topple over when put down without that being counted as " - "movement. Especially helps when dropping robots from the sky at " - "the start." -) - -parser.add_argument( - '--fitness-size-factor', - default=0, type=float, - help="Multiplication factor of robot size in the fitness function. Note " - "that this needs to be negative to discount size." -) - -parser.add_argument( - '--fitness-velocity-factor', - default=1.0, type=float, - help="Multiplication factor of robot velocity in the fitness function." + help="OLD. Explicit subdirectory of the output directory, if a world " + "state is present in this directory it will be restored. Default \"restore\"." ) parser.add_argument( - '--fitness-displacement-factor', - default=5.0, type=float, - help="Multiplication factor of robot displacement velocity (= velocity in " - "a straight line in the fitness function." -) - -parser.add_argument( - '--fitness-size-discount', - default=0, type=float, - help="Another possible way of discounting robot size, multiplies the " - "previously calculated fitness by (1 - d * size) where `d` is this " - "discount factor." -) - -parser.add_argument( - '--fitness-limit', - default=1.0, type=float, - help="Minimum fitness value that is considered unrealistic and should " - "probably be attributed to a simulator instability. A fitness of " - "zero is returned in this case." + '--sensor-update-rate', + default=8, type=int, + help='The rate at which Gazebo sensors are set to update their values. Default \"8\".' ) parser.add_argument( - '--tournament-size', - default=4, type=int, - help="The size of the random tournament used for parent selection, if" - " selection is enabled. When individuals are chosen for reproduction," - " this number of possible parents is randomly sampled from the " - "population, and out of these the best is chosen. A larger number " - "here means higher selection pressure but less selection variance " - "and vice versa." + '--controller-update-rate', + default=8, type=int, + help='The rate at which the `RobotController` is requested to update. Default \"8\".' ) parser.add_argument( - '--max-mating-attempts', + '--pose-update-frequency', default=5, type=int, - help="Maximum number of mating attempts between two parents." -) - - -parser.add_argument( - '--world-step-size', - default=0.003, type=float, - help="The physics step size configured in the simulation world file." - "This needs to match in order to configure some physics parameters." -) -parser.add_argument( - '--learner', - default='ann', type=str, - help="The learner used for robot's gait learning." -) -parser.add_argument( - '--genome', - default=None, type=str, - help="A robot's genome in YAML format. It is easier to transfer it " - "than to convert it from SDF." + help="The frequency at which the world is requested to send robot pose" + " updates (in number of times per *simulation* second). Default \"5\"." ) @@ -374,8 +207,5 @@ def make_revolve_config(conf): """ conf.enable_wheel_parts = False - conf.brain_conf = { - 'learner': conf.learner, - 'genome': conf.genome, - } + conf.brain_conf = {} return conf diff --git a/pyrevolve/logging/__init__.py b/pyrevolve/custom_logging/__init__.py similarity index 58% rename from pyrevolve/logging/__init__.py rename to pyrevolve/custom_logging/__init__.py index d18777b318..c3961685ab 100644 --- a/pyrevolve/logging/__init__.py +++ b/pyrevolve/custom_logging/__init__.py @@ -1,3 +1 @@ from __future__ import absolute_import - -from .logger import logger diff --git a/pyrevolve/custom_logging/logger.py b/pyrevolve/custom_logging/logger.py new file mode 100644 index 0000000000..f9dc68d3d6 --- /dev/null +++ b/pyrevolve/custom_logging/logger.py @@ -0,0 +1,33 @@ +from __future__ import absolute_import + +import logging +import sys + + +def create_logger(name='revolve', level=logging.DEBUG, handlers=None): + _logger = logging.getLogger(name) + _logger.setLevel(level) + handlers = logging.StreamHandler(sys.stdout) if handlers is None else handlers + handlers = [handlers] if type(handlers) is not list else handlers + for handler in handlers: + _console_handler = handler + _console_handler.setLevel(level) + _revolve_formatter = logging.Formatter('[%(asctime)s %(name)10s] %(levelname)-8s %(message)s') + _console_handler.setFormatter(_revolve_formatter) + _logger.addHandler(_console_handler) + return _logger + + +# General logger to standard output +logger = create_logger( + name='revolve', + level=logging.DEBUG, + handlers=[logging.StreamHandler(sys.stdout), logging.FileHandler('./revolve.log', mode='a')] +) + +# Genotype logger for logging mutation and crossover details to a file +genotype_logger = create_logger( + name='genotype', + level=logging.INFO, + handlers=logging.FileHandler('./genotype.log', mode='a') +) diff --git a/pyrevolve/data_analisys/check_robot_collision.py b/pyrevolve/data_analisys/check_robot_collision.py new file mode 100644 index 0000000000..8c102e6715 --- /dev/null +++ b/pyrevolve/data_analisys/check_robot_collision.py @@ -0,0 +1,70 @@ +import asyncio +import logging +import os + +import sys +import time + +from pyrevolve import parser +from pyrevolve.custom_logging import logger +from pyrevolve.gazebo.analyze import BodyAnalyzer +from pyrevolve.revolve_bot import RevolveBot +from pyrevolve.util.supervisor.supervisor_collision import CollisionSimSupervisor + + +async def test_collision_robot(robot_file_path: str): + log = logger.create_logger('experiment', handlers=[ + logging.StreamHandler(sys.stdout), + ]) + + # Set debug level to DEBUG + log.setLevel(logging.DEBUG) + + # Parse command line / file input arguments + settings = parser.parse_args() + + assert (settings.test_robot_collision is not None) + robot = RevolveBot(_id=settings.test_robot_collision) + robot.load_file(robot_file_path, conf_type='yaml') + robot.save_file(f'{robot_file_path}.sdf', conf_type='sdf') + + def simulator_died_callback(_process, _ret_code): + pass + + # Start Simulator + if settings.simulator_cmd != 'debug': + simulator_supervisor = CollisionSimSupervisor( + world_file=os.path.join('tools', 'analyzer', 'analyzer-world.world'), + simulator_cmd=settings.simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name='gazebo', + process_terminated_callback=simulator_died_callback, + ) + await simulator_supervisor.launch_simulator(port=settings.port_start) + await asyncio.sleep(0.1) + + log.debug("simulator ready") + + # Connect to the simulator and pause + analyzer = await BodyAnalyzer.create('127.0.0.1', settings.port_start) + log.debug("connection ready") + await asyncio.sleep(1) + + log.info("Sending robot to the analyzer simulator") + start = time.time() + result = await analyzer.analyze_robot(robot) + end = time.time() + + log.debug(f'Analyzer finished in {end-start}') + log.debug('result:') + log.debug(result) + + await analyzer.disconnect() + log.debug("disconnected") + + if settings.simulator_cmd != 'debug': + await simulator_supervisor.stop() + + log.debug("simulator killed") diff --git a/pyrevolve/data_analisys/visualize_robot.py b/pyrevolve/data_analisys/visualize_robot.py new file mode 100644 index 0000000000..aada5c5bab --- /dev/null +++ b/pyrevolve/data_analisys/visualize_robot.py @@ -0,0 +1,61 @@ +import asyncio +import logging +import sys +import os + +from pyrevolve import parser +from pyrevolve.custom_logging import logger +from pyrevolve.revolve_bot import RevolveBot +from pyrevolve.SDF.math import Vector3 +from pyrevolve.tol.manage import World +from pyrevolve.util.supervisor.supervisor_multi import DynamicSimSupervisor +from pyrevolve.evolution import fitness + + +async def test_robot_run(robot_file_path: str): + log = logger.create_logger('experiment', handlers=[ + logging.StreamHandler(sys.stdout), + ]) + + # Set debug level to DEBUG + log.setLevel(logging.DEBUG) + + # Parse command line / file input arguments + settings = parser.parse_args() + + # Start Simulator + if settings.simulator_cmd != 'debug': + simulator_supervisor = DynamicSimSupervisor( + world_file=settings.world, + simulator_cmd=settings.simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name='gazebo' + ) + await simulator_supervisor.launch_simulator(port=settings.port_start) + await asyncio.sleep(0.1) + + # Connect to the simulator and pause + connection = await World.create(settings, world_address=('127.0.0.1', settings.port_start)) + await asyncio.sleep(1) + + # init finished + + robot = RevolveBot(_id=settings.test_robot) + robot.load_file(robot_file_path, conf_type='yaml') + robot.save_file(f'{robot_file_path}.sdf', conf_type='sdf') + + await connection.pause(True) + robot_manager = await connection.insert_robot(robot, Vector3(0, 0, 0.25), life_timeout=None) + await asyncio.sleep(1.0) + + # Start the main life loop + while True: + # Print robot fitness every second + status = 'dead' if robot_manager.dead else 'alive' + print(f"Robot fitness ({status}) is \n" + f" OLD: {fitness.online_old_revolve(robot_manager)}\n" + f" DISPLAC: {fitness.displacement(robot_manager, robot)}\n" + f" DIS_VEL: {fitness.displacement_velocity(robot_manager, robot)}") + await asyncio.sleep(1.0) diff --git a/pyrevolve/evolution/__init__.py b/pyrevolve/evolution/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/pyrevolve/evolution/fitness.py b/pyrevolve/evolution/fitness.py new file mode 100644 index 0000000000..95be1c03cf --- /dev/null +++ b/pyrevolve/evolution/fitness.py @@ -0,0 +1,83 @@ +import random as py_random +from pyrevolve.tol.manage import measures + + +def stupid(_robot_manager, robot): + return 1.0 + + +def random(_robot_manager, robot): + return py_random.random() + + +def displacement(robot_manager, robot): + displacement_vec = measures.displacement(robot_manager)[0] + displacement_vec.z = 0 + return displacement_vec.magnitude() + + +def displacement_velocity(robot_manager, robot): + return measures.displacement_velocity(robot_manager) + + +def online_old_revolve(robot_manager): + """ + Fitness is proportional to both the displacement and absolute + velocity of the center of mass of the robot, in the formula: + + (1 - d l) * (a dS + b S + c l) + + Where dS is the displacement over a direct line between the + start and end points of the robot, S is the distance that + the robot has moved and l is the robot size. + + Since we use an active speed window, we use this formula + in context of velocities instead. The parameters a, b and c + are modifyable through config. + :return: fitness value + """ + # these parameters used to be command line parameters + warmup_time = 0.0 + v_fac = 1.0 # fitness_velocity_factor + d_fac = 5.0 # fitness_displacement_factor + s_fac = 0.0 # fitness_size_factor + fitness_size_discount = 0.0 + fitness_limit = 1.0 + + age = robot_manager.age() + if age < (0.25 * robot_manager.conf.evaluation_time) \ + or age < warmup_time: + # We want at least some data + return 0.0 + + d = 1.0 - (fitness_size_discount * robot_manager.size) + v = d * (d_fac * measures.displacement_velocity(robot_manager) + + v_fac * measures.velocity(robot_manager) + + s_fac * robot_manager.size) + return v if v <= fitness_limit else 0.0 + + +def displacement_velocity_hill(robot_manager, robot): + _displacement_velocity_hill = measures.displacement_velocity_hill(robot_manager) + if _displacement_velocity_hill < 0: + _displacement_velocity_hill /= 10 + elif _displacement_velocity_hill == 0: + _displacement_velocity_hill = -0.1 + # temp elif + # elif _displacement_velocity_hill > 0: + # _displacement_velocity_hill *= _displacement_velocity_hill + + return _displacement_velocity_hill + + +def floor_is_lava(robot_manager, robot): + _displacement_velocity_hill = measures.displacement_velocity_hill(robot_manager) + _contacts = measures.contacts(robot_manager, robot) + + _contacts = max(_contacts, 0.0001) + if _displacement_velocity_hill >= 0: + fitness = _displacement_velocity_hill / _contacts + else: + fitness = _displacement_velocity_hill * _contacts + + return fitness diff --git a/pyrevolve/evolution/individual.py b/pyrevolve/evolution/individual.py new file mode 100644 index 0000000000..c2448b3423 --- /dev/null +++ b/pyrevolve/evolution/individual.py @@ -0,0 +1,56 @@ +# (G,P) + + +class Individual: + def __init__(self, genotype, phenotype=None): + """ + Creates an Individual object with the given genotype and optionally the phenotype. + + :param genotype: genotype of the individual + :param phenotype (optional): phenotype of the individual + """ + self.genotype = genotype + self.phenotype = phenotype + self.fitness = None + self.parents = None + self.failed_eval_attempt_count = 0 + + def develop(self): + """ + Develops genotype into a intermediate phenotype + + """ + if self.phenotype is None: + self.phenotype = self.genotype.develop() + + @property + def id(self): + _id = None + if self.phenotype is not None: + _id = self.phenotype.id + elif self.genotype.id is not None: + _id = self.genotype.id + return _id + + def export_genotype(self, folder): + self.genotype.export_genotype(f'{folder}/genotypes/genotype_{self.phenotype.id}.txt') + + def export_phenotype(self, folder): + if self.phenotype is not None: + self.phenotype.save_file(f'{folder}/phenotypes/{self.phenotype.id}.yaml', conf_type='yaml') + + def export_fitness(self, folder): + """ + It's saving the fitness into a file. The fitness can be a floating point number or None + :param folder: folder where to save the fitness + """ + with open(f'{folder}/fitness_{self.id}.txt', 'w') as f: + f.write(str(self.fitness)) + + def export(self, folder): + self.export_genotype(folder) + self.export_phenotype(folder) + self.export_fitness(folder) + + def __repr__(self): + return f'Individual_{self.id}({self.fitness})' diff --git a/pyrevolve/evolution/pop_management/__init__.py b/pyrevolve/evolution/pop_management/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/pyrevolve/evolution/pop_management/generational.py b/pyrevolve/evolution/pop_management/generational.py new file mode 100644 index 0000000000..56aba792e2 --- /dev/null +++ b/pyrevolve/evolution/pop_management/generational.py @@ -0,0 +1,3 @@ +def generational_population_management(old_individuals, new_individuals): + assert (len(old_individuals) == len(new_individuals)) + return new_individuals diff --git a/pyrevolve/evolution/pop_management/steady_state.py b/pyrevolve/evolution/pop_management/steady_state.py new file mode 100644 index 0000000000..1f675664c7 --- /dev/null +++ b/pyrevolve/evolution/pop_management/steady_state.py @@ -0,0 +1,8 @@ +from pyrevolve.evolution.selection import multiple_selection + + +def steady_state_population_management(old_individuals, new_individuals, selector): + pop_size = len(old_individuals) + selection_pool = old_individuals + new_individuals + + return multiple_selection(selection_pool, pop_size, selector) diff --git a/pyrevolve/evolution/population.py b/pyrevolve/evolution/population.py new file mode 100644 index 0000000000..45ad959032 --- /dev/null +++ b/pyrevolve/evolution/population.py @@ -0,0 +1,269 @@ +# [(G,P), (G,P), (G,P), (G,P), (G,P)] + +from pyrevolve.evolution.individual import Individual +from pyrevolve.SDF.math import Vector3 +from pyrevolve.tol.manage import measures +from ..custom_logging.logger import logger +import time +import asyncio +import os + + +class PopulationConfig: + def __init__(self, + population_size: int, + genotype_constructor, + genotype_conf, + fitness_function, + mutation_operator, + mutation_conf, + crossover_operator, + crossover_conf, + selection, + parent_selection, + population_management, + population_management_selector, + evaluation_time, + experiment_name, + experiment_management, + offspring_size=None, + next_robot_id=1): + """ + Creates a PopulationConfig object that sets the particular configuration for the population + + :param population_size: size of the population + :param genotype_constructor: class of the genotype used + :param genotype_conf: configuration for genotype constructor + :param fitness_function: function that takes in a `RobotManager` as a parameter and produces a fitness for the robot + :param mutation_operator: operator to be used in mutation + :param mutation_conf: configuration for mutation operator + :param crossover_operator: operator to be used in crossover + :param selection: selection type + :param parent_selection: selection type during parent selection + :param population_management: type of population management ie. steady state or generational + :param evaluation_time: duration of an experiment + :param experiment_name: name for the folder of the current experiment + :param experiment_management: object with methods for managing the current experiment + :param offspring_size (optional): size of offspring (for steady state) + """ + self.population_size = population_size + self.genotype_constructor = genotype_constructor + self.genotype_conf = genotype_conf + self.fitness_function = fitness_function + self.mutation_operator = mutation_operator + self.mutation_conf = mutation_conf + self.crossover_operator = crossover_operator + self.crossover_conf = crossover_conf + self.parent_selection = parent_selection + self.selection = selection + self.population_management = population_management + self.population_management_selector = population_management_selector + self.evaluation_time = evaluation_time + self.experiment_name = experiment_name + self.experiment_management = experiment_management + self.offspring_size = offspring_size + self.next_robot_id = next_robot_id + + +class Population: + def __init__(self, conf: PopulationConfig, simulator_queue, analyzer_queue=None, next_robot_id=1): + """ + Creates a Population object that initialises the + individuals in the population with an empty list + and stores the configuration of the system to the + conf variable. + + :param conf: configuration of the system + :param simulator_queue: connection to the simulator queue + :param analyzer_queue: connection to the analyzer simulator queue + :param next_robot_id: (sequential) id of the next individual to be created + """ + self.conf = conf + self.individuals = [] + self.analyzer_queue = analyzer_queue + self.simulator_queue = simulator_queue + self.next_robot_id = next_robot_id + + def _new_individual(self, genotype): + individual = Individual(genotype) + individual.develop() + self.conf.experiment_management.export_genotype(individual) + self.conf.experiment_management.export_phenotype(individual) + self.conf.experiment_management.export_phenotype_images(os.path.join('data_fullevolution', 'phenotype_images'), individual) + individual.phenotype.measure_phenotype() + individual.phenotype.export_phenotype_measurements(self.conf.experiment_management.data_folder) + + return individual + + async def load_individual(self, id): + data_path = self.conf.experiment_management.data_folder + genotype = self.conf.genotype_constructor(self.conf.genotype_conf, id) + genotype.load_genotype(os.path.join(data_path, 'genotypes', f'genotype_{id}.txt')) + + individual = Individual(genotype) + individual.develop() + individual.phenotype.measure_phenotype() + + with open(os.path.join(data_path, 'fitness', f'fitness_{id}.txt')) as f: + data = f.readlines()[0] + individual.fitness = None if data == 'None' else float(data) + + with open(os.path.join(data_path, 'descriptors', f'behavior_desc_{id}.txt')) as f: + lines = f.readlines() + if lines[0] == 'None': + individual.phenotype._behavioural_measurements = None + else: + individual.phenotype._behavioural_measurements = measures.BehaviouralMeasurements() + for line in lines: + if line.split(' ')[0] == 'velocity': + individual.phenotype._behavioural_measurements.velocity = float(line.split(' ')[1]) + #if line.split(' ')[0] == 'displacement': + # individual.phenotype._behavioural_measurements.displacement = float(line.split(' ')[1]) + if line.split(' ')[0] == 'displacement_velocity': + individual.phenotype._behavioural_measurements.displacement_velocity = float(line.split(' ')[1]) + if line.split(' ')[0] == 'displacement_velocity_hill': + individual.phenotype._behavioural_measurements.displacement_velocity_hill = float(line.split(' ')[1]) + if line.split(' ')[0] == 'head_balance': + individual.phenotype._behavioural_measurements.head_balance = float(line.split(' ')[1]) + if line.split(' ')[0] == 'contacts': + individual.phenotype._behavioural_measurements.contacts = float(line.split(' ')[1]) + + return individual + + async def load_snapshot(self, gen_num): + """ + Recovers all genotypes and fitnesses of robots in the lastest selected population + :param gen_num: number of the generation snapshot to recover + """ + data_path = self.conf.experiment_management.experiment_folder + for r, d, f in os.walk(data_path +'/selectedpop_'+str(gen_num)): + for file in f: + if 'body' in file: + id = file.split('.')[0].split('_')[-2]+'_'+file.split('.')[0].split('_')[-1] + self.individuals.append(await self.load_individual(id)) + + async def load_offspring(self, last_snapshot, population_size, offspring_size, next_robot_id): + """ + Recovers the part of an unfinished offspring + :param + :return: + """ + individuals = [] + # number of robots expected until the latest snapshot + if last_snapshot == -1: + n_robots = 0 + else: + n_robots = population_size + last_snapshot * offspring_size + + for robot_id in range(n_robots+1, next_robot_id): + individuals.append(await self.load_individual('robot_'+str(robot_id))) + + self.next_robot_id = next_robot_id + return individuals + + async def init_pop(self, recovered_individuals=[]): + """ + Populates the population (individuals list) with Individual objects that contains their respective genotype. + """ + for i in range(self.conf.population_size-len(recovered_individuals)): + individual = self._new_individual(self.conf.genotype_constructor(self.conf.genotype_conf, self.next_robot_id)) + self.individuals.append(individual) + self.next_robot_id += 1 + + await self.evaluate(self.individuals, 0) + self.individuals = recovered_individuals + self.individuals + + async def next_gen(self, gen_num, recovered_individuals=[]): + """ + Creates next generation of the population through selection, mutation, crossover + + :param gen_num: generation number + :param individuals: recovered offspring + :return: new population + """ + + new_individuals = [] + + for _i in range(self.conf.offspring_size-len(recovered_individuals)): + # Selection operator (based on fitness) + # Crossover + if self.conf.crossover_operator is not None: + parents = self.conf.parent_selection(self.individuals) + child_genotype = self.conf.crossover_operator(parents, self.conf.genotype_conf, self.conf.crossover_conf) + child = Individual(child_genotype) + else: + child = self.conf.selection(self.individuals) + + child.genotype.id = self.next_robot_id + self.next_robot_id += 1 + + # Mutation operator + child_genotype = self.conf.mutation_operator(child.genotype, self.conf.mutation_conf) + # Insert individual in new population + individual = self._new_individual(child_genotype) + + new_individuals.append(individual) + + # evaluate new individuals + await self.evaluate(new_individuals, gen_num) + + new_individuals = recovered_individuals + new_individuals + + # create next population + if self.conf.population_management_selector is not None: + new_individuals = self.conf.population_management(self.individuals, new_individuals, + self.conf.population_management_selector) + else: + new_individuals = self.conf.population_management(self.individuals, new_individuals) + new_population = Population(self.conf, self.simulator_queue, self.analyzer_queue, self.next_robot_id) + new_population.individuals = new_individuals + logger.info(f'Population selected in gen {gen_num} with {len(new_population.individuals)} individuals...') + + return new_population + + async def evaluate(self, new_individuals, gen_num, type_simulation = 'evolve'): + """ + Evaluates each individual in the new gen population + + :param new_individuals: newly created population after an evolution iteration + :param gen_num: generation number + """ + # Parse command line / file input arguments + # await self.simulator_connection.pause(True) + robot_futures = [] + for individual in new_individuals: + logger.info(f'Evaluating individual (gen {gen_num}) {individual.genotype.id} ...') + robot_futures.append(asyncio.ensure_future(self.evaluate_single_robot(individual))) + + await asyncio.sleep(1) + + for i, future in enumerate(robot_futures): + individual = new_individuals[i] + logger.info(f'Evaluation of Individual {individual.phenotype.id}') + individual.fitness, individual.phenotype._behavioural_measurements = await future + + if individual.phenotype._behavioural_measurements is None: + assert (individual.fitness is None) + + if type_simulation == 'evolve': + self.conf.experiment_management.export_behavior_measures(individual.phenotype.id, individual.phenotype._behavioural_measurements) + + logger.info(f'Individual {individual.phenotype.id} has a fitness of {individual.fitness}') + if type_simulation == 'evolve': + self.conf.experiment_management.export_fitness(individual) + + async def evaluate_single_robot(self, individual): + """ + :param individual: individual + :return: Returns future of the evaluation, future returns (fitness, [behavioural] measurements) + """ + if individual.phenotype is None: + individual.develop() + + if self.analyzer_queue is not None: + collisions, _bounding_box = await self.analyzer_queue.test_robot(individual, self.conf) + if collisions > 0: + logger.info(f"discarding robot {individual} because there are {collisions} self collisions") + return None, None + + return await self.simulator_queue.test_robot(individual, self.conf) diff --git a/pyrevolve/evolution/selection.py b/pyrevolve/evolution/selection.py new file mode 100644 index 0000000000..9b3e06cb8c --- /dev/null +++ b/pyrevolve/evolution/selection.py @@ -0,0 +1,41 @@ +from random import randint + +_neg_inf = -float('Inf') + + +def _compare_maj_fitness(indiv_1, indiv_2): + fit_1 = _neg_inf if indiv_1.fitness is None else indiv_1.fitness + fit_2 = _neg_inf if indiv_2.fitness is None else indiv_2.fitness + return fit_1 > fit_2 + + +def tournament_selection(population, k=2): + """ + Perform tournament selection and return best individual + :param k: amount of individuals to participate in tournament + """ + best_individual = None + for _ in range(k): + individual = population[randint(0, len(population) - 1)] + if (best_individual is None) or (_compare_maj_fitness(individual, best_individual)): + best_individual = individual + return best_individual + + +def multiple_selection(population, selection_size, selection_function): + """ + Perform selection on population of distinct group, can be used in the form parent selection or survival selection + :param population: parent selection in population + :param selection_size: amount of indivuals to select + :param selection_function: + """ + assert (len(population) >= selection_size) + selected_individuals = [] + for _ in range(selection_size): + new_individual = False + while new_individual is False: + selected_individual = selection_function(population) + if selected_individual not in selected_individuals: + selected_individuals.append(selected_individual) + new_individual = True + return selected_individuals diff --git a/pyrevolve/examples/analyze_body.py b/pyrevolve/examples/analyze_body.py index 174afa8601..636ceabf22 100644 --- a/pyrevolve/examples/analyze_body.py +++ b/pyrevolve/examples/analyze_body.py @@ -15,6 +15,7 @@ from pyrevolve.sdfbuilder.math import Vector3 from .generated_sdf import generate_robot, builder, robot_to_sdf from ..gazebo import get_analysis_robot, BodyAnalyzer +from ..custom_logging.logger import logger import asyncio @@ -25,7 +26,7 @@ seed = random.randint(0, 10000) random.seed(seed) -print("Seed: {}".format(seed), file=sys.stderr) +logger.info("Seed: {}".format(seed)) async def analysis_func(): @@ -40,27 +41,27 @@ async def analysis_func(): # Find out its intersections and bounding box intersections, bbox = await ( - analyzer.analyze_robot(robot, builder=builder)) + analyzer.analyze_robot(robot, builder=builder)) if intersections: - print("Invalid model - intersections detected.", file=sys.stderr) + logger.info("Invalid model - intersections detected.", file=sys.stderr) else: - print("No model intersections detected!", file=sys.stderr) + logger.info("No model intersections detected!", file=sys.stderr) if bbox: # Translate the model in z direction so it stands directly on # the ground - print("Model bounding box: ({}, {}, {}), ({}, {}, {})".format( - bbox.min.x, - bbox.min.y, - bbox.min.z, - bbox.max.x, - bbox.max.y, - bbox.max.z + logger.info("Model bounding box: ({}, {}, {}), ({}, {}, {})".format( + bbox.min.x, + bbox.min.y, + bbox.min.z, + bbox.max.x, + bbox.max.y, + bbox.max.z ), file=sys.stderr) model = sdf.elements[0] model.translate(Vector3(0, 0, -bbox.min.z)) - print(str(robot_to_sdf(robot, "test_bot", "controllerplugin.so"))) + logger.info(str(robot_to_sdf(robot, "test_bot", "controllerplugin.so"))) break loop = asyncio.get_event_loop() diff --git a/pyrevolve/examples/from_yaml.py b/pyrevolve/examples/from_yaml.py index c77b437197..67851e8234 100644 --- a/pyrevolve/examples/from_yaml.py +++ b/pyrevolve/examples/from_yaml.py @@ -10,6 +10,8 @@ from .generated_sdf import body_spec, brain_spec +from ..custom_logging.logger import logger + bot_yaml = ''' --- body: @@ -54,4 +56,4 @@ model.translate(Vector3(0, 0, 0.5)) sdf = SDF() sdf.add_element(model) -print(str(sdf)) +logger.info(str(sdf)) diff --git a/pyrevolve/examples/generated_sdf.py b/pyrevolve/examples/generated_sdf.py index a770208b41..f00d3f4993 100644 --- a/pyrevolve/examples/generated_sdf.py +++ b/pyrevolve/examples/generated_sdf.py @@ -32,6 +32,8 @@ from pyrevolve.build.sdf import VelocityMotor from pyrevolve.build.sdf import PID +from ..custom_logging.logger import logger + # Some configuration # This is the number of times per second we will call our # robot's brain update (in the default controller). We'll @@ -58,9 +60,9 @@ def apply_color(self): to all links in this body part. """ self.make_color( - self.part_params["red"], - self.part_params["green"], - self.part_params["blue"]) + self.part_params["red"], + self.part_params["green"], + self.part_params["blue"]) # Below, we define some body parts @@ -126,32 +128,32 @@ def _initialize(self, **kwargs): # (such as self_collide) which you generally need. length = kwargs["length"] self.var_block = self.create_component( - BoxGeom(length, self.y, self.z, 0.1), "var-block") + BoxGeom(length, self.y, self.z, 0.1), "var-block") # We move the block in the x-direction so that it # just about overlaps with the other block (to # make it seem like a somewhat realistic joint) self.var_block.translate( - Vector3(0.5 * (length + self.x) - self.JOINT_OFFSET, 0, 0)) + Vector3(0.5 * (length + self.x) - self.JOINT_OFFSET, 0, 0)) # Now create a revolute joint at this same position. The # joint axis is in the y-direction. axis = Vector3(0, 1, 0) passive_joint = Joint( - joint_type="revolute", - parent=self.component, - child=self.var_block, - axis=axis) + joint_type="revolute", + parent=self.component, + child=self.var_block, + axis=axis) # Set some movement limits on the joint passive_joint.axis.limit = Limit( - lower=math.radians(-45), - upper=math.radians(45), - effort=1.0) + lower=math.radians(-45), + upper=math.radians(45), + effort=1.0) # Set the joint position - in the child frame! passive_joint.set_position( - Vector3(-0.5 * length + self.JOINT_OFFSET, 0, 0)) + Vector3(-0.5 * length + self.JOINT_OFFSET, 0, 0)) # Don't forget to add the joint and the link self.add_joint(passive_joint) @@ -243,10 +245,10 @@ def _initialize(self, **kwargs): # Create revolute joint. Remember: joint position is in child frame motor_joint = Joint( - joint_type="revolute", - parent=self.component, - child=self.attachment, - axis=axis) + joint_type="revolute", + parent=self.component, + child=self.attachment, + axis=axis) motor_joint.set_position(Vector3(0, 0, -0.5 * box_size)) # Set a force limit on the joint @@ -259,12 +261,12 @@ def _initialize(self, **kwargs): pid = PID(proportional_gain=1.0, integral_gain=0.1) max_speed = 2 * math.pi * 50.0 / 60 self.motors.append(VelocityMotor( - part_id=self.id, - motor_id="rotate", - joint=motor_joint, - pid=pid, - min_velocity=-max_speed, - max_velocity=max_speed)) + part_id=self.id, + motor_id="rotate", + joint=motor_joint, + pid=pid, + min_velocity=-max_speed, + max_velocity=max_speed)) self.apply_color() def get_slot(self, slot_id): @@ -371,10 +373,10 @@ def generate_robot(robot_id=0): def robot_to_sdf(robot, name="test_bot", plugin_controller=None): model = builder.sdf_robot( - robot=robot, - controller_plugin=plugin_controller, - update_rate=UPDATE_RATE, - name=name) + robot=robot, + controller_plugin=plugin_controller, + update_rate=UPDATE_RATE, + name=name) model_sdf = SDF() model_sdf.add_element(model) return model_sdf @@ -388,4 +390,4 @@ def generate_sdf_robot(robot_id=0, plugin_controller=None, name="test_bot"): if __name__ == "__main__": # Create SDF and output sdf = generate_sdf_robot() - print(str(sdf)) + logger.info(str(sdf)) diff --git a/pyrevolve/experiment_management.py b/pyrevolve/experiment_management.py new file mode 100644 index 0000000000..af9f38207c --- /dev/null +++ b/pyrevolve/experiment_management.py @@ -0,0 +1,123 @@ +import os +import shutil +import numpy as np +from pyrevolve.custom_logging.logger import logger +import sys + + +class ExperimentManagement: + # ids of robots in the name of all types of files are always phenotype ids, and the standard for id is 'robot_ID' + + def __init__(self, settings): + self.settings = settings + manager_folder = os.path.dirname(self.settings.manager) + self._experiment_folder = os.path.join(manager_folder, 'data', self.settings.experiment_name, self.settings.run) + self._data_folder = os.path.join(self._experiment_folder, 'data_fullevolution') + + def create_exp_folders(self): + if os.path.exists(self.experiment_folder): + shutil.rmtree(self.experiment_folder) + os.makedirs(self.experiment_folder) + os.mkdir(self.data_folder) + os.mkdir(os.path.join(self.data_folder, 'genotypes')) + os.mkdir(os.path.join(self.data_folder, 'phenotypes')) + os.mkdir(os.path.join(self.data_folder, 'descriptors')) + os.mkdir(os.path.join(self.data_folder, 'fitness')) + os.mkdir(os.path.join(self.data_folder, 'phenotype_images')) + os.mkdir(os.path.join(self.data_folder, 'failed_eval_robots')) + + @property + def experiment_folder(self): + return self._experiment_folder + + @property + def data_folder(self): + return self._data_folder + + def export_genotype(self, individual): + if self.settings.recovery_enabled: + individual.export_genotype(self.data_folder) + + def export_phenotype(self, individual): + if self.settings.export_phenotype: + individual.export_phenotype(self.data_folder) + + def export_fitnesses(self, individuals): + folder = self.data_folder + for individual in individuals: + individual.export_fitness(folder) + + def export_fitness(self, individual): + folder = os.path.join(self.data_folder, 'fitness') + individual.export_fitness(folder) + + def export_behavior_measures(self, _id, measures): + filename = os.path.join(self.data_folder, 'descriptors', f'behavior_desc_{_id}.txt') + with open(filename, "w") as f: + if measures is None: + f.write(str(None)) + else: + for key, val in measures.items(): + f.write(f"{key} {val}\n") + + def export_phenotype_images(self, dirpath, individual): + individual.phenotype.render_body(os.path.join(self.experiment_folder, dirpath, f'body_{individual.phenotype.id}.png')) + individual.phenotype.render_brain(os.path.join(self.experiment_folder, dirpath, f'brain_{individual.phenotype.id}.png')) + + def export_failed_eval_robot(self, individual): + individual.genotype.export_genotype(os.path.join(self.data_folder, 'failed_eval_robots', f'genotype_{individual.phenotype.id}.txt')) + individual.phenotype.save_file(os.path.join(self.data_folder, 'failed_eval_robots', f'phenotype_{individual.phenotype.id}.yaml')) + individual.phenotype.save_file(os.path.join(self.data_folder, 'failed_eval_robots', f'phenotype_{individual.phenotype.id}.sdf'), conf_type='sdf') + + def export_snapshots(self, individuals, gen_num): + if self.settings.recovery_enabled: + path = os.path.join(self.experiment_folder, f'selectedpop_{gen_num}') + if os.path.exists(path): + shutil.rmtree(path) + os.mkdir(path) + for ind in individuals: + self.export_phenotype_images(f'selectedpop_{str(gen_num)}', ind) + logger.info(f'Exported snapshot {str(gen_num)} with {str(len(individuals))} individuals') + + def experiment_is_new(self): + if not os.path.exists(self.experiment_folder): + return True + path, dirs, files = next(os.walk(os.path.join(self.data_folder, 'fitness'))) + if len(files) == 0: + return True + else: + return False + + def read_recovery_state(self, population_size, offspring_size): + snapshots = [] + + for r, d, f in os.walk(self.experiment_folder): + for dir in d: + if 'selectedpop' in dir: + exported_files = len([name for name in os.listdir(os.path.join(self.experiment_folder, dir)) if os.path.isfile(os.path.join(self.experiment_folder, dir, name))]) + if exported_files == (population_size * 2): # body and brain files + snapshots.append(int(dir.split('_')[1])) + + if len(snapshots) > 0: + # the latest complete snapshot + last_snapshot = np.sort(snapshots)[-1] + # number of robots expected until the snapshot + n_robots = population_size + last_snapshot * offspring_size + else: + last_snapshot = -1 + n_robots = 0 + + robot_ids = [] + for r, d, f in os.walk(os.path.join(self.data_folder, 'fitness')): + for file in f: + robot_ids.append(int(file.split('.')[0].split('_')[-1])) + last_id = np.sort(robot_ids)[-1] + + # if there are more robots to recover than the number expected in this snapshot + if last_id > n_robots: + # then recover also this partial offspring + has_offspring = True + else: + has_offspring = False + + return last_snapshot, has_offspring, last_id+1 diff --git a/pyrevolve/gazebo/analyze.py b/pyrevolve/gazebo/analyze.py index b2bbf20ceb..88284ae450 100644 --- a/pyrevolve/gazebo/analyze.py +++ b/pyrevolve/gazebo/analyze.py @@ -1,14 +1,6 @@ -from __future__ import absolute_import -from __future__ import print_function - -import asyncio -import logging -import sys - -from pyrevolve.sdfbuilder import SDF -from pyrevolve.sdfbuilder.sensor import Sensor - -from ..spec import BodyAnalysisResponse +from pyrevolve.custom_logging.logger import logger +from pyrevolve.SDF.math import Vector3 +from pyrevolve.spec import BodyAnalysisResponse from .connect import connect, RequestHandler # Message ID sequencer, start at some high value to prevent ID clashes @@ -23,68 +15,13 @@ def _msg_id(): return r -# Prevent the trollius logging warning -kl = logging.getLogger("trollius") -kl.addHandler(logging.StreamHandler(sys.stdout)) - - -def get_analysis_robot(robot, builder): - """ - Creates an SDF model suitable for analysis from a robot object - and a builder. - :param robot: - :type robot: Robot - :param builder: - :type builder: BodyBuilder - :return: - """ - model = builder.sdf_robot( - robot=robot, - controller_plugin=None, - name="analyze_bot", - analyzer_mode=True) - model.remove_elements_of_type(Sensor, recursive=True) - sdf = SDF() - sdf.add_element(model) - return sdf - - -def analyze_body(sdf, address=("127.0.0.1", 11346)): - """ - Single body analyzer. Opens a new connection, analyzes the - body, and returns the result. If you already have a manager - running doing other things, create an instance of `BodyAnalyzer` - instead. - - :param sdf: SDF object consisting of BodyPart - instances. - :type sdf: SDF - :param address: Tuple of the hostname and port where the analyzer - resides. Note that the default is one up from the default - Gazebo port, since it is meant to be used with the - `run-analyzer.sh` tool. - :type address: (str, int) - :return: - :rtype: (bool, (float, float, float)) - """ - response_obj = [None] - - async def internal_analyze(): - analyzer = await (BodyAnalyzer.create(address)) - response_obj[0] = await (analyzer.analyze_sdf(sdf)) - - loop = asyncio.get_event_loop() - loop.run_until_complete(internal_analyze()) - return response_obj[0] - - class BodyAnalyzer(object): """ Class used to make body analysis requests. """ _PRIVATE = object() - def __init__(self, _private, address): + def __init__(self, _private, address, port): """ Private constructor - use the `create` coroutine instead. @@ -97,20 +34,21 @@ def __init__(self, _private, address): "the `create` coroutine.") self.address = address + self.port = port self.manager = None self.request_handler = None @classmethod - async def create(cls, address=("127.0.0.1", 11346)): + async def create(cls, address, port): """ Instantiates a new body analyzer at the given address. - :param address: host, port tuple. - :type address: (str, int) + :param address: hostname. + :param port: host port. :return: """ - self = cls(cls._PRIVATE, address) - await (self._init()) + self = cls(cls._PRIVATE, address, port) + await self._init() return self async def _init(self): @@ -118,22 +56,24 @@ async def _init(self): BodyAnalyzer initialization coroutine :return: """ - self.manager = await (connect(self.address)) + self.manager = await connect(self.address, self.port) self.request_handler = await ( RequestHandler.create(self.manager, msg_id_base=_msg_id())) - async def analyze_robot(self, robot, builder, max_attempts=5): + async def disconnect(self): + await self.manager.stop() + await self.request_handler.stop() + + async def analyze_robot(self, robot, max_attempts=5): """ Performs body analysis of a given Robot object. :param robot: :type robot: Robot - :param builder: - :type builder: Builder :param max_attempts: :return: """ - sdf = get_analysis_robot(robot, builder) - ret = await (self.analyze_sdf(sdf, max_attempts=max_attempts)) + sdf = robot.to_sdf(pose=Vector3(0, 0, 0)) + ret = await self.analyze_sdf(sdf, max_attempts=max_attempts) return ret async def analyze_sdf(self, sdf, max_attempts=5): @@ -149,17 +89,14 @@ async def analyze_sdf(self, sdf, max_attempts=5): msg = None rh = self.request_handler for _ in range(max_attempts): - future = await (rh.do_gazebo_request("analyze_body", str(sdf))) - await future - - response = future.result() + response = await rh.do_gazebo_request("analyze_body", str(sdf)) if response.response == "success": msg = BodyAnalysisResponse() msg.ParseFromString(response.serialized_data) break if not msg: - # Error return + logger.error("analyze_sdf returned not valid message") return None if msg.HasField("boundingBox"): diff --git a/pyrevolve/gazebo/connect.py b/pyrevolve/gazebo/connect.py index 6bd55bb3d6..ff47ce5c05 100644 --- a/pyrevolve/gazebo/connect.py +++ b/pyrevolve/gazebo/connect.py @@ -1,17 +1,18 @@ from __future__ import absolute_import -from asyncio import Future +import asyncio import pygazebo from pygazebo.msg import request_pb2, response_pb2 # Default connection address to keep things DRY. This is an array rather than # a tuple, so it is writeable as long as you change the separate elements. -default_address = ["127.0.0.1", 11345] +DEFAULT_ADDRESS = "127.0.0.1" +DEFAULT_PORT = 11345 -async def connect(address=default_address): - manager = await pygazebo.connect(address=tuple(address)) +async def connect(address=DEFAULT_ADDRESS, port=DEFAULT_PORT): + manager = await pygazebo.connect(address=address, port=port) return manager @@ -121,19 +122,22 @@ async def _init(self): if self.publisher is not None: return - self.subscriber = self.manager.subscribe( + self.subscriber = await self.manager.subscribe( self.subscribe, self.response_type, self._callback ) - self.publisher = await (self.manager.advertise( - self.advertise, self.request_type)) + self.publisher = await self.manager.advertise( + self.advertise, self.request_type) if self.wait_for_publisher: - await (self.subscriber.wait_for_connection()) + await self.subscriber.wait_for_connection() if self.wait_for_subscriber: - await (self.publisher.wait_for_listener()) + await self.publisher.wait_for_listener() + + async def stop(self): + await self.subscriber.remove() def _callback(self, data): """ @@ -151,6 +155,8 @@ def _callback(self, data): # Message was not requested here, ignore it return + #TODO why you save this here if you are about to delete this? + # deletion happens in self._handled() req[msg_id] = msg # Call the future's set_result @@ -213,7 +219,7 @@ async def do_gazebo_request( :param msg_id: Force the message to use this ID. Sequencer is used if no message ID is specified. :type msg_id: int - :return: + :return: Response to the request """ if msg_id is None: msg_id = self.get_msg_id() @@ -228,8 +234,7 @@ async def do_gazebo_request( if dbl_data is not None: req.dbl_data = dbl_data - future = await (self.do_request(req)) - return future + return await self.do_request(req) def _get_response_map(self, request_type): """ @@ -253,7 +258,7 @@ async def do_request(self, msg): from going over the same pipe. The returned future is for the response. :param msg: Message object to publish - :return: + :return: Response to the request """ msg_id = str(self.get_id_from_msg(msg)) request_type = str(self.get_request_type_from_msg(msg)) @@ -264,8 +269,13 @@ async def do_request(self, msg): "Duplicate request ID: `{}` for type `{}`".format( msg_id, request_type)) - future = Future() + future = asyncio.Future() req[msg_id] = None cb[msg_id] = future + + # Ensures the message is sent, but don't wait for it. + # it sends to multiple listeners, some of them stop responding after a while, making this function stop for no + # real reason await self.publisher.publish(msg) - return future + await future + return future.result() diff --git a/pyrevolve/gazebo/manage/world.py b/pyrevolve/gazebo/manage/world.py index 893794f999..c5452dac59 100644 --- a/pyrevolve/gazebo/manage/world.py +++ b/pyrevolve/gazebo/manage/world.py @@ -8,7 +8,8 @@ # Revolve from ..connect import connect, RequestHandler -from ...logging import logger +import logging +from ...custom_logging.logger import logger # Construct a message base from the time. This should make # it unique enough for consecutive use when the script @@ -58,12 +59,16 @@ async def create( :return: """ self = cls( - _private=cls._PRIVATE, - world_address=world_address, + _private=cls._PRIVATE, + world_address=world_address, ) await self._init() return self + async def disconnect(self): + await self.manager.stop() + await self.request_handler.stop() + async def _init(self): """ Initializes connections for the world manager @@ -74,20 +79,20 @@ async def _init(self): # Initialize the manager connections as well as the general request # handler - self.manager = await (connect(self.world_address)) + self.manager = await connect(self.world_address[0], self.world_address[1]) - self.world_control = await (self.manager.advertise( - topic_name='/gazebo/default/world_control', - msg_type='gazebo.msgs.WorldControl' - )) + self.world_control = await self.manager.advertise( + topic_name='/gazebo/default/world_control', + msg_type='gazebo.msgs.WorldControl' + ) - self.request_handler = await (RequestHandler.create( - manager=self.manager, - msg_id_base=MSG_BASE - )) + self.request_handler = await RequestHandler.create( + manager=self.manager, + msg_id_base=MSG_BASE + ) # Wait for connections - await (self.world_control.wait_for_listener()) + await self.world_control.wait_for_listener() async def pause(self, pause=True): """ @@ -96,13 +101,13 @@ async def pause(self, pause=True): :return: Future for the published message """ if pause: - logger.debug("Pausing the world.") + logger.info("Pausing the world.") else: - logger.debug("Resuming the world.") + logger.info("Resuming the world.") msg = world_control_pb2.WorldControl() msg.pause = pause - future = await (self.world_control.publish(msg)) + future = await self.world_control.publish(msg) return future async def reset( @@ -117,17 +122,15 @@ async def reset( :param model_only: :param time_only: :param rall: - :return: """ - logger.debug("Resetting the world state.") + logger.info("Resetting the world state.") msg = world_control_pb2.WorldControl() msg.reset.all = rall msg.reset.model_only = model_only msg.reset.time_only = time_only - future = await (self.world_control.publish(msg)) - return future + await self.world_control.publish(msg) - async def insert_model(self, sdf): + async def insert_model(self, sdf, timeout=None): """ Insert a model wrapped in an SDF tag into the world. Make sure it has a unique name, as it will be literally inserted into the @@ -139,13 +142,15 @@ async def insert_model(self, sdf): :param sdf: :type sdf: SDF + :param timeout: Life span of the model + :type timeout: float|None :return: """ - future = await (self.request_handler.do_gazebo_request( - request="insert_sdf", - data=str(sdf) - )) - return future + return await self.request_handler.do_gazebo_request( + request="insert_sdf", + data=str(sdf), + dbl_data=timeout, + ) async def delete_model( self, @@ -160,8 +165,7 @@ async def delete_model( occurring from deleting sensors. :return: """ - future = await (self.request_handler.do_gazebo_request( - request=req, - data=name - )) - return future + return await self.request_handler.do_gazebo_request( + request=req, + data=name + ) diff --git a/pyrevolve/generate/__init__.py b/pyrevolve/generate/__init__.py new file mode 100755 index 0000000000..e69de29bb2 diff --git a/pyrevolve/genotype/genotype.py b/pyrevolve/genotype/genotype.py index 69ad7074eb..4317fad3f4 100644 --- a/pyrevolve/genotype/genotype.py +++ b/pyrevolve/genotype/genotype.py @@ -1,6 +1,33 @@ - class Genotype: + def clone(self): + """ + Create an returns deep copy of the genotype + """ + raise NotImplementedError("Method must be implemented by genome") + + def develop(self): + """ + Develops the genome into a revolve_bot (proto-phenotype) + + :return: a RevolveBot instance + :rtype: RevolveBot + """ + raise NotImplementedError("Method must be implemented by genome") + - def __init__(self): - self.id = None - self.representation = None \ No newline at end of file +class GenotypeConfig: + def __init__(self, + e_max_groups, + axiom_w, + i_iterations, + weight_min, + weight_max, + oscillator_param_min, + oscillator_param_max): + self.e_max_groups = e_max_groups + self.axiom_w = axiom_w + self.i_iterations = i_iterations + self.weight_min = weight_min + self.weight_max = weight_max + self.oscillator_param_min = oscillator_param_min + self.oscillator_param_max = oscillator_param_max diff --git a/pyrevolve/genotype/plasticoding/crossover/__init__.py b/pyrevolve/genotype/plasticoding/crossover/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/pyrevolve/genotype/plasticoding/crossover/crossover.py b/pyrevolve/genotype/plasticoding/crossover/crossover.py new file mode 100644 index 0000000000..7e6d7e1cac --- /dev/null +++ b/pyrevolve/genotype/plasticoding/crossover/crossover.py @@ -0,0 +1,9 @@ +class CrossoverConfig: + def __init__(self, + crossover_prob): + """ + Creates a Crossover object that sets the configuration for the crossover operator + + :param crossover_prob: crossover probability + """ + self.crossover_prob = crossover_prob diff --git a/pyrevolve/genotype/plasticoding/crossover/standard_crossover.py b/pyrevolve/genotype/plasticoding/crossover/standard_crossover.py new file mode 100644 index 0000000000..d95ad6286c --- /dev/null +++ b/pyrevolve/genotype/plasticoding/crossover/standard_crossover.py @@ -0,0 +1,42 @@ +from pyrevolve.genotype.plasticoding.plasticoding import Plasticoding, Alphabet, PlasticodingConfig +from pyrevolve.evolution.individual import Individual +import random +from ....custom_logging.logger import genotype_logger + + +def generate_child_genotype(parent_genotypes, genotype_conf, crossover_conf): + """ + Generates a child (individual) by randomly mixing production rules from two parents + + :param parents: parents to be used for crossover + + :return: child genotype + """ + grammar = {} + crossover_attempt = random.uniform(0.0, 1.0) + if crossover_attempt > crossover_conf.crossover_prob: + grammar = parent_genotypes[0].grammar + else: + for letter in Alphabet.modules(): + parent = random.randint(0, 1) + # gets the production rule for the respective letter + grammar[letter[0]] = parent_genotypes[parent].grammar[letter[0]] + + genotype = Plasticoding(genotype_conf, 'tmp') + genotype.grammar = grammar + return genotype.clone() + + +def standard_crossover(parent_individuals, genotype_conf, crossover_conf): + """ + Creates an child (individual) through crossover with two parents + + :param parent_genotypes: genotypes of the parents to be used for crossover + :return: genotype result of the crossover + """ + parent_genotypes = [p.genotype for p in parent_individuals] + new_genotype = generate_child_genotype(parent_genotypes, genotype_conf, crossover_conf) + #TODO what if you have more than 2 parents? fix log + genotype_logger.info( + f'crossover: for genome {new_genotype.id} - p1: {parent_genotypes[0].id} p2: {parent_genotypes[1].id}.') + return new_genotype diff --git a/pyrevolve/genotype/plasticoding/initialization.py b/pyrevolve/genotype/plasticoding/initialization.py index 6eff7512f9..7f784313f0 100644 --- a/pyrevolve/genotype/plasticoding/initialization.py +++ b/pyrevolve/genotype/plasticoding/initialization.py @@ -2,12 +2,13 @@ from pyrevolve.genotype.plasticoding.plasticoding import Alphabet import random -def random_initialization(conf): + +def _generate_random_grammar(conf): """ - Initializing the ... + Initializing a new genotype, :param conf: e_max_groups, maximum number of groups of symbols :return: a random new Genome - :rtype: Plasticoding + :rtype: dictionary """ s_segments = random.randint(1, conf.e_max_groups) grammar = {} @@ -20,29 +21,40 @@ def random_initialization(conf): grammar[symbol[0]] = [] for s in range(0, s_segments): - symbol_module = random.randint( - 1, len(Alphabet.modules()) - 1) + 1, len(Alphabet.modules()) - 1) symbol_mounting = random.randint( - 0, len(Alphabet.morphologyMountingCommands()) - 1) + 0, len(Alphabet.morphology_mounting_commands()) - 1) symbol_morph_moving = random.randint( - 0, len(Alphabet.morphologyMovingCommands()) - 1) + 0, len(Alphabet.morphology_moving_commands()) - 1) symbol_contr_moving = random.randint( - 0, len(Alphabet.controllerMovingCommands()) - 1) + 0, len(Alphabet.controller_moving_commands()) - 1) symbol_changing = random.randint( - 0, len(Alphabet.controllerChangingCommands()) - 1) + 0, len(Alphabet.controller_changing_commands()) - 1) grammar[symbol[0]].extend([ - Plasticoding.build_symbol( - Alphabet.controllerMovingCommands()[symbol_contr_moving], conf), - Plasticoding.build_symbol( - Alphabet.controllerChangingCommands()[symbol_changing], conf), - Plasticoding.build_symbol( - Alphabet.morphologyMountingCommands()[symbol_mounting], conf), - Plasticoding.build_symbol( - Alphabet.modules()[symbol_module], conf), - Plasticoding.build_symbol( - Alphabet.morphologyMovingCommands()[symbol_morph_moving], conf), - ]) + Plasticoding.build_symbol( + Alphabet.controller_moving_commands()[symbol_contr_moving], conf), + Plasticoding.build_symbol( + Alphabet.controller_changing_commands()[symbol_changing], conf), + Plasticoding.build_symbol( + Alphabet.morphology_mounting_commands()[symbol_mounting], conf), + Plasticoding.build_symbol( + Alphabet.modules()[symbol_module], conf), + Plasticoding.build_symbol( + Alphabet.morphology_moving_commands()[symbol_morph_moving], conf), + ]) return grammar + +def random_initialization(conf, next_robot_id): + """ + Initializing a random genotype. + :type conf: PlasticodingConfig + :return: a Genome + :rtype: Plasticoding + """ + genotype = Plasticoding(conf, next_robot_id) + genotype.grammar = _generate_random_grammar(conf) + + return genotype diff --git a/pyrevolve/genotype/plasticoding/mutation/__init__.py b/pyrevolve/genotype/plasticoding/mutation/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/pyrevolve/genotype/plasticoding/mutation/mutation.py b/pyrevolve/genotype/plasticoding/mutation/mutation.py new file mode 100644 index 0000000000..26c20f1c65 --- /dev/null +++ b/pyrevolve/genotype/plasticoding/mutation/mutation.py @@ -0,0 +1,12 @@ +class MutationConfig: + def __init__(self, + mutation_prob, + genotype_conf): + """ + Creates a MutationConfig object that sets the configuration for the mutation operator + + :param mutation_prob: mutation probability + :param genotype_conf: configuration for the genotype to be mutated + """ + self.mutation_prob = mutation_prob + self.genotype_conf = genotype_conf diff --git a/pyrevolve/genotype/plasticoding/mutation/standard_mutation.py b/pyrevolve/genotype/plasticoding/mutation/standard_mutation.py new file mode 100644 index 0000000000..e877a947a1 --- /dev/null +++ b/pyrevolve/genotype/plasticoding/mutation/standard_mutation.py @@ -0,0 +1,130 @@ +import random +from pyrevolve.genotype.plasticoding.plasticoding import Alphabet, Plasticoding +from ....custom_logging.logger import genotype_logger + + + + +def handle_deletion(genotype): + """ + Deletes symbols from genotype + + :param genotype: genotype to be modified + + :return: genotype + """ + target_production_rule = random.choice(list(genotype.grammar)) + if (len(genotype.grammar[target_production_rule])) > 1: + symbol_to_delete = random.choice(genotype.grammar[target_production_rule]) + if symbol_to_delete[0] != Alphabet.CORE_COMPONENT: + genotype.grammar[target_production_rule].remove(symbol_to_delete) + genotype_logger.info( + f'mutation: remove in {genotype.id} for {target_production_rule} at {symbol_to_delete[0]}.') + return genotype + + +def handle_swap(genotype): + """ + Swaps symbols within the genotype + + :param genotype: genotype to be modified + + :return: genotype + """ + target_production_rule = random.choice(list(genotype.grammar)) + if (len(genotype.grammar[target_production_rule])) > 1: + symbols_to_swap = random.choices(population=genotype.grammar[target_production_rule], k=2) + for symbol in symbols_to_swap: + if symbol[0] == Alphabet.CORE_COMPONENT: + return genotype + item_index_1 = genotype.grammar[target_production_rule].index(symbols_to_swap[0]) + item_index_2 = genotype.grammar[target_production_rule].index(symbols_to_swap[1]) + genotype.grammar[target_production_rule][item_index_2], genotype.grammar[target_production_rule][item_index_1] = \ + genotype.grammar[target_production_rule][item_index_1], genotype.grammar[target_production_rule][item_index_2] + genotype_logger.info( + f'mutation: swap in {genotype.id} for {target_production_rule} between {symbols_to_swap[0]} and {symbols_to_swap[1]}.') + return genotype + + +def generate_symbol(genotype_conf): + """ + Generates a symbol for addition + + :param genotype_conf: configuration for the genotype + + :return: symbol + """ + symbol_category = random.randint(1, 5) + # Modules + if symbol_category == 1: + alphabet = random.randint(1, len(Alphabet.modules()) - 1) + symbol = Plasticoding.build_symbol(Alphabet.modules()[alphabet], genotype_conf) + # Morphology mounting commands + elif symbol_category == 2: + alphabet = random.randint(0, len(Alphabet.morphology_mounting_commands()) - 1) + symbol = Plasticoding.build_symbol(Alphabet.morphology_mounting_commands()[alphabet], genotype_conf) + # Morphology moving commands + elif symbol_category == 3: + alphabet = random.randint(0, len(Alphabet.morphology_moving_commands()) - 1) + symbol = Plasticoding.build_symbol(Alphabet.morphology_moving_commands()[alphabet], genotype_conf) + # Controller moving commands + elif symbol_category == 4: + alphabet = random.randint(0, len(Alphabet.controller_moving_commands()) - 1) + symbol = Plasticoding.build_symbol(Alphabet.controller_moving_commands()[alphabet], genotype_conf) + # Controller changing commands + elif symbol_category == 5: + alphabet = random.randint(0, len(Alphabet.controller_changing_commands()) - 1) + symbol = Plasticoding.build_symbol(Alphabet.controller_changing_commands()[alphabet], genotype_conf) + else: + raise Exception( + 'random number did not generate a number between 1 and 5. The value was: {}'.format(symbol_category)) + + return symbol + + +def handle_addition(genotype, genotype_conf): + """ + Adds symbol to genotype + + :param genotype: genotype to add to + :param genotype_conf: configuration for the genotype + + :return: genotype + """ + target_production_rule = random.choice(list(genotype.grammar)) + if target_production_rule == Alphabet.CORE_COMPONENT: + addition_index = random.randint(1, len(genotype.grammar[target_production_rule]) - 1) + else: + addition_index = random.randint(0, len(genotype.grammar[target_production_rule]) - 1) + symbol_to_add = generate_symbol(genotype_conf) + genotype.grammar[target_production_rule].insert(addition_index, symbol_to_add) + genotype_logger.info( + f'mutation: add {symbol_to_add} in {genotype.id} for {target_production_rule} at {addition_index}.') + return genotype + + +def standard_mutation(genotype, mutation_conf): + """ + Mutates genotype through addition/removal/swapping of symbols + + :param genotype: genotype to be mutated + :param mutation_conf: configuration for mutation + + :return: modified genotype + """ + new_genotype = genotype.clone() + mutation_attempt = random.uniform(0.0, 1.0) + if mutation_attempt > mutation_conf.mutation_prob: + return new_genotype + else: + mutation_type = random.randint(1, 3) # NTS: better way? + if mutation_type == 1: + modified_genotype = handle_deletion(new_genotype) + elif mutation_type == 2: + modified_genotype = handle_swap(new_genotype) + elif mutation_type == 3: + modified_genotype = handle_addition(new_genotype, mutation_conf.genotype_conf) + else: + raise Exception( + 'mutation_type value was not in the expected range (1,3). The value was: {}'.format(mutation_type)) + return modified_genotype diff --git a/pyrevolve/genotype/plasticoding/plasticoding.py b/pyrevolve/genotype/plasticoding/plasticoding.py index a45edd3f9b..5cd314997d 100644 --- a/pyrevolve/genotype/plasticoding/plasticoding.py +++ b/pyrevolve/genotype/plasticoding/plasticoding.py @@ -2,8 +2,21 @@ from enum import Enum from pyrevolve.genotype import Genotype +from pyrevolve.revolve_bot import RevolveBot +from pyrevolve.revolve_bot.revolve_module import Orientation +from pyrevolve.revolve_bot.revolve_module import CoreModule +from pyrevolve.revolve_bot.revolve_module import ActiveHingeModule +from pyrevolve.revolve_bot.revolve_module import BrickModule +from pyrevolve.revolve_bot.revolve_module import TouchSensorModule +from pyrevolve.revolve_bot.brain.brain_nn import BrainNN +from pyrevolve.revolve_bot.brain.brain_nn import Node +from pyrevolve.revolve_bot.brain.brain_nn import Connection +from pyrevolve.revolve_bot.brain.brain_nn import Params +from ...custom_logging.logger import logger import random import math +import copy +import itertools class Alphabet(Enum): @@ -41,46 +54,46 @@ class Alphabet(Enum): @staticmethod def modules(): return [ - [Alphabet.CORE_COMPONENT,[]], - [Alphabet.JOINT_HORIZONTAL,[]], - [Alphabet.JOINT_VERTICAL,[]], - [Alphabet.BLOCK,[]], - [Alphabet.SENSOR,[]], + [Alphabet.CORE_COMPONENT, []], + [Alphabet.JOINT_HORIZONTAL, []], + [Alphabet.JOINT_VERTICAL, []], + [Alphabet.BLOCK, []], + [Alphabet.SENSOR, []], ] @staticmethod - def morphologyMountingCommands(): + def morphology_mounting_commands(): return [ - [Alphabet.ADD_RIGHT,[]], - [Alphabet.ADD_FRONT,[]], - [Alphabet.ADD_LEFT,[]] + [Alphabet.ADD_RIGHT, []], + [Alphabet.ADD_FRONT, []], + [Alphabet.ADD_LEFT, []] ] @staticmethod - def morphologyMovingCommands(): + def morphology_moving_commands(): return [ - [Alphabet.MOVE_RIGHT,[]], - [Alphabet.MOVE_FRONT,[]], - [Alphabet.MOVE_LEFT,[]], - [Alphabet.MOVE_BACK,[]] + [Alphabet.MOVE_RIGHT, []], + [Alphabet.MOVE_FRONT, []], + [Alphabet.MOVE_LEFT, []], + [Alphabet.MOVE_BACK, []] ] @staticmethod - def controllerChangingCommands(): + def controller_changing_commands(): return [ - [Alphabet.ADD_EDGE,[]], - [Alphabet.MUTATE_EDGE,[]], - [Alphabet.LOOP,[]], - [Alphabet.MUTATE_AMP,[]], - [Alphabet.MUTATE_PER,[]], - [Alphabet.MUTATE_OFF,[]] + [Alphabet.ADD_EDGE, []], + [Alphabet.MUTATE_EDGE, []], + [Alphabet.LOOP, []], + [Alphabet.MUTATE_AMP, []], + [Alphabet.MUTATE_PER, []], + [Alphabet.MUTATE_OFF, []] ] @staticmethod - def controllerMovingCommands(): + def controller_moving_commands(): return [ - [Alphabet.MOVE_REF_S,[]], - [Alphabet.MOVE_REF_O,[]] + [Alphabet.MOVE_REF_S, []], + [Alphabet.MOVE_REF_O, []] ] @@ -89,18 +102,37 @@ class Plasticoding(Genotype): L-system genotypic representation, enhanced with epigenetic capabilities for phenotypic plasticity, through Genetic Programming. """ - def __init__(self, conf): + def __init__(self, conf, robot_id): """ - :param conf: + :param conf: configurations for lsystem + :param robot_id: unique id of the robot :type conf: PlasticodingConfig """ self.conf = conf + self.id = str(robot_id) self.grammar = {} + + # Auxiliary variables + self.substrate_coordinates_all = {(0, 0): '1'} + self.valid = False self.intermediate_phenotype = None self.phenotype = None - - def load_genotype(self, genotype_path): - with open(genotype_path) as f: + self.morph_mounting_container = None + self.mounting_reference = None + self.mounting_reference_stack = [] + self.quantity_modules = 1 + self.quantity_nodes = 0 + self.index_symbol = 0 + self.index_params = 1 + self.inputs_stack = [] + self.outputs_stack = [] + self.edges = {} + + def clone(self): + return copy.deepcopy(self) + + def load_genotype(self, genotype_file): + with open(genotype_file) as f: lines = f.readlines() for line in lines: @@ -108,90 +140,536 @@ def load_genotype(self, genotype_path): repleceable_symbol = Alphabet(line_array[0]) self.grammar[repleceable_symbol] = [] rule = line_array[1:len(line_array)-1] - for s in rule: - s_array = s.split('_') - symbol = Alphabet(s_array[0]) - if len(s_array) > 1: - params = s_array[1].split('|') + for symbol_array in rule: + symbol_array = symbol_array.split('_') + symbol = Alphabet(symbol_array[0]) + if len(symbol_array) > 1: + params = symbol_array[1].split('|') else: params = [] self.grammar[repleceable_symbol].append([symbol, params]) - def develop(self, new_genotype, genotype_path=''): - - if new_genotype == 'new': - self.grammar = self.conf.initialization_genome(self.conf) + def export_genotype(self, filepath): + file = open(filepath, 'w+') + for key, rule in self.grammar.items(): + line = key.value + ' ' + for item_rule in range(0, len(rule)): + symbol = rule[item_rule][self.index_symbol].value + if len(rule[item_rule][self.index_params]) > 0: + params = '_' + for param in range(0, len(rule[item_rule][self.index_params])): + params += str(rule[item_rule][self.index_params][param]) + if param < len(rule[item_rule][self.index_params])-1: + params += '|' + symbol += params + line += symbol + ' ' + file.write(line+'\n') + file.close() + + def load_and_develop(self, load, genotype_path='', id_genotype=None): + + self.id = id_genotype + if not load: + self.grammar = self.conf.initialization_genome(self.conf).grammar + logger.info('Robot {} was initialized.'.format(self.id)) else: - self.load_genotype(genotype_path) + self.load_genotype('{}{}.txt'.format(genotype_path, self.id)) + logger.info('Robot {} was loaded.'.format(self.id)) - print('-------debug genotype------') - for g in self.grammar: - print('----') - print('symbol:', g) - #print(self.grammar[g]) - for j in range(0, len(self.grammar[g])): - print(self.grammar[g][j]) + self.phenotype = self.develop() - self.early_development(); + def check_validity(self): + if self.phenotype._morphological_measurements.measurement_to_dict()['hinge_count'] > 0: + self.valid = True + + def develop(self): + self.early_development() + phenotype = self.late_development() + return phenotype def early_development(self): - print('-------debug early development------') + self.intermediate_phenotype = [[self.conf.axiom_w, []]] - for i in range(0,self.conf.i_iterations): - print('--iteration--'+str(i)) + for i in range(0, self.conf.i_iterations): position = 0 for aux_index in range(0, len(self.intermediate_phenotype)): + symbol = self.intermediate_phenotype[position] - if [symbol[0], []] in Alphabet.modules(): + if [symbol[self.index_symbol], []] in Alphabet.modules(): # removes symbol self.intermediate_phenotype.pop(position) # replaces by its production rule - for ii in range(0, len(self.grammar[symbol[0]])): + for ii in range(0, len(self.grammar[symbol[self.index_symbol]])): self.intermediate_phenotype.insert(position+ii, - self.grammar[symbol[0]][ii]) + self.grammar[symbol[self.index_symbol]][ii]) position = position+ii+1 else: position = position + 1 - #print(self.intermediate_phenotype) - for j in range(0, len(self.intermediate_phenotype)): - print(self.intermediate_phenotype[j]) + # logger.info('Robot ' + str(self.id) + ' was early-developed.') + + def late_development(self): + + self.phenotype = RevolveBot() + self.phenotype._id = self.id if type(self.id) == str and self.id.startswith("robot") else "robot_{}".format(self.id) + self.phenotype._brain = BrainNN() + + for symbol in self.intermediate_phenotype: + + if symbol[self.index_symbol] == Alphabet.CORE_COMPONENT: + module = CoreModule() + self.phenotype._body = module + module.id = str(self.quantity_modules) + module.info = {'orientation': Orientation.NORTH, + 'new_module_type': Alphabet.CORE_COMPONENT} + module.orientation = 0 + module.rgb = [1, 1, 0] + self.mounting_reference = module + + if [symbol[self.index_symbol], []] in Alphabet.morphology_mounting_commands(): + self.morph_mounting_container = symbol[self.index_symbol] + + if [symbol[self.index_symbol], []] in Alphabet.modules() \ + and symbol[self.index_symbol] is not Alphabet.CORE_COMPONENT \ + and self.morph_mounting_container is not None: + + if type(self.mounting_reference) == CoreModule \ + or type(self.mounting_reference) == BrickModule: + slot = self.get_slot(self.morph_mounting_container).value + if type(self.mounting_reference) == ActiveHingeModule: + slot = Orientation.NORTH.value + + if self.quantity_modules < self.conf.max_structural_modules: + self.new_module(slot, + symbol[self.index_symbol], + symbol) + + if [symbol[self.index_symbol], []] in Alphabet.morphology_moving_commands(): + self.move_in_body(symbol) + + if [symbol[self.index_symbol], []] in Alphabet.controller_changing_commands(): + self.decode_brain_changing(symbol) + + if [symbol[self.index_symbol], []] in Alphabet.controller_moving_commands(): + self.decode_brain_moving(symbol) + + self.add_imu_nodes() + logger.info('Robot ' + str(self.id) + ' was late-developed.') + + return self.phenotype + + def move_in_body(self, symbol): + + if symbol[self.index_symbol] == Alphabet.MOVE_BACK \ + and len(self.mounting_reference_stack) > 0: + self.mounting_reference = self.mounting_reference_stack[-1] + self.mounting_reference_stack.pop() + + elif symbol[self.index_symbol] == Alphabet.MOVE_FRONT \ + and self.mounting_reference.children[Orientation.NORTH.value] is not None: + if type(self.mounting_reference.children[Orientation.NORTH.value]) is not TouchSensorModule: + self.mounting_reference_stack.append(self.mounting_reference) + self.mounting_reference = \ + self.mounting_reference.children[Orientation.NORTH.value] + + elif symbol[self.index_symbol] == Alphabet.MOVE_LEFT \ + and type(self.mounting_reference) is not ActiveHingeModule: + if self.mounting_reference.children[Orientation.WEST.value] is not None: + if type(self.mounting_reference.children[Orientation.WEST.value]) is not TouchSensorModule: + self.mounting_reference_stack.append(self.mounting_reference) + self.mounting_reference = \ + self.mounting_reference.children[Orientation.WEST.value] + + elif symbol[self.index_symbol] == Alphabet.MOVE_RIGHT \ + and type(self.mounting_reference) is not ActiveHingeModule: + if self.mounting_reference.children[Orientation.EAST.value] is not None: + if type(self.mounting_reference.children[Orientation.EAST.value]) is not TouchSensorModule: + self.mounting_reference_stack.append(self.mounting_reference) + self.mounting_reference = \ + self.mounting_reference.children[Orientation.EAST.value] + + elif (symbol[self.index_symbol] == Alphabet.MOVE_RIGHT \ + or symbol[self.index_symbol] == Alphabet.MOVE_LEFT) \ + and type(self.mounting_reference) is ActiveHingeModule \ + and self.mounting_reference.children[Orientation.NORTH.value] is not None: + self.mounting_reference_stack.append(self.mounting_reference) + self.mounting_reference = \ + self.mounting_reference.children[Orientation.NORTH.value] + + def decode_brain_changing(self, symbol): + + # if there is at least both one oscillator + if len(self.outputs_stack) > 0: + + if symbol[self.index_symbol] == Alphabet.MUTATE_PER: + self.outputs_stack[-1].params.period += float(symbol[self.index_params][0]) + if self.outputs_stack[-1].params.period > self.conf.oscillator_param_max: + self.outputs_stack[-1].params.period = self.conf.oscillator_param_max + if self.outputs_stack[-1].params.period < self.conf.oscillator_param_min: + self.outputs_stack[-1].params.period = self.conf.oscillator_param_min + + if symbol[self.index_symbol] == Alphabet.MUTATE_AMP: + self.outputs_stack[-1].params.amplitude += float(symbol[self.index_params][0]) + if self.outputs_stack[-1].params.amplitude > self.conf.oscillator_param_max: + self.outputs_stack[-1].params.amplitude = self.conf.oscillator_param_max + if self.outputs_stack[-1].params.amplitude < self.conf.oscillator_param_min: + self.outputs_stack[-1].params.amplitude = self.conf.oscillator_param_min + + if symbol[self.index_symbol] == Alphabet.MUTATE_OFF: + self.outputs_stack[-1].params.phase_offset += float(symbol[self.index_params][0]) + if self.outputs_stack[-1].params.phase_offset > self.conf.oscillator_param_max: + self.outputs_stack[-1].params.phase_offset = self.conf.oscillator_param_max + if self.outputs_stack[-1].params.phase_offset < self.conf.oscillator_param_min: + self.outputs_stack[-1].params.phase_offset = self.conf.oscillator_param_min + + if symbol[self.index_symbol] == Alphabet.MUTATE_EDGE: + if len(self.edges) > 0: + if (self.inputs_stack[-1].id, self.outputs_stack[-1].id) in self.edges.keys(): + self.edges[self.inputs_stack[-1].id, self.outputs_stack[-1].id].weight \ + += float(symbol[self.index_params][0]) + if self.edges[self.inputs_stack[-1].id, self.outputs_stack[-1].id].weight \ + > self.conf.weight_param_max: + self.edges[self.inputs_stack[-1].id, self.outputs_stack[-1].id].weight \ + = self.conf.weight_param_max + if self.edges[self.inputs_stack[-1].id, self.outputs_stack[-1].id].weight \ + < self.conf.weight_param_min: + self.edges[self.inputs_stack[-1].id, self.outputs_stack[-1].id].weight \ + = self.conf.weight_param_min + + # if there is at least both one sensor and one oscillator + if len(self.outputs_stack) > 0 and len(self.inputs_stack) > 0: + if symbol[self.index_symbol] == Alphabet.LOOP: + + if (self.outputs_stack[-1].id, self.outputs_stack[-1].id) not in self.edges.keys(): + connection = Connection() + connection.src = self.outputs_stack[-1].id + connection.dst = connection.src + connection.weight = float(symbol[self.index_params][0]) + self.edges[connection.src, connection.src] = connection + self.phenotype._brain.connections.append(connection) + + if symbol[self.index_symbol] == Alphabet.ADD_EDGE: + if (self.inputs_stack[-1].id, self.outputs_stack[-1].id) not in self.edges.keys(): + connection = Connection() + connection.src = self.inputs_stack[-1].id + connection.dst = self.outputs_stack[-1].id + connection.weight = float(symbol[self.index_params][0]) + self.edges[connection.src, connection.dst] = connection + self.phenotype._brain.connections.append(connection) + self.inputs_stack[-1].output_nodes.append(self.outputs_stack[-1]) + self.outputs_stack[-1].input_nodes.append(self.inputs_stack[-1]) + + def decode_brain_moving(self, symbol): + + # if there is at least both one sensor and one oscillator + if len(self.outputs_stack) > 0 and len(self.inputs_stack) > 0: + + intermediate = int(float(symbol[self.index_params][0])) + sibling = int(float(symbol[self.index_params][1])) + + if symbol[self.index_symbol] == Alphabet.MOVE_REF_S: + + if len(self.inputs_stack[-1].output_nodes) < intermediate: + intermediate = len(self.inputs_stack[-1].output_nodes) - 1 + else: + intermediate = intermediate - 1 + + if len(self.inputs_stack[-1].output_nodes[intermediate].input_nodes) < sibling: + sibling = len(self.inputs_stack[-1].output_nodes[intermediate].input_nodes) - 1 + else: + sibling = sibling - 1 + + self.inputs_stack[-1] = self.inputs_stack[-1].output_nodes[intermediate].input_nodes[sibling] + + if symbol[self.index_symbol] == Alphabet.MOVE_REF_O: + + if len(self.outputs_stack[-1].input_nodes) < intermediate: + intermediate = len(self.outputs_stack[-1].input_nodes) - 1 + else: + intermediate = intermediate - 1 + + if len(self.outputs_stack[-1].input_nodes[intermediate].output_nodes) < sibling: + sibling = len(self.outputs_stack[-1].input_nodes[intermediate].output_nodes) - 1 + else: + sibling = sibling - 1 + + self.outputs_stack[-1] = self.outputs_stack[-1].input_nodes[intermediate].output_nodes[sibling] + + def get_color(self, new_module_type): + + rgb = [] + if new_module_type == Alphabet.BLOCK: + rgb = [0, 0, 1] + if new_module_type == Alphabet.JOINT_HORIZONTAL: + rgb = [1, 0.08, 0.58] + if new_module_type == Alphabet.JOINT_VERTICAL: + rgb = [0.7, 0, 0] + if new_module_type == Alphabet.SENSOR: + rgb = [0.7, 0.7, 0.7] + return rgb + + def get_slot(self, morph_mounting_container): + + slot = None + if morph_mounting_container == Alphabet.ADD_FRONT: + slot = Orientation.NORTH + if morph_mounting_container == Alphabet.ADD_LEFT: + slot = Orientation.WEST + if morph_mounting_container == Alphabet.ADD_RIGHT: + slot = Orientation.EAST + return slot + + def get_angle(self, new_module_type, parent): + angle = 0 + if new_module_type == Alphabet.JOINT_VERTICAL: + if parent.info['new_module_type'] is Alphabet.JOINT_VERTICAL: + angle = 0 + else: + angle = 90 + else: + if parent.info['new_module_type'] is Alphabet.JOINT_VERTICAL: + angle = 270 + return angle + + def check_intersection(self, parent, slot, module): + """ + Update coordinates of module + :return: + """ + dic = {Orientation.NORTH.value: 0, + Orientation.WEST.value: 1, + Orientation.SOUTH.value: 2, + Orientation.EAST.value: 3} + + inverse_dic = {0: Orientation.NORTH.value, + 1: Orientation.WEST.value, + 2: Orientation.SOUTH.value, + 3: Orientation.EAST.value} + + direction = dic[parent.info['orientation'].value] + dic[slot] + if direction >= len(dic): + direction = direction - len(dic) + + new_direction = Orientation(inverse_dic[direction]) + if new_direction == Orientation.WEST: + coordinates = [parent.substrate_coordinates[0], + parent.substrate_coordinates[1] - 1] + if new_direction == Orientation.EAST: + coordinates = [parent.substrate_coordinates[0], + parent.substrate_coordinates[1] + 1] + if new_direction == Orientation.NORTH: + coordinates = [parent.substrate_coordinates[0] + 1, + parent.substrate_coordinates[1]] + if new_direction == Orientation.SOUTH: + coordinates = [parent.substrate_coordinates[0] - 1, + parent.substrate_coordinates[1]] + + module.substrate_coordinates = coordinates + module.info['orientation'] = new_direction + if (coordinates[0], coordinates[1]) in self.substrate_coordinates_all: + return True + else: + self.substrate_coordinates_all[coordinates[0], + coordinates[1]] = module.id + return False + + def new_module(self, slot, new_module_type, symbol): + + mount = False + if self.mounting_reference.children[slot] is None \ + and not (new_module_type == Alphabet.SENSOR + and type(self.mounting_reference) is ActiveHingeModule): + mount = True + + if type(self.mounting_reference) is CoreModule \ + and self.mounting_reference.children[1] is not None \ + and self.mounting_reference.children[2] is not None \ + and self.mounting_reference.children[3] is not None \ + and self.mounting_reference.children[0] is None: + slot = 0 + mount = True + + if mount: + if new_module_type == Alphabet.BLOCK: + module = BrickModule() + if new_module_type == Alphabet.JOINT_VERTICAL \ + or new_module_type == Alphabet.JOINT_HORIZONTAL: + module = ActiveHingeModule() + if new_module_type == Alphabet.SENSOR: + module = TouchSensorModule() + + module.info = {} + module.info['new_module_type'] = new_module_type + module.orientation = self.get_angle(new_module_type, + self.mounting_reference) + module.rgb = self.get_color(new_module_type) + + if new_module_type != Alphabet.SENSOR: + self.quantity_modules += 1 + module.id = str(self.quantity_modules) + intersection = self.check_intersection(self.mounting_reference, slot, module) + + if not intersection: + self.mounting_reference.children[slot] = module + self.morph_mounting_container = None + self.mounting_reference_stack.append(self.mounting_reference) + self.mounting_reference = module + if new_module_type == Alphabet.JOINT_HORIZONTAL \ + or new_module_type == Alphabet.JOINT_VERTICAL: + self.decode_brain_node(symbol, module.id) + else: + self.quantity_modules -= 1 + else: + self.mounting_reference.children[slot] = module + self.morph_mounting_container = None + module.id = self.mounting_reference.id+'s'+str(slot) + self.decode_brain_node(symbol, module.id) + + def decode_brain_node(self, symbol, part_id): + + self.quantity_nodes += 1 + node = NodeExtended() + node.id = 'node'+str(self.quantity_nodes) + node.weight = float(symbol[self.index_params][0]) + node.part_id = part_id + + if symbol[self.index_symbol] == Alphabet.SENSOR: + + node.layer = 'input' + node.type = 'Input' + + # stacks sensor if there are no oscillators yet + if len(self.outputs_stack) == 0: + self.inputs_stack.append(node) + else: + # if it is the first senor ever + if len(self.inputs_stack) > 0: + self.inputs_stack = [node] + else: + self.inputs_stack.append(node) + + # connects sensor to all oscillators in the stack + for output_node in range(0, len(self.outputs_stack)): + self.outputs_stack[output_node].input_nodes.append(node) + node.output_nodes.append(self.outputs_stack[output_node]) + + connection = Connection() + connection.src = node.id + connection.dst = self.outputs_stack[output_node].id + + if output_node == len(self.outputs_stack)-1: + connection.weight = node.weight + else: + connection.weight = float(self.outputs_stack[output_node].weight) + self.edges[connection.src, connection.dst] = connection + self.phenotype._brain.connections.append(connection) + self.outputs_stack = [self.outputs_stack[-1]] + + if symbol[self.index_symbol] == Alphabet.JOINT_VERTICAL \ + or symbol[self.index_symbol] == Alphabet.JOINT_HORIZONTAL: + + node.layer = 'output' + node.type = 'Oscillator' + + params = Params() + params.period = float(symbol[self.index_params][1]) + params.phase_offset = float(symbol[self.index_params][2]) + params.amplitude = float(symbol[self.index_params][3]) + node.params = params + self.phenotype._brain.params[node.id] = params + + # stacks oscillator if there are no sensors yet + if len(self.inputs_stack) == 0: + self.outputs_stack.append(node) + else: + # if it is the first oscillator ever + if len(self.outputs_stack) > 0: + self.outputs_stack = [node] + else: + self.outputs_stack.append(node) + + # connects oscillator to all sensors in the stack + for input_node in range(0, len(self.inputs_stack)): + self.inputs_stack[input_node].output_nodes.append(node) + node.input_nodes.append(self.inputs_stack[input_node]) + + connection = Connection() + connection.src = self.inputs_stack[input_node].id + connection.dst = node.id + if input_node == len(self.inputs_stack)-1: + connection.weight = node.weight + else: + connection.weight = float(self.inputs_stack[input_node].weight) + self.edges[connection.src, connection.dst] = connection + self.phenotype._brain.connections.append(connection) + self.inputs_stack = [self.inputs_stack[-1]] + + self.phenotype._brain.nodes[node.id] = node + + def add_imu_nodes(self): + for p in range(1, 7): + id = 'node-core'+str(p) + node = Node() + node.layer = 'input' + node.type = 'Input' + node.part_id = self.phenotype._body.id + node.id = id + self.phenotype._brain.nodes[id] = node - # adds params for symbols that need it - # in symbol, [0] has the symbol and [1] the params + @staticmethod def build_symbol(symbol, conf): - if symbol[0] == Alphabet.JOINT_HORIZONTAL \ - or symbol[0] == Alphabet.JOINT_VERTICAL: - symbol[1] = [random.uniform(conf.weight_min, conf.weight_max), - random.uniform(conf.oscillator_param_min, - conf.oscillator_param_max), - random.uniform(conf.oscillator_param_min, - conf.oscillator_param_max), - random.uniform(conf.oscillator_param_min, - conf.oscillator_param_max)] - - if symbol[0] == Alphabet.SENSOR \ - or symbol[0] == Alphabet.ADD_EDGE \ - or symbol[0] == Alphabet.LOOP: - symbol[1] = [random.uniform(conf.weight_min, conf.weight_max)] - - if symbol[0] == Alphabet.MUTATE_EDGE \ - or symbol[0] == Alphabet.MUTATE_AMP \ - or symbol[0] == Alphabet.MUTATE_PER \ - or symbol[0] == Alphabet.MUTATE_OFF: - symbol[1] = [random.normalvariate(0, 1)] - - if symbol[0] == Alphabet.MOVE_REF_S \ - or symbol[0] == Alphabet.MOVE_REF_O: + """ + Adds params for alphabet symbols (when it applies). + :return: + """ + index_symbol = 0 + index_params = 1 + + if symbol[index_symbol] is Alphabet.JOINT_HORIZONTAL \ + or symbol[index_symbol] is Alphabet.JOINT_VERTICAL: + + symbol[index_params] = [random.uniform(conf.weight_min, conf.weight_max), + random.uniform(conf.oscillator_param_min, + conf.oscillator_param_max), + random.uniform(conf.oscillator_param_min, + conf.oscillator_param_max), + random.uniform(conf.oscillator_param_min, + conf.oscillator_param_max)] + + if symbol[index_symbol] is Alphabet.SENSOR \ + or symbol[index_symbol] is Alphabet.ADD_EDGE \ + or symbol[index_symbol] is Alphabet.LOOP: + + symbol[index_params] = [random.uniform(conf.weight_min, conf.weight_max)] + + if symbol[index_symbol] is Alphabet.MUTATE_EDGE \ + or symbol[index_symbol] is Alphabet.MUTATE_AMP \ + or symbol[index_symbol] is Alphabet.MUTATE_PER \ + or symbol[index_symbol] is Alphabet.MUTATE_OFF: + + symbol[index_params] = [random.normalvariate(0, 1)] + + if symbol[index_symbol] is Alphabet.MOVE_REF_S \ + or symbol[index_symbol] is Alphabet.MOVE_REF_O: + intermediate_temp = random.normalvariate(0, 1) final_temp = random.normalvariate(0, 1) - symbol[1] = [math.ceil(math.sqrt(math.pow(intermediate_temp, 2))), - math.ceil(math.sqrt(math.pow(final_temp, 2)))] + symbol[index_params] = [math.ceil(math.sqrt(math.pow(intermediate_temp, 2))), + math.ceil(math.sqrt(math.pow(final_temp, 2)))] return symbol +class NodeExtended(Node): + def __init__(self): + super().__init__() + self.weight = None + self.input_nodes = [] + self.output_nodes = [] + self.params = None + + from pyrevolve.genotype.plasticoding import initialization @@ -201,16 +679,24 @@ def __init__(self, e_max_groups=3, oscillator_param_min=1, oscillator_param_max=10, + weight_param_min=-1, + weight_param_max=1, weight_min=-1, weight_max=1, axiom_w=Alphabet.CORE_COMPONENT, - i_iterations=3 + i_iterations=3, + max_structural_modules=100, + robot_id=0 ): self.initialization_genome = initialization_genome self.e_max_groups = e_max_groups self.oscillator_param_min = oscillator_param_min self.oscillator_param_max = oscillator_param_max + self.weight_param_min = weight_param_min + self.weight_param_max = weight_param_max self.weight_min = weight_min self.weight_max = weight_max self.axiom_w = axiom_w self.i_iterations = i_iterations + self.max_structural_modules = max_structural_modules + self.robot_id = robot_id diff --git a/pyrevolve/logging/logger.py b/pyrevolve/logging/logger.py deleted file mode 100644 index 67f8075ddb..0000000000 --- a/pyrevolve/logging/logger.py +++ /dev/null @@ -1,5 +0,0 @@ -from __future__ import absolute_import - -import logging - -logger = logging.getLogger("revolve") diff --git a/pyrevolve/revolve_bot/brain/__init__.py b/pyrevolve/revolve_bot/brain/__init__.py index 09c1b19705..900e38923c 100644 --- a/pyrevolve/revolve_bot/brain/__init__.py +++ b/pyrevolve/revolve_bot/brain/__init__.py @@ -1,3 +1,4 @@ from .base import Brain from .brain_nn import BrainNN from .rlpower_splines import BrainRLPowerSplines +from .bo_cpg import BrainCPGBO diff --git a/pyrevolve/revolve_bot/brain/base.py b/pyrevolve/revolve_bot/brain/base.py index 2a7fef81c2..b16ea73b8b 100644 --- a/pyrevolve/revolve_bot/brain/base.py +++ b/pyrevolve/revolve_bot/brain/base.py @@ -11,6 +11,8 @@ def from_yaml(yaml_brain): return pyrevolve.revolve_bot.brain.BrainNN.from_yaml(yaml_brain) elif brain_type == pyrevolve.revolve_bot.brain.BrainRLPowerSplines.TYPE: return pyrevolve.revolve_bot.brain.BrainRLPowerSplines.from_yaml(yaml_brain) + elif brain_type == pyrevolve.revolve_bot.brain.BrainCPGBO.TYPE: + return pyrevolve.revolve_bot.brain.BrainCPGBO.from_yaml(yaml_brain) else: return Brain() diff --git a/pyrevolve/revolve_bot/brain/bo_cpg.py b/pyrevolve/revolve_bot/brain/bo_cpg.py new file mode 100644 index 0000000000..7f8a28c140 --- /dev/null +++ b/pyrevolve/revolve_bot/brain/bo_cpg.py @@ -0,0 +1,114 @@ +""" +Note: Parameters are not set in this file. They are imported from the robot yaml-file, containing the +physical properties of the robot, as well as the brain (learner and controller) and the corresponding +parameters. +""" + +import xml.etree.ElementTree +from .base import Brain +import time + + +class BrainCPGBO(Brain): + TYPE = 'bo-cpg' + + def __init__(self): + # CPG hyper-parameters + self.abs_output_bound = None + self.use_frame_of_reference = "false" + self.signal_factor_all = "" + self.signal_factor_mid = None + self.signal_factor_left_right = None + self.range_lb = None + self.range_ub = None + self.init_neuron_state = None + + # BO hyper-parameters + self.init_method = None # {RS, LHS} + self.acquisition_function = None + self.kernel_noise = None + self.kernel_optimize_noise = None + self.kernel_sigma_sq = None + self.kernel_l = None + self.kernel_squared_exp_ard_k = None + self.acqui_gpucb_delta = None + self.acqui_ucb_alpha = None + self.acqui_ei_jitter = None + self.n_init_samples = None + + # Various + self.robot_size = None + self.n_learning_iterations = None + self.n_cooldown_iterations = None + self.load_brain = None + self.output_directory = None + self.run_analytics = None + self.reset_robot_position = None + self.reset_neuron_state_bool = None + self.reset_neuron_random = None + self.verbose = None + self.startup_time = None + self.evaluation_rate = None + + @staticmethod + def from_yaml(yaml_object): + BCPGBO = BrainCPGBO() + + for my_type in ["controller", "learner", "meta"]: + try: + my_object = yaml_object[my_type] + for key, value in my_object.items(): + try: + setattr(BCPGBO, key, value) + except: + print("Couldn't set {}, {}", format(key, value)) + except: + print("Didn't load {} parameters".format(my_type)) + + return BCPGBO + + def to_yaml(self): + return { + 'type': self.TYPE + } + + def learner_sdf(self): + return xml.etree.ElementTree.Element('rv:learner', { + 'type': 'bo', + 'robot_size': str(self.robot_size), + 'n_init_samples': str(self.n_init_samples), + 'n_learning_iterations': str(self.n_learning_iterations), + 'n_cooldown_iterations': str(self.n_cooldown_iterations), + 'evaluation_rate': str(self.evaluation_rate), + 'abs_output_bound': str(self.abs_output_bound), + 'init_method': self.init_method, + 'kernel_noise': str(self.kernel_noise), + 'kernel_optimize_noise': str(self.kernel_optimize_noise), + 'kernel_sigma_sq': str(self.kernel_sigma_sq), + 'kernel_l': str(self.kernel_l), + 'kernel_squared_exp_ard_k': str(self.kernel_squared_exp_ard_k), + 'acquisition_function': str(self.acquisition_function), + 'acqui_gpucb_delta': str(self.acqui_gpucb_delta), + 'acqui_ucb_alpha': str(self.acqui_ucb_alpha), + 'acqui_ei_jitter': str(self.acqui_ei_jitter), + }) + + def controller_sdf(self): + return xml.etree.ElementTree.Element('rv:controller', { + 'type': 'cpg', + 'reset_robot_position': self.reset_robot_position, + 'reset_neuron_state_bool': str(self.reset_neuron_state_bool), + 'reset_neuron_random': str(self.reset_neuron_random), + 'load_brain': self.load_brain, + 'use_frame_of_reference': str(self.use_frame_of_reference), + 'run_analytics': str(self.run_analytics), + 'init_neuron_state': str(self.init_neuron_state), + 'output_directory': str(self.output_directory), + 'verbose': str(self.verbose), + 'range_lb': str(self.range_lb), + 'range_ub': str(self.range_ub), + 'signal_factor_all': str(self.signal_factor_all), + 'signal_factor_mid': str(self.signal_factor_mid), + 'signal_factor_left_right': str(self.signal_factor_left_right), + 'startup_time': str(self.startup_time), + }) diff --git a/pyrevolve/revolve_bot/brain/rlpower_splines.py b/pyrevolve/revolve_bot/brain/rlpower_splines.py index 4a794fa880..ba93bdf59a 100644 --- a/pyrevolve/revolve_bot/brain/rlpower_splines.py +++ b/pyrevolve/revolve_bot/brain/rlpower_splines.py @@ -5,6 +5,9 @@ class BrainRLPowerSplines(Brain): TYPE = 'rlpower-splines' + def __init__(self, evaluation_rate=30.0): + self._evaluation_rate = evaluation_rate + @staticmethod def from_yaml(yaml_object): return BrainRLPowerSplines() @@ -15,7 +18,10 @@ def to_yaml(self): } def learner_sdf(self): - return xml.etree.ElementTree.Element('rv:learner', {'type': 'rlpower'}) + return xml.etree.ElementTree.Element('rv:learner', { + 'type': 'rlpower', + 'evaluation_rate': str(self._evaluation_rate), + }) def controller_sdf(self): return xml.etree.ElementTree.Element('rv:controller', {'type': 'spline'}) diff --git a/pyrevolve/revolve_bot/measure/measure_body.py b/pyrevolve/revolve_bot/measure/measure_body.py index b0e4a35746..76f984e1fc 100644 --- a/pyrevolve/revolve_bot/measure/measure_body.py +++ b/pyrevolve/revolve_bot/measure/measure_body.py @@ -2,32 +2,56 @@ from ..render.render import Render from ..render.grid import Grid from ..revolve_module import ActiveHingeModule, BrickModule, TouchSensorModule, BrickSensorModule, CoreModule +from ...custom_logging.logger import logger class MeasureBody: def __init__(self, body): self.body = body + + # Absolute branching self.branching_modules_count = None + # Relative branching self.branching = None + # Absolute number of limbs self.extremities = None + # Relative number of limbs self.limbs = None + # Absolute length of limbs self.extensiveness = None + # Relative length of limbs self.length_of_limbs = None + # Coverage self.coverage = None + # Relative number of effective active joints self.joints = None + # Absolute number of effective active joints + self.active_hinges_count = None + # Proportion self.proportion = None + # Width self.width = None + # Height self.height = None + # Absolute size self.absolute_size = None + # Relative size in respect of the max body size `self.max_permitted_modules` self.size = None + # Proportion of sensor vs empty slots self.sensors = None + # Body symmetry self.symmetry = None + # Number of active joints self.hinge_count = None - self.active_hinges_count = None + # Number of bricks self.brick_count = None + # Number of brick sensors self.brick_sensor_count = None + # Number of touch sensors self.touch_sensor_count = None + # Number of free slots self.free_slots = None + # Maximum number of modules allowed (sensors excluded) self.max_permitted_modules = None def count_branching_bricks(self, module=None, init=True): @@ -51,8 +75,7 @@ def count_branching_bricks(self, module=None, init=True): if (isinstance(module, BrickModule) and children_count == 3) or (isinstance(module, CoreModule) and children_count == 4): self.branching_modules_count += 1 except Exception as e: - print('Failed counting branching bricks') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed counting branching bricks') def measure_branching(self): """ @@ -60,14 +83,11 @@ def measure_branching(self): """ if self.absolute_size is None: self.measure_absolute_size() - if self.absolute_size < 5: - self.branching = 0 - return self.branching if self.branching_modules_count is None: self.count_branching_bricks() - if self.branching_modules_count == 0: + if self.branching_modules_count == 0 or self.absolute_size < 5: self.branching = 0 - return 0 + return self.branching practical_limit_branching_bricks = math.floor((self.absolute_size-2)/3) self.branching = self.branching_modules_count / practical_limit_branching_bricks return self.branching @@ -98,8 +118,7 @@ def calculate_extremities_extensiveness(self, module=None, extremities=False, ex if children_count == 1 and not (isinstance(module, CoreModule) or isinstance(module, TouchSensorModule)) and extensiveness: self.extensiveness += 1 except Exception as e: - print('Failed calculating extremities or extensiveness') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed calculating extremities or extensiveness') def measure_limbs(self): """ @@ -113,7 +132,7 @@ def measure_limbs(self): practical_limit_limbs = self.absolute_size - 1 else: practical_limit_limbs = 2 * math.floor((self.absolute_size - 6) / 3) + ((self.absolute_size - 6) % 3) + 4 - + if self.extremities is None: self.calculate_extremities_extensiveness(None, True, False) if self.extremities == 0: @@ -129,11 +148,11 @@ def measure_length_of_limbs(self): """ if self.absolute_size is None: self.measure_absolute_size() - if self.absolute_size < 3: - self.length_of_limbs = 0 - return 0 if self.extensiveness is None: self.calculate_extremities_extensiveness(None, False, True) + if self.absolute_size < 3: + self.length_of_limbs = 0 + return self.length_of_limbs practical_limit_extensiveness = self.absolute_size - 2 self.length_of_limbs = self.extensiveness / practical_limit_extensiveness return self.length_of_limbs @@ -169,8 +188,7 @@ def measure_symmetry(self): return self.symmetry except Exception as e: - print('Failed measuring symmetry') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed measuring symmetry') def measure_coverage(self): """ @@ -202,8 +220,7 @@ def count_active_hinges(self, module=None, init=True): continue self.count_active_hinges(child_module, False) except Exception as e: - print('Failed calculating count') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed calculating count') def measure_joints(self): """ @@ -212,15 +229,12 @@ def measure_joints(self): """ if self.absolute_size is None: self.measure_absolute_size() - if self.absolute_size < 3: - self.joints = 0 - return 0 if self.active_hinges_count is None: self.count_active_hinges() - practical_limit_active_hinges = self.absolute_size - 2 - if self.active_hinges_count == 0: + if self.active_hinges_count == 0 or self.absolute_size < 3: self.joints = 0 - return 0 + return self.joints + practical_limit_active_hinges = self.absolute_size - 2 self.joints = self.active_hinges_count / practical_limit_active_hinges return self.joints @@ -263,6 +277,8 @@ def measure_sensors(self, module=None): """ if self.free_slots is None: self.count_free_slots() + if self.free_slots == 0: + self.free_slots = 0.0001 self.sensors = self.touch_sensor_count / self.free_slots return self.sensors @@ -277,8 +293,7 @@ def measure_absolute_size(self, module=None): self.absolute_size = self.brick_count + self.hinge_count + 1 return self.absolute_size except Exception as e: - print('Failed measuring absolute size') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed measuring absolute size') def calculate_count(self, module=None, init=True): """ @@ -289,7 +304,7 @@ def calculate_count(self, module=None, init=True): self.hinge_count = 0 self.brick_count = 0 self.brick_sensor_count = 0 - self.touch_sensor_count = 0 + self.touch_sensor_count = 0 if module is None: module = self.body elif isinstance(module, ActiveHingeModule): @@ -307,8 +322,7 @@ def calculate_count(self, module=None, init=True): continue self.calculate_count(child_module, False) except Exception as e: - print('Failed calculating count') - print('Exception: {}'.format(e)) + logger.exception(f'Exception: {e}. \nFailed calculating count') def measure_width_height(self): """ @@ -321,19 +335,7 @@ def measure_width_height(self): self.width = render.grid.width self.height = render.grid.height except Exception as e: - print('Failed measuring width and height') - print('Exception: {}'.format(e)) - - def measure_size(self): - """ - Measure size of robot, specified by the amount of modules divided by the limit - :return: False if max_permitted_modules is None - """ - if self.max_permitted_modules is None: - return False - if self.absolute_size is None: - self.measure_absolute_size() - self.size = self.absolute_size / self.max_permitted_modules + logger.exception(f'Exception: {e}. \nFailed measuring width and height') def measure_all(self): """ @@ -350,9 +352,9 @@ def measure_all(self): self.measure_symmetry() self.measure_branching() self.measure_sensors() - return self.measurement_to_dict() + return self.measurements_to_dict() - def measurement_to_dict(self): + def measurements_to_dict(self): """ Return dict of all measurements :return: @@ -361,7 +363,7 @@ def measurement_to_dict(self): 'branching': self.branching, 'branching_modules_count': self.branching_modules_count, 'limbs': self.limbs, - 'extremeties': self.extremities, + 'extremities': self.extremities, 'length_of_limbs': self.length_of_limbs, 'extensiveness': self.extensiveness, 'coverage': self.coverage, @@ -375,7 +377,9 @@ def measurement_to_dict(self): 'width': self.width, 'height': self.height, 'absolute_size': self.absolute_size, - 'size': self.size, 'sensors': self.sensors, 'symmetry': self.symmetry } + + def __repr__(self): + return self.measurements_to_dict().__repr__() \ No newline at end of file diff --git a/pyrevolve/revolve_bot/measure/measure_brain.py b/pyrevolve/revolve_bot/measure/measure_brain.py index 8520335e35..5ef3096b47 100644 --- a/pyrevolve/revolve_bot/measure/measure_brain.py +++ b/pyrevolve/revolve_bot/measure/measure_brain.py @@ -2,27 +2,47 @@ import math # belong to TODO import fnmatch +from ..brain.brain_nn import BrainNN +from ...custom_logging.logger import logger class MeasureBrain: - def __init__(self, brain, max_param): + def __init__(self, brain: BrainNN, max_param: int): + """ + Initializing function, for calculating measurements use measure_all + :param brain: brain to measure, only BrainNN supported + :param max_param: Range of oscillator parameter + """ self.brain = brain self.max_param = max_param + self.params = None self.count_oscillators = None self.periods = None self.phase_offsets = None self.amplitudes = None + # Average Period self.avg_period = None + # Deviation of Period self.dev_period = None + # Average Phase Offset self.avg_phase_offset = None + # Deviation of Phase Offset self.dev_phase_offset = None + # Average Amplitude self.avg_amplitude = None + # Deviation of Amplitude self.dev_amplitude = None + # Average Intra-Deviation of Parameters self.avg_intra_dev_params = None + # Average Inter-Deviation of Parameters self.avg_inter_dev_params = None + # Sensors Reach self.sensors_reach = None + # Recurrence self.recurrence = None + # Synaptic Reception self.synaptic_reception = None + self.collect_sets_of_params() def sigmoid(self, value): """ @@ -30,22 +50,44 @@ def sigmoid(self, value): """ return 1 / (1 + math.exp(-value)) + def set_measurements_to_zero(self): + """ + Set all measurements to zero + """ + self.avg_period = 0 + self.dev_period = 0 + self.avg_phase_offset = 0 + self.dev_phase_offset = 0 + self.avg_amplitude = 0 + self.dev_amplitude = 0 + self.avg_intra_dev_params = 0 + self.avg_inter_dev_params = 0 + self.sensors_reach = 0 + self.recurrence = 0 + self.synaptic_reception = 0 + def collect_sets_of_params(self): """ Create lists of parameter values """ - params = self.brain.params - if self.periods is None: - self.periods = [params[param].period for param in params] - if self.phase_offsets is None: - self.phase_offsets = [params[param].phase_offset for param in params] - if self.amplitudes is None: - self.amplitudes = [params[param].amplitude for param in params] + if not isinstance(self.brain, BrainNN): + logger.error('Brain not supported') + return + self.params = self.brain.params + if self.params is not None: + if self.periods is None: + self.periods = [self.params[param].period for param in self.params] + if self.phase_offsets is None: + self.phase_offsets = [self.params[param].phase_offset for param in self.params] + if self.amplitudes is None: + self.amplitudes = [self.params[param].amplitude for param in self.params] def calc_count_oscillators(self): """ Calculate amount of oscillators in brain """ + if not isinstance(self.brain, BrainNN): + return oscillators = 0 nodes = self.brain.nodes for node in nodes: @@ -57,81 +99,120 @@ def measure_avg_period(self): """ Measure average (median) Period among the oscillators of the controller """ + if self.params is None: + self.avg_period = 0 + return self.avg_period if self.periods is None: self.collect_sets_of_params() - median = np.median(self.periods) - self.avg_period = median / self.max_param + median = np.median(self.periods) if self.periods else 0 + if median == 0 or self.max_param == 0: + self.avg_period = 0 + else: + self.avg_period = median / self.max_param return self.avg_period def measure_dev_period(self): """ Measure standard deviation of Period among the oscillators of the controller """ + if self.params is None: + self.dev_period = 0 + return self.dev_period if self.periods is None: self.collect_sets_of_params() - self.dev_period = self.sigmoid(np.std(self.periods)) + self.dev_period = self.sigmoid(np.std(self.periods)) if self.periods else 0 return self.dev_period def measure_avg_phase_offset(self): """ Measure average (median) Phase Offset among the oscillators of the controller """ + if self.params is None: + self.avg_phase_offset = 0 + return self.avg_phase_offset if self.phase_offsets is None: self.collect_sets_of_params() - median = np.median(self.phase_offsets) - self.avg_phase_offset = median / self.max_param + median = np.median(self.phase_offsets) if self.phase_offsets else 0 + if median == 0 or self.max_param == 0: + self.avg_phase_offset = 0 + else: + self.avg_phase_offset = median / self.max_param return self.avg_phase_offset def measure_dev_phase_offset(self): """ Measure standard deviation of Phase Offset among the oscillators of the controller """ + if self.params is None: + self.dev_phase_offset = 0 + return self.dev_phase_offset if self.phase_offsets is None: self.collect_sets_of_params() - self.dev_phase_offset = self.sigmoid(np.std(self.phase_offsets)) + self.dev_phase_offset = self.sigmoid(np.std(self.phase_offsets)) if self.phase_offsets else 0 return self.dev_phase_offset def measure_avg_amplitude(self): """ Measure average (median) Amplitude among the oscillators of the controller """ + if self.params is None: + self.avg_amplitude = 0 + return self.avg_amplitude if self.amplitudes is None: self.collect_sets_of_params() - median = np.median(self.amplitudes) - self.avg_amplitude = median / self.max_param + median = np.median(self.amplitudes) if self.amplitudes else 0 + if median == 0 or self.max_param == 0: + self.avg_amplitude = 0 + else: + self.avg_amplitude = median / self.max_param return self.avg_amplitude def measure_dev_amplitude(self): """ Measure standard deviation of Amplitude among the oscillators of the controller """ + if self.params is None: + self.dev_amplitude = 0 + return self.dev_amplitude if self.amplitudes is None: self.collect_sets_of_params() - self.dev_amplitude = self.sigmoid(np.std(self.amplitudes)) + self.dev_amplitude = self.sigmoid(np.std(self.amplitudes)) if self.amplitudes else 0 return self.dev_amplitude def measure_avg_intra_dev_params(self): """ Describes the average (median) among the oscillators, regarding the standard deviation of Period, Phase Offset, and Amplitude, """ - params = self.brain.params - dt = [np.std([params[param].period, params[param].phase_offset, params[param].amplitude]) for param in params] - self.avg_intra_dev_params = self.sigmoid(np.median(dt)) + if self.params is None: + self.avg_intra_dev_params = 0 + return self.avg_intra_dev_params + params = self.params + dt = [np.std([params[param].period, params[param].phase_offset, params[param].amplitude]) for param in params] if params else 0 + self.avg_intra_dev_params = self.sigmoid(np.median(dt)) if dt else 0 return self.avg_intra_dev_params def measure_avg_inter_dev_params(self): """ Measure average (mean) of the parameters Period, Phase Offset, and Amplitude, regarding their deviations among the oscillator """ + if self.params is None: + self.avg_inter_dev_params = 0 + return self.avg_inter_dev_params if self.periods is None or self.phase_offsets is None or self.amplitudes is None: self.collect_sets_of_params() - self.avg_inter_dev_params = self.sigmoid((np.std(self.periods) + np.std(self.phase_offsets) + np.std(self.amplitudes)) / 3) + periods_std = np.std(self.periods) if self.periods else 0 + p_offset_std = np.std(self.phase_offsets) if self.phase_offsets else 0 + amplitude_std = np.std(self.amplitudes) if self.amplitudes else 0 + self.avg_inter_dev_params = self.sigmoid((periods_std + p_offset_std + amplitude_std) / 3) return self.avg_inter_dev_params def measure_sensors_reach(self): """ Describes how connected the sensors are to the oscillators """ + if self.params is None: + self.sensors_reach = 0 + return self.sensors_reach if self.count_oscillators is None: self.calc_count_oscillators() @@ -145,17 +226,23 @@ def measure_sensors_reach(self): for connection in self.brain.connections: if connection.src == nodes[node].id: connections_of_node += 1 - connections.append(connections_of_node/self.count_oscillators) + if connections_of_node == 0 or self.count_oscillators == 0: + connections.append(0) + else: + connections.append(connections_of_node/self.count_oscillators) if not connections: self.sensors_reach = 0 - return 0 - self.sensors_reach = np.median(connections) + return self.sensors_reach + self.sensors_reach = np.median(connections) if connections else 0 return self.sensors_reach def measure_recurrence(self): """ Describes the proportion of oscillators that have a recurrent connection """ + if self.params is None: + self.recurrence = 0 + return self.recurrence connections = self.brain.connections recurrent = 0 for connection in connections: @@ -165,9 +252,9 @@ def measure_recurrence(self): if self.count_oscillators is None: self.calc_count_oscillators() - if recurrent is 0: + if recurrent == 0 or self.count_oscillators == 0: self.recurrence = 0 - return 0 + return self.recurrence else: self.recurrence = recurrent/self.count_oscillators @@ -177,35 +264,40 @@ def measure_synaptic_reception(self): """ Describes the average (median) balance between inhibitory and excitatory connections from the sensors to the oscillators in the controller """ + if self.params is None: + self.synaptic_reception = 0 + return self.synaptic_reception balance_set = [] nodes = self.brain.nodes connections = self.brain.connections for node in nodes: if nodes[node].type == 'Oscillator': inhibitory = [] - excitatory = [] + excitatory = [] for connection in connections: if connection.dst == nodes[node].id and connection.src != nodes[node].id: if connection.weight < 0: inhibitory.append(abs(connection.weight)) if connection.weight > 0: excitatory.append(connection.weight) - inhibitory_sum = np.sum(inhibitory) - excitatory_sum = np.sum(excitatory) + inhibitory_sum = np.sum(inhibitory) if inhibitory else 0 + excitatory_sum = np.sum(excitatory) if excitatory else 0 min_value = min(inhibitory_sum, excitatory_sum) max_value = max(inhibitory_sum, excitatory_sum) if min_value == 0 or max_value == 0: balance_set.append(0) else: balance_set.append(min_value / max_value) - self.synaptic_reception = np.median(balance_set) + self.synaptic_reception = np.median(balance_set) if balance_set else 0 return self.synaptic_reception def measure_all(self): """ - Perform all brain measuerments + Perform all brain measurements """ - self.collect_sets_of_params() + if not isinstance(self.brain, BrainNN): + self.set_measurements_to_zero() + raise RuntimeError('Brain not supported') self.calc_count_oscillators() self.measure_avg_period() self.measure_dev_period() @@ -218,7 +310,19 @@ def measure_all(self): self.measure_sensors_reach() self.measure_recurrence() self.measure_synaptic_reception() - return self.measurements_to_dict() + + def set_all_zero(self): + self.avg_period = 0 + self.dev_period = 0 + self.avg_phase_offset = 0 + self.dev_phase_offset = 0 + self.avg_amplitude = 0 + self.dev_amplitude = 0 + self.avg_intra_dev_params = 0 + self.avg_inter_dev_params = 0 + self.sensors_reach = 0 + self.recurrence = 0 + self.synaptic_reception = 0 def measurements_to_dict(self): """ @@ -237,3 +341,6 @@ def measurements_to_dict(self): 'recurrence': self.recurrence, 'synaptic_reception': self.synaptic_reception } + + def __repr__(self): + return self.measurements_to_dict().__repr__() \ No newline at end of file diff --git a/pyrevolve/revolve_bot/render/brain_graph.py b/pyrevolve/revolve_bot/render/brain_graph.py index 4e86bbe48f..f3233a87cb 100644 --- a/pyrevolve/revolve_bot/render/brain_graph.py +++ b/pyrevolve/revolve_bot/render/brain_graph.py @@ -1,11 +1,19 @@ from graphviz import Digraph, render # belong to TODO import fnmatch +import re +import os class BrainGraph: def __init__(self, brain, name='brain', typename='brain'): - self.graph = Digraph(typename, filename=name, format='png') + name, ext = os.path.splitext(name) + if ext == '' or ext == '.png': + format = 'png' + else: + format = ext[1:] + + self.graph = Digraph(typename, filename=name, format=format, node_attr={'margin': '0'}) self.brain = brain def add_node(self, node_id, node_type, text): @@ -28,17 +36,19 @@ def add_edge(self, source_id, desitnation_id, label): @param destination_id: id of destination node @param label: label of edge """ - self.graph.edge(source_id, desitnation_id, label) + self.graph.edge(str(source_id), str(desitnation_id), str(label)) def save_graph(self): """ Save graph """ - self.graph.render() + self.graph.render(cleanup=True) - def brain_to_graph(self): + def brain_to_graph(self, round_params=False, decimals=4): """ Export complete brain to graph + @param round_params: round parameters if True + @param decimals: decimals to round """ nodes = self.brain.nodes @@ -49,12 +59,32 @@ def brain_to_graph(self): # TODO REMOVE condition WHEN duplicated nodes bug is fixed -- duplicated nodes end in '-[0-9]+' or '-core[0-9]+' (node2-2, node2-core1) if node not in duplicates: node_id = nodes[node].id - text = node_id + text = node_id + '\n' + if nodes[node].type == 'Oscillator': + text += 'Oscillator \n {}'.format(nodes[node].part_id) + elif nodes[node].type == 'Input': + text += 'Sensor \n {}'.format(nodes[node].part_id) if node_id in params: - param = params[node_id] - text += '\n Oscillator {0} \n period: {1} \n phase_offset: {2} \n amplitude: {3}'.format( - nodes[node].part_id, params[node_id].period, params[node_id].phase_offset, params[node_id].amplitude) + if params[node_id].period is not None: + period = round(float(params[node_id].period), decimals) if round_params else float(params[node_id].period) + text += '\n period: {0}'.format(period) + if params[node_id].phase_offset is not None: + phase_offset = round(float(params[node_id].phase_offset), decimals) if round_params else float(params[node_id].phase_offset) + text += '\n phase_offset: {0}'.format(phase_offset) + if params[node_id].amplitude is not None: + amplitude = round(float(params[node_id].amplitude), decimals) if round_params else float(params[node_id].amplitude) + text += '\n amplitude: {0}'.format(amplitude) + if params[node_id].bias is not None: + bias = round(float(params[node_id].bias), decimals) if round_params else float(params[node_id].bias) + text += '\n bias: {0}'.format(bias) + if params[node_id].gain is not None: + gain = round(float(params[node_id].gain), decimals) if round_params else float(params[node_id].gain) + text += '\n gain: {0}'.format(gain) + self.add_node(node_id, nodes[node].type, text) for connection in self.brain.connections: - self.add_edge(str(connection.src), str(connection.dst), str(connection.weight)) + if round_params: + self.add_edge(connection.src, connection.dst, round(float(connection.weight), decimals)) + else: + self.add_edge(connection.src, connection.dst, float(connection.weight)) diff --git a/pyrevolve/revolve_bot/render/canvas.py b/pyrevolve/revolve_bot/render/canvas.py index b7b79d3546..4b01b73089 100644 --- a/pyrevolve/revolve_bot/render/canvas.py +++ b/pyrevolve/revolve_bot/render/canvas.py @@ -154,7 +154,7 @@ def sign_id(self, mod_id): self.context.show_text(mod_id) self.context.stroke() - def draw_controller(self): + def draw_controller(self, mod_id): """Draw a controller (yellow) in the middle of the canvas""" self.context.rectangle(Canvas.x_pos, Canvas.y_pos, 1, 1) self.context.set_source_rgb(255, 255, 0) @@ -162,7 +162,7 @@ def draw_controller(self): self.context.set_source_rgb(0, 0, 0) self.context.set_line_width(0.01) self.context.stroke() - self.sign_id(0) + self.sign_id(mod_id) Canvas.movement_stack.append([Canvas.x_pos, Canvas.y_pos, Canvas.orientation, Canvas.rotating_orientation]) def draw_hinge(self, mod_id): diff --git a/pyrevolve/revolve_bot/render/render.py b/pyrevolve/revolve_bot/render/render.py index 149c607969..1d943553e7 100644 --- a/pyrevolve/revolve_bot/render/render.py +++ b/pyrevolve/revolve_bot/render/render.py @@ -2,96 +2,98 @@ from .canvas import Canvas from .grid import Grid from ..revolve_module import RevolveModule, CoreModule, BrickModule, ActiveHingeModule, TouchSensorModule, BrickSensorModule +from ...custom_logging.logger import logger + class Render: - def __init__(self): - """Instantiate grid""" - self.grid = Grid() + def __init__(self): + """Instantiate grid""" + self.grid = Grid() - def parse_body_to_draw(self, canvas, module, slot): - """ - Parse the body to the canvas to draw the png - @param canvas: instance of the Canvas class - @param module: body of the robot - @param slot: parent slot of module - """ - if isinstance(module, CoreModule): - canvas.draw_controller() - elif isinstance(module, ActiveHingeModule): - canvas.move_by_slot(slot) - Canvas.rotating_orientation += module.orientation - canvas.draw_hinge(module.id) - canvas.draw_connector_to_parent() - elif isinstance(module, BrickModule): - canvas.move_by_slot(slot) - Canvas.rotating_orientation += module.orientation - canvas.draw_module(module.id) - canvas.draw_connector_to_parent() - elif isinstance(module, TouchSensorModule) or isinstance(module, BrickSensorModule): - canvas.move_by_slot(slot) - Canvas.rotating_orientation += module.orientation - canvas.save_sensor_position() + def parse_body_to_draw(self, canvas, module, slot): + """ + Parse the body to the canvas to draw the png + @param canvas: instance of the Canvas class + @param module: body of the robot + @param slot: parent slot of module + """ + if isinstance(module, CoreModule): + canvas.draw_controller(module.id) + elif isinstance(module, ActiveHingeModule): + canvas.move_by_slot(slot) + Canvas.rotating_orientation += module.orientation + canvas.draw_hinge(module.id) + canvas.draw_connector_to_parent() + elif isinstance(module, BrickModule): + canvas.move_by_slot(slot) + Canvas.rotating_orientation += module.orientation + canvas.draw_module(module.id) + canvas.draw_connector_to_parent() + elif isinstance(module, TouchSensorModule) or isinstance(module, BrickSensorModule): + canvas.move_by_slot(slot) + Canvas.rotating_orientation += module.orientation + canvas.save_sensor_position() - if module.has_children(): - # Traverse children of element to draw on canvas - for core_slot, child_module in module.iter_children(): - if child_module is None: - continue - self.parse_body_to_draw(canvas, child_module, core_slot) - canvas.move_back() - else: - # Element has no children, move back to previous state - canvas.move_back() + if module.has_children(): + # Traverse children of element to draw on canvas + for core_slot, child_module in module.iter_children(): + if child_module is None: + continue + self.parse_body_to_draw(canvas, child_module, core_slot) + canvas.move_back() + else: + # Element has no children, move back to previous state + canvas.move_back() - def traverse_path_of_robot(self, module, slot, include_sensors=True): - """ - Traverse path of robot to obtain visited coordinates - @param module: body of the robot - @param slot: attachment of parent slot - @param include_sensors: add sensors to visisted_cooridnates if True - """ - if isinstance(module, ActiveHingeModule) or isinstance(module, BrickModule) or isinstance(module, TouchSensorModule) or isinstance(module, BrickSensorModule): - self.grid.move_by_slot(slot) - self.grid.add_to_visited(include_sensors, isinstance(module, TouchSensorModule)) - if module.has_children(): - # Traverse path of children of module - for core_slot, child_module in module.iter_children(): - if child_module is None: - continue - self.traverse_path_of_robot(child_module, core_slot, include_sensors) - self.grid.move_back() - else: - # Element has no children, move back to previous state - self.grid.move_back() + def traverse_path_of_robot(self, module, slot, include_sensors=True): + """ + Traverse path of robot to obtain visited coordinates + @param module: body of the robot + @param slot: attachment of parent slot + @param include_sensors: add sensors to visisted_cooridnates if True + """ + if isinstance(module, ActiveHingeModule) or isinstance(module, BrickModule) or isinstance(module, TouchSensorModule) or isinstance(module, BrickSensorModule): + self.grid.move_by_slot(slot) + self.grid.add_to_visited(include_sensors, isinstance(module, TouchSensorModule)) + if module.has_children(): + # Traverse path of children of module + for core_slot, child_module in module.iter_children(): + if child_module is None: + continue + self.traverse_path_of_robot(child_module, core_slot, include_sensors) + self.grid.move_back() + else: + # Element has no children, move back to previous state + self.grid.move_back() - def render_robot(self, body, image_path): - """ - Render robot and save image file - @param body: body of robot - @param image_path: file path for saving image - """ - try: - # Calculate dimensions of drawing and core position - self.traverse_path_of_robot(body, 0) - self.grid.calculate_grid_dimensions() - core_position = self.grid.calculate_core_position() + def render_robot(self, body, image_path): + """ + Render robot and save image file + @param body: body of robot + @param image_path: file path for saving image + """ + try: + # Calculate dimensions of drawing and core position + self.traverse_path_of_robot(body, 0) + self.grid.calculate_grid_dimensions() + core_position = self.grid.calculate_core_position() - # Draw canvas - cv = Canvas(self.grid.width, self.grid.height, 100) - cv.set_position(core_position[0], core_position[1]) + # Draw canvas + cv = Canvas(self.grid.width, self.grid.height, 100) + cv.set_position(core_position[0], core_position[1]) - # Draw body of robot - self.parse_body_to_draw(cv, body, 0) + # Draw body of robot + self.parse_body_to_draw(cv, body, 0) - # Draw sensors after, so that they don't get overdrawn - cv.draw_sensors() + # Draw sensors after, so that they don't get overdrawn + cv.draw_sensors() - cv.save_png(image_path) + cv.save_png(image_path) - # Reset variables to default values - cv.reset_canvas() - self.grid.reset_grid() + # Reset variables to default values + cv.reset_canvas() + self.grid.reset_grid() - except Exception as e: - print('Exception {}'.format(e)) + except Exception as e: + logger.exception('Could not render robot and save image file') diff --git a/pyrevolve/revolve_bot/revolve_bot.py b/pyrevolve/revolve_bot/revolve_bot.py index 0a9869a869..f9b59456dc 100644 --- a/pyrevolve/revolve_bot/revolve_bot.py +++ b/pyrevolve/revolve_bot/revolve_bot.py @@ -4,17 +4,21 @@ import yaml import traceback from collections import OrderedDict +from collections import deque from pyrevolve import SDF -from .revolve_module import CoreModule, Orientation -from .brain import Brain, BrainNN, BrainRLPowerSplines +from .revolve_module import CoreModule, TouchSensorModule, Orientation +from .revolve_module import Orientation +from .brain import Brain, BrainNN from .render.render import Render from .render.brain_graph import BrainGraph from .measure.measure_body import MeasureBody from .measure.measure_brain import MeasureBrain +from ..custom_logging.logger import logger +import os class RevolveBot: """ @@ -23,11 +27,15 @@ class RevolveBot: a robot's sdf mode """ - def __init__(self, _id=None): + def __init__(self, _id=None, self_collide=True): self._id = _id self._body = None self._brain = None - # self._battery_level = None + self._morphological_measurements = None + self._brain_measurements = None + self._behavioural_measurements = None + self.self_collide = self_collide + self.battery_level = 0.0 @property def id(self): @@ -43,7 +51,6 @@ def brain(self): def size(self): robot_size = 1 + self._recursive_size_measurement(self._body) - print("calculating robot size: {}".format(robot_size)) return robot_size def _recursive_size_measurement(self, module): @@ -61,30 +68,47 @@ def measure_behaviour(self): """ pass + def measure_phenotype(self): + self._morphological_measurements = self.measure_body() + self._brain_measurements = self.measure_brain() + logger.info('Robot ' + str(self.id) + ' was measured.') + def measure_body(self): """ - :return: dict of body measurements + :return: instance of MeasureBody after performing all measurements """ if self._body is None: - raise RuntimeError('Brain not initialized') + raise RuntimeError('Body not initialized') try: measure = MeasureBody(self._body) - return measure.measure_all() + measure.measure_all() + return measure except Exception as e: - print('Exception: {}'.format(e)) + logger.exception('Failed measuring body') + + def export_phenotype_measurements(self, data_path): + filepath = os.path.join(data_path, 'descriptors', f'phenotype_desc_{self.id}.txt') + with open(filepath, 'w+') as file: + for key, value in self._morphological_measurements.measurements_to_dict().items(): + file.write(f'{key} {value}\n') + for key, value in self._brain_measurements.measurements_to_dict().items(): + file.write(f'{key} {value}\n') def measure_brain(self): """ - :return: dict of brain measurements + :return: instance of MeasureBrain after performing all measurements """ - if self._brain == None: - raise RuntimeError('Brain not initialized') - else: - try: - measure = MeasureBrain(self._brain, 10) - return measure.measure_all() - except: - print('Failed measuring brain') + try: + measure = MeasureBrain(self._brain, 10) + measure_b = MeasureBody(self._body) + measure_b.count_active_hinges() + if measure_b.active_hinges_count > 0: + measure.measure_all() + else: + measure.set_all_zero() + return measure + except Exception as e: + logger.exception('Failed measuring brain') def load(self, text, conf_type): """ @@ -118,7 +142,7 @@ def load_yaml(self, text): self._brain = Brain() except: self._brain = Brain() - print('Failed to load brain, setting to None') + logger.exception('Failed to load brain, setting to None') def load_file(self, path, conf_type='yaml'): """ @@ -135,7 +159,7 @@ def load_file(self, path, conf_type='yaml'): def to_sdf(self, pose=SDF.math.Vector3(0, 0, 0.25), nice_format=None): if type(nice_format) is bool: nice_format = '\t' if nice_format else None - return SDF.revolve_bot_to_sdf(self, pose, nice_format) + return SDF.revolve_bot_to_sdf(self, pose, nice_format, self_collide=self.self_collide) def to_yaml(self): """ @@ -174,9 +198,9 @@ def update_substrate(self, raise_for_intersections=False): :param raise_for_intersections: enable raising an exception if a collision of coordinates is detected :raises self.ItersectionCollisionException: If a collision of coordinates is detected (and check is enabled) """ - substrate_coordinates_all = {(0, 0): self._body.id} + substrate_coordinates_map = {(0, 0): self._body.id} self._body.substrate_coordinates = (0, 0) - self._update_substrate(raise_for_intersections, self._body, Orientation.NORTH, substrate_coordinates_all) + self._update_substrate(raise_for_intersections, self._body, Orientation.NORTH, substrate_coordinates_map) class ItersectionCollisionException(Exception): """ @@ -236,7 +260,7 @@ def _update_substrate(self, module.substrate_coordinates = coordinates # For Karine: If you need to validate old robots, remember to add this condition to this if: - # if raise_for_intersections and coordinates in substrate_coordinates_all and type(module) is not TouchSensorModule: + # if raise_for_intersections and coordinates in substrate_coordinates_map and type(module) is not TouchSensorModule: if raise_for_intersections: if coordinates in substrate_coordinates_map: raise self.ItersectionCollisionException(substrate_coordinates_map) @@ -247,6 +271,15 @@ def _update_substrate(self, new_direction, substrate_coordinates_map) + def _iter_all_elements(self): + to_process = deque([self._body]) + while len(to_process) > 0: + elem = to_process.popleft() + for _i, child in elem.iter_children(): + if child is not None: + to_process.append(child) + yield elem + def render_brain(self, img_path): """ Render image of brain @@ -254,17 +287,17 @@ def render_brain(self, img_path): """ if self._brain is None: raise RuntimeError('Brain not initialized') - else: + elif isinstance(self._brain, BrainNN): try: brain_graph = BrainGraph(self._brain, img_path) - brain_graph.brain_to_graph() + brain_graph.brain_to_graph(True) brain_graph.save_graph() except Exception as e: - print('Failed rendering brain. Exception:') - print(e) - print(traceback.format_exc()) + logger.exception('Failed rendering brain. Exception:') + else: + raise RuntimeError('Brain {} image rendering not supported'.format(type(self._brain))) - def render2d(self, img_path): + def render_body(self, img_path): """ Render 2d representation of robot and store as png :param img_path: path of storing png file @@ -276,6 +309,7 @@ def render2d(self, img_path): render = Render() render.render_robot(self._body, img_path) except Exception as e: - print('Failed rendering 2d robot. Exception:') - print(e) - print(traceback.format_exc()) + logger.exception('Failed rendering 2d robot') + + def __repr__(self): + return f'RevolveBot({self.id})' diff --git a/pyrevolve/revolve_bot/revolve_module.py b/pyrevolve/revolve_bot/revolve_module.py index ce6e2d36f6..16367bc5c7 100644 --- a/pyrevolve/revolve_bot/revolve_module.py +++ b/pyrevolve/revolve_bot/revolve_module.py @@ -36,6 +36,8 @@ def short_repr(self): return 'E' elif self == self.WEST: return 'W' + else: + assert False class RevolveModule: @@ -55,6 +57,7 @@ def __init__(self): self.rgb = None # RevolveModule.DEFAULT_COLOR self.substrate_coordinates = None self.children = [None, None, None, None] + self.info = None def color(self): return self.rgb if self.rgb is not None else self.DEFAULT_COLOR @@ -136,7 +139,7 @@ def _generate_yaml_children(self): has_children = False children = {} - for i, child in enumerate(self.children): + for i, child in self.iter_children(): if child is not None: children[i] = child.to_yaml() has_children = True @@ -215,6 +218,7 @@ class CoreModule(RevolveModule): def __init__(self): super().__init__() + self.substrate_coordinates = (0, 0) def possible_slots(self): return ( diff --git a/pyrevolve/spec/msgs/body_pb2.py b/pyrevolve/spec/msgs/body_pb2.py index 2e6d11e3f3..b6aa3ef246 100644 --- a/pyrevolve/spec/msgs/body_pb2.py +++ b/pyrevolve/spec/msgs/body_pb2.py @@ -40,7 +40,7 @@ has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='type', full_name='revolve.msgs.BodyPart.type', index=1, number=2, type=9, cpp_type=9, label=2, @@ -54,48 +54,49 @@ has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='y', full_name='revolve.msgs.BodyPart.y', index=3, number=4, type=5, cpp_type=1, label=2, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='orientation', full_name='revolve.msgs.BodyPart.orientation', index=4, number=5, type=1, cpp_type=5, label=2, has_default_value=False, default_value=float(0), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='child', full_name='revolve.msgs.BodyPart.child', index=5, number=6, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='param', full_name='revolve.msgs.BodyPart.param', index=6, number=7, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='label', full_name='revolve.msgs.BodyPart.label', index=7, number=8, type=9, cpp_type=9, label=1, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -119,27 +120,28 @@ has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='dst_slot', full_name='revolve.msgs.BodyConnection.dst_slot', index=1, number=2, type=5, cpp_type=1, label=2, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='part', full_name='revolve.msgs.BodyConnection.part', index=2, number=3, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -163,13 +165,14 @@ has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/model_inserted_pb2.py b/pyrevolve/spec/msgs/model_inserted_pb2.py index 978013611e..3e1056bcd0 100644 --- a/pyrevolve/spec/msgs/model_inserted_pb2.py +++ b/pyrevolve/spec/msgs/model_inserted_pb2.py @@ -20,6 +20,7 @@ name='model_inserted.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x14model_inserted.proto\x12\x0crevolve.msgs\x1a\x0bmodel.proto\x1a\ntime.proto\"S\n\rModelInserted\x12\x1f\n\x04time\x18\x01 \x02(\x0b\x32\x11.gazebo.msgs.Time\x12!\n\x05model\x18\x02 \x02(\x0b\x32\x12.gazebo.msgs.Model') , dependencies=[model__pb2.DESCRIPTOR,time__pb2.DESCRIPTOR,]) @@ -40,20 +41,21 @@ has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='model', full_name='revolve.msgs.ModelInserted.model', index=1, number=2, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/neural_net_pb2.py b/pyrevolve/spec/msgs/neural_net_pb2.py index c3c377b632..7f9d29f97b 100644 --- a/pyrevolve/spec/msgs/neural_net_pb2.py +++ b/pyrevolve/spec/msgs/neural_net_pb2.py @@ -19,6 +19,7 @@ name='neural_net.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x10neural_net.proto\x12\x0crevolve.msgs\x1a\x0fparameter.proto\"<\n\x10NeuralConnection\x12\x0b\n\x03src\x18\x01 \x02(\t\x12\x0b\n\x03\x64st\x18\x02 \x02(\t\x12\x0e\n\x06weight\x18\x03 \x02(\x01\"i\n\x06Neuron\x12\n\n\x02id\x18\x01 \x02(\t\x12\r\n\x05layer\x18\x02 \x02(\t\x12\x0c\n\x04type\x18\x03 \x02(\t\x12\x0e\n\x06partId\x18\x04 \x01(\t\x12&\n\x05param\x18\x05 \x03(\x0b\x32\x17.revolve.msgs.Parameter\"i\n\rNeuralNetwork\x12$\n\x06neuron\x18\x01 \x03(\x0b\x32\x14.revolve.msgs.Neuron\x12\x32\n\nconnection\x18\x02 \x03(\x0b\x32\x1e.revolve.msgs.NeuralConnection\"\xb9\x01\n\x13ModifyNeuralNetwork\x12\x15\n\rremove_hidden\x18\x01 \x03(\t\x12(\n\nadd_hidden\x18\x02 \x03(\x0b\x32\x14.revolve.msgs.Neuron\x12,\n\x0eset_parameters\x18\x04 \x03(\x0b\x32\x14.revolve.msgs.Neuron\x12\x33\n\x0bset_weights\x18\x03 \x03(\x0b\x32\x1e.revolve.msgs.NeuralConnection') , dependencies=[parameter__pb2.DESCRIPTOR,]) @@ -39,27 +40,28 @@ has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='dst', full_name='revolve.msgs.NeuralConnection.dst', index=1, number=2, type=9, cpp_type=9, label=2, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='weight', full_name='revolve.msgs.NeuralConnection.weight', index=2, number=3, type=1, cpp_type=5, label=2, has_default_value=False, default_value=float(0), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -83,41 +85,42 @@ has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='layer', full_name='revolve.msgs.Neuron.layer', index=1, number=2, type=9, cpp_type=9, label=2, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='type', full_name='revolve.msgs.Neuron.type', index=2, number=3, type=9, cpp_type=9, label=2, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='partId', full_name='revolve.msgs.Neuron.partId', index=3, number=4, type=9, cpp_type=9, label=1, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='param', full_name='revolve.msgs.Neuron.param', index=4, number=5, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -141,20 +144,21 @@ has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='connection', full_name='revolve.msgs.NeuralNetwork.connection', index=1, number=2, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -178,34 +182,35 @@ has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='add_hidden', full_name='revolve.msgs.ModifyNeuralNetwork.add_hidden', index=1, number=2, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='set_parameters', full_name='revolve.msgs.ModifyNeuralNetwork.set_parameters', index=2, number=4, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='set_weights', full_name='revolve.msgs.ModifyNeuralNetwork.set_weights', index=3, number=3, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/parameter_pb2.py b/pyrevolve/spec/msgs/parameter_pb2.py index 8e57dfce6e..c666d55583 100644 --- a/pyrevolve/spec/msgs/parameter_pb2.py +++ b/pyrevolve/spec/msgs/parameter_pb2.py @@ -18,6 +18,7 @@ name='parameter.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x0fparameter.proto\x12\x0crevolve.msgs\"\x1a\n\tParameter\x12\r\n\x05value\x18\x01 \x02(\x01') ) @@ -37,13 +38,14 @@ has_default_value=False, default_value=float(0), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/robot_pb2.py b/pyrevolve/spec/msgs/robot_pb2.py index 9714145531..885f0a1630 100644 --- a/pyrevolve/spec/msgs/robot_pb2.py +++ b/pyrevolve/spec/msgs/robot_pb2.py @@ -20,6 +20,7 @@ name='robot.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x0brobot.proto\x12\x0crevolve.msgs\x1a\nbody.proto\x1a\x10neural_net.proto\"a\n\x05Robot\x12\n\n\x02id\x18\x01 \x02(\x05\x12 \n\x04\x62ody\x18\x02 \x02(\x0b\x32\x12.revolve.msgs.Body\x12*\n\x05\x62rain\x18\x03 \x02(\x0b\x32\x1b.revolve.msgs.NeuralNetwork') , dependencies=[body__pb2.DESCRIPTOR,neural__net__pb2.DESCRIPTOR,]) @@ -40,27 +41,28 @@ has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='body', full_name='revolve.msgs.Robot.body', index=1, number=2, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='brain', full_name='revolve.msgs.Robot.brain', index=2, number=3, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/robot_states_pb2.py b/pyrevolve/spec/msgs/robot_states_pb2.py index 6517c3f8f5..9d09a2680d 100644 --- a/pyrevolve/spec/msgs/robot_states_pb2.py +++ b/pyrevolve/spec/msgs/robot_states_pb2.py @@ -20,7 +20,8 @@ name='robot_states.proto', package='revolve.msgs', syntax='proto2', - serialized_pb=_b('\n\x12robot_states.proto\x12\x0crevolve.msgs\x1a\ntime.proto\x1a\npose.proto\"G\n\nRobotState\x12\n\n\x02id\x18\x01 \x02(\r\x12\x0c\n\x04name\x18\x02 \x02(\t\x12\x1f\n\x04pose\x18\x03 \x02(\x0b\x32\x11.gazebo.msgs.Pose\"]\n\x0bRobotStates\x12\x1f\n\x04time\x18\x01 \x02(\x0b\x32\x11.gazebo.msgs.Time\x12-\n\x0brobot_state\x18\x02 \x03(\x0b\x32\x18.revolve.msgs.RobotState') + serialized_options=None, + serialized_pb=_b('\n\x12robot_states.proto\x12\x0crevolve.msgs\x1a\ntime.proto\x1a\npose.proto\"U\n\nRobotState\x12\n\n\x02id\x18\x01 \x02(\r\x12\x0c\n\x04name\x18\x02 \x02(\t\x12\x1f\n\x04pose\x18\x03 \x02(\x0b\x32\x11.gazebo.msgs.Pose\x12\x0c\n\x04\x64\x65\x61\x64\x18\x04 \x01(\x08\"]\n\x0bRobotStates\x12\x1f\n\x04time\x18\x01 \x02(\x0b\x32\x11.gazebo.msgs.Time\x12-\n\x0brobot_state\x18\x02 \x03(\x0b\x32\x18.revolve.msgs.RobotState') , dependencies=[time__pb2.DESCRIPTOR,pose__pb2.DESCRIPTOR,]) @@ -40,34 +41,42 @@ has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='name', full_name='revolve.msgs.RobotState.name', index=1, number=2, type=9, cpp_type=9, label=2, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='pose', full_name='revolve.msgs.RobotState.pose', index=2, number=3, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), + _descriptor.FieldDescriptor( + name='dead', full_name='revolve.msgs.RobotState.dead', index=3, + number=4, type=8, cpp_type=7, label=1, + has_default_value=False, default_value=False, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], oneofs=[ ], serialized_start=60, - serialized_end=131, + serialized_end=145, ) @@ -84,27 +93,28 @@ has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='robot_state', full_name='revolve.msgs.RobotStates.robot_state', index=1, number=2, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], oneofs=[ ], - serialized_start=133, - serialized_end=226, + serialized_start=147, + serialized_end=240, ) _ROBOTSTATE.fields_by_name['pose'].message_type = pose__pb2._POSE diff --git a/pyrevolve/spec/msgs/sdf_body_analyze_pb2.py b/pyrevolve/spec/msgs/sdf_body_analyze_pb2.py index 1e0bb4b381..154482fab6 100644 --- a/pyrevolve/spec/msgs/sdf_body_analyze_pb2.py +++ b/pyrevolve/spec/msgs/sdf_body_analyze_pb2.py @@ -11,6 +11,7 @@ _sym_db = _symbol_database.Default() + from pygazebo.msg import vector3d_pb2 as vector3d__pb2 @@ -18,6 +19,7 @@ name='sdf_body_analyze.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x16sdf_body_analyze.proto\x12\x0crevolve.msgs\x1a\x0evector3d.proto\"1\n\x07\x43ontact\x12\x12\n\ncollision1\x18\x01 \x02(\t\x12\x12\n\ncollision2\x18\x02 \x02(\t\"U\n\x0b\x42oundingBox\x12\"\n\x03min\x18\x01 \x02(\x0b\x32\x15.gazebo.msgs.Vector3d\x12\"\n\x03max\x18\x02 \x02(\x0b\x32\x15.gazebo.msgs.Vector3d\"n\n\x14\x42odyAnalysisResponse\x12.\n\x0b\x62oundingBox\x18\x01 \x01(\x0b\x32\x19.revolve.msgs.BoundingBox\x12&\n\x07\x63ontact\x18\x02 \x03(\x0b\x32\x15.revolve.msgs.Contact') , dependencies=[vector3d__pb2.DESCRIPTOR,]) @@ -38,20 +40,21 @@ has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='collision2', full_name='revolve.msgs.Contact.collision2', index=1, number=2, type=9, cpp_type=9, label=2, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -75,20 +78,21 @@ has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='max', full_name='revolve.msgs.BoundingBox.max', index=1, number=2, type=11, cpp_type=10, label=2, has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -112,20 +116,21 @@ has_default_value=False, default_value=None, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='contact', full_name='revolve.msgs.BodyAnalysisResponse.contact', index=1, number=2, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/spec/msgs/spline_policy_pb2.py b/pyrevolve/spec/msgs/spline_policy_pb2.py index 75c361422f..5b367e44d1 100644 --- a/pyrevolve/spec/msgs/spline_policy_pb2.py +++ b/pyrevolve/spec/msgs/spline_policy_pb2.py @@ -12,13 +12,14 @@ _sym_db = _symbol_database.Default() -import parameter_pb2 as parameter__pb2 +from . import parameter_pb2 as parameter__pb2 DESCRIPTOR = _descriptor.FileDescriptor( name='spline_policy.proto', package='revolve.msgs', syntax='proto2', + serialized_options=None, serialized_pb=_b('\n\x13spline_policy.proto\x12\x0crevolve.msgs\x1a\x0fparameter.proto\"M\n\x06Spline\x12\r\n\x05index\x18\x01 \x02(\x05\x12\x0c\n\x04size\x18\x02 \x02(\x05\x12&\n\x05param\x18\x05 \x03(\x0b\x32\x17.revolve.msgs.Parameter\"\x17\n\x06Policy\x12\r\n\x05index\x18\x01 \x03(\x05\"6\n\x0cModifyPolicy\x12\x11\n\tadd_point\x18\x01 \x03(\x01\x12\x13\n\x0binterpolate\x18\x02 \x03(\t') , dependencies=[parameter__pb2.DESCRIPTOR,]) @@ -39,27 +40,28 @@ has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='size', full_name='revolve.msgs.Spline.size', index=1, number=2, type=5, cpp_type=1, label=2, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='param', full_name='revolve.msgs.Spline.param', index=2, number=5, type=11, cpp_type=10, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -83,13 +85,14 @@ has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], @@ -113,20 +116,21 @@ has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), _descriptor.FieldDescriptor( name='interpolate', full_name='revolve.msgs.ModifyPolicy.interpolate', index=1, number=2, type=9, cpp_type=9, label=3, has_default_value=False, default_value=[], message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, - ), + serialized_options=None, file=DESCRIPTOR), ], extensions=[ ], nested_types=[], enum_types=[ ], + serialized_options=None, is_extendable=False, syntax='proto2', extension_ranges=[], diff --git a/pyrevolve/tol/manage/measures.py b/pyrevolve/tol/manage/measures.py new file mode 100644 index 0000000000..05b32cd0cd --- /dev/null +++ b/pyrevolve/tol/manage/measures.py @@ -0,0 +1,168 @@ +import numpy as np + +from pyrevolve.SDF.math import Vector3 +from pyrevolve.util import Time +import math +import sys + + +class BehaviouralMeasurements: + """ + Calculates all the measurements and saves them in one object + """ + def __init__(self, robot_manager = None, robot = None): + """ + :param robot_manager: Revolve Manager that holds the life of the robot + :param robot: Revolve Bot for measurements relative to the robot morphology and brain + :type robot: RevolveBot + """ + if robot_manager is not None and robot is not None: + self.velocity = velocity(robot_manager) + self.displacement = displacement(robot_manager) + self.displacement_velocity = displacement_velocity(robot_manager) + self.displacement_velocity_hill = displacement_velocity_hill(robot_manager) + self.head_balance = head_balance(robot_manager) + self.contacts = contacts(robot_manager, robot) + else: + self.velocity = None + self.displacement = None + self.displacement_velocity = None + self.displacement_velocity_hill = None + self.head_balance = None + self.contacts = None + + def items(self): + return { + 'velocity': self.velocity, + #'displacement': self.displacement, + 'displacement_velocity': self.displacement_velocity, + 'displacement_velocity_hill': self.displacement_velocity_hill, + 'head_balance': self.head_balance, + 'contacts': self.contacts + }.items() + + + +def velocity(robot_manager): + """ + Returns the velocity over the maintained window + :return: + """ + return robot_manager._dist / robot_manager._time if robot_manager._time > 0 else 0 + + +def displacement(robot_manager): + """ + Returns a tuple of the displacement in both time and space + between the first and last registered element in the speed + window. + :return: Tuple where the first item is a displacement vector + and the second a `Time` instance. + :rtype: tuple(Vector3, Time) + """ + if len(robot_manager._positions) == 0: + return Vector3(0, 0, 0), Time() + return ( + robot_manager._positions[-1] - robot_manager._positions[0], + robot_manager._times[-1] - robot_manager._times[0] + ) + + +def path_length(robot_manager): + return robot_manager._dist + + +def displacement_velocity(robot_manager): + """ + Returns the displacement velocity, i.e. the velocity + between the first and last recorded position of the + robot in the speed window over a straight line, + ignoring the path that was taken. + :return: + """ + dist, time = displacement(robot_manager) + if time.is_zero(): + return 0.0 + return np.sqrt(dist.x ** 2 + dist.y ** 2) / float(time) + + +def displacement_velocity_hill(robot_manager): + dist, time = displacement(robot_manager) + if time.is_zero(): + return 0.0 + return dist.y / float(time) + + +def head_balance(robot_manager): + """ + Returns the average rotation of teh head in the roll and pitch dimensions. + :return: + """ + roll = 0 + pitch = 0 + instants = len(robot_manager._orientations) + for o in robot_manager._orientations: + roll = roll + abs(o[0]) * 180 / math.pi + pitch = pitch + abs(o[1]) * 180 / math.pi + # accumulated angles for each type of rotation + # divided by iterations * maximum angle * each type of rotation + if instants == 0: + balance = None + else: + balance = (roll + pitch) / (instants * 180 * 2) + # turns imbalance to balance + balance = 1 - balance + return balance + + +def contacts(robot_manager, robot): + """ + Measures the average number of contacts with the floor relative to the body size + + WARN: this measurement could be faulty, several robots were + found to have 0 contacts if simulation is too fast + + :param robot_manager: reference to the robot in simulation + :param robot: reference to the robot for size measurement + :return: average number of contacts per block in the lifetime + """ + avg_contacts = 0 + for c in robot_manager._contacts: + avg_contacts += c + avg_contacts = avg_contacts / robot.phenotype._morphological_measurements.measurements_to_dict()['absolute_size'] + return avg_contacts + + +def logs_position_orientation(robot_manager, o, evaluation_time, robotid, path): + with open(path + '/data_fullevolution/descriptors/positions_' + robotid + '.txt', "a+") as f: + if robot_manager.second <= evaluation_time: + robot_manager.avg_roll += robot_manager._orientations[o][0] + robot_manager.avg_pitch += robot_manager._orientations[o][1] + robot_manager.avg_yaw += robot_manager._orientations[o][2] + robot_manager.avg_x += robot_manager._positions[o].x + robot_manager.avg_y += robot_manager._positions[o].y + robot_manager.avg_z += robot_manager._positions[o].z + robot_manager.avg_roll = robot_manager.avg_roll / robot_manager.count_group + robot_manager.avg_pitch = robot_manager.avg_pitch / robot_manager.count_group + robot_manager.avg_yaw = robot_manager.avg_yaw / robot_manager.count_group + robot_manager.avg_x = robot_manager.avg_x / robot_manager.count_group + robot_manager.avg_y = robot_manager.avg_y / robot_manager.count_group + robot_manager.avg_z = robot_manager.avg_z / robot_manager.count_group + robot_manager.avg_roll = robot_manager.avg_roll * 180 / math.pi + robot_manager.avg_pitch = robot_manager.avg_pitch * 180 / math.pi + robot_manager.avg_yaw = robot_manager.avg_yaw * 180 / math.pi + f.write(str(robot_manager.second) + ' ' + + str(robot_manager.avg_roll) + ' ' + + str(robot_manager.avg_pitch) + ' ' + + str(robot_manager.avg_yaw) + ' ' + + str(robot_manager.avg_x) + ' ' + + str(robot_manager.avg_y) + ' ' + + str(robot_manager.avg_z) + '\n') + robot_manager.second += 1 + robot_manager.avg_roll = 0 + robot_manager.avg_pitch = 0 + robot_manager.avg_yaw = 0 + robot_manager.avg_x = 0 + robot_manager.avg_y = 0 + robot_manager.avg_z = 0 + robot_manager.count_group = 1 diff --git a/pyrevolve/tol/manage/robotmanager.py b/pyrevolve/tol/manage/robotmanager.py index ebe32d60e7..78200e0010 100644 --- a/pyrevolve/tol/manage/robotmanager.py +++ b/pyrevolve/tol/manage/robotmanager.py @@ -6,6 +6,9 @@ from pyrevolve.angle import RobotManager as RvRobotManager from pyrevolve.util import Time +from pyrevolve.tol.manage import measures as ms +from pyrevolve.evolution import fitness + class RobotManager(RvRobotManager): """ @@ -18,7 +21,9 @@ def __init__( robot, position, time, - battery_level=0.0 + battery_level=0.0, + position_log_size=None, + warmup_time=0.0, ): """ :param conf: @@ -31,14 +36,16 @@ def __init__( :type battery_level: float :return: """ - speed_window = int(conf.evaluation_time * conf.pose_update_frequency) + time = conf.evaluation_time if time is None else time + speed_window = int(float(time) * conf.pose_update_frequency) + 1 if position_log_size is None \ + else position_log_size super(RobotManager, self).__init__( robot=robot, position=position, time=time, battery_level=battery_level, speed_window=speed_window, - warmup_time=conf.warmup_time, + warmup_time=warmup_time, ) # Set of robots this bot has mated with @@ -57,7 +64,7 @@ def will_mate_with(self, other): :type other: RobotManager :return: """ - if self.age() < self.conf.warmup_time: + if self.age() < self.warmup_time: # Don't mate within the warmup time return False @@ -77,8 +84,8 @@ def will_mate_with(self, other): self.conf.mating_distance_threshold: return False - my_fitness = self.fitness() - other_fitness = other.fitness() + my_fitness = self.old_revolve_fitness() + other_fitness = other.old_revolve_fitness() # Only mate with robots with nonzero fitness, check for self # zero-fitness to prevent division by zero. @@ -87,21 +94,6 @@ def will_mate_with(self, other): (other_fitness / my_fitness) >= self.conf.mating_fitness_threshold ) - def distance_to(self, vec, planar=True): - """ - Calculates the Euclidean distance from this robot to - the given vector position. - :param vec: - :type vec: Vector3 - :param planar: If true, only x/y coordinates are considered. - :return: - """ - diff = self.last_position - vec - if planar: - diff.z = 0 - - return diff.norm() - @staticmethod def header(): """ @@ -145,43 +137,15 @@ def header(): # # csv_writer.writerow(row) - def fitness(self): - """ - Fitness is proportional to both the displacement and absolute - velocity of the center of mass of the robot, in the formula: - - (1 - d l) * (a dS + b S + c l) - - Where dS is the displacement over a direct line between the - start and end points of the robot, S is the distance that - the robot has moved and l is the robot size. - - Since we use an active speed window, we use this formula - in context of velocities instead. The parameters a, b and c - are modifyable through config. - :return: - """ - age = self.age() - if age < (0.25 * self.conf.evaluation_time) \ - or age < self.conf.warmup_time: - # We want at least some data - return 0.0 - - v_fac = self.conf.fitness_velocity_factor - d_fac = self.conf.fitness_displacement_factor - s_fac = self.conf.fitness_size_factor - d = 1.0 - (self.conf.fitness_size_discount * self.size) - v = d * (d_fac * self.displacement_velocity() - + v_fac * self.velocity() - + s_fac * self.size) - return v if v <= self.conf.fitness_limit else 0.0 + def old_revolve_fitness(self): + return fitness.online_old_revolve(self) def is_evaluated(self): """ Returns true if this robot is at least one full evaluation time old. :return: """ - return self.age() >= (self.conf.warmup_time + self.conf.evaluation_time) + return self.age() >= (self.warmup_time + self.conf.evaluation_time) def charge(self): """ @@ -190,6 +154,13 @@ def charge(self): """ return self.initial_charge - (float(self.age()) * self.size) + def inverse_charge(self): + """ + Returns the remaining battery charge of this robot. + :return: + """ + return self.initial_charge - (float(self.age()) / self.size) + def did_mate_with(self, other): """ Called when this robot mated with another robot successfully. diff --git a/pyrevolve/tol/manage/world.py b/pyrevolve/tol/manage/world.py index 603df93cd5..651ab01553 100644 --- a/pyrevolve/tol/manage/world.py +++ b/pyrevolve/tol/manage/world.py @@ -37,22 +37,22 @@ class World(WorldManager): future that resolves when the response is delivered. """ - def __init__(self, conf, _private): + def __init__(self, conf, _private, world_address): """ - :param conf: - :return: """ + world_address = ("127.0.0.1", 11345) if world_address is None else world_address + conf = make_revolve_config(conf) super(World, self).__init__( - _private=_private, - world_address=str_to_address(conf.world_address), - # analyzer_address=str_to_address(conf.analyzer_address), - output_directory=conf.output_directory, - builder=None, - state_update_frequency=conf.pose_update_frequency, - generator=None, - restore=conf.restore_directory + _private=_private, + world_address=world_address, + # analyzer_address=str_to_address(conf.analyzer_address), + output_directory=conf.output_directory, + builder=None, + state_update_frequency=conf.pose_update_frequency, + generator=None, + restore=conf.restore_directory ) self.conf = conf @@ -76,20 +76,21 @@ def __init__(self, conf, _private): self._reproducing = False # Write settings to config file - if self.output_directory: + if None:#self.output_directory: parser.record( - args=conf, - file=os.path.join(self.output_directory, "settings.conf") + args=conf, + file=os.path.join(self.output_directory, "settings.conf") ) @classmethod - async def create(cls, conf): + async def create(cls, conf, world_address=None): """ Coroutine to instantiate a Revolve.Angle WorldManager :param conf: + :param world_address: :return: """ - self = cls(_private=cls._PRIVATE, conf=conf) + self = cls(_private=cls._PRIVATE, conf=conf, world_address=world_address) await self._init() return self @@ -114,10 +115,11 @@ def create_robot_manager( :return: """ return RobotManager( - conf=self.conf, - robot=robot, - position=position, - time=time, + conf=self.conf, + robot=robot, + position=position, + time=time, + battery_level=robot.battery_level, ) async def add_highlight(self, position, color): @@ -127,7 +129,7 @@ async def add_highlight(self, position, color): :param color: :return: """ - hl = Highlight("highlight_"+str(self.get_robot_id()), color) + hl = Highlight("highlight_" + str(self.get_robot_id()), color) position = position.copy() position.z = 0 hl.set_position(position) @@ -143,7 +145,7 @@ async def generate_population(self, n): :return: Future with a list of valid robot trees and corresponding bounding boxes. """ - logger.debug("Generating population of size %d..." % n) + logger.info("Generating population of size %d..." % n) trees = [] bboxes = [] @@ -168,12 +170,12 @@ async def insert_population(self, trees, poses): """ futures = [] for tree, pose in zip(trees, poses): - future = await (self.insert_robot(tree, pose)) + future = self.insert_robot(tree, pose) futures.append(future) future = multi_future(futures) future.add_done_callback( - lambda _: logger.debug("Done inserting population.")) + lambda _: logger.info("Done inserting population.")) return future def to_sdfbot(self, robot, robot_name, initial_battery=0.0): @@ -184,11 +186,11 @@ def to_sdfbot(self, robot, robot_name, initial_battery=0.0): :return: """ return to_sdfbot( - robot=robot, - name=robot_name, - builder=None, - conf=self.conf, - battery_charge=initial_battery + robot=robot, + name=robot_name, + builder=None, + conf=self.conf, + battery_charge=initial_battery ) async def build_walls(self, points): @@ -204,12 +206,12 @@ async def build_walls(self, points): start = points[i] end = points[(i + 1) % length] wall = Wall( - name="wall_%d" % i, - start=start, - end=end, - thickness=constants.WALL_THICKNESS, - height=constants.WALL_HEIGHT) - future = await (self.insert_model(SDF(elements=[wall]))) + name="wall_%d" % i, + start=start, + end=end, + thickness=constants.WALL_THICKNESS, + height=constants.WALL_HEIGHT) + future = self.insert_model(SDF(elements=[wall])) futures.append(future) return multi_future(futures) @@ -221,18 +223,18 @@ async def attempt_mate(self, ra, rb): :param rb: :return: """ - logger.debug("Attempting mating between `{}` and `{}`...".format( - ra.name, - rb.name)) + logger.info("Attempting mating between `{}` and `{}`...".format( + ra.name, + rb.name)) # Attempt to create a child through crossover success, child = self.crossover.crossover(ra.tree, rb.tree) if not success: - logger.debug("Crossover failed.") + logger.info("Crossover failed.") return False # Apply mutation - logger.debug("Crossover succeeded, applying mutation...") + logger.info("Crossover succeeded, applying mutation...") self.mutator.mutate(child, in_place=True) # if self.conf.enforce_planarity: @@ -240,16 +242,16 @@ async def attempt_mate(self, ra, rb): _, outputs, _ = child.root.io_count(recursive=True) if not outputs: - logger.debug("Evolution resulted in child without motors.") + logger.info("Evolution resulted in child without motors.") return False # Check if the robot body is valid ret = await (self.analyze_tree(child)) if ret is None or ret[0]: - logger.debug("Intersecting body parts: Miscarriage.") + logger.info("Intersecting body parts: Miscarriage.") return False - logger.debug("Viable child created.") + logger.info("Viable child created.") return child, ret[1] diff --git a/pyrevolve/tol/scenery/birth_clinic.py b/pyrevolve/tol/scenery/birth_clinic.py index f9c15fcff4..65ad74622d 100644 --- a/pyrevolve/tol/scenery/birth_clinic.py +++ b/pyrevolve/tol/scenery/birth_clinic.py @@ -7,6 +7,7 @@ from pyrevolve.sdfbuilder.structure import Mesh, Visual, Collision from pyrevolve.sdfbuilder.math import Vector3 from pyrevolve.sdfbuilder.util import number_format as nf +from ...custom_logging.logger import logger from .. import constants @@ -73,4 +74,4 @@ def __init__(self, diameter=3.0, height=3.0, name="birth_clinic"): if __name__ == '__main__': sdf = SDF(elements=[BirthClinic()]) - print(sdf) + logger.info(sdf) diff --git a/pyrevolve/util/asyncio_timer.py b/pyrevolve/util/asyncio_timer.py new file mode 100644 index 0000000000..a4154e003c --- /dev/null +++ b/pyrevolve/util/asyncio_timer.py @@ -0,0 +1,19 @@ +import asyncio + + +class AsyncTimer: + def __init__(self, timeout, callback): + self._timeout = timeout + self._callback = callback + self._task = asyncio.ensure_future(self._job()) + self._stop = False + + async def _job(self): + await asyncio.sleep(self._timeout) + await self._callback() + if not self._stop: + self._task = asyncio.ensure_future(self._job()) + + def cancel(self): + self._task.cancel() + self._stop = True diff --git a/pyrevolve/util/futures.py b/pyrevolve/util/futures.py index c2e3f92b7e..98c9202c97 100644 --- a/pyrevolve/util/futures.py +++ b/pyrevolve/util/futures.py @@ -8,6 +8,7 @@ import sys from asyncio import Future +from ..custom_logging.logger import logger def multi_future(children, quiet_exceptions=()): @@ -37,8 +38,7 @@ def callback(ft): except Exception as e: if future.done(): if not isinstance(e, quiet_exceptions): - print("Multiple exceptions in yield list", - file=sys.stderr) + logger.error("Multiple exceptions in yield list") else: future.set_exception(sys.exc_info()) if not future.done(): diff --git a/pyrevolve/util/supervisor/analyzer_queue.py b/pyrevolve/util/supervisor/analyzer_queue.py new file mode 100644 index 0000000000..1dfd3869b4 --- /dev/null +++ b/pyrevolve/util/supervisor/analyzer_queue.py @@ -0,0 +1,35 @@ +import os + +from pyrevolve.custom_logging.logger import logger +from pyrevolve.gazebo.analyze import BodyAnalyzer +from pyrevolve.util.supervisor.simulator_queue import SimulatorQueue +from pyrevolve.util.supervisor.supervisor_collision import CollisionSimSupervisor + + +class AnalyzerQueue(SimulatorQueue): + EVALUATION_TIMEOUT = 30 # seconds + + def __init__(self, n_cores: int, settings, port_start=11345, simulator_cmd='gzserver'): + super(AnalyzerQueue, self).__init__(n_cores, settings, port_start, simulator_cmd) + + def _simulator_supervisor(self, simulator_name_postfix): + return CollisionSimSupervisor( + world_file=os.path.join('tools', 'analyzer', 'analyzer-world.world'), + simulator_cmd=self._simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name=f'analyzer_{simulator_name_postfix}' + ) + + async def _connect_to_simulator(self, settings, address, port): + return await BodyAnalyzer.create(address, port) + + async def _evaluate_robot(self, simulator_connection, robot, conf): + if robot.failed_eval_attempt_count == 3: + logger.info(f'Robot {robot.phenotype.id} analyze failed (reached max attempt of 3), fitness set to None.') + analyze_result = None + return analyze_result + else: + analyze_result = await simulator_connection.analyze_robot(robot.phenotype) + return analyze_result diff --git a/pyrevolve/util/supervisor/nbsr.py b/pyrevolve/util/supervisor/nbsr.py index dc235d0619..6a26c170ce 100644 --- a/pyrevolve/util/supervisor/nbsr.py +++ b/pyrevolve/util/supervisor/nbsr.py @@ -28,7 +28,7 @@ def _populate_queue(stream, queue): while True: line = stream.readline() - if line and line != '\n': + if line and line != '\n' and 'ODE Message 3' not in line.decode(): queue.put(line) else: # This used to throw an exception, but we cannot diff --git a/pyrevolve/util/supervisor/simulator_queue.py b/pyrevolve/util/supervisor/simulator_queue.py new file mode 100644 index 0000000000..8f69eb52a9 --- /dev/null +++ b/pyrevolve/util/supervisor/simulator_queue.py @@ -0,0 +1,177 @@ +import asyncio +import os +import time + +from pyrevolve.custom_logging.logger import logger +from pyrevolve.evolution.population import PopulationConfig +from pyrevolve.tol.manage import World +from pyrevolve.util.supervisor.supervisor_multi import DynamicSimSupervisor +from pyrevolve.SDF.math import Vector3 +from pyrevolve.tol.manage import measures + + +class SimulatorQueue: + EVALUATION_TIMEOUT = 120 # seconds + + def __init__(self, n_cores: int, settings, port_start=11345, simulator_cmd=None): + assert (n_cores > 0) + self._n_cores = n_cores + self._settings = settings + self._port_start = port_start + self._simulator_cmd = settings.simulator_cmd if simulator_cmd is None else simulator_cmd + self._supervisors = [] + self._connections = [] + self._robot_queue = asyncio.Queue() + self._free_simulator = [True for _ in range(n_cores)] + self._workers = [] + + def _simulator_supervisor(self, simulator_name_postfix): + return DynamicSimSupervisor( + world_file=self._settings.world, + simulator_cmd=self._simulator_cmd, + simulator_args=["--verbose"], + plugins_dir_path=os.path.join('.', 'build', 'lib'), + models_dir_path=os.path.join('.', 'models'), + simulator_name=f'gazebo_{simulator_name_postfix}' + ) + + async def _connect_to_simulator(self, settings, address, port): + return await World.create(settings, world_address=(address, port)) + + async def _start_debug(self): + connection = await self._connect_to_simulator(self._settings, "127.0.0.1", self._port_start) + self._connections.append(connection) + self._workers.append(asyncio.ensure_future(self._simulator_queue_worker(0))) + + async def start(self): + if self._settings.simulator_cmd == 'debug': + await self._start_debug() + return + future_launches = [] + future_connections = [] + for i in range(self._n_cores): + simulator_supervisor = self._simulator_supervisor( + simulator_name_postfix=i + ) + simulator_future_launch = simulator_supervisor.launch_simulator(port=self._port_start+i) + + future_launches.append(simulator_future_launch) + self._supervisors.append(simulator_supervisor) + + await asyncio.sleep(5) + + for i, future_launch in enumerate(future_launches): + await future_launch + connection_future = self._connect_to_simulator(self._settings, "127.0.0.1", self._port_start+i) + future_connections.append(connection_future) + + for i, future_conn in enumerate(future_connections): + self._connections.append(await future_conn) + self._workers.append(asyncio.ensure_future(self._simulator_queue_worker(i))) + + await asyncio.sleep(1) + + def test_robot(self, robot, conf: PopulationConfig): + """ + :param robot: robot phenotype + :param conf: configuration of the experiment + :return: + """ + future = asyncio.Future() + self._robot_queue.put_nowait((robot, future, conf)) + return future + + async def _restart_simulator(self, i): + # restart simulator + address = '127.0.0.1' + port = self._port_start+i + logger.error("Restarting simulator") + logger.error("Restarting simulator... disconnecting") + try: + await asyncio.wait_for(self._connections[i].disconnect(), 10) + except asyncio.TimeoutError: + pass + logger.error("Restarting simulator... restarting") + await self._supervisors[i].relaunch(10, address=address, port=port) + await asyncio.sleep(10) + logger.debug("Restarting simulator done... connecting") + self._connections[i] = await self._connect_to_simulator(self._settings, address, port) + logger.debug("Restarting simulator done... connection done") + + async def _worker_evaluate_robot(self, connection, robot, future, conf): + await asyncio.sleep(0.01) + start = time.time() + try: + timeout = self.EVALUATION_TIMEOUT # seconds + result = await asyncio.wait_for(self._evaluate_robot(connection, robot, conf), timeout=timeout) + except asyncio.TimeoutError: + # WAITED TO MUCH, RESTART SIMULATOR + elapsed = time.time()-start + logger.error(f"Simulator restarted after {elapsed}") + return False + except Exception: + logger.exception(f"Exception running robot {robot.phenotype}") + return False + + elapsed = time.time()-start + logger.info(f"time taken to do a simulation {elapsed}") + + robot.failed_eval_attempt_count = 0 + future.set_result(result) + return True + + async def _simulator_queue_worker(self, i): + try: + self._free_simulator[i] = True + while True: + logger.info(f"simulator {i} waiting for robot") + (robot, future, conf) = await self._robot_queue.get() + self._free_simulator[i] = False + logger.info(f"Picking up robot {robot.phenotype.id} into simulator {i}") + success = await self._worker_evaluate_robot(self._connections[i], robot, future, conf) + if success: + if robot.failed_eval_attempt_count == 3: + logger.info("Robot failed to be evaluated 3 times. Saving robot to failed_eval file") + conf.experiment_management.export_failed_eval_robot(robot) + robot.failed_eval_attempt_count = 0 + logger.info(f"simulator {i} finished robot {robot.phenotype.id}") + else: + # restart of the simulator happened + robot.failed_eval_attempt_count += 1 + logger.info(f"Robot {robot.phenotype.id} current failed attempt: {robot.failed_eval_attempt_count}") + await self._robot_queue.put((robot, future, conf)) + await self._restart_simulator(i) + self._robot_queue.task_done() + self._free_simulator[i] = True + except Exception: + logger.exception(f"Exception occurred for Simulator worker {i}") + + async def _evaluate_robot(self, simulator_connection, robot, conf): + if robot.failed_eval_attempt_count == 3: + logger.info(f'Robot {robot.phenotype.id} evaluation failed (reached max attempt of 3), fitness set to None.') + robot_fitness = None + return robot_fitness, None + else: + # Change this `max_age` from the command line parameters (--evalution-time) + max_age = conf.evaluation_time + robot_manager = await simulator_connection.insert_robot(robot.phenotype, Vector3(0, 0, self._settings.z_start), max_age) + start = time.time() + # Start a run loop to do some stuff + while not robot_manager.dead: # robot_manager.age() < max_age: + await asyncio.sleep(1.0 / 2) # 5= state_update_frequency + end = time.time() + elapsed = end-start + logger.info(f'Time taken: {elapsed}') + + robot_fitness = conf.fitness_function(robot_manager, robot) + + simulator_connection.unregister_robot(robot_manager) + # await simulator_connection.delete_all_robots() + # await simulator_connection.delete_robot(robot_manager) + # await simulator_connection.pause(True) + await simulator_connection.reset(rall=True, time_only=True, model_only=False) + return robot_fitness, measures.BehaviouralMeasurements(robot_manager, robot) + + async def _joint(self): + await self._robot_queue.join() + diff --git a/pyrevolve/util/supervisor/stream.py b/pyrevolve/util/supervisor/stream.py new file mode 100644 index 0000000000..7a741dfd24 --- /dev/null +++ b/pyrevolve/util/supervisor/stream.py @@ -0,0 +1,16 @@ +class StreamEnded(Exception): + pass + + +class PrettyStreamReader(object): + def __init__(self, stream): + self._stream = stream + + async def readline(self): + if self._stream.at_eof(): + raise StreamEnded() + line = await self._stream.readline() + return line.decode('utf-8').strip() + + def at_eof(self): + return self._stream.at_eof() diff --git a/pyrevolve/util/supervisor/supervisor.py b/pyrevolve/util/supervisor/supervisor.py index 9644c2b194..0f43f369db 100644 --- a/pyrevolve/util/supervisor/supervisor.py +++ b/pyrevolve/util/supervisor/supervisor.py @@ -10,6 +10,8 @@ from datetime import datetime +from ...custom_logging.logger import logger + from .nbsr import NonBlockingStreamReader as NBSR mswindows = (sys.platform == "win32") @@ -36,9 +38,9 @@ class Supervisor(object): Utility class that allows you to automatically restore a crashing experiment and continue to run it from a snapshotted. It does so by assuming a snapshot functionality similar to that in Revolve.Angle's - WorldManager. The supervisor launches subprocesses for (a) a world + WorldManager. The supervisor launches subprocesses for (a) a world and (b) your manager / experiment. It determines a fixed output directory - for this experiment run, which is provided to the manager with + for this experiment run, which is provided to the manager with the `restore_arg` argument. The experiment is considered finished if any of the processes exit with 0 @@ -87,8 +89,8 @@ def __init__(self, self.output_directory = 'output' \ if output_directory is None else os.path.abspath(output_directory) self.snapshot_directory = os.path.join( - self.output_directory, - self.restore_directory) + self.output_directory, + self.restore_directory) self.snapshot_world_file = snapshot_world_file self.restore_arg = restore_arg self.simulator_args = simulator_args if simulator_args is not None else ["-u"] @@ -112,8 +114,8 @@ def __init__(self, plugins_dir_path = os.path.abspath(plugins_dir_path) try: new_env_var = "{curr_paths}:{new_path}".format( - curr_paths=os.environ["GAZEBO_PLUGIN_PATH"], - new_path=plugins_dir_path) + curr_paths=os.environ["GAZEBO_PLUGIN_PATH"], + new_path=plugins_dir_path) except KeyError: new_env_var = plugins_dir_path os.environ["GAZEBO_PLUGIN_PATH"] = new_env_var @@ -123,29 +125,29 @@ def __init__(self, models_dir_path = os.path.abspath(models_dir_path) try: new_env_var = "{curr_paths}:{new_path}".format( - curr_paths=os.environ["GAZEBO_MODEL_PATH"], - new_path=models_dir_path) + curr_paths=os.environ["GAZEBO_MODEL_PATH"], + new_path=models_dir_path) except KeyError: new_env_var = models_dir_path os.environ['GAZEBO_MODEL_PATH'] = new_env_var - print("Created Supervisor with:" - "\n\t- manager command: {} {}" - "\n\t- simulator command: {} {}" - "\n\t- world file: {}" - "\n\t- simulator plugin dir: {}" - "\n\t- simulator models dir: {}" - .format(manager_cmd, - manager_args, - simulator_cmd, - simulator_args, - world_file, - plugins_dir_path, - models_dir_path) - ) + logger.info("Created Supervisor with:" + "\n\t- manager command: {} {}" + "\n\t- simulator command: {} {}" + "\n\t- world file: {}" + "\n\t- simulator plugin dir: {}" + "\n\t- simulator models dir: {}" + .format(manager_cmd, + manager_args, + simulator_cmd, + simulator_args, + world_file, + plugins_dir_path, + models_dir_path) + ) def launch_simulator(self): - print("\nNOTE: launching only a simulator, not a manager script!\n") + logger.info("\nNOTE: launching only a simulator, not a manager script!\n") self._launch_simulator() # Wait for the end @@ -168,12 +170,12 @@ def launch(self): (Re)launches the experiment. :return: """ - if not os.path.exists(self.output_directory): - os.mkdir(self.output_directory) - if not os.path.exists(self.snapshot_directory): - os.mkdir(self.snapshot_directory) + # if not os.path.exists(self.output_directory): + # os.mkdir(self.output_directory) + # if not os.path.exists(self.snapshot_directory): + # os.mkdir(self.snapshot_directory) - print("Launching all processes...") + logger.info("Launching all processes...") self._launch_simulator() self._launch_manager() @@ -217,7 +219,7 @@ def _pass_through_stdout(self): if err: self.write_stderr(err) except Exception as e: - print("Exception while handling file reading:\n{}".format(e), file=sys.stderr) + logger.exception("Exception while handling file reading") @staticmethod def write_stdout(data): @@ -247,7 +249,7 @@ def _terminate_all(self): Terminates all running processes :return: """ - print("Terminating processes...") + logger.info("Terminating processes...") for proc in list(self.procs.values()): if proc.poll() is None: terminate_process(proc) @@ -274,33 +276,33 @@ def _launch_simulator(self, ready_str="World plugin loaded", output_tag="simulat Launches the simulator :return: """ - print("Launching the simulator...") + logger.info("Launching the simulator...") gz_args = self.simulator_cmd + self.simulator_args snapshot_world = os.path.join( - self.snapshot_directory, - self.snapshot_world_file) + self.snapshot_directory, + self.snapshot_world_file) world = snapshot_world \ if os.path.exists(snapshot_world) else self.world_file gz_args.append(world) self.procs[output_tag] = self._launch_with_ready_str( - cmd=gz_args, - ready_str=ready_str, - output_tag=output_tag) + cmd=gz_args, + ready_str=ready_str, + output_tag=output_tag) self._add_output_stream(output_tag) def _launch_manager(self): """ :return: """ - print("Launching experiment manager...") + logger.info("Launching experiment manager...") os.environ['PYTHONUNBUFFERED'] = 'True' args = self.manager_cmd + self.manager_args args += [self.restore_arg, self.restore_directory] process = subprocess.Popen( - args, - bufsize=1, - stdout=subprocess.PIPE, - stderr=subprocess.PIPE) + args, + bufsize=1, + stdout=subprocess.PIPE, + stderr=subprocess.PIPE) self.procs['manager'] = process self._add_output_stream('manager') @@ -313,10 +315,10 @@ def _launch_with_ready_str(cmd, ready_str, output_tag="simulator"): :return: """ process = subprocess.Popen( - cmd, - bufsize=1, - stdout=subprocess.PIPE, - stderr=subprocess.PIPE) + cmd, + bufsize=1, + stdout=subprocess.PIPE, + stderr=subprocess.PIPE) # make out and err non-blocking pipes if not mswindows: diff --git a/pyrevolve/util/supervisor/supervisor_collision.py b/pyrevolve/util/supervisor/supervisor_collision.py new file mode 100644 index 0000000000..1d8f875a50 --- /dev/null +++ b/pyrevolve/util/supervisor/supervisor_collision.py @@ -0,0 +1,35 @@ +from .supervisor_multi import DynamicSimSupervisor + + +class CollisionSimSupervisor(DynamicSimSupervisor): + def __init__(self, + world_file, + output_directory=None, + simulator_cmd="gzserver", + simulator_args=None, + restore_arg="--restore-directory", + snapshot_world_file="snapshot.world", + restore_directory=None, + plugins_dir_path=None, + models_dir_path=None, + simulator_name='collision', + process_terminated_callback=None, + ): + super().__init__(world_file, + output_directory, + simulator_cmd, + simulator_args, + restore_arg, + snapshot_world_file, + restore_directory, + plugins_dir_path, + models_dir_path, + simulator_name, + process_terminated_callback) + + async def _launch_simulator(self, + ready_str="Body analyzer ready", + output_tag="simulator", + address='localhost', + port=11345): + return await super()._launch_simulator(ready_str, output_tag, address, port) diff --git a/pyrevolve/util/supervisor/supervisor_multi.py b/pyrevolve/util/supervisor/supervisor_multi.py new file mode 100644 index 0000000000..7bc1cb7b73 --- /dev/null +++ b/pyrevolve/util/supervisor/supervisor_multi.py @@ -0,0 +1,339 @@ +from __future__ import absolute_import +from __future__ import print_function + +import atexit +import subprocess +import os +import psutil +import sys +import asyncio +import platform + +from datetime import datetime + +from ...custom_logging.logger import create_logger +from ...custom_logging.logger import logger as revolve_logger + +from .stream import PrettyStreamReader + +mswindows = (sys.platform == "win32") + + +def terminate_process(proc): + """ + Recursively kills a process and all of its children + :param proc: Result of `subprocess.Popen` + + Inspired by http://stackoverflow.com/a/25134985/358873 + + TODO Check if terminate fails and kill instead? + :return: + """ + process = psutil.Process(proc.pid) + for child in process.children(recursive=True): + child.terminate() + + process.terminate() + + +class DynamicSimSupervisor(object): + """ + Utility class that allows you to automatically restore a crashing + experiment and continue to run it from a snapshotted. It does so + by assuming a snapshot functionality similar to that in Revolve.Angle's + WorldManager. The supervisor launches subprocesses for (a) a world + and (b) your manager / experiment. It determines a fixed output directory + for this experiment run, which is provided to the manager with + the `restore_arg` argument. + + The experiment is considered finished if any of the processes exit with 0 + code. If any of processes exit with non zero code, the experiment dies. + """ + + def __init__(self, + world_file, + output_directory=None, + simulator_cmd="gzserver", + simulator_args=None, + restore_arg="--restore-directory", + snapshot_world_file="snapshot.world", + restore_directory=None, + plugins_dir_path=None, + models_dir_path=None, + simulator_name='simulator', + process_terminated_callback=None, + ): + """ + + :param world_file: Full path (or relative to cwd) to the Gazebo world + file to load. + :param output_directory: Full path (or relative to cwd) to the output + directory, which will be the parent of the + restore directory. + :param simulator_cmd: Command to runs the Simulator + :param simulator_args: Arguments to the Simulator, *excluding* the world file name + :param restore_arg: Argument used to pass the snapshot/restore + directory name to the manager. Note that the + output directory is not passed as part of this + name, just the relative path. + :param snapshot_world_file: + :param restore_directory: + :param plugins_dir_path: Full path (or relative to cwd) to the simulator + plugins directory (setting env variable + GAZEBO_PLUGIN_PATH). + :param models_dir_path: Full path (or relative to cwd) to the simulator + models directory (setting env variable + GAZEBO_MODEL_PATH). + :param process_terminated_callback: Callback to execute when a process dies + :type process_terminated_callback: lambda (process, ret_code) -> None + """ + if mswindows: + text = "Starting the simulator with WINDOWS may cause issues! BEWARE!!!" + revolve_logger.error(text) + print(text, file=sys.stderr) + + self.restore_directory = datetime.now().strftime('%Y%m%d%H%M%S') \ + if restore_directory is None else restore_directory + self.output_directory = 'output' \ + if output_directory is None else os.path.abspath(output_directory) + self.snapshot_directory = os.path.join( + self.output_directory, + self.restore_directory) + self.snapshot_world_file = snapshot_world_file + self.restore_arg = restore_arg + self.simulator_args = simulator_args if simulator_args is not None else ["-u"] + self.simulator_cmd = simulator_cmd \ + if isinstance(simulator_cmd, list) else [simulator_cmd] + self._simulator_name = simulator_name + + self.world_file = os.path.abspath(world_file) + + self.streams = {} + self.procs = {} + self._logger = create_logger(simulator_name) + self._process_terminated_callback = process_terminated_callback + self._process_terminated_futures = [] + + # Terminate all processes when the supervisor exits + atexit.register(lambda: + asyncio.get_event_loop().run_until_complete(self._terminate_all()) + ) + + # Set plugins dir path for Gazebo + if plugins_dir_path is not None: + plugins_dir_path = os.path.abspath(plugins_dir_path) + try: + new_env_var = "{curr_paths}:{new_path}".format( + curr_paths=os.environ["GAZEBO_PLUGIN_PATH"], + new_path=plugins_dir_path) + except KeyError: + new_env_var = plugins_dir_path + os.environ["GAZEBO_PLUGIN_PATH"] = new_env_var + + # Set models dir path for Gazebo + if models_dir_path is not None: + models_dir_path = os.path.abspath(models_dir_path) + try: + new_env_var = "{curr_paths}:{new_path}".format( + curr_paths=os.environ["GAZEBO_MODEL_PATH"], + new_path=models_dir_path) + except KeyError: + new_env_var = models_dir_path + os.environ['GAZEBO_MODEL_PATH'] = new_env_var + + self._logger.info("Created Supervisor with:" + f"\n\t- simulator command: {simulator_cmd} {simulator_args}" + f"\n\t- world file: {world_file}" + f"\n\t- GAZEBO_PLUGIN_PATH: {plugins_dir_path}" + f"\n\t- GAZEBO_MODEL_PATH: {models_dir_path}") + + async def launch_simulator(self, address='localhost', port=11345): + """ + Launches the simulator process + :param address: + :param port: + """ + await self._launch_simulator(output_tag=self._simulator_name, address=address, port=port) + self._enable_process_terminate_callbacks() + + async def relaunch(self, sleep_time=1, address='localhost', port=11345): + """ + Stops and restarts the process, waiting `sleep_time` in between + :param sleep_time: + :param address: + :param port: + """ + await self.stop() + await asyncio.sleep(sleep_time) + await self.launch_simulator(address=address, port=port) + + async def stop(self): + """ + Stops the simulator and all other process (companion and children processes) + """ + self._disable_process_terminate_callbacks() + await self._terminate_all() + + async def _terminate_all(self): + """ + Terminates all running processes and sub-processes + """ + self._logger.info("Terminating processes...") + for proc in list(self.procs.values()): + try: + if proc.returncode is None: + terminate_process(proc) + except psutil.NoSuchProcess: + self._logger.debug(f'Cannot terminate already dead process "{proc}"') + + # flush output of all processes + await self._flush_output_streams() + + for proc in self.procs.values(): + retcode = await proc.wait() + self._logger.info(f'Process exited with code {retcode}') + + self.procs = {} + + async def _flush_output_streams(self): + """ + Waits until all streams in this supervisor are at EOF + """ + for out, err in self.streams.values(): + await out + await err + + def _add_output_stream(self, name): + """ + Creates an async stream reader for the process with + the given name, and adds it to the streams that are passed + through. + :param name: + """ + process = self.procs[name] + + stdout = PrettyStreamReader(process.stdout) + stderr = PrettyStreamReader(process.stderr) + + async def poll_output(stream, logger): + while not stream.at_eof(): + line = await stream.readline() + logger(line) + + self.streams[name] = ( + asyncio.ensure_future(poll_output(stdout, self._logger.info)), + asyncio.ensure_future(poll_output(stderr, self._logger.error)), + ) + + async def _launch_simulator(self, ready_str="World plugin loaded", output_tag="simulator", address='localhost', + port=11345): + """ + Launches the simulator + """ + + self._logger.info("Launching the simulator...") + gz_args = self.simulator_cmd + self.simulator_args + snapshot_world = os.path.join( + self.snapshot_directory, + self.snapshot_world_file) + world = snapshot_world \ + if os.path.exists(snapshot_world) else self.world_file + gz_args.append(world) + + env = {} + for key, value in os.environ.items(): + env[key] = value + env['GAZEBO_MASTER_URI'] = f'http://{address}:{port}' + + process = subprocess.run(['which', self.simulator_cmd[0]], stdout=subprocess.PIPE) + process.check_returncode() + gazebo_libraries_path = process.stdout.decode() + gazebo_libraries_path = os.path.dirname(gazebo_libraries_path) + for lib_f in ['lib', 'lib64']: + _gazebo_libraries_path = os.path.join(gazebo_libraries_path, '..', lib_f) + if os.path.isfile(os.path.join(_gazebo_libraries_path, 'libgazebo_common.so')): + gazebo_libraries_path = _gazebo_libraries_path + break + + if platform.system() == 'Darwin': + env['DYLD_LIBRARY_PATH'] = gazebo_libraries_path + else: # linux + env['LD_LIBRARY_PATH'] = gazebo_libraries_path + self.procs[output_tag] = await self._launch_with_ready_str( + cmd=gz_args, + ready_str=ready_str, + env=env) + self._add_output_stream(output_tag) + + def _enable_process_terminate_callbacks(self): + for proc in self.procs.values(): + dead_process_future = asyncio.ensure_future(proc.wait()) + + def create_callback(_process): + def _callback(ret_code): + if self._process_terminated_callback is not None: + self._process_terminated_callback(_process, ret_code) + return _callback + + dead_process_future.add_done_callback(create_callback(proc)) + self._process_terminated_futures.append(dead_process_future) + + def _disable_process_terminate_callbacks(self): + for dead_process_future in self._process_terminated_futures: + dead_process_future.cancel() + self._process_terminated_futures.clear() + + async def _launch_with_ready_str(self, cmd, ready_str, env): + + process = await asyncio.create_subprocess_exec( + cmd[0], + *cmd[1:], + env=env, + stdout=asyncio.subprocess.PIPE, + stderr=asyncio.subprocess.PIPE, + ) + + stdout = PrettyStreamReader(process.stdout) + stderr = PrettyStreamReader(process.stderr) + + ready_str_found = asyncio.Future() + + class SimulatorEnded(Exception): + pass + + async def read_stdout(): + while not ready_str_found.done(): + if process.returncode is None: + ready_str_found.set_exception(SimulatorEnded()) + out = await stdout.readline() + self._logger.info(f'[starting] {out}') + if ready_str in out: + ready_str_found.set_result(None) + + async def read_stderr(): + while not ready_str_found.done() and process.returncode is None: + err = await stderr.readline() + if err: + self._logger.error(f'[starting] {err}') + + stdout_async = asyncio.ensure_future(read_stdout()) + stderr_async = asyncio.ensure_future(read_stderr()) + + try: + await ready_str_found + except SimulatorEnded: + pass + finally: + await stdout_async + await stderr_async + + if process.returncode is not None: + await process.wait() + while not process.stdout.at_eof(): + self._logger.info(await stdout.readline()) + while not process.stderr.at_eof(): + self._logger.error(await stderr.readline()) + await asyncio.sleep(0.1) + raise RuntimeError(f'Process "{cmd[0]}" exited before it was ready. Exit code {process.returncode}') + + return process diff --git a/requirements.txt b/requirements.txt index 7305a47fbe..978b209b36 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,7 +5,12 @@ numpy>=1.9.2 PyYAML>=3.11 protobuf>=3.0.0 psutil==3.4.2 +matplotlib pycairo>=1.18.0 -graphviz>=0.10.1 +graphviz>=0.10.1 +joblib +pandas +neat-python>=0.92 +python-dateutil>=2.8.0 --e git+https://github.com/ci-group/pygazebo.git@py2to3#egg=pygazebo +-e git+https://github.com/ci-group/pygazebo.git@master#egg=pygazebo diff --git a/revolve.py b/revolve.py index a8b0a44694..b54d23a334 100755 --- a/revolve.py +++ b/revolve.py @@ -1,54 +1,71 @@ #!/usr/bin/env python3 import os import sys +import asyncio +import importlib +from pyrevolve.data_analisys.visualize_robot import test_robot_run +from pyrevolve.data_analisys.check_robot_collision import test_collision_robot from pyrevolve import parser -from pyrevolve.util import Supervisor +from experiments.examples import only_gazebo here = os.path.dirname(os.path.abspath(__file__)) rvpath = os.path.abspath(os.path.join(here, '..', 'revolve')) sys.path.append(os.path.dirname(os.path.abspath(__file__))) -class OnlineEvolutionSupervisor(Supervisor): - """ - Supervisor class that adds some output filtering for ODE errors - """ - - def __init__(self, *args, **kwargs): - super(OnlineEvolutionSupervisor, self).__init__(*args, **kwargs) - self.ode_errors = 0 - - def write_stderr(self, data): - """ - :param data: - :return: - """ - if 'ODE Message 3' in data: - self.ode_errors += 1 - elif data.strip(): - sys.stderr.write(data) - - if self.ode_errors >= 100: - self.ode_errors = 0 - sys.stderr.write('ODE Message 3 (100)\n') - - -if __name__ == "__main__": - settings = parser.parse_args() - manager_settings = sys.argv[1:] - supervisor = OnlineEvolutionSupervisor( - manager_cmd=settings.manager, - manager_args=manager_settings, - world_file=settings.world, - simulator_cmd=settings.simulator_cmd, - simulator_args=["--verbose"], - plugins_dir_path=os.path.join(rvpath, 'build', 'lib'), - models_dir_path=os.path.join(rvpath, 'models') - ) - - if settings.manager is None: - ret = supervisor.launch_simulator() +def run(loop, arguments): + if arguments.test_robot is not None: + return loop.run_until_complete(test_robot_run(arguments.test_robot)) + + if arguments.test_robot_collision is not None: + return loop.run_until_complete(test_collision_robot(arguments.test_robot_collision)) + + if arguments.manager is not None: + # this split will give errors on windows + manager_lib = os.path.splitext(arguments.manager)[0] + manager_lib = '.'.join(manager_lib.split('/')) + manager = importlib.import_module(manager_lib).run + return loop.run_until_complete(manager()) else: - ret = supervisor.launch() - sys.exit(ret) + # no test robot, no manager -> just run gazebo + loop.run_until_complete(only_gazebo.run()) + loop.run_forever() + + +def main(): + import traceback + + def handler(_loop, context): + try: + exc = context['exception'] + except KeyError: + print(context['message']) + return + + if isinstance(exc, ConnectionResetError): + print("Got disconnect / connection reset - shutting down.") + sys.exit(0) + + if isinstance(exc, OSError) and exc.errno == 9: + print(exc) + traceback.print_exc() + return + + # traceback.print_exc() + raise exc + + try: + arguments = parser.parse_args() + loop = asyncio.get_event_loop() + loop.set_exception_handler(handler) + run(loop, arguments) + except KeyboardInterrupt: + print("Got CtrlC, shutting down.") + + +if __name__ == '__main__': + print("STARTING") + main() + print("FINISHED") + diff --git a/setup.py b/setup.py deleted file mode 100644 index 73869868f6..0000000000 --- a/setup.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 -from __future__ import absolute_import - -from setuptools import setup - -setup(name='pyrevolve', - version='0.3', - description='Revolve: robot evolution framework', - author='CI Group', - author_email='m.decarlo@vu.nl', - url='https://github.com/ci-group/revolve', - packages=[ - 'pyrevolve', - 'pyrevolve.angle', - 'pyrevolve.build', - 'pyrevolve.build.sdf', - 'pyrevolve.convert', - 'pyrevolve.gazebo', - 'pyrevolve.generate', - 'pyrevolve.spec', - 'pyrevolve.sdfbuilder', - 'pyrevolve.util', - ], - install_requires=[ - 'numpy', - 'protobuf', - 'pygazebo', - 'PyYAML', - 'psutil', - ]) diff --git a/test_py/plasticonding/__init__.py b/test_py/plasticonding/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/test_py/plasticonding/genotype_176.txt b/test_py/plasticonding/genotype_176.txt new file mode 100644 index 0000000000..52e007abc6 --- /dev/null +++ b/test_py/plasticonding/genotype_176.txt @@ -0,0 +1,5 @@ +AJ1 brainmoveFTS_1.000000|1.000000 brainloop_0.416317 addl B moveb mover brainmoveFTS_1.000000|1.000000 brainampperturb_0.055473 addr AJ2_-0.233663|2.183440|3.291942|4.403511 movel movef +AJ2 brainmoveFTS_1.000000|1.000000 brainperperturb_0.802147 addr AJ2_-0.451750|2.034820|7.606433|6.574293 mover movel brainmoveFTS_1.000000|1.000000 brainoffperturb_0.344535 addf AJ2_0.395370|5.811625|3.816685|8.139162 moveb moveb brainmoveFTS_4.000000|2.000000 brainloop_-0.991706 addl B mover movef +B brainmoveTTS_2.000000|1.000000 brainloop_0.802269 addr B movef movel brainmoveFTS_2.000000|1.000000 brainedge_-0.381986 addf ST_0.780739 movel movef brainmoveFTS_3.000000|1.000000 brainedge_-0.077519 addf AJ2_-0.547769|6.412029|8.911399|9.774277 moveb mover +C C brainmoveFTS_2.000000|3.000000 brainoffperturb_-1.051822 addf AJ1_-0.571851|1.839181|4.364775|1.276114 movef moveb brainmoveTTS_3.000000|1.000000 brainperperturb_-0.759291 addf AJ1_0.697915|8.120513|3.796636|6.375849 movel mover +ST brainmoveTTS_1.000000|1.000000 brainperperturb_-1.003928 addr AJ1_-0.091552|9.117664|6.366138|9.261707 mover mover diff --git a/test_py/plasticonding/genotype_180.txt b/test_py/plasticonding/genotype_180.txt new file mode 100644 index 0000000000..bdb4dafd96 --- /dev/null +++ b/test_py/plasticonding/genotype_180.txt @@ -0,0 +1,5 @@ +AJ1 brainmoveTTS_1.000000|1.000000 brainperperturb_-0.393406 addl AJ1_-0.393280|1.988274|1.096442|9.835634 movel movel brainmoveFTS_1.000000|1.000000 brainedge_-0.101278 addf B mover movel brainmoveFTS_2.000000|1.000000 brainedge_-0.979029 addf B moveb moveb +AJ2 brainmoveTTS_1.000000|1.000000 brainperperturb_-1.448493 addl AJ2_-0.655487|8.519603|9.441968|6.030500 addl moveb movel +B brainmoveTTS_1.000000|1.000000 brainperperturb_-0.192989 addf AJ1_0.814148|7.880737|6.556612|5.823772 movef mover brainmoveFTS_1.000000|1.000000 brainedge_0.984046 addl B movel movel +C C brainmoveFTS_1.000000|2.000000 brainperturb_-1.116291 addr B mover movef brainmoveFTS_1.000000|1.000000 brainedge_-0.413422 ST_-0.482408 addr ST_0.425158 moveb movef brainmoveTTS_1.000000|1.000000 brainampperturb_-1.216602 addf ST_0.351256 moveb moveb +ST brainmoveFTS_1.000000|1.000000 brainampperturb_0.930132 addr AJ1_0.706664|3.625587|6.327397|6.959880 mover mover brainmoveFTS_1.000000|1.000000 brainoffperturb_0.884765 addf AJ1_-0.945926|2.032773|3.248924|1.285235 movef mover diff --git a/test_py/plasticonding/test_development.py b/test_py/plasticonding/test_development.py new file mode 100644 index 0000000000..248e7c0d3c --- /dev/null +++ b/test_py/plasticonding/test_development.py @@ -0,0 +1,157 @@ +import unittest +import os + +import pyrevolve.revolve_bot +import pyrevolve.genotype.plasticoding.plasticoding + +LOCAL_FOLDER = os.path.dirname(__file__) + + +class TestPlastiCoding(unittest.TestCase): + def setUp(self): + self.conf = pyrevolve.genotype.plasticoding.plasticoding.PlasticodingConfig() + self.genotype = pyrevolve.genotype.plasticoding.plasticoding.initialization.random_initialization(self.conf, 176) + + def test_development(self): + robot = self.genotype.develop() + + def test_substrate(self): + robot = self.genotype.develop() + robot.update_substrate(raise_for_intersections=True) + + def test_measure_body(self): + robot = self.genotype.develop() + robot.measure_body() + + def test_measure_brain(self): + robot = self.genotype.develop() + robot.measure_brain() + + def test_read_write_file(self): + file1 = '/tmp/test_genotype.txt' + file2 = '/tmp/test_genotype2.txt' + + self.genotype.export_genotype(file1) + + genotype2 = pyrevolve.genotype.plasticoding.plasticoding.Plasticoding(self.conf, self.genotype.id) + genotype2.id = self.genotype.id + genotype2.load_genotype(file1) + genotype2.export_genotype(file2) + + file1_txt = open(file1) + file2_txt = open(file2) + + self.assertListEqual(file1_txt.readlines(), file2_txt.readlines()) + + file1_txt.close() + file2_txt.close() + + def test_collision(self): + genotype_180 = pyrevolve.genotype.plasticoding.plasticoding.Plasticoding(self.conf, 180) + genotype_180.load_genotype(os.path.join(LOCAL_FOLDER, 'genotype_180.txt')) + robot = genotype_180.develop() + robot.update_substrate(raise_for_intersections=True) + + +class Test176(unittest.TestCase): + def setUp(self): + self.conf = pyrevolve.genotype.plasticoding.plasticoding.PlasticodingConfig() + + _id = 176 + self.genotype = pyrevolve.genotype.plasticoding.plasticoding.Plasticoding(self.conf, _id) + self.genotype.load_genotype(os.path.join(LOCAL_FOLDER, 'genotype_176.txt')) + + self.robot = self.genotype.develop() + + def test_measurements_body(self): + branching = 0.333 + connectivity1 = 0.625 + connectivity1_abs = 5 + connectivity2 = 0.444 + connectivity2_abs = 4 + connectivity3 = 1 + connectivity4 = 1 + coverage = 0.44 + effective_joints = 0.444 + joints_abs = 6 + length_ratio = 1 + sensors = 0.2 + symmetry = 0.667 + total_components = 0.11 + total_components_abs = 11 + + self.robot.render_body('/tmp/robot_body.png') + self.genotype.export_genotype('/tmp/genotype.txt') + + m = self.robot.measure_body() + self.assertAlmostEqual(branching, m.branching, 3) + self.assertAlmostEqual(connectivity1, m.limbs, 3) + self.assertAlmostEqual(connectivity1_abs, m.extremities, 3) + self.assertAlmostEqual(connectivity2, m.length_of_limbs, 3) + self.assertAlmostEqual(connectivity2_abs, m.extensiveness, 3) + # self.assertAlmostEqual(connectivity3, m., 3) + self.assertAlmostEqual(connectivity4, m.branching_modules_count, 3) + self.assertAlmostEqual(coverage, m.coverage, 3) + self.assertAlmostEqual(effective_joints, m.joints, 3) + self.assertAlmostEqual(joints_abs, m.hinge_count, 3) + self.assertAlmostEqual(length_ratio, m.proportion, 3) + self.assertAlmostEqual(sensors, m.sensors, 3) + self.assertAlmostEqual(symmetry, m.symmetry, 3) + # self.assertAlmostEqual(total_components, m.size, 3) + self.assertAlmostEqual(total_components_abs, m.absolute_size, 3) + + def test_measurements_brain(self): + amplitude_average = 0.551664 + amplitude_deviation = 0.915769767 + inputs_reach = 0.583333 + inter_params_dev_average = 0.8811009266695952 + intra_params_dev_average = 0.8187877255612809 + offset_average = 0.37370865000000003 + offset_deviation = 0.857319047568582 + period_average = 0.25102035 + period_deviation = 0.8616760913682427 + recurrence = 0.5 + synaptic_reception = 0 + + self.robot.render_brain('/tmp/robot_brain.png') + + m = self.robot.measure_brain() + self.assertAlmostEqual(amplitude_average, m.avg_amplitude, 3) + self.assertAlmostEqual(amplitude_deviation, m.dev_amplitude, 3) + self.assertAlmostEqual(inputs_reach, m.sensors_reach, 3) + self.assertAlmostEqual(inter_params_dev_average, m.avg_inter_dev_params, 3) + self.assertAlmostEqual(intra_params_dev_average, m.avg_intra_dev_params, 3) + self.assertAlmostEqual(offset_average, m.avg_phase_offset, 3) + self.assertAlmostEqual(offset_deviation, m.dev_phase_offset, 3) + self.assertAlmostEqual(period_average, m.avg_period, 3) + self.assertAlmostEqual(period_deviation, m.dev_period, 3) + self.assertAlmostEqual(recurrence, m.recurrence, 3) + self.assertAlmostEqual(synaptic_reception, m.synaptic_reception, 3) + + def test_measurements_brain_pdf(self): + amplitude_average = 0.551664 + amplitude_deviation = 0.915769767 + inputs_reach = 0.583333 + inter_params_dev_average = 0.8811009266695952 + intra_params_dev_average = 0.8187877255612809 + offset_average = 0.37370865000000003 + offset_deviation = 0.857319047568582 + period_average = 0.25102035 + period_deviation = 0.8616760913682427 + recurrence = 0.5 + synaptic_reception = 0 + + self.robot.render_brain('/tmp/robot_brain.pdf') + + m = self.robot.measure_brain() + self.assertAlmostEqual(amplitude_average, m.avg_amplitude, 3) + self.assertAlmostEqual(amplitude_deviation, m.dev_amplitude, 3) + self.assertAlmostEqual(inputs_reach, m.sensors_reach, 3) + self.assertAlmostEqual(inter_params_dev_average, m.avg_inter_dev_params, 3) + self.assertAlmostEqual(intra_params_dev_average, m.avg_intra_dev_params, 3) + self.assertAlmostEqual(offset_average, m.avg_phase_offset, 3) + self.assertAlmostEqual(offset_deviation, m.dev_phase_offset, 3) + self.assertAlmostEqual(period_average, m.avg_period, 3) + self.assertAlmostEqual(period_deviation, m.dev_period, 3) + self.assertAlmostEqual(recurrence, m.recurrence, 3) + self.assertAlmostEqual(synaptic_reception, m.synaptic_reception, 3) diff --git a/test_robots.py b/test_robots.py new file mode 100755 index 0000000000..bfb4e156d3 --- /dev/null +++ b/test_robots.py @@ -0,0 +1,45 @@ +import asyncio + +from pyrevolve import parser +from pyrevolve.revolve_bot import RevolveBot +from pyrevolve.tol.manage import World + + +async def run(): + + settings = parser.parse_args() + yaml_file = 'experiments/'+ settings.experiment_name +'/data_fullevolution/phenotypes/'+'phenotype_'+settings.test_robot+'.yaml' + + r = RevolveBot(_id=settings.test_robot) + r.load_file(yaml_file, conf_type='yaml') + #r.save_file('experiments/'+ settings +'/data_fullevolution/phenotype_35.sdf.xml', conf_type='sdf') + #r.render_body('experiments/'+ settings +'/data_fullevolution/phenotypes/phenotype_35.body.png') + + connection = await World.create(settings, world_address=("127.0.0.1", settings.port_start)) + await connection.insert_robot(r) + + +def main(): + import traceback + + def handler(_loop, context): + try: + exc = context['exception'] + except KeyError: + print(context['message']) + return + traceback.print_exc() + raise exc + + try: + loop = asyncio.get_event_loop() + loop.set_exception_handler(handler) + loop.run_until_complete(run()) + except KeyboardInterrupt: + print("Got CtrlC, shutting down.") + + +if __name__ == '__main__': + print("STARTING") + main() + print("FINISHED") diff --git a/thirdparty/PIGPIO/CMakeLists.txt b/thirdparty/PIGPIO/CMakeLists.txt new file mode 100644 index 0000000000..292fa0e1f4 --- /dev/null +++ b/thirdparty/PIGPIO/CMakeLists.txt @@ -0,0 +1,70 @@ +cmake_minimum_required(VERSION 3.1.0) + +message("Building PIGPIO") + +set(THREADS_PREFER_PTHREAD_FLAG ON) +find_package(Threads REQUIRED) + +add_library(pigpio SHARED + pigpio.c + command.c) +target_link_libraries(pigpio + PUBLIC Threads::Threads) + +add_library(pigpio_if SHARED + pigpiod_if.c + command.c) +target_link_libraries(pigpio_if + PUBLIC Threads::Threads) + +add_library(pigpio_if2 SHARED + pigpiod_if2.c + command.c) +target_link_libraries(pigpio_if2 + PUBLIC Threads::Threads) + +add_executable(x_pigpio + x_pigpio.c) +target_link_libraries(x_pigpio PUBLIC pigpio) + +add_executable(x_pigpiod_if + x_pigpiod_if.c) +target_link_libraries(x_pigpiod_if + PUBLIC pigpio_if) + +add_executable(x_pigpiod_if2 + x_pigpiod_if2.c) +target_link_libraries(x_pigpiod_if2 + PUBLIC pigpio_if2) + +add_executable(pigpiod + pigpiod.c) +target_link_libraries(pigpiod PUBLIC pigpio) + +add_executable(pigs + pigs.c + command.c) + +add_executable(pig2vcd + pig2vcd.c) + +set(PIGPIO_HEADER_DIR ${CMAKE_CURRENT_SOURCE_DIR} PARENT_SCOPE) + +install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + PUBLIC_HEADER DESTINATION include + FILES_MATCHING PATTERN "pi*.h") + +install(TARGETS pigpio pigpio_if pigpio_if2 pig2vcd pigpiod pigs + RUNTIME DESTINATION bin + LIBRARY DESTINATION lib) + +install(FILES pigpio.service + DESTINATION /etc/systemd/system/) + +enable_testing() +add_test(NAME pigpio + COMMAND x_pigpio) +add_test(NAME pigpiod_if + COMMAND x_pigpiod_if) +add_test(NAME pigpiod_if2 + COMMAND x_pigpiod_if2) \ No newline at end of file diff --git a/thirdparty/PIGPIO/MakeRemote b/thirdparty/PIGPIO/MakeRemote new file mode 100644 index 0000000000..250d40eda1 --- /dev/null +++ b/thirdparty/PIGPIO/MakeRemote @@ -0,0 +1,101 @@ +# +CC = gcc +SIZE = size +SHLIB = gcc -shared +STRIPLIB = strip --strip-unneeded + +CFLAGS += -O3 -Wall -pthread + +ALL = libpigpiod_if.so libpigpiod_if2.so pigs x_pigpiod_if x_pigpiod_if2 + +prefix = /usr/local +exec_prefix = $(prefix) +bindir = $(exec_prefix)/bin +includedir = $(prefix)/include +libdir = $(prefix)/lib +mandir = $(prefix)/man + +all: $(ALL) pigpio.py setup.py + +pigpiod_if.o: pigpiod_if.c pigpio.h command.h pigpiod_if.h + $(CC) $(CFLAGS) -fpic -c -o pigpiod_if.o pigpiod_if.c + +pigpiod_if2.o: pigpiod_if2.c pigpio.h command.h pigpiod_if2.h + $(CC) $(CFLAGS) -fpic -c -o pigpiod_if2.o pigpiod_if2.c + +command.o: command.c pigpio.h command.h + $(CC) $(CFLAGS) -fpic -c -o command.o command.c + +pigs: command.o pigs.o + $(CC) $(CFLAGS) -fpic -o pigs pigs.c command.c + +x_pigpiod_if: x_pigpiod_if.o $(LIB1) + $(CC) -o x_pigpiod_if x_pigpiod_if.o $(LL1) + +x_pigpiod_if2: x_pigpiod_if2.o $(LIB2) + $(CC) -o x_pigpiod_if2 x_pigpiod_if2.o $(LL2) + +clean: + rm -f *.o *.i *.s *~ $(ALL) + +install: $(LIB1) $(LIB2) + install -m 0755 -d $(DESTDIR)$(includedir) + install -m 0644 pigpio.h $(DESTDIR)$(includedir) + install -m 0644 pigpiod_if.h $(DESTDIR)$(includedir) + install -m 0644 pigpiod_if2.h $(DESTDIR)$(includedir) + install -m 0755 -d $(DESTDIR)$(libdir) + install -m 0644 libpigpiod_if.so $(DESTDIR)$(libdir) + install -m 0644 libpigpiod_if2.so $(DESTDIR)$(libdir) + install -m 0755 -d $(DESTDIR)$(bindir) + install -m 0755 pigs $(DESTDIR)$(bindir) + python2 setup.py install + python3 setup.py install + install -m 0755 -d $(DESTDIR)$(mandir)/man1 + install -m 0644 *.1 $(DESTDIR)$(mandir)/man1 + install -m 0755 -d $(DESTDIR)$(mandir)/man3 + install -m 0644 *.3 $(DESTDIR)$(mandir)/man3 + +uninstall: + rm -f $(DESTDIR)$(includedir)/pigpio.h + rm -f $(DESTDIR)$(includedir)/pigpiod_if.h + rm -f $(DESTDIR)$(includedir)/pigpiod_if2.h + rm -f $(DESTDIR)$(libdir)/libpigpiod_if.so + rm -f $(DESTDIR)$(libdir)/libpigpiod_if2.so + echo removing python2 files + python2 setup.py install --record /tmp/pigpio >/dev/null + xargs rm -f < /tmp/pigpio >/dev/null + echo removing python3 files + python3 setup.py install --record /tmp/pigpio >/dev/null + xargs rm -f < /tmp/pigpio >/dev/null + rm -f $(DESTDIR)$(bindir)/pigs + rm -f $(DESTDIR)$(mandir)/man1/pig*.1 + rm -f $(DESTDIR)$(mandir)/man3/pig*.3 + +LL1 = -L. -lpigpiod_if -pthread -lrt +LL2 = -L. -lpigpiod_if2 -pthread -lrt + +LIB1 = libpigpiod_if.so +OBJ1 = pigpiod_if.o command.o + +LIB2 = libpigpiod_if2.so +OBJ2 = pigpiod_if2.o command.o + +$(LIB1): $(OBJ1) + $(SHLIB) -o $(LIB1) $(OBJ1) + $(STRIPLIB) $(LIB1) + $(SIZE) $(LIB1) + +$(LIB2): $(OBJ2) + $(SHLIB) -o $(LIB2) $(OBJ2) + $(STRIPLIB) $(LIB2) + $(SIZE) $(LIB2) + +# generated using gcc -MM *.c + +command.o: command.c pigpio.h command.h +pigpiod.o: pigpiod.c pigpio.h +pigpiod_if.o: pigpiod_if.c pigpio.h pigpiod_if.h command.h +pigpiod_if2.o: pigpiod_if2.c pigpio.h pigpiod_if2.h command.h +pigs.o: pigs.c pigpio.h command.h pigs.h + + diff --git a/thirdparty/PIGPIO/Makefile b/thirdparty/PIGPIO/Makefile new file mode 100644 index 0000000000..3d94f4d32a --- /dev/null +++ b/thirdparty/PIGPIO/Makefile @@ -0,0 +1,142 @@ +# +# Set CROSS_PREFIX to prepend to all compiler tools at once for easier +# cross-compilation. +CROSS_PREFIX = +CC = $(CROSS_PREFIX)gcc +AR = $(CROSS_PREFIX)ar +RANLIB = $(CROSS_PREFIX)ranlib +SIZE = $(CROSS_PREFIX)size +STRIP = $(CROSS_PREFIX)strip +SHLIB = $(CC) -shared +STRIPLIB = $(STRIP) --strip-unneeded + +CFLAGS += -O3 -Wall -pthread + +LIB1 = libpigpio.so +OBJ1 = pigpio.o command.o + +LIB2 = libpigpiod_if.so +OBJ2 = pigpiod_if.o command.o + +LIB3 = libpigpiod_if2.so +OBJ3 = pigpiod_if2.o command.o + +LIB = $(LIB1) $(LIB2) $(LIB3) + +ALL = $(LIB) x_pigpio x_pigpiod_if x_pigpiod_if2 pig2vcd pigpiod pigs + +LL1 = -L. -lpigpio -pthread -lrt + +LL2 = -L. -lpigpiod_if -pthread -lrt + +LL3 = -L. -lpigpiod_if2 -pthread -lrt + +prefix = /usr/local +exec_prefix = $(prefix) +bindir = $(exec_prefix)/bin +includedir = $(prefix)/include +libdir = $(prefix)/lib +mandir = $(prefix)/man + +all: $(ALL) + +lib: $(LIB) + +pigpio.o: pigpio.c pigpio.h command.h custom.cext + $(CC) $(CFLAGS) -fpic -c -o pigpio.o pigpio.c + +pigpiod_if.o: pigpiod_if.c pigpio.h command.h pigpiod_if.h + $(CC) $(CFLAGS) -fpic -c -o pigpiod_if.o pigpiod_if.c + +pigpiod_if2.o: pigpiod_if2.c pigpio.h command.h pigpiod_if2.h + $(CC) $(CFLAGS) -fpic -c -o pigpiod_if2.o pigpiod_if2.c + +command.o: command.c pigpio.h command.h + $(CC) $(CFLAGS) -fpic -c -o command.o command.c + +x_pigpio: x_pigpio.o $(LIB1) + $(CC) -o x_pigpio x_pigpio.o $(LL1) + +x_pigpiod_if: x_pigpiod_if.o $(LIB2) + $(CC) -o x_pigpiod_if x_pigpiod_if.o $(LL2) + +x_pigpiod_if2: x_pigpiod_if2.o $(LIB3) + $(CC) -o x_pigpiod_if2 x_pigpiod_if2.o $(LL3) + +pigpiod: pigpiod.o $(LIB1) + $(CC) -o pigpiod pigpiod.o $(LL1) + $(STRIP) pigpiod + +pigs: pigs.o command.o + $(CC) -o pigs pigs.o command.o + $(STRIP) pigs + +pig2vcd: pig2vcd.o + $(CC) -o pig2vcd pig2vcd.o + $(STRIP) pig2vcd + +clean: + rm -f *.o *.i *.s *~ $(ALL) + +install: $(ALL) + install -m 0755 -d $(DESTDIR)/opt/pigpio/cgi + install -m 0755 -d $(DESTDIR)$(includedir) + install -m 0644 pigpio.h $(DESTDIR)$(includedir) + install -m 0644 pigpiod_if.h $(DESTDIR)$(includedir) + install -m 0644 pigpiod_if2.h $(DESTDIR)$(includedir) + install -m 0755 -d $(DESTDIR)$(libdir) + install -m 0755 libpigpio.so $(DESTDIR)$(libdir) + install -m 0755 libpigpiod_if.so $(DESTDIR)$(libdir) + install -m 0755 libpigpiod_if2.so $(DESTDIR)$(libdir) + install -m 0755 -d $(DESTDIR)$(bindir) + install -m 0755 pig2vcd $(DESTDIR)$(bindir) + install -m 0755 pigpiod $(DESTDIR)$(bindir) + install -m 0755 pigs $(DESTDIR)$(bindir) + if which python2; then python2 setup.py install; fi + if which python3; then python3 setup.py install; fi + install -m 0755 -d $(DESTDIR)$(mandir)/man1 + install -m 0644 *.1 $(DESTDIR)$(mandir)/man1 + install -m 0755 -d $(DESTDIR)$(mandir)/man3 + install -m 0644 *.3 $(DESTDIR)$(mandir)/man3 + ldconfig + +uninstall: + rm -f $(DESTDIR)$(includedir)/pigpio.h + rm -f $(DESTDIR)$(includedir)/pigpiod_if.h + rm -f $(DESTDIR)$(includedir)/pigpiod_if2.h + rm -f $(DESTDIR)$(libdir)/libpigpio.so + rm -f $(DESTDIR)$(libdir)/libpigpiod_if.so + rm -f $(DESTDIR)$(libdir)/libpigpiod_if2.so + rm -f $(DESTDIR)$(bindir)/pig2vcd + rm -f $(DESTDIR)$(bindir)/pigpiod + rm -f $(DESTDIR)$(bindir)/pigs + if which python2; then python2 setup.py install --record /tmp/pigpio >/dev/null; xargs rm -f < /tmp/pigpio >/dev/null; fi + if which python3; then python3 setup.py install --record /tmp/pigpio >/dev/null; xargs rm -f < /tmp/pigpio >/dev/null; fi + rm -f $(DESTDIR)$(mandir)/man1/pig*.1 + rm -f $(DESTDIR)$(mandir)/man3/pig*.3 + ldconfig + +$(LIB1): $(OBJ1) + $(SHLIB) -o $(LIB1) $(OBJ1) + $(STRIPLIB) $(LIB1) + $(SIZE) $(LIB1) + +$(LIB2): $(OBJ2) + $(SHLIB) -o $(LIB2) $(OBJ2) + $(STRIPLIB) $(LIB2) + $(SIZE) $(LIB2) + +$(LIB3): $(OBJ3) + $(SHLIB) -o $(LIB3) $(OBJ3) + $(STRIPLIB) $(LIB3) + $(SIZE) $(LIB3) + +# generated using gcc -MM *.c + +pig2vcd.o: pig2vcd.c pigpio.h +pigpiod.o: pigpiod.c pigpio.h +pigs.o: pigs.c pigpio.h command.h pigs.h +x_pigpio.o: x_pigpio.c pigpio.h +x_pigpiod_if.o: x_pigpiod_if.c pigpiod_if.h pigpio.h +x_pigpiod_if2.o: x_pigpiod_if2.c pigpiod_if2.h pigpio.h + diff --git a/thirdparty/PIGPIO/README b/thirdparty/PIGPIO/README new file mode 100644 index 0000000000..ed453a902b --- /dev/null +++ b/thirdparty/PIGPIO/README @@ -0,0 +1,174 @@ +NOTE + +The initial part of the make, the compilation of pigpio.c, +takes 100 seconds on early model Pis. Be patient. The overall +install takes just over 3 minutes. + +INSTALL + +Extract the archive to a directory. + +IN THAT DIRECTORY + +Enter the following two commands (in this order) + +make +sudo make install + +This will install + +o the library (libpigpio.so) in /usr/local/lib +o the library (libpigpiod_if.so) in /usr/local/lib +o the library (libpigpiod_if2.so) in /usr/local/lib +o the header file (pigpio.h) in /usr/local/include +o the header file (pigpiod_if.h) in /usr/local/include +o the header file (pigpiod_if2.h) in /usr/local/include +o the header file (pigs.h) in /usr/local/include +o the daemon (pigpiod) in /usr/local/bin +o the socket interface (pigs) in /usr/local/bin +o the utility pig2vcd in /usr/local/bin +o man pages in /usr/local/man/man1 and /usr/local/man/man3 +o the Python module pigpio.py for Python 2 and 3 + +TEST (optional) + +*** WARNING ************************************************ +* * +* All the tests make extensive use of gpio 25 (pin 22). * +* Ensure that either nothing or just a LED is connected to * +* gpio 25 before running any of the tests. * +* * +* Some tests are statistical in nature and so may on * +* occasion fail. Repeated failures on the same test or * +* many failures in a group of tests indicate a problem. * +************************************************************ + +To test the library do + +sudo ./x_pigpio + +To test the pigpio daemon do + +sudo pigpiod + +./x_pigpiod_if # test the C I/F to the pigpio daemon +./x_pigpiod_if2 # test the C I/F to the pigpio daemon +./x_pigpio.py # test the Python I/F to the pigpio daemon +./x_pigs # test the socket I/F to the pigpio daemon +./x_pipe # test the pipe I/F to the pigpio daemon + +EXAMPLE CODE + +x_pigpio.c, pig2vcd.c, and pigpiod.c show examples of interfacing +with the pigpio library. + +pigs.c, pigpio.py, x_pigpiod_if, x_pigpiod_if2.c, x_pigpio.py, +x_pigs, and x_pipe show examples of interfacing with the pigpio +daemon. x_pipe uses the pipe interface, the others use the +socket interface. + +DAEMON + +To launch the daemon do + +sudo pigpiod (pigpiod -? for options) + +Once the daemon is launched the socket and pipe interfaces will be +available. + +When the library starts it locks + +/var/run/pigpio.pid + +The file should be automatically deleted when the library terminates. + +SOCKET INTERFACE + +Use pigs for the socket interface (pigs help for help). + +PIPE INTERFACE + +The pipe interface accepts commands written to /dev/pigpio. + +Results are read from /dev/pigout. + +Errors are output on /dev/pigerr. + +To test the pipe interface perhaps do + +cat /dev/pigout & +cat /dev/pigerr & + +echo "help" >/dev/pigpio + +PYTHON MODULE + +The Python pigpio module is installed to the default Python location +for Python 2 and Python 3. + +You can install it for additional Python versions by + +pythonx.y setup.py install + +where x.y is the Python version. + +STOP DAEMON + +To stop the pigpiod daemon + +sudo killall pigpiod + +RUNNING ON NON Pi's + +You can access the pigpiod daemon running on the Pi from any machine which +is connected to it over the network. This access is via the socket interface. + +In particular this allows you to use the following on non-Pi's. + +o pigs +o the pigpio Python module +o the C socket I/F using libpigpiod_if (header file pigpiod_if.h) +o the C socket I/F using libpigpiod_if2 (header file pigpiod_if2.h) + +On a Linux machine + +make -f MakeRemote clean +make -f MakeRemote +make -f MakeRemote install + +This will install + +o the library (libpigpiod_if.so) in /usr/local/lib +o the library (libpigpiod_if2.so) in /usr/local/lib +o the header file (pigpio.h) in /usr/local/include +o the header file (pigpiod_if.h) in /usr/local/include +o the header file (pigpiod_if2.h) in /usr/local/include +o the socket interface (pigs) in /usr/local/bin +o man pages in /usr/local/man/man1 and /usr/local/man/man3 +o the Python module pigpio.py + +On Windows machines (and possibly Macs) + +The Python module should install with + +python setup.py install + +pigs, pigpiod_if, and pigpiod_if2 will need minor mods to +reflect the Windows/Mac socket interface. + +DOCUMENTATION + +The most up to date should be http://abyz.me.uk/rpi/pigpio/ + +On the Pi try + +man pigs +man pigpiod +man pig2vcd + +man pigpio +man pigpiod_if +man pigpiod_if2 + +pydoc pigpio + diff --git a/thirdparty/PIGPIO/UNLICENCE b/thirdparty/PIGPIO/UNLICENCE new file mode 100644 index 0000000000..471f09f4cf --- /dev/null +++ b/thirdparty/PIGPIO/UNLICENCE @@ -0,0 +1,25 @@ +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to + diff --git a/thirdparty/PIGPIO/command.c b/thirdparty/PIGPIO/command.c new file mode 100644 index 0000000000..d1ca59ab7a --- /dev/null +++ b/thirdparty/PIGPIO/command.c @@ -0,0 +1,1406 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* +This version is for pigpio version 67+ +*/ + +#include +#include +#include +#include +#include + +#include "pigpio.h" +#include "command.h" + +cmdInfo_t cmdInfo[]= +{ + /* num str vfyt retv */ + + {PI_CMD_BC1, "BC1", 111, 1}, // gpioWrite_Bits_0_31_Clear + {PI_CMD_BC2, "BC2", 111, 1}, // gpioWrite_Bits_32_53_Clear + + {PI_CMD_BI2CC, "BI2CC", 112, 0}, // bbI2CClose + {PI_CMD_BI2CO, "BI2CO", 131, 0}, // bbI2COpen + {PI_CMD_BI2CZ, "BI2CZ", 193, 6}, // bbI2CZip + + {PI_CMD_BR1, "BR1", 101, 3}, // gpioRead_Bits_0_31 + {PI_CMD_BR2, "BR2", 101, 3}, // gpioRead_Bits_32_53 + + {PI_CMD_BS1, "BS1", 111, 1}, // gpioWrite_Bits_0_31_Set + {PI_CMD_BS2, "BS2", 111, 1}, // gpioWrite_Bits_32_53_Set + + {PI_CMD_BSCX, "BSCX", 193, 8}, // bscXfer + + {PI_CMD_BSPIC, "BSPIC", 112, 0}, // bbSPIClose + {PI_CMD_BSPIO, "BSPIO", 134, 0}, // bbSPIOpen + {PI_CMD_BSPIX, "BSPIX", 193, 6}, // bbSPIXfer + + {PI_CMD_CF1, "CF1", 195, 2}, // gpioCustom1 + {PI_CMD_CF2, "CF2", 195, 6}, // gpioCustom2 + + {PI_CMD_CGI, "CGI", 101, 4}, // gpioCfgGetInternals + {PI_CMD_CSI, "CSI", 111, 1}, // gpioCfgSetInternals + + {PI_CMD_EVM, "EVM", 122, 1}, // eventMonitor + {PI_CMD_EVT, "EVT", 112, 0}, // eventTrigger + + {PI_CMD_FC, "FC", 112, 0}, // fileClose + + {PI_CMD_FG, "FG", 121, 0}, // gpioGlitchFilter + + {PI_CMD_FL, "FL", 127, 6}, // fileList + + {PI_CMD_FN, "FN", 131, 0}, // gpioNoiseFilter + + {PI_CMD_FO, "FO", 127, 2}, // fileOpen + {PI_CMD_FR, "FR", 121, 6}, // fileRead + {PI_CMD_FS, "FS", 133, 2}, // fileSeek + {PI_CMD_FW, "FW", 193, 0}, // fileWrite + + {PI_CMD_GDC, "GDC", 112, 2}, // gpioGetPWMdutycycle + {PI_CMD_GPW, "GPW", 112, 2}, // gpioGetServoPulsewidth + + {PI_CMD_HELP, "H", 101, 5}, // cmdUsage + {PI_CMD_HELP, "HELP", 101, 5}, // cmdUsage + + {PI_CMD_HC, "HC", 121, 0}, // gpioHardwareClock + {PI_CMD_HP, "HP", 131, 0}, // gpioHardwarePWM + + {PI_CMD_HWVER, "HWVER", 101, 4}, // gpioHardwareRevision + + {PI_CMD_I2CC, "I2CC", 112, 0}, // i2cClose + {PI_CMD_I2CO, "I2CO", 131, 2}, // i2cOpen + + {PI_CMD_I2CPC, "I2CPC", 131, 2}, // i2cProcessCall + {PI_CMD_I2CPK, "I2CPK", 194, 6}, // i2cBlockProcessCall + + {PI_CMD_I2CRB, "I2CRB", 121, 2}, // i2cReadByteData + {PI_CMD_I2CRD, "I2CRD", 121, 6}, // i2cReadDevice + {PI_CMD_I2CRI, "I2CRI", 131, 6}, // i2cReadI2CBlockData + {PI_CMD_I2CRK, "I2CRK", 121, 6}, // i2cReadBlockData + {PI_CMD_I2CRS, "I2CRS", 112, 2}, // i2cReadByte + {PI_CMD_I2CRW, "I2CRW", 121, 2}, // i2cReadWordData + + {PI_CMD_I2CWB, "I2CWB", 131, 0}, // i2cWriteByteData + {PI_CMD_I2CWD, "I2CWD", 193, 0}, // i2cWriteDevice + {PI_CMD_I2CWI, "I2CWI", 194, 0}, // i2cWriteI2CBlockData + {PI_CMD_I2CWK, "I2CWK", 194, 0}, // i2cWriteBlockData + {PI_CMD_I2CWQ, "I2CWQ", 121, 0}, // i2cWriteQuick + {PI_CMD_I2CWS, "I2CWS", 121, 0}, // i2cWriteByte + {PI_CMD_I2CWW, "I2CWW", 131, 0}, // i2cWriteWordData + + {PI_CMD_I2CZ, "I2CZ", 193, 6}, // i2cZip + + {PI_CMD_MICS, "MICS", 112, 0}, // gpioDelay + {PI_CMD_MILS, "MILS", 112, 0}, // gpioDelay + + {PI_CMD_MODEG, "MG" , 112, 2}, // gpioGetMode + {PI_CMD_MODEG, "MODEG", 112, 2}, // gpioGetMode + + {PI_CMD_MODES, "M", 125, 0}, // gpioSetMode + {PI_CMD_MODES, "MODES", 125, 0}, // gpioSetMode + + {PI_CMD_NB, "NB", 122, 0}, // gpioNotifyBegin + {PI_CMD_NC, "NC", 112, 0}, // gpioNotifyClose + {PI_CMD_NO, "NO", 101, 2}, // gpioNotifyOpen + {PI_CMD_NP, "NP", 112, 0}, // gpioNotifyPause + + {PI_CMD_PADG, "PADG", 112, 2}, // gpioGetPad + {PI_CMD_PADS, "PADS", 121, 0}, // gpioSetPad + + {PI_CMD_PARSE, "PARSE", 115, 0}, // cmdParseScript + + {PI_CMD_PFG, "PFG", 112, 2}, // gpioGetPWMfrequency + {PI_CMD_PFS, "PFS", 121, 2}, // gpioSetPWMfrequency + + {PI_CMD_PIGPV, "PIGPV", 101, 4}, // gpioVersion + + {PI_CMD_PRG, "PRG", 112, 2}, // gpioGetPWMrange + + {PI_CMD_PROC, "PROC", 115, 2}, // gpioStoreScript + {PI_CMD_PROCD, "PROCD", 112, 0}, // gpioDeleteScript + {PI_CMD_PROCP, "PROCP", 112, 7}, // gpioScriptStatus + {PI_CMD_PROCR, "PROCR", 191, 0}, // gpioRunScript + {PI_CMD_PROCS, "PROCS", 112, 0}, // gpioStopScript + {PI_CMD_PROCU, "PROCU", 191, 0}, // gpioUpdateScript + + {PI_CMD_PRRG, "PRRG", 112, 2}, // gpioGetPWMrealRange + {PI_CMD_PRS, "PRS", 121, 2}, // gpioSetPWMrange + + {PI_CMD_PUD, "PUD", 126, 0}, // gpioSetPullUpDown + + {PI_CMD_PWM, "P", 121, 0}, // gpioPWM + {PI_CMD_PWM, "PWM", 121, 0}, // gpioPWM + + {PI_CMD_READ, "R", 112, 2}, // gpioRead + {PI_CMD_READ, "READ", 112, 2}, // gpioRead + + {PI_CMD_SERRB, "SERRB", 112, 2}, // serReadByte + {PI_CMD_SERWB, "SERWB", 121, 0}, // serWriteByte + {PI_CMD_SERC, "SERC", 112, 0}, // serClose + {PI_CMD_SERDA, "SERDA", 112, 2}, // serDataAvailable + {PI_CMD_SERO, "SERO", 132, 2}, // serOpen + {PI_CMD_SERR, "SERR", 121, 6}, // serRead + {PI_CMD_SERW, "SERW", 193, 0}, // serWrite + + {PI_CMD_SERVO, "S", 121, 0}, // gpioServo + {PI_CMD_SERVO, "SERVO", 121, 0}, // gpioServo + + {PI_CMD_SHELL, "SHELL", 128, 2}, // shell + + {PI_CMD_SLR, "SLR", 121, 6}, // gpioSerialRead + {PI_CMD_SLRC, "SLRC", 112, 0}, // gpioSerialReadClose + {PI_CMD_SLRO, "SLRO", 131, 0}, // gpioSerialReadOpen + {PI_CMD_SLRI, "SLRI", 121, 0}, // gpioSerialReadInvert + + {PI_CMD_SPIC, "SPIC", 112, 0}, // spiClose + {PI_CMD_SPIO, "SPIO", 131, 2}, // spiOpen + {PI_CMD_SPIR, "SPIR", 121, 6}, // spiRead + {PI_CMD_SPIW, "SPIW", 193, 0}, // spiWrite + {PI_CMD_SPIX, "SPIX", 193, 6}, // spiXfer + + {PI_CMD_TICK, "T", 101, 4}, // gpioTick + {PI_CMD_TICK, "TICK", 101, 4}, // gpioTick + + {PI_CMD_TRIG, "TRIG", 131, 0}, // gpioTrigger + + {PI_CMD_WDOG, "WDOG", 121, 0}, // gpioSetWatchdog + + {PI_CMD_WRITE, "W", 121, 0}, // gpioWrite + {PI_CMD_WRITE, "WRITE", 121, 0}, // gpioWrite + + {PI_CMD_WVAG, "WVAG", 192, 2}, // gpioWaveAddGeneric + {PI_CMD_WVAS, "WVAS", 196, 2}, // gpioWaveAddSerial + {PI_CMD_WVTAT, "WVTAT", 101, 2}, // gpioWaveTxAt + {PI_CMD_WVBSY, "WVBSY", 101, 2}, // gpioWaveTxBusy + {PI_CMD_WVCHA, "WVCHA", 197, 0}, // gpioWaveChain + {PI_CMD_WVCLR, "WVCLR", 101, 0}, // gpioWaveClear + {PI_CMD_WVCRE, "WVCRE", 101, 2}, // gpioWaveCreate + {PI_CMD_WVDEL, "WVDEL", 112, 0}, // gpioWaveDelete + {PI_CMD_WVGO, "WVGO" , 101, 2}, // gpioWaveTxStart + {PI_CMD_WVGOR, "WVGOR", 101, 2}, // gpioWaveTxStart + {PI_CMD_WVHLT, "WVHLT", 101, 0}, // gpioWaveTxStop + {PI_CMD_WVNEW, "WVNEW", 101, 0}, // gpioWaveAddNew + {PI_CMD_WVSC, "WVSC", 112, 2}, // gpioWaveGet*Cbs + {PI_CMD_WVSM, "WVSM", 112, 2}, // gpioWaveGet*Micros + {PI_CMD_WVSP, "WVSP", 112, 2}, // gpioWaveGet*Pulses + {PI_CMD_WVTX, "WVTX", 112, 2}, // gpioWaveTxSend + {PI_CMD_WVTXM, "WVTXM", 121, 2}, // gpioWaveTxSend + {PI_CMD_WVTXR, "WVTXR", 112, 2}, // gpioWaveTxSend + + {PI_CMD_ADD , "ADD" , 111, 0}, + {PI_CMD_AND , "AND" , 111, 0}, + {PI_CMD_CALL , "CALL" , 114, 0}, + {PI_CMD_CMDR ,"CMDR" , 111, 0}, + {PI_CMD_CMDW , "CMDW" , 111, 0}, + {PI_CMD_CMP , "CMP" , 111, 0}, + {PI_CMD_DCR , "DCR" , 113, 0}, + {PI_CMD_DCRA , "DCRA" , 101, 0}, + {PI_CMD_DIV , "DIV" , 111, 0}, + {PI_CMD_EVTWT, "EVTWT", 111, 0}, + {PI_CMD_HALT , "HALT" , 101, 0}, + {PI_CMD_INR , "INR" , 113, 0}, + {PI_CMD_INRA , "INRA" , 101, 0}, + {PI_CMD_JM , "JM" , 114, 0}, + {PI_CMD_JMP , "JMP" , 114, 0}, + {PI_CMD_JNZ , "JNZ" , 114, 0}, + {PI_CMD_JP , "JP" , 114, 0}, + {PI_CMD_JZ , "JZ" , 114, 0}, + {PI_CMD_LD , "LD" , 123, 0}, + {PI_CMD_LDA , "LDA" , 111, 0}, + {PI_CMD_LDAB , "LDAB" , 111, 0}, + {PI_CMD_MLT , "MLT" , 111, 0}, + {PI_CMD_MOD , "MOD" , 111, 0}, + {PI_CMD_NOP , "NOP" , 101, 0}, + {PI_CMD_OR , "OR" , 111, 0}, + {PI_CMD_POP , "POP" , 113, 0}, + {PI_CMD_POPA , "POPA" , 101, 0}, + {PI_CMD_PUSH , "PUSH" , 113, 0}, + {PI_CMD_PUSHA, "PUSHA", 101, 0}, + {PI_CMD_RET , "RET" , 101, 0}, + {PI_CMD_RL , "RL" , 123, 0}, + {PI_CMD_RLA , "RLA" , 111, 0}, + {PI_CMD_RR , "RR" , 123, 0}, + {PI_CMD_RRA , "RRA" , 111, 0}, + {PI_CMD_STA , "STA" , 113, 0}, + {PI_CMD_STAB , "STAB" , 111, 0}, + {PI_CMD_SUB , "SUB" , 111, 0}, + {PI_CMD_SYS , "SYS" , 116, 0}, + {PI_CMD_TAG , "TAG" , 114, 0}, + {PI_CMD_WAIT , "WAIT" , 111, 0}, + {PI_CMD_X , "X" , 124, 0}, + {PI_CMD_XA , "XA" , 113, 0}, + {PI_CMD_XOR , "XOR" , 111, 0}, + +}; + + +char * cmdUsage = "\n\ +BC1 bits Clear GPIO in bank 1\n\ +BC2 bits Clear GPIO in bank 2\n\ +BI2CC sda Close bit bang I2C\n\ +BI2CO sda scl baud | Open bit bang I2C\n\ +BI2CZ sda ... I2C bit bang multiple transactions\n\ +\n\ +BSPIC cs Close bit bang SPI\n\ +BSPIO cs miso mosi sclk baud flag | Open bit bang SPI\n\ +BSPIX cs ... SPI bit bang transfer\n\ +\n\ +BR1 Read bank 1 GPIO\n\ +BR2 Read bank 2 GPIO\n\ +\n\ +BS1 bits Set GPIO in bank 1\n\ +BS2 bits Set GPIO in bank 2\n\ +\n\ +BSCX bctl bvs BSC I2C/SPI transfer\n\ +\n\ +CF1 ... Custom function 1\n\ +CF2 ... Custom function 2\n\ +\n\ +CGI Configuration get internals\n\ +CSI v Configuration set internals\n\ +\n\ +EVM h bits Set events to monitor\n\ +EVT n Trigger event\n\ +\n\ +FC h Close file handle\n\ +FG g steady Set glitch filter on GPIO\n\ +FL pat n List files which match pattern\n\ +FN g steady active | Set noise filter on GPIO\n\ +FO file mode Open a file in mode\n\ +FR h n Read bytes from file handle\n\ +FS h n from Seek to file handle position\n\ +FW h ... Write bytes to file handle\n\ +\n\ +GDC g Get PWM dutycycle for GPIO\n\ +GPW g Get servo pulsewidth for GPIO\n\ +\n\ +H/HELP Display command help\n\ +HC g f Set hardware clock frequency\n\ +HP g f dc Set hardware PWM frequency and dutycycle\n\ +HWVER Get hardware version\n\ +\n\ +I2CC h Close I2C handle\n\ +I2CO bus device flags | Open I2C bus and device with flags\n\ +I2CPC h r word SMBus Process Call: exchange register with word\n\ +I2CPK h r ... SMBus Block Process Call: exchange data bytes with register\n\ +I2CRB h r SMBus Read Byte Data: read byte from register\n\ +I2CRD h n I2C Read bytes\n\ +I2CRI h r n SMBus Read I2C Block Data: read bytes from register\n\ +I2CRK h r SMBus Read Block Data: read data from register\n\ +I2CRS h SMBus Read Byte: read byte\n\ +I2CRW h r SMBus Read Word Data: read word from register\n\ +I2CWB h r byte SMBus Write Byte Data: write byte to register\n\ +I2CWD h ... I2C Write data\n\ +I2CWI h r ... SMBus Write I2C Block Data\n\ +I2CWK h r ... SMBus Write Block Data: write data to register\n\ +I2CWQ h b SMBus Write Quick: write bit\n\ +I2CWS h b SMBus Write Byte: write byte\n\ +I2CWW h r word SMBus Write Word Data: write word to register\n\ +I2CZ h ... I2C multiple transactions\n\ +\n\ +M/MODES g mode Set GPIO mode\n\ +MG/MODEG g Get GPIO mode\n\ +MICS n Delay for microseconds\n\ +MILS n Delay for milliseconds\n\ +\n\ +NB h bits Start notification\n\ +NC h Close notification\n\ +NO Request a notification\n\ +NP h Pause notification\n\ +\n\ +P/PWM g v Set GPIO PWM value\n\ +PADG pad Get pad drive strength\n\ +PADS pad v Set pad drive strength\n\ +PARSE text Validate script\n\ +PFG g Get GPIO PWM frequency\n\ +PFS g v Set GPIO PWM frequency\n\ +PIGPV Get pigpio library version\n\ +PRG g Get GPIO PWM range\n\ +PROC text Store script\n\ +PROCD sid Delete script\n\ +PROCP sid Get script status and parameters\n\ +PROCR sid ... Run script\n\ +PROCS sid Stop script\n\ +PROCU sid ... Set script parameters\n\ +PRRG g Get GPIO PWM real range\n\ +PRS g v Set GPIO PWM range\n\ +PUD g pud Set GPIO pull up/down\n\ +\n\ +R/READ g Read GPIO level\n\ +\n\ +S/SERVO g v Set GPIO servo pulsewidth\n\ +SERC h Close serial handle\n\ +SERDA h Check for serial data ready to read\n\ +SERO text baud flags | Open serial device at baud with flags\n\ +SERR h n Read bytes from serial handle\n\ +SERRB h Read byte from serial handle\n\ +SERW h ... Write bytes to serial handle\n\ +SERWB h byte Write byte to serial handle\n\ +SHELL name str Execute a shell command\n\ +SLR g v Read bit bang serial data from GPIO\n\ +SLRC g Close GPIO for bit bang serial data\n\ +SLRO g baud bitlen | Open GPIO for bit bang serial data\n\ +SLRI g invert Invert serial logic (1 invert, 0 normal)\n\ +SPIC h SPI close handle\n\ +SPIO channel baud flags | SPI open channel at baud with flags\n\ +SPIR h v SPI read bytes from handle\n\ +SPIW h ... SPI write bytes to handle\n\ +SPIX h ... SPI transfer bytes to handle\n\ +\n\ +T/TICK Get current tick\n\ +TRIG g micros l Trigger level for micros on GPIO\n\ +\n\ +W/WRITE g l Write level to GPIO\n\ +WDOG g millis Set millisecond watchdog on GPIO\n\ +WVAG triplets Wave add generic pulses\n\ +WVAS g baud bitlen stopbits offset ... | Wave add serial data\n\ +WVBSY Check if wave busy\n\ +WVCHA Transmit a chain of waves\n\ +WVCLR Wave clear\n\ +WVCRE Create wave from added pulses\n\ +WVDEL wid Delete waves w and higher\n\ +WVGO Wave transmit (DEPRECATED)\n\ +WVGOR Wave transmit repeatedly (DEPRECATED)\n\ +WVHLT Wave stop\n\ +WVNEW Start a new empty wave\n\ +WVSC 0,1,2 Wave get DMA control block stats\n\ +WVSM 0,1,2 Wave get micros stats\n\ +WVSP 0,1,2 Wave get pulses stats\n\ +WVTAT Returns the current transmitting wave\n\ +WVTX wid Transmit wave as one-shot\n\ +WVTXM wid wmde Transmit wave using mode\n\ +WVTXR wid Transmit wave repeatedly\n\ +\n\ +Numbers may be entered as hex (prefix 0x), octal (prefix 0),\n\ +otherwise they are assumed to be decimal.\n\ +\n\ +Examples\n\ +\n\ +pigs w 4 1 # set GPIO 4 high\n\ +pigs r 5 # read GPIO 5\n\ +pigs t # get current tick\n\ +pigs i2co 1 0x20 0 # get handle to device 0x20 on I2C bus 1\n\ +\n\ +man pigs for full details.\n\ +\n"; + +typedef struct +{ + int error; + char * str; +} errInfo_t; + +static errInfo_t errInfo[]= +{ + {PI_INIT_FAILED , "pigpio initialisation failed"}, + {PI_BAD_USER_GPIO , "GPIO not 0-31"}, + {PI_BAD_GPIO , "GPIO not 0-53"}, + {PI_BAD_MODE , "mode not 0-7"}, + {PI_BAD_LEVEL , "level not 0-1"}, + {PI_BAD_PUD , "pud not 0-2"}, + {PI_BAD_PULSEWIDTH , "pulsewidth not 0 or 500-2500"}, + {PI_BAD_DUTYCYCLE , "dutycycle not 0-range (default 255)"}, + {PI_BAD_TIMER , "timer not 0-9"}, + {PI_BAD_MS , "ms not 10-60000"}, + {PI_BAD_TIMETYPE , "timetype not 0-1"}, + {PI_BAD_SECONDS , "seconds < 0"}, + {PI_BAD_MICROS , "micros not 0-999999"}, + {PI_TIMER_FAILED , "gpioSetTimerFunc failed"}, + {PI_BAD_WDOG_TIMEOUT , "timeout not 0-60000"}, + {PI_NO_ALERT_FUNC , "DEPRECATED"}, + {PI_BAD_CLK_PERIPH , "clock peripheral not 0-1"}, + {PI_BAD_CLK_SOURCE , "DEPRECATED"}, + {PI_BAD_CLK_MICROS , "clock micros not 1, 2, 4, 5, 8, or 10"}, + {PI_BAD_BUF_MILLIS , "buf millis not 100-10000"}, + {PI_BAD_DUTYRANGE , "dutycycle range not 25-40000"}, + {PI_BAD_SIGNUM , "signum not 0-63"}, + {PI_BAD_PATHNAME , "can't open pathname"}, + {PI_NO_HANDLE , "no handle available"}, + {PI_BAD_HANDLE , "unknown handle"}, + {PI_BAD_IF_FLAGS , "ifFlags > 4"}, + {PI_BAD_CHANNEL , "DMA channel not 0-14"}, + {PI_BAD_SOCKET_PORT , "socket port not 1024-30000"}, + {PI_BAD_FIFO_COMMAND , "unknown fifo command"}, + {PI_BAD_SECO_CHANNEL , "DMA secondary channel not 0-14"}, + {PI_NOT_INITIALISED , "function called before gpioInitialise"}, + {PI_INITIALISED , "function called after gpioInitialise"}, + {PI_BAD_WAVE_MODE , "waveform mode not 0-1"}, + {PI_BAD_CFG_INTERNAL , "bad parameter in gpioCfgInternals call"}, + {PI_BAD_WAVE_BAUD , "baud rate not 50-250K(RX)/50-1M(TX)"}, + {PI_TOO_MANY_PULSES , "waveform has too many pulses"}, + {PI_TOO_MANY_CHARS , "waveform has too many chars"}, + {PI_NOT_SERIAL_GPIO , "no bit bang serial read in progress on GPIO"}, + {PI_BAD_SERIAL_STRUC , "bad (null) serial structure parameter"}, + {PI_BAD_SERIAL_BUF , "bad (null) serial buf parameter"}, + {PI_NOT_PERMITTED , "no permission to update GPIO"}, + {PI_SOME_PERMITTED , "no permission to update one or more GPIO"}, + {PI_BAD_WVSC_COMMND , "bad WVSC subcommand"}, + {PI_BAD_WVSM_COMMND , "bad WVSM subcommand"}, + {PI_BAD_WVSP_COMMND , "bad WVSP subcommand"}, + {PI_BAD_PULSELEN , "trigger pulse length not 1-100"}, + {PI_BAD_SCRIPT , "invalid script"}, + {PI_BAD_SCRIPT_ID , "unknown script id"}, + {PI_BAD_SER_OFFSET , "add serial data offset > 30 minute"}, + {PI_GPIO_IN_USE , "GPIO already in use"}, + {PI_BAD_SERIAL_COUNT , "must read at least a byte at a time"}, + {PI_BAD_PARAM_NUM , "script parameter id not 0-9"}, + {PI_DUP_TAG , "script has duplicate tag"}, + {PI_TOO_MANY_TAGS , "script has too many tags"}, + {PI_BAD_SCRIPT_CMD , "illegal script command"}, + {PI_BAD_VAR_NUM , "script variable id not 0-149"}, + {PI_NO_SCRIPT_ROOM , "no more room for scripts"}, + {PI_NO_MEMORY , "can't allocate temporary memory"}, + {PI_SOCK_READ_FAILED , "socket read failed"}, + {PI_SOCK_WRIT_FAILED , "socket write failed"}, + {PI_TOO_MANY_PARAM , "too many script parameters (> 10)"}, + {PI_SCRIPT_NOT_READY , "script initialising"}, + {PI_BAD_TAG , "script has unresolved tag"}, + {PI_BAD_MICS_DELAY , "bad MICS delay (too large)"}, + {PI_BAD_MILS_DELAY , "bad MILS delay (too large)"}, + {PI_BAD_WAVE_ID , "non existent wave id"}, + {PI_TOO_MANY_CBS , "No more CBs for waveform"}, + {PI_TOO_MANY_OOL , "No more OOL for waveform"}, + {PI_EMPTY_WAVEFORM , "attempt to create an empty waveform"}, + {PI_NO_WAVEFORM_ID , "no more waveform ids"}, + {PI_I2C_OPEN_FAILED , "can't open I2C device"}, + {PI_SER_OPEN_FAILED , "can't open serial device"}, + {PI_SPI_OPEN_FAILED , "can't open SPI device"}, + {PI_BAD_I2C_BUS , "bad I2C bus"}, + {PI_BAD_I2C_ADDR , "bad I2C address"}, + {PI_BAD_SPI_CHANNEL , "bad SPI channel"}, + {PI_BAD_FLAGS , "bad i2c/spi/ser open flags"}, + {PI_BAD_SPI_SPEED , "bad SPI speed"}, + {PI_BAD_SER_DEVICE , "bad serial device name"}, + {PI_BAD_SER_SPEED , "bad serial baud rate"}, + {PI_BAD_PARAM , "bad i2c/spi/ser parameter"}, + {PI_I2C_WRITE_FAILED , "I2C write failed"}, + {PI_I2C_READ_FAILED , "I2C read failed"}, + {PI_BAD_SPI_COUNT , "bad SPI count"}, + {PI_SER_WRITE_FAILED , "ser write failed"}, + {PI_SER_READ_FAILED , "ser read failed"}, + {PI_SER_READ_NO_DATA , "ser read no data available"}, + {PI_UNKNOWN_COMMAND , "unknown command"}, + {PI_SPI_XFER_FAILED , "spi xfer/read/write failed"}, + {PI_BAD_POINTER , "bad (NULL) pointer"}, + {PI_NO_AUX_SPI , "no auxiliary SPI on Pi A or B"}, + {PI_NOT_PWM_GPIO , "GPIO is not in use for PWM"}, + {PI_NOT_SERVO_GPIO , "GPIO is not in use for servo pulses"}, + {PI_NOT_HCLK_GPIO , "GPIO has no hardware clock"}, + {PI_NOT_HPWM_GPIO , "GPIO has no hardware PWM"}, + {PI_BAD_HPWM_FREQ , "hardware PWM frequency not 1-125M"}, + {PI_BAD_HPWM_DUTY , "hardware PWM dutycycle not 0-1M"}, + {PI_BAD_HCLK_FREQ , "hardware clock frequency not 4689-250M"}, + {PI_BAD_HCLK_PASS , "need password to use hardware clock 1"}, + {PI_HPWM_ILLEGAL , "illegal, PWM in use for main clock"}, + {PI_BAD_DATABITS , "serial data bits not 1-32"}, + {PI_BAD_STOPBITS , "serial (half) stop bits not 2-8"}, + {PI_MSG_TOOBIG , "socket/pipe message too big"}, + {PI_BAD_MALLOC_MODE , "bad memory allocation mode"}, + {PI_TOO_MANY_SEGS , "too many I2C transaction segments"}, + {PI_BAD_I2C_SEG , "an I2C transaction segment failed"}, + {PI_BAD_SMBUS_CMD , "SMBus command not supported by driver"}, + {PI_NOT_I2C_GPIO , "no bit bang I2C in progress on GPIO"}, + {PI_BAD_I2C_WLEN , "bad I2C write length"}, + {PI_BAD_I2C_RLEN , "bad I2C read length"}, + {PI_BAD_I2C_CMD , "bad I2C command"}, + {PI_BAD_I2C_BAUD , "bad I2C baud rate, not 50-500k"}, + {PI_CHAIN_LOOP_CNT , "bad chain loop count"}, + {PI_BAD_CHAIN_LOOP , "empty chain loop"}, + {PI_CHAIN_COUNTER , "too many chain counters"}, + {PI_BAD_CHAIN_CMD , "bad chain command"}, + {PI_BAD_CHAIN_DELAY , "bad chain delay micros"}, + {PI_CHAIN_NESTING , "chain counters nested too deeply"}, + {PI_CHAIN_TOO_BIG , "chain is too long"}, + {PI_DEPRECATED , "deprecated function removed"}, + {PI_BAD_SER_INVERT , "bit bang serial invert not 0 or 1"}, + {PI_BAD_EDGE , "bad ISR edge, not 1, 1, or 2"}, + {PI_BAD_ISR_INIT , "bad ISR initialisation"}, + {PI_BAD_FOREVER , "loop forever must be last chain command"}, + {PI_BAD_FILTER , "bad filter parameter"}, + {PI_BAD_PAD , "bad pad number"}, + {PI_BAD_STRENGTH , "bad pad drive strength"}, + {PI_FIL_OPEN_FAILED , "file open failed"}, + {PI_BAD_FILE_MODE , "bad file mode"}, + {PI_BAD_FILE_FLAG , "bad file flag"}, + {PI_BAD_FILE_READ , "bad file read"}, + {PI_BAD_FILE_WRITE , "bad file write"}, + {PI_FILE_NOT_ROPEN , "file not open for read"}, + {PI_FILE_NOT_WOPEN , "file not open for write"}, + {PI_BAD_FILE_SEEK , "bad file seek"}, + {PI_NO_FILE_MATCH , "no files match pattern"}, + {PI_NO_FILE_ACCESS , "no permission to access file"}, + {PI_FILE_IS_A_DIR , "file is a directory"}, + {PI_BAD_SHELL_STATUS , "bad shell return status"}, + {PI_BAD_SCRIPT_NAME , "bad script name"}, + {PI_BAD_SPI_BAUD , "bad SPI baud rate, not 50-500k"}, + {PI_NOT_SPI_GPIO , "no bit bang SPI in progress on GPIO"}, + {PI_BAD_EVENT_ID , "bad event id"}, + {PI_CMD_INTERRUPTED , "command interrupted, Python"}, + +}; + +static char * fmtMdeStr="RW540123"; +static char * fmtPudStr="ODU"; + +static int cmdMatch(char *str) +{ + int i; + + for (i=0; i<(sizeof(cmdInfo)/sizeof(cmdInfo_t)); i++) + { + if (strcasecmp(str, cmdInfo[i].name) == 0) return i; + } + return CMD_UNKNOWN_CMD; +} + +static int getNum(char *str, uint32_t *val, int8_t *opt) +{ + int f, n; + intmax_t v; + + *opt = 0; + + f = sscanf(str, " %ji %n", &v, &n); + + if (f == 1) + { + *val = v; + *opt = CMD_NUMERIC; + return n; + } + + f = sscanf(str, " v%ji %n", &v, &n); + + if (f == 1) + { + *val = v; + if (v < PI_MAX_SCRIPT_VARS) *opt = CMD_VAR; + else *opt = -CMD_VAR; + return n; + } + + f = sscanf(str, " p%ji %n", &v, &n); + + if (f == 1) + { + *val = v; + if (v < PI_MAX_SCRIPT_PARAMS) *opt = CMD_PAR; + else *opt = -CMD_PAR; + return n; + } + + return 0; +} + +static char intCmdStr[32]; + +char *cmdStr(void) +{ + return intCmdStr; +} + +int cmdParse( + char *buf, uint32_t *p, unsigned ext_len, char *ext, cmdCtlParse_t *ctl) +{ + int f, valid, idx, val, pp, pars, n, n2; + char *p8; + int32_t *p32; + char c; + uint32_t tp1=0, tp2=0, tp3=0, tp4=0, tp5=0; + int8_t to1, to2, to3, to4, to5; + int eaten; + + /* Check that ext is big enough for the largest message. */ + if (ext_len < (4 * CMD_MAX_PARAM)) return CMD_EXT_TOO_SMALL; + + bzero(&ctl->opt, sizeof(ctl->opt)); + + sscanf(buf+ctl->eaten, " %31s %n", intCmdStr, &pp); + + ctl->eaten += pp; + + p[0] = -1; + + idx = cmdMatch(intCmdStr); + + if (idx < 0) return idx; + + valid = 0; + + p[0] = cmdInfo[idx].cmd; + p[1] = 0; + p[2] = 0; + p[3] = 0; + + switch (cmdInfo[idx].vt) + { + case 101: /* BR1 BR2 CGI H HELP HWVER + DCRA HALT INRA NO + PIGPV POPA PUSHA RET T TICK WVBSY WVCLR + WVCRE WVGO WVGOR WVHLT WVNEW + + No parameters, always valid. + */ + valid = 1; + + break; + + case 111: /* ADD AND BC1 BC2 BS1 BS2 + CMP CSI DIV LDA LDAB MLT + MOD OR RLA RRA STAB SUB WAIT XOR + + One parameter, any value. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if (ctl->opt[1] > 0) valid = 1; + + break; + + case 112: /* BI2CC FC GDC GPW I2CC I2CRB + MG MICS MILS MODEG NC NP PADG PFG PRG + PROCD PROCP PROCS PRRG R READ SLRC SPIC + WVDEL WVSC WVSM WVSP WVTX WVTXR BSPIC + + One positive parameter. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0)) valid = 1; + + break; + + case 113: /* DCR INR POP PUSH STA XA + + One register parameter. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] > 0) && (p[1] < PI_MAX_SCRIPT_VARS)) valid = 1; + + break; + + case 114: /* CALL JM JMP JNZ JP JZ TAG + + One numeric parameter, any value. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + if (ctl->opt[1] == CMD_NUMERIC) valid = 1; + + break; + + case 115: /* PARSE PROC + + One parameter, string (rest of input). + */ + p[3] = strlen(buf+ctl->eaten); + memcpy(ext, buf+ctl->eaten, p[3]); + ctl->eaten += p[3]; + valid = 1; + + break; + + case 116: /* SYS + + One parameter, a string. + */ + f = sscanf(buf+ctl->eaten, " %*s%n %n", &n, &n2); + if ((f >= 0) && n) + { + p[3] = n; + ctl->opt[3] = CMD_NUMERIC; + memcpy(ext, buf+ctl->eaten, n); + ctl->eaten += n2; + valid = 1; + } + + break; + + case 121: /* HC FR I2CRD I2CRR I2CRW I2CWB I2CWQ P + PADS PFS PRS PWM S SERVO SLR SLRI W + WDOG WRITE WVTXM + + Two positive parameters. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0)) valid = 1; + + break; + + case 122: /* NB + + Two parameters, first positive, second any value. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0)) valid = 1; + + break; + + case 123: /* LD RL RR + + Two parameters, first register, second any value. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && + (p[1] < PI_MAX_SCRIPT_VARS) && + (ctl->opt[2] > 0)) valid = 1; + + break; + + case 124: /* X + + Two register parameters. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && (p[1] < PI_MAX_SCRIPT_VARS) && + (ctl->opt[2] > 0) && (p[2] < PI_MAX_SCRIPT_VARS)) valid = 1; + + break; + + case 125: /* M MODES + + Two parameters, first positive, second in 'RW540123'. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + f = sscanf(buf+ctl->eaten, " %c %n", &c, &n); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && (f >= 1)) + { + ctl->eaten += n; + val = toupper(c); + p8 = strchr(fmtMdeStr, val); + + if (p8 != NULL) + { + val = p8 - fmtMdeStr; + p[2] = val; + valid = 1; + } + } + + break; + + case 126: /* PUD + + Two parameters, first positive, second in 'ODU'. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + f = sscanf(buf+ctl->eaten, " %c %n", &c, &n); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && (f >= 1)) + { + ctl->eaten += n; + val = toupper(c); + p8 = strchr(fmtPudStr, val); + if (p8 != NULL) + { + val = p8 - fmtPudStr; + p[2] = val; + valid = 1; + } + } + + break; + + case 127: /* FL FO + + Two parameters, first a string, other positive. + */ + f = sscanf(buf+ctl->eaten, " %*s%n %n", &n, &n2); + if ((f >= 0) && n) + { + p[3] = n; + ctl->opt[2] = CMD_NUMERIC; + memcpy(ext, buf+ctl->eaten, n); + ctl->eaten += n2; + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0)) + valid = 1; + } + + break; + + case 128: /* SHELL + + Two string parameters, the first space teminated. + The second arbitrary. + */ + f = sscanf(buf+ctl->eaten, " %*s%n %n", &n, &n2); + + if ((f >= 0) && n) + { + valid = 1; + + p[1] = n; + memcpy(ext, buf+ctl->eaten, n); + ctl->eaten += n; + ext[n] = 0; /* terminate first string */ + + n2 = strlen(buf+ctl->eaten+1); + memcpy(ext+n+1, buf+ctl->eaten+1, n2); + ctl->eaten += n2; + ctl->eaten ++; + p[3] = p[1] + n2 + 1; + } + + break; + + case 131: /* BI2CO HP I2CO I2CPC I2CRI I2CWB I2CWW + SLRO SPIO TRIG + + Three positive parameters. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &ctl->opt[3]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0) && + (ctl->opt[3] > 0) && ((int)tp1 >= 0)) + { + p[3] = 4; + memcpy(ext, &tp1, 4); + valid = 1; + } + + break; + + case 132: /* SERO + + Three parameters, first a string, rest >=0 + */ + f = sscanf(buf+ctl->eaten, " %*s%n %n", &n, &n2); + if ((f >= 0) && n) + { + p[3] = n; + ctl->opt[2] = CMD_NUMERIC; + memcpy(ext, buf+ctl->eaten, n); + ctl->eaten += n2; + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0)) + valid = 1; + } + + break; + + case 133: /* FS + + Three parameters. First and third positive. + Second may be negative when interpreted as an int. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && + (to1 == CMD_NUMERIC) && ((int)tp1 >= 0)) + { + p[3] = 4; + memcpy(ext, &tp1, 4); + valid = 1; + } + + break; + + case 134: /* BSPIO + + Six parameters. First to Fifth positive. + Sixth may be negative when interpreted as an int. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + ctl->eaten += getNum(buf+ctl->eaten, &tp2, &to2); + ctl->eaten += getNum(buf+ctl->eaten, &tp3, &to3); + ctl->eaten += getNum(buf+ctl->eaten, &tp4, &to4); + ctl->eaten += getNum(buf+ctl->eaten, &tp5, &to5); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (to1 == CMD_NUMERIC) && ((int)tp1 >= 0) && + (to2 == CMD_NUMERIC) && ((int)tp2 >= 0) && + (to3 == CMD_NUMERIC) && ((int)tp3 >= 0) && + (to4 == CMD_NUMERIC) && ((int)tp4 >= 0) && + (to5 == CMD_NUMERIC)) + { + p[3] = 5 * 4; + memcpy(ext+ 0, &tp1, 4); + memcpy(ext+ 4, &tp2, 4); + memcpy(ext+ 8, &tp3, 4); + memcpy(ext+12, &tp4, 4); + memcpy(ext+16, &tp5, 4); + valid = 1; + } + + break; + + case 191: /* PROCR PROCU + + One to 11 parameters, first positive, + optional remainder, any value. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0)) + { + pars = 0; + p32 = (int32_t *)ext; + + while (pars < PI_MAX_SCRIPT_PARAMS) + { + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + pars++; + *p32++ = tp1; + } + else break; + } + + p[3] = pars * 4; + + valid = 1; + } + + break; + + case 192: /* WVAG + + One or more triplets (gpios on, gpios off, delay), + any value. + */ + + pars = 0; + p32 = (int32_t *)ext; + + while (pars < CMD_MAX_PARAM) + { + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + pars++; + *p32++ = tp1; + } + else break; + } + + p[3] = pars * 4; + + if (pars && ((pars % 3) == 0)) valid = 1; + + break; + + case 193: /* BI2CZ BSCX BSPIX FW I2CWD I2CZ SERW + SPIW SPIX + + Two or more parameters, first >=0, rest 0-255. + + BSCX is special case one or more. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0)) + { + pars = 0; + p8 = ext; + + while (pars < CMD_MAX_PARAM) + { + eaten = getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + if (((int)tp1>=0) && ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + ctl->eaten += eaten; + } + else break; /* invalid number, end of command */ + } + else break; + } + + p[3] = pars; + + if (pars || (p[0]==PI_CMD_BSCX)) valid = 1; + } + + break; + + case 194: /* I2CPK I2CWI I2CWK + + Three to 34 parameters, all 0-255. + */ + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] == CMD_NUMERIC) && + (ctl->opt[2] == CMD_NUMERIC) && + ((int)p[1]>=0) && ((int)p[2]>=0) && ((int)p[2]<=255)) + { + pars = 0; + p8 = ext; + + while (pars < 32) + { + eaten = getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + if (((int)tp1>=0) && ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + ctl->eaten += eaten; + } + else break; /* invalid number, end of command */ + } + else break; + } + + p[3] = pars; + + if (pars > 0) valid = 1; + } + + break; + + case 195: /* CF1 CF2 + + Zero or more parameters, first two >=0, rest 0-255. + */ + valid = 1; + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if (ctl->opt[1] == CMD_NUMERIC) + { + if ((int)p[1] >= 0) + { + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if (ctl->opt[2] == CMD_NUMERIC) + { + if ((int)p[2] >= 0) + { + pars = 0; + p8 = ext; + + while (pars < CMD_MAX_PARAM) + { + eaten = getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + if (((int)tp1>=0) && ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + ctl->eaten += eaten; + } + else break; + } + else break; + } + + p[3] = pars; + } + else valid = 0; + } + } + else valid = 0; + } + + break; + + case 196: /* WVAS + + gpio baud offset char... + + p1 gpio + p2 baud + p3 len + 4 + --------- + uint32_t databits + uint32_t stophalfbits + uint32_t offset + uint8_t[len] + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + ctl->eaten += getNum(buf+ctl->eaten, &tp2, &to2); + ctl->eaten += getNum(buf+ctl->eaten, &tp3, &to3); + + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0) && + (ctl->opt[2] == CMD_NUMERIC) && ((int)p[2] > 0) && + (to1 == CMD_NUMERIC) && + (to2 == CMD_NUMERIC) && + (to3 == CMD_NUMERIC)) + { + pars = 0; + + memcpy(ext, &tp1, 4); + memcpy(ext+4, &tp2, 4); + memcpy(ext+8, &tp3, 4); + p8 = ext + 12; + while (pars < CMD_MAX_PARAM) + { + eaten = getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + if (((int)tp1>=0) && ((int)tp1<=255)) + { + *p8++ = tp1; + pars++; + ctl->eaten += eaten; + } + else break; /* invalid number, end of command */ + } + else break; + } + + p[3] = pars + 12; + + if (pars > 0) valid = 1; + } + + break; + + case 197: /* WVCHA + + One or more parameters, all 0-255. + */ + pars = 0; + p8 = ext; + + while (pars < CMD_MAX_PARAM) + { + eaten = getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + if (((int)tp1>=0) && ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + ctl->eaten += eaten; + } + else break; /* invalid number, end of command */ + } + else break; + } + + p[3] = pars; + + if (pars) valid = 1; + + break; + + + } + + if (valid) return idx; else return CMD_BAD_PARAMETER; +} + +char * cmdErrStr(int error) +{ + int i; + + for (i=0; i<(sizeof(errInfo)/sizeof(errInfo_t)); i++) + { + if (errInfo[i].error == error) return errInfo[i].str; + } + return "unknown error"; +} + +int cmdParseScript(char *script, cmdScript_t *s, int diags) +{ + int idx, len, b, i, j, tags, resolved; + int status; + uint32_t p[10]; + cmdInstr_t instr; + cmdCtlParse_t ctl; + char v[CMD_MAX_EXTENSION]; + + ctl.eaten = 0; + + status = 0; + + cmdTagStep_t tag_step[PI_MAX_SCRIPT_TAGS]; + + len = strlen(script); + + /* calloc space for PARAMS, VARS, CMDS, and STRINGS */ + + b = (sizeof(int) * (PI_MAX_SCRIPT_PARAMS + PI_MAX_SCRIPT_VARS)) + + (sizeof(cmdInstr_t) * (len + 2) / 2) + len; + + s->par = calloc(1, b); + + if (s->par == NULL) return -1; + + s->var = s->par + PI_MAX_SCRIPT_PARAMS; + + s->instr = (cmdInstr_t *)(s->var + PI_MAX_SCRIPT_VARS); + + s->str_area = (char *)(s->instr + ((len + 2) / 2)); + + s->str_area_len = len; + s->str_area_pos = 0; + + s->instrs = 0; + + tags = 0; + + idx = 0; + + while (ctl.eaten= 0) + { + if (p[3]) + { + memcpy(s->str_area + s->str_area_pos, v, p[3]); + s->str_area[s->str_area_pos + p[3]] = 0; + p[4] = (intptr_t) s->str_area + s->str_area_pos; + s->str_area_pos += (p[3] + 1); + } + + memcpy(&instr.p, p, sizeof(instr.p)); + + if (instr.p[0] == PI_CMD_TAG) + { + if (tags < PI_MAX_SCRIPT_TAGS) + { + /* check tag not already used */ + for (j=0; jinstrs; + tags++; + } + else + { + if (diags) + { + fprintf(stderr, "Too many tags: %d\n", instr.p[1]); + } + if (!status) status = PI_TOO_MANY_TAGS; + idx = -1; + } + } + } + else + { + if (diags) + { + if (idx == CMD_UNKNOWN_CMD) + fprintf(stderr, "Unknown command: %s\n", cmdStr()); + else + fprintf(stderr, "Bad parameter to %s\n", cmdStr()); + } + if (!status) status = PI_BAD_SCRIPT_CMD; + } + + if (idx >= 0) + { + if (instr.p[0] != PI_CMD_TAG) + { + memcpy(instr.opt, &ctl.opt, sizeof(instr.opt)); + s->instr[s->instrs++] = instr; + } + } + } + + for (i=0; iinstrs; i++) + { + instr = s->instr[i]; + + /* resolve jumps */ + + if ((instr.p[0] == PI_CMD_JMP) || (instr.p[0] == PI_CMD_CALL) || + (instr.p[0] == PI_CMD_JZ) || (instr.p[0] == PI_CMD_JNZ) || + (instr.p[0] == PI_CMD_JM) || (instr.p[0] == PI_CMD_JP)) + { + resolved = 0; + + for (j=0; jinstr[i].p[1] = tag_step[j].step; + resolved = 1; + break; + } + } + + if (!resolved) + { + if (diags) + { + fprintf(stderr, "Can't resolve tag %d\n", instr.p[1]); + } + if (!status) status = PI_BAD_TAG; + } + } + } + return status; +} + diff --git a/thirdparty/PIGPIO/command.h b/thirdparty/PIGPIO/command.h new file mode 100644 index 0000000000..eede5929db --- /dev/null +++ b/thirdparty/PIGPIO/command.h @@ -0,0 +1,122 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* +This version is for pigpio version 57+ +*/ + +#ifndef COMMAND_H +#define COMMAND_H + +#include +#include + +#include "pigpio.h" + +#define CMD_MAX_PARAM 512 +#define CMD_MAX_EXTENSION (1<<16) + +#define CMD_UNKNOWN_CMD -1 +#define CMD_BAD_PARAMETER -2 +#define CMD_EXT_TOO_SMALL -3 + +#define CMD_P_ARR 10 +#define CMD_V_ARR 10 + +#define CMD_NUMERIC 1 +#define CMD_VAR 2 +#define CMD_PAR 3 + +typedef struct +{ + uint32_t cmd; + uint32_t p1; + uint32_t p2; + union + { + uint32_t p3; + uint32_t ext_len; + uint32_t res; + }; +} cmdCmd_t; + +typedef struct +{ + int eaten; + int8_t opt[4]; +} cmdCtlParse_t; + +typedef struct +{ + int cmd; /* command number */ + char *name; /* command name */ + int vt; /* command verification type */ + int rv; /* command return value type */ +} cmdInfo_t; + +typedef struct +{ + uint32_t tag; + int step; +} cmdTagStep_t; + +typedef struct +{ + uint32_t p[5]; + int8_t opt[4]; +} cmdInstr_t; + +typedef struct +{ + /* + +-----------+---------+---------+----------------+ + | PARAMS... | VARS... | CMDS... | STRING AREA... | + +-----------+---------+---------+----------------+ + */ + int *par; + int *var; + cmdInstr_t *instr; + int instrs; + char *str_area; + int str_area_len; + int str_area_pos; +} cmdScript_t; + +extern cmdInfo_t cmdInfo[]; + +extern char *cmdUsage; + +int cmdParse(char *buf, uint32_t *p, unsigned ext_len, char *ext, cmdCtlParse_t *ctl); + +int cmdParseScript(char *script, cmdScript_t *s, int diags); + +char *cmdErrStr(int error); + +char *cmdStr(void); + +#endif + diff --git a/thirdparty/PIGPIO/custom.cext b/thirdparty/PIGPIO/custom.cext new file mode 100644 index 0000000000..905884d433 --- /dev/null +++ b/thirdparty/PIGPIO/custom.cext @@ -0,0 +1,54 @@ +/* +This version is for pigpio version 26+ + +If you want customised functions replace this file with your own +definitions for gpioCustom1 and gpioCustom2. +*/ + +#include "pigpio.h" + +int gpioCustom1(unsigned arg1, unsigned arg2, char *argx, unsigned count) +{ + int i; + unsigned max; + + DBG(DBG_USER, "arg1=%d arg2=%d count=%d [%s]", + arg1, arg2, count, myBuf2Str(count, argx)); + + CHECK_INITED; + + /* for dummy just return max parameter */ + + if (arg1 > arg2) max = arg1; else max = arg2; + + for (i=0; i max) max = argx[i]; + + return max; +} + + +int gpioCustom2(unsigned arg1, char *argx, unsigned count, + char *retBuf, unsigned retMax) +{ + int i, j, t; + + DBG(DBG_USER, "arg1=%d count=%d [%s] retMax=%d", + arg1, count, myBuf2Str(count, argx), retMax); + + CHECK_INITED; + + /* for dummy just return argx reversed */ + + if (count > retMax) count = retMax; + + for (i=0, j=count-1; i<=j; i++, j--) + { + /* t used as argx and retBuf may be the same buffer */ + t = argx[i]; + retBuf[i] = argx[j]; + retBuf[j] = t; + } + + return count; +} + diff --git a/thirdparty/PIGPIO/pig2vcd.1 b/thirdparty/PIGPIO/pig2vcd.1 new file mode 100644 index 0000000000..e5271ee2e3 --- /dev/null +++ b/thirdparty/PIGPIO/pig2vcd.1 @@ -0,0 +1,246 @@ + +." Process this file with +." groff -man -Tascii pig2vcd.1 +." +.TH pig2vcd 1 2012-2018 Linux "pigpio archive" +.SH NAME +pig2vd - A utility to convert pigpio notifications to VCD. + +.SH SYNOPSIS + +pig2vcd file.VCD +.SH DESCRIPTION + + +.ad l + +.nh +pig2vcd is a utility which reads notifications on stdin and writes the +output as a Value Change Dump (VCD) file on stdout. + +.br + +.br +The VCD file can be viewed using GTKWave. + +.br + +.br +.SS Notifications +.br + +.br +Notifications consist of 12 bytes with the following binary format. + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint16_t seqno; +.br + uint16_t flags; +.br + uint32_t tick; +.br + uint32_t level; +.br +} gpioReport_t; +.br + +.EE + +.br + +.br +seqno: starts at 0 each time the handle is opened and then increments by one for each report. + +.br + +.br +flags: two flags are defined, PI_NTFY_FLAGS_WDOG and PI_NTFY_FLAGS_ALIVE. If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags indicate a gpio which has had a watchdog timeout; if bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive signal on the pipe/socket and is sent once a minute in the absence of other notification activity. + +.br + +.br +tick: the number of microseconds since system boot. It wraps around after 1h12m. + +.br + +.br +level: indicates the level of each gpio. If bit 1< +*/ + +/* +This version is for pigpio version 3+ +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "pigpio.h" + +/* +This software converts pigpio notification reports +into a VCD format understood by GTKWave. +*/ + +#define RS (sizeof(gpioReport_t)) + +static char * timeStamp() +{ + static char buf[32]; + + struct timeval now; + struct tm tmp; + + gettimeofday(&now, NULL); + + localtime_r(&now.tv_sec, &tmp); + strftime(buf, sizeof(buf), "%F %T", &tmp); + + return buf; +} + +int symbol(int bit) +{ + if (bit < 26) return ('A' + bit); + else return ('a' + bit - 26); +} + +int main(int argc, char * argv[]) +{ + int b, r, v; + uint32_t t0; + uint32_t lastLevel, changed; + + gpioReport_t report; + + r=read(STDIN_FILENO, &report, RS); + + if (r != RS) exit(-1); + + printf("$date %s $end\n", timeStamp()); + printf("$version pig2vcd V1 $end\n"); + printf("$timescale 1 us $end\n"); + printf("$scope module top $end\n"); + + for (b=0; b<32; b++) + printf("$var wire 1 %c %d $end\n", symbol(b), b); + + printf("$upscope $end\n"); + printf("$enddefinitions $end\n"); + + t0 = report.tick; + lastLevel =0; + + while ((r=read(STDIN_FILENO, &report, RS)) == RS) + { + if (report.level != lastLevel) + { + printf("#%u\n", report.tick - t0); + + changed = report.level ^ lastLevel; + + lastLevel = report.level; + + for (b=0; b<32; b++) + { + if (changed & (1< + + +gcc -Wall -pthread -o prog prog.c -lpigpio -lrt + +sudo ./prog +.SH DESCRIPTION + + +.ad l + +.nh + +.br + +.br +pigpio is a C library for the Raspberry which allows control of the GPIO. + +.br + +.br +.SS Features +.br + +.br +o hardware timed PWM on any of GPIO 0-31 + +.br + +.br +o hardware timed servo pulses on any of GPIO 0-31 + +.br + +.br +o callbacks when any of GPIO 0-31 change state + +.br + +.br +o callbacks at timed intervals + +.br + +.br +o reading/writing all of the GPIO in a bank as one operation + +.br + +.br +o individually setting GPIO modes, reading and writing + +.br + +.br +o notifications when any of GPIO 0-31 change state + +.br + +.br +o the construction of output waveforms with microsecond timing + +.br + +.br +o rudimentary permission control over GPIO + +.br + +.br +o a simple interface to start and stop new threads + +.br + +.br +o I2C, SPI, and serial link wrappers + +.br + +.br +o creating and running scripts + +.br + +.br +.SS GPIO +.br + +.br +ALL GPIO are identified by their Broadcom number. + +.br + +.br +.SS Credits +.br + +.br +The PWM and servo pulses are timed using the DMA and PWM peripherals. + +.br + +.br +This use was inspired by Richard Hirst's servoblaster kernel module. + +.br + +.br +See \fBhttps://github.com/richardghirst/PiBits/tree/master/ServoBlaster\fP + +.br + +.br +.SS Usage +.br + +.br +Include in your source files. + +.br + +.br +Assuming your source is in prog.c use the following command to build and +run the executable. + +.br + +.br + +.EX +gcc -Wall -pthread -o prog prog.c -lpigpio -lrt +.br +sudo ./prog +.br + +.EE + +.br + +.br +For examples of usage see the C programs within the pigpio archive file. + +.br + +.br +.SS Notes +.br + +.br +All the functions which return an int return < 0 on error. + +.br + +.br +\fBgpioInitialise\fP must be called before all other library functions +with the following exceptions: + +.br + +.br + +.EX +\fBgpioCfg*\fP +.br +\fBgpioVersion\fP +.br +\fBgpioHardwareRevision\fP +.br + +.EE + +.br + +.br +If the library is not initialised all but the \fBgpioCfg*\fP, +\fBgpioVersion\fP, and \fBgpioHardwareRevision\fP functions will +return error PI_NOT_INITIALISED. + +.br + +.br +If the library is initialised the \fBgpioCfg*\fP functions will return +error PI_INITIALISED. + +.br + +.br +.SH FUNCTIONS + +.IP "\fBint gpioInitialise(void)\fP" +.IP "" 4 +Initialises the library. + +.br + +.br +Returns the pigpio version number if OK, otherwise PI_INIT_FAILED. + +.br + +.br +gpioInitialise must be called before using the other library functions +with the following exceptions: + +.br + +.br + +.EX +\fBgpioCfg*\fP +.br +\fBgpioVersion\fP +.br +\fBgpioHardwareRevision\fP +.br + +.EE + +.br + +.br +\fBExample\fP +.br + +.EX +if (gpioInitialise() < 0) +.br +{ +.br + // pigpio initialisation failed. +.br +} +.br +else +.br +{ +.br + // pigpio initialised okay. +.br +} +.br + +.EE + +.IP "\fBvoid gpioTerminate(void)\fP" +.IP "" 4 +Terminates the library. + +.br + +.br +Returns nothing. + +.br + +.br +Call before program exit. + +.br + +.br +This function resets the used DMA channels, releases memory, and +terminates any running threads. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioTerminate(); +.br + +.EE + +.IP "\fBint gpioSetMode(unsigned gpio, unsigned mode)\fP" +.IP "" 4 +Sets the GPIO mode, typically input or output. + +.br + +.br + +.EX +gpio: 0-53 +.br +mode: 0-7 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE. + +.br + +.br +Arduino style: pinMode. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSetMode(17, PI_INPUT); // Set GPIO17 as input. +.br + +.br +gpioSetMode(18, PI_OUTPUT); // Set GPIO18 as output. +.br + +.br +gpioSetMode(22,PI_ALT0); // Set GPIO22 to alternative mode 0. +.br + +.EE + +.br + +.br +See \fBhttp://www.raspberrypi.org/documentation/hardware/raspberrypi/bcm2835/BCM2835-ARM-Peripherals.pdf\fP page 102 for an overview of the modes. + +.IP "\fBint gpioGetMode(unsigned gpio)\fP" +.IP "" 4 +Gets the GPIO mode. + +.br + +.br + +.EX +gpio: 0-53 +.br + +.EE + +.br + +.br +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. + +.br + +.br +\fBExample\fP +.br + +.EX +if (gpioGetMode(17) != PI_ALT0) +.br +{ +.br + gpioSetMode(17, PI_ALT0); // set GPIO17 to ALT0 +.br +} +.br + +.EE + +.IP "\fBint gpioSetPullUpDown(unsigned gpio, unsigned pud)\fP" +.IP "" 4 +Sets or clears resistor pull ups or downs on the GPIO. + +.br + +.br + +.EX +gpio: 0-53 +.br + pud: 0-2 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSetPullUpDown(17, PI_PUD_UP); // Sets a pull-up. +.br + +.br +gpioSetPullUpDown(18, PI_PUD_DOWN); // Sets a pull-down. +.br + +.br +gpioSetPullUpDown(23, PI_PUD_OFF); // Clear any pull-ups/downs. +.br + +.EE + +.IP "\fBint gpioRead(unsigned gpio)\fP" +.IP "" 4 +Reads the GPIO level, on or off. + +.br + +.br + +.EX +gpio: 0-53 +.br + +.EE + +.br + +.br +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. + +.br + +.br +Arduino style: digitalRead. + +.br + +.br +\fBExample\fP +.br + +.EX +printf("GPIO24 is level %d", gpioRead(24)); +.br + +.EE + +.IP "\fBint gpioWrite(unsigned gpio, unsigned level)\fP" +.IP "" 4 +Sets the GPIO level, on or off. + +.br + +.br + +.EX + gpio: 0-53 +.br +level: 0-1 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL. + +.br + +.br +If PWM or servo pulses are active on the GPIO they are switched off. + +.br + +.br +Arduino style: digitalWrite + +.br + +.br +\fBExample\fP +.br + +.EX +gpioWrite(24, 1); // Set GPIO24 high. +.br + +.EE + +.IP "\fBint gpioPWM(unsigned user_gpio, unsigned dutycycle)\fP" +.IP "" 4 +Starts PWM on the GPIO, dutycycle between 0 (off) and range (fully on). +Range defaults to 255. + +.br + +.br + +.EX +user_gpio: 0-31 +.br +dutycycle: 0-range +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE. + +.br + +.br +Arduino style: analogWrite + +.br + +.br +This and the servo functionality use the DMA and PWM or PCM peripherals +to control and schedule the pulse lengths and dutycycles. + +.br + +.br +The \fBgpioSetPWMrange\fP function may be used to change the default +range of 255. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioPWM(17, 255); // Sets GPIO17 full on. +.br + +.br +gpioPWM(18, 128); // Sets GPIO18 half on. +.br + +.br +gpioPWM(23, 0); // Sets GPIO23 full off. +.br + +.EE + +.IP "\fBint gpioGetPWMdutycycle(unsigned user_gpio)\fP" +.IP "" 4 +Returns the PWM dutycycle setting for the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + +.EE + +.br + +.br +Returns between 0 (off) and range (fully on) if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +.br + +.br +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see \fBgpioGetPWMrange\fP). + +.br + +.br +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). + +.br + +.br +Normal PWM range defaults to 255. + +.IP "\fBint gpioSetPWMrange(unsigned user_gpio, unsigned range)\fP" +.IP "" 4 +Selects the dutycycle range to be used for the GPIO. Subsequent calls +to gpioPWM will use a dutycycle between 0 (off) and range (fully on). + +.br + +.br + +.EX +user_gpio: 0-31 +.br + range: 25-40000 +.br + +.EE + +.br + +.br +Returns the real range for the given GPIO's frequency if OK, +otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE. + +.br + +.br +If PWM is currently active on the GPIO its dutycycle will be scaled +to reflect the new range. + +.br + +.br +The real range, the number of steps between fully off and fully +on for each frequency, is given in the following table. + +.br + +.br + +.EX + 25, 50, 100, 125, 200, 250, 400, 500, 625, +.br + 800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000 +.br + +.EE + +.br + +.br +The real value set by \fBgpioPWM\fP is (dutycycle * real range) / range. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSetPWMrange(24, 2000); // Now 2000 is fully on +.br + // 1000 is half on +.br + // 500 is quarter on, etc. +.br + +.EE + +.IP "\fBint gpioGetPWMrange(unsigned user_gpio)\fP" +.IP "" 4 +Returns the dutycycle range used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + +.EE + +.br + +.br +If a hardware clock or hardware PWM is active on the GPIO +the reported range will be 1000000 (1M). + +.br + +.br +\fBExample\fP +.br + +.EX +r = gpioGetPWMrange(23); +.br + +.EE + +.IP "\fBint gpioGetPWMrealRange(unsigned user_gpio)\fP" +.IP "" 4 +Returns the real range used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + +.EE + +.br + +.br +If a hardware clock is active on the GPIO the reported real +range will be 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +.br + +.br +\fBExample\fP +.br + +.EX +rr = gpioGetPWMrealRange(17); +.br + +.EE + +.IP "\fBint gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency)\fP" +.IP "" 4 +Sets the frequency in hertz to be used for the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br +frequency: >=0 +.br + +.EE + +.br + +.br +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO. + +.br + +.br +If PWM is currently active on the GPIO it will be +switched off and then back on at the new frequency. + +.br + +.br +Each GPIO can be independently set to one of 18 different PWM +frequencies. + +.br + +.br +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). + +.br + +.br +The frequencies for each sample rate are: + +.br + +.br + +.EX + Hertz +.br + +.br + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 +.br + 1250 1000 800 500 400 250 200 100 50 +.br + +.br + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 +.br + 625 500 400 250 200 125 100 50 25 +.br + +.br + 4: 10000 5000 2500 2000 1250 1000 625 500 400 +.br + 313 250 200 125 100 63 50 25 13 +.br +sample +.br + rate +.br + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 +.br + 250 200 160 100 80 50 40 20 10 +.br + +.br + 8: 5000 2500 1250 1000 625 500 313 250 200 +.br + 156 125 100 63 50 31 25 13 6 +.br + +.br + 10: 4000 2000 1000 800 500 400 250 200 160 +.br + 125 100 80 50 40 25 20 10 5 +.br + +.EE + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSetPWMfrequency(23, 0); // Set GPIO23 to lowest frequency. +.br + +.br +gpioSetPWMfrequency(24, 500); // Set GPIO24 to 500Hz. +.br + +.br +gpioSetPWMfrequency(25, 100000); // Set GPIO25 to highest frequency. +.br + +.EE + +.IP "\fBint gpioGetPWMfrequency(unsigned user_gpio)\fP" +.IP "" 4 +Returns the frequency (in hertz) used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + +.EE + +.br + +.br +For normal PWM the frequency will be that defined for the GPIO by +\fBgpioSetPWMfrequency\fP. + +.br + +.br +If a hardware clock is active on the GPIO the reported frequency +will be that set by \fBgpioHardwareClock\fP. + +.br + +.br +If hardware PWM is active on the GPIO the reported frequency +will be that set by \fBgpioHardwarePWM\fP. + +.br + +.br +\fBExample\fP +.br + +.EX +f = gpioGetPWMfrequency(23); // Get frequency used for GPIO23. +.br + +.EE + +.IP "\fBint gpioServo(unsigned user_gpio, unsigned pulsewidth)\fP" +.IP "" 4 +Starts servo pulses on the GPIO, 0 (off), 500 (most anti-clockwise) to +2500 (most clockwise). + +.br + +.br + +.EX + user_gpio: 0-31 +.br +pulsewidth: 0, 500-2500 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH. + +.br + +.br +The range supported by servos varies and should probably be determined +by experiment. A value of 1500 should always be safe and represents +the mid-point of rotation. You can DAMAGE a servo if you command it +to move beyond its limits. + +.br + +.br +The following causes an on pulse of 1500 microseconds duration to be +transmitted on GPIO 17 at a rate of 50 times per second. This will +command a servo connected to GPIO 17 to rotate to its mid-point. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioServo(17, 1000); // Move servo to safe position anti-clockwise. +.br + +.br +gpioServo(23, 1500); // Move servo to centre position. +.br + +.br +gpioServo(25, 2000); // Move servo to safe position clockwise. +.br + +.EE + +.br + +.br +OTHER UPDATE RATES: + +.br + +.br +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +.br + +.br + +.EX +PWM Hz 50 100 200 400 500 +.br +1E6/Hz 20000 10000 5000 2500 2000 +.br + +.EE + +.br + +.br +Firstly set the desired PWM frequency using \fBgpioSetPWMfrequency\fP. + +.br + +.br +Then set the PWM range using \fBgpioSetPWMrange\fP to 1E6/frequency. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +.br + +.br +E.g. If you want to update a servo connected to GPIO25 at 400Hz + +.br + +.br + +.EX +gpioSetPWMfrequency(25, 400); +.br + +.br +gpioSetPWMrange(25, 2500); +.br + +.EE + +.br + +.br +Thereafter use the PWM command to move the servo, +e.g. gpioPWM(25, 1500) will set a 1500 us pulse. + +.IP "\fBint gpioGetServoPulsewidth(unsigned user_gpio)\fP" +.IP "" 4 +Returns the servo pulsewidth setting for the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + +.EE + +.br + +.br +Returns 0 (off), 500 (most anti-clockwise) to 2500 (most clockwise) +if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. + +.IP "\fBint gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f)\fP" +.IP "" 4 +Registers a function to be called (a callback) when the specified +GPIO changes state. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + f: the callback function +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. + +.br + +.br +One callback may be registered per GPIO. + +.br + +.br +The callback is passed the GPIO, the new level, and the tick. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +level 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.EE + +.br + +.br +The alert may be cancelled by passing NULL as the function. + +.br + +.br +The GPIO are sampled at a rate set when the library is started. + +.br + +.br +If a value isn't specifically set the default of 5 us is used. + +.br + +.br +The number of samples per second is given in the following table. + +.br + +.br + +.EX + samples +.br + per sec +.br + +.br + 1 1,000,000 +.br + 2 500,000 +.br +sample 4 250,000 +.br +rate 5 200,000 +.br +(us) 8 125,000 +.br + 10 100,000 +.br + +.EE + +.br + +.br +Level changes shorter than the sample rate may be missed. + +.br + +.br +The thread which calls the alert functions is triggered nominally +1000 times per second. The active alert functions will be called +once per level change since the last time the thread was activated. +i.e. The active alert functions will get all level changes but there +will be a latency. + +.br + +.br +The tick value is the time stamp of the sample in microseconds, see +\fBgpioTick\fP for more details. + +.br + +.br +\fBExample\fP +.br + +.EX +void aFunction(int gpio, int level, uint32_t tick) +.br +{ +.br + printf("GPIO %d became %d at %d", gpio, level, tick); +.br +} +.br + +.br +// call aFunction whenever GPIO 4 changes state +.br + +.br +gpioSetAlertFunc(4, aFunction); +.br + +.EE + +.IP "\fBint gpioSetAlertFuncEx(unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) when the specified +GPIO changes state. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + f: the callback function +.br + userdata: pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. + +.br + +.br +One callback may be registered per GPIO. + +.br + +.br +The callback is passed the GPIO, the new level, the tick, and +the userdata pointer. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +level 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.br +userdata pointer Pointer to an arbitrary object +.br + +.EE + +.br + +.br +See \fBgpioSetAlertFunc\fP for further details. + +.br + +.br +Only one of \fBgpioSetAlertFunc\fP or \fBgpioSetAlertFuncEx\fP can be +registered per GPIO. + +.IP "\fBint gpioSetISRFunc(unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f)\fP" +.IP "" 4 +Registers a function to be called (a callback) whenever the specified +GPIO interrupt occurs. + +.br + +.br + +.EX + gpio: 0-53 +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE +.br +timeout: interrupt timeout in milliseconds (<=0 to cancel) +.br + f: the callback function +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE, +or PI_BAD_ISR_INIT. + +.br + +.br +One function may be registered per GPIO. + +.br + +.br +The function is passed the GPIO, the current level, and the +current tick. The level will be PI_TIMEOUT if the optional +interrupt timeout expires. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-53 The GPIO which has changed state +.br + +.br +level 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (interrupt timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.EE + +.br + +.br +The underlying Linux sysfs GPIO interface is used to provide +the interrupt services. + +.br + +.br +The first time the function is called, with a non-NULL f, the +GPIO is exported, set to be an input, and set to interrupt +on the given edge and timeout. + +.br + +.br +Subsequent calls, with a non-NULL f, can vary one or more of the +edge, timeout, or function. + +.br + +.br +The ISR may be cancelled by passing a NULL f, in which case the +GPIO is unexported. + +.br + +.br +The tick is that read at the time the process was informed of +the interrupt. This will be a variable number of microseconds +after the interrupt occurred. Typically the latency will be of +the order of 50 microseconds. The latency is not guaranteed +and will vary with system load. + +.br + +.br +The level is that read at the time the process was informed of +the interrupt, or PI_TIMEOUT if the optional interrupt timeout +expired. It may not be the same as the expected edge as +interrupts happening in rapid succession may be missed by the +kernel (i.e. this mechanism can not be used to capture several +interrupts only a few microseconds apart). + +.IP "\fBint gpioSetISRFuncEx(unsigned gpio, unsigned edge, int timeout, gpioISRFuncEx_t f, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) whenever the specified +GPIO interrupt occurs. + +.br + +.br + +.EX + gpio: 0-53 +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE +.br + timeout: interrupt timeout in milliseconds (<=0 to cancel) +.br + f: the callback function +.br +userdata: pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE, +or PI_BAD_ISR_INIT. + +.br + +.br +The function is passed the GPIO, the current level, the +current tick, and the userdata pointer. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-53 The GPIO which has changed state +.br + +.br +level 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (interrupt timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.br +userdata pointer Pointer to an arbitrary object +.br + +.EE + +.br + +.br +Only one of \fBgpioSetISRFunc\fP or \fBgpioSetISRFuncEx\fP can be +registered per GPIO. + +.br + +.br +See \fBgpioSetISRFunc\fP for further details. + +.IP "\fBint gpioNotifyOpen(void)\fP" +.IP "" 4 +This function requests a free notification handle. + +.br + +.br +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +.br + +.br +A notification is a method for being notified of GPIO state changes +via a pipe or socket. + +.br + +.br +Pipe notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). E.g. if the +function returns 15 then the notifications must be read +from /dev/pigpio15. + +.br + +.br +Socket notifications are returned to the socket which requested the +handle. + +.br + +.br +\fBExample\fP +.br + +.EX +h = gpioNotifyOpen(); +.br + +.br +if (h >= 0) +.br +{ +.br + sprintf(str, "/dev/pigpio%d", h); +.br + +.br + fd = open(str, O_RDONLY); +.br + +.br + if (fd >= 0) +.br + { +.br + // Okay. +.br + } +.br + else +.br + { +.br + // Error. +.br + } +.br +} +.br +else +.br +{ +.br + // Error. +.br +} +.br + +.EE + +.IP "\fBint gpioNotifyOpenWithSize(int bufSize)\fP" +.IP "" 4 +This function requests a free notification handle. + +.br + +.br +It differs from \fBgpioNotifyOpen\fP in that the pipe size may be +specified, whereas \fBgpioNotifyOpen\fP uses the default pipe size. + +.br + +.br +See \fBgpioNotifyOpen\fP for further details. + +.IP "\fBint gpioNotifyBegin(unsigned handle, uint32_t bits)\fP" +.IP "" 4 +This function starts notifications on a previously opened handle. + +.br + +.br + +.EX +handle: >=0, as returned by \fBgpioNotifyOpen\fP +.br + bits: a bit mask indicating the GPIO of interest +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +The notification sends state changes for each GPIO whose corresponding +bit in bits is set. + +.br + +.br +Each notification occupies 12 bytes in the fifo and has the +following structure. + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint16_t seqno; +.br + uint16_t flags; +.br + uint32_t tick; +.br + uint32_t level; +.br +} gpioReport_t; +.br + +.EE + +.br + +.br +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +.br + +.br +flags: three flags are defined, PI_NTFY_FLAGS_WDOG, +PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT. + +.br + +.br +If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +.br + +.br +If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +.br + +.br +If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags +indicate an event which has been triggered. + +.br + +.br +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +.br + +.br +level: indicates the level of each GPIO. If bit 1<=0, as returned by \fBgpioNotifyOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +Notifications for the handle are suspended until \fBgpioNotifyBegin\fP +is called again. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioNotifyPause(h); +.br + +.EE + +.IP "\fBint gpioNotifyClose(unsigned handle)\fP" +.IP "" 4 +This function stops notifications on a previously opened handle +and releases the handle for reuse. + +.br + +.br + +.EX +handle: >=0, as returned by \fBgpioNotifyOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioNotifyClose(h); +.br + +.EE + +.IP "\fBint gpioWaveClear(void)\fP" +.IP "" 4 +This function clears all waveforms and any data added by calls to the +\fBgpioWaveAdd*\fP functions. + +.br + +.br +Returns 0 if OK. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioWaveClear(); +.br + +.EE + +.IP "\fBint gpioWaveAddNew(void)\fP" +.IP "" 4 +This function starts a new empty waveform. + +.br + +.br +You wouldn't normally need to call this function as it is automatically +called after a waveform is created with the \fBgpioWaveCreate\fP function. + +.br + +.br +Returns 0 if OK. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioWaveAddNew(); +.br + +.EE + +.IP "\fBint gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses)\fP" +.IP "" 4 +This function adds a number of pulses to the current waveform. + +.br + +.br + +.EX +numPulses: the number of pulses +.br + pulses: an array of pulses +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +.br + +.br +The pulses are interleaved in time order within the existing waveform +(if any). + +.br + +.br +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +.br + +.br +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. + +.br + +.br +\fBExample\fP +.br + +.EX +// Construct and send a 30 microsecond square wave. +.br + +.br +gpioSetMode(gpio, PI_OUTPUT); +.br + +.br +pulse[0].gpioOn = (1<= 0) +.br +{ +.br + gpioWaveTxSend(wave_id, PI_WAVE_MODE_REPEAT); +.br + +.br + // Transmit for 30 seconds. +.br + +.br + sleep(30); +.br + +.br + gpioWaveTxStop(); +.br +} +.br +else +.br +{ +.br + // Wave create failed. +.br +} +.br + +.EE + +.IP "\fBint gpioWaveAddSerial(unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)\fP" +.IP "" 4 +This function adds a waveform representing serial data to the +existing waveform (if any). The serial data starts offset +microseconds from the start of the waveform. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + baud: 50-1000000 +.br +data_bits: 1-32 +.br +stop_bits: 2-8 +.br + offset: >=0 +.br + numBytes: >=1 +.br + str: an array of chars (which may contain nulls) +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOPBITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +.br + +.br +NOTES: + +.br + +.br +The serial data is formatted as one start bit, data_bits data bits, and +stop_bits/2 stop bits. + +.br + +.br +It is legal to add serial data streams with different baud rates to +the same waveform. + +.br + +.br +numBytes is the number of bytes of data in str. + +.br + +.br +The bytes required for each character depend upon data_bits. + +.br + +.br +For data_bits 1-8 there will be one byte per character. +.br +For data_bits 9-16 there will be two bytes per character. +.br +For data_bits 17-32 there will be four bytes per character. + +.br + +.br +\fBExample\fP +.br + +.EX +#define MSG_LEN 8 +.br + +.br +int i; +.br +char *str; +.br +char data[MSG_LEN]; +.br + +.br +str = "Hello world!"; +.br + +.br +gpioWaveAddSerial(4, 9600, 8, 2, 0, strlen(str), str); +.br + +.br +for (i=0; i=0, as returned by \fBgpioWaveCreate\fP +.br + +.EE + +.br + +.br +Wave ids are allocated in order, 0, 1, 2, etc. + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. + +.IP "\fBint gpioWaveTxSend(unsigned wave_id, unsigned wave_mode)\fP" +.IP "" 4 +This function transmits the waveform with id wave_id. The mode +determines whether the waveform is sent once or cycles endlessly. +The SYNC variants wait for the current waveform to reach the +end of a cycle or finish before starting the new waveform. + +.br + +.br +WARNING: bad things may happen if you delete the previous +waveform before it has been synced to the new waveform. + +.br + +.br +NOTE: Any hardware PWM started by \fBgpioHardwarePWM\fP will be cancelled. + +.br + +.br + +.EX + wave_id: >=0, as returned by \fBgpioWaveCreate\fP +.br +wave_mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT, +.br + PI_WAVE_MODE_ONE_SHOT_SYNC, PI_WAVE_MODE_REPEAT_SYNC +.br + +.EE + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint gpioWaveChain(char *buf, unsigned bufSize)\fP" +.IP "" 4 +This function transmits a chain of waveforms. + +.br + +.br +NOTE: Any hardware PWM started by \fBgpioHardwarePWM\fP will be cancelled. + +.br + +.br +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of \fBwave_id\fPs and optional command +codes and related data. + +.br + +.br + +.EX + buf: pointer to the wave_ids and optional command codes +.br +bufSize: the number of bytes in buf +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +.br + +.br +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +.br + +.br +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +.br + +.br +Delays between waves may be added with the delay command. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +Loop Start 255 0 Identify start of a wave block +.br +Loop Repeat 255 1 x y loop x + y*256 times +.br +Delay 255 2 x y delay x + y*256 microseconds +.br +Loop Forever 255 3 loop forever +.br + +.br + +.br +If present Loop Forever must be the last entry in the chain. + +.br + +.br +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +#define WAVES 5 +.br +#define GPIO 4 +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int i, wid[WAVES]; +.br + +.br + if (gpioInitialise()<0) return -1; +.br + +.br + gpioSetMode(GPIO, PI_OUTPUT); +.br + +.br + printf("start piscope, press return"); getchar(); +.br + +.br + for (i=0; i=0 +.br + +.EE + +.br + +.br +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +.br + +.br +The bytes returned for each character depend upon the number of +data bits \fBdata_bits\fP specified in the \fBgpioSerialReadOpen\fP command. + +.br + +.br +For \fBdata_bits\fP 1-8 there will be one byte per character. +.br +For \fBdata_bits\fP 9-16 there will be two bytes per character. +.br +For \fBdata_bits\fP 17-32 there will be four bytes per character. + +.IP "\fBint gpioSerialReadClose(unsigned user_gpio)\fP" +.IP "" 4 +This function closes a GPIO for bit bang reading of serial data. + +.br + +.br + +.EX +user_gpio: 0-31, previously opened with \fBgpioSerialReadOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. + +.IP "\fBint i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags)\fP" +.IP "" 4 +This returns a handle for the device at the address on the I2C bus. + +.br + +.br + +.EX + i2cBus: >=0 +.br + i2cAddr: 0-0x7F +.br +i2cFlags: 0 +.br + +.EE + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.br + +.br +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + SDA SCL +.br +I2C 0 0 1 +.br +I2C 1 2 3 +.br + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +.br + +.br +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +.br + +.br + +.EX +S (1 bit) : Start bit +.br +P (1 bit) : Stop bit +.br +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +.br +A, NA (1 bit) : Accept and not accept bit. +.br +.br +.br +Addr (7 bits): I2C 7 bit address. +.br +i2cReg (8 bits): Command byte, a byte which often selects a register. +.br +Data (8 bits): A data byte. +.br +Count (8 bits): A byte defining the length of a block operation. +.br + +.br +[..]: Data sent by the device. +.br + +.EE + +.IP "\fBint i2cClose(unsigned handle)\fP" +.IP "" 4 +This closes the I2C device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint i2cWriteQuick(unsigned handle, unsigned bit)\fP" +.IP "" 4 +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + bit: 0-1, the value to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Quick command. SMBus 2.0 5.5.1 + +.EX +S Addr bit [A] P +.br + +.EE + +.IP "\fBint i2cWriteByte(unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This sends a single byte to the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + bVal: 0-0xFF, the value to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Send byte. SMBus 2.0 5.5.2 + +.EX +S Addr Wr [A] bVal [A] P +.br + +.EE + +.IP "\fBint i2cReadByte(unsigned handle)\fP" +.IP "" 4 +This reads a single byte from the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +.br + +.br +Receive byte. SMBus 2.0 5.5.3 + +.EX +S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal)\fP" +.IP "" 4 +This writes a single byte to the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write +.br + bVal: 0-0xFF, the value to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write byte. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] i2cReg [A] bVal [A] P +.br + +.EE + +.IP "\fBint i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal)\fP" +.IP "" 4 +This writes a single 16 bit word to the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write +.br + wVal: 0-0xFFFF, the value to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write word. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] P +.br + +.EE + +.IP "\fBint i2cReadByteData(unsigned handle, unsigned i2cReg)\fP" +.IP "" 4 +This reads a single byte from the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to read +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read byte. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] i2cReg [A] S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2cReadWordData(unsigned handle, unsigned i2cReg)\fP" +.IP "" 4 +This reads a single 16 bit word from the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to read +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read word. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] i2cReg [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal)\fP" +.IP "" 4 +This writes 16 bits of data to the specified register of the device +associated with handle and reads 16 bits of data in return. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write/read +.br + wVal: 0-0xFFFF, the value to write +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Process call. SMBus 2.0 5.5.6 + +.EX +S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] +.br + S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2cWriteBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes up to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write +.br + buf: an array with the data to send +.br + count: 1-32, the number of bytes to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Block write. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] i2cReg [A] count [A] +.br + buf0 [A] buf1 [A] ... [A] bufn [A] P +.br + +.EE + +.IP "\fBint i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf)\fP" +.IP "" 4 +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to read +.br + buf: an array to receive the read data +.br + +.EE + +.br + +.br +The amount of returned data is set by the device. + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Block read. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] i2cReg [A] +.br + S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2cBlockProcessCall(unsigned handle, unsigned i2cReg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write/read +.br + buf: an array with the data to send and to receive the read data +.br + count: 1-32, the number of bytes to write +.br + +.EE + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +The SMBus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +.br + +.br +Block write-block read. SMBus 2.0 5.5.8 + +.EX +S Addr Wr [A] i2cReg [A] count [A] buf0 [A] ... bufn [A] +.br + S Addr Rd [A] [Count] A [buf0] A ... [bufn] A P +.br + +.EE + +.IP "\fBint i2cReadI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to read +.br + buf: an array to receive the read data +.br + count: 1-32, the number of bytes to read +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] i2cReg [A] +.br + S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2cWriteI2CBlockData(unsigned handle, unsigned i2cReg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br +i2cReg: 0-255, the register to write +.br + buf: the data to write +.br + count: 1-32, the number of bytes to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] i2cReg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +.br + +.EE + +.IP "\fBint i2cReadDevice(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the raw device into buf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + buf: an array to receive the read data bytes +.br + count: >0, the number of bytes to read +.br + +.EE + +.br + +.br +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. + +.br + +.br + +.EX +S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2cWriteDevice(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This writes count bytes from buf to the raw device. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + buf: an array containing the data bytes to write +.br + count: >0, the number of bytes to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +.br + +.EE + +.IP "\fBvoid i2cSwitchCombined(int setting)\fP" +.IP "" 4 +This sets the I2C (i2c-bcm2708) module "use combined transactions" +parameter on or off. + +.br + +.br + +.EX +setting: 0 to set the parameter off, non-zero to set it on +.br + +.EE + +.br + +.br + +.br + +.br +NOTE: when the flag is on a write followed by a read to the same +slave address will use a repeated start (rather than a stop/start). + +.IP "\fBint i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs)\fP" +.IP "" 4 +This function executes multiple I2C segments in one transaction by +calling the I2C_RDWR ioctl. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + segs: an array of I2C segments +.br +numSegs: >0, the number of I2C segments +.br + +.EE + +.br + +.br +Returns the number of segments if OK, otherwise PI_BAD_I2C_SEG. + +.IP "\fBint i2cZip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +On 2 Switch combined flag on +.br +Off 3 Switch combined flag off +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53, write 0x32, read 6 bytes +.br +Set address 0x1E, write 0x03, read 6 bytes +.br +Set address 0x68, write 0x1B, read 8 bytes +.br +End +.br + +.br +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +.br +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +.br +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +.br +0x00 +.br + +.EE + +.IP "\fBint bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud)\fP" +.IP "" 4 +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +.br + +.br +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +.br + +.br +o baud rates as low as 50 +.br +o repeated starts +.br +o clock stretching +.br +o I2C on any pair of spare GPIO + +.br + +.br + +.EX + SDA: 0-31 +.br + SCL: 0-31 +.br +baud: 50-500000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +.br + +.br +NOTE: + +.br + +.br +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. + +.IP "\fBint bbI2CClose(unsigned SDA)\fP" +.IP "" 4 +This function stops bit banging I2C on a pair of GPIO previously +opened with \fBbbI2COpen\fP. + +.br + +.br + +.EX +SDA: 0-31, the SDA GPIO used in a prior call to \fBbbI2COpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. + +.IP "\fBint bbI2CZip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX + SDA: 0-31 (as used in a prior call to \fBbbI2COpen\fP) +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +Start 2 Start condition +.br +Stop 3 Stop condition +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +.br + +.br +No flags are currently defined. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53 +.br +start, write 0x32, (re)start, read 6 bytes, stop +.br +Set address 0x1E +.br +start, write 0x03, (re)start, read 6 bytes, stop +.br +Set address 0x68 +.br +start, write 0x1B, (re)start, read 8 bytes, stop +.br +End +.br + +.br +0x04 0x53 +.br +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x1E +.br +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x68 +.br +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 +.br + +.br +0x00 +.br + +.EE + +.IP "\fBint bscXfer(bsc_xfer_t *bsc_xfer)\fP" +.IP "" 4 +This function provides a low-level interface to the +SPI/I2C Slave peripheral. This peripheral allows the +Pi to act as a slave device on an I2C or SPI bus. + +.br + +.br +I can't get SPI to work properly. I tried with a +control word of 0x303 and swapped MISO and MOSI. + +.br + +.br +The function sets the BSC mode, writes any data in +the transmit buffer to the BSC transmit FIFO, and +copies any data in the BSC receive FIFO to the +receive buffer. + +.br + +.br + +.EX +bsc_xfer:= a structure defining the transfer +.br + +.br +typedef struct +.br +{ +.br + uint32_t control; // Write +.br + int rxCnt; // Read only +.br + char rxBuf[BSC_FIFO_SIZE]; // Read only +.br + int txCnt; // Write +.br + char txBuf[BSC_FIFO_SIZE]; // Write +.br +} bsc_xfer_t; +.br + +.EE + +.br + +.br +To start a transfer set control (see below) and copy the bytes to +be sent (if any) to txBuf and set the byte count in txCnt. + +.br + +.br +Upon return rxCnt will be set to the number of received bytes placed +in rxBuf. + +.br + +.br +Note that the control word sets the BSC mode. The BSC will stay in +that mode until a different control word is sent. + +.br + +.br +The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode +and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You +need to swap MISO/MOSI between master and slave. + +.br + +.br +When a zero control word is received GPIO 18-21 will be reset +to INPUT mode. + +.br + +.br +The returned function value is the status of the transfer (see below). + +.br + +.br +If there was an error the status will be less than zero +(and will contain the error code). + +.br + +.br +The most significant word of the returned status contains the number +of bytes actually copied from txBuf to the BSC transmit FIFO (may be +less than requested if the FIFO already contained untransmitted data). + +.br + +.br +control consists of the following bits. + +.br + +.br + +.EX +22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN +.br + +.EE + +.br + +.br +Bits 0-13 are copied unchanged to the BSC CR register. See +pages 163-165 of the Broadcom peripherals document for full +details. + +.br + +.br +aaaaaaa defines the I2C slave address (only relevant in I2C mode) +.br +IT invert transmit status flags +.br +HC enable host control +.br +TF enable test FIFO +.br +IR invert receive status flags +.br +RE enable receive +.br +TE enable transmit +.br +BK abort operation and clear FIFOs +.br +EC send control register as first I2C byte +.br +ES send status register as first I2C byte +.br +PL set SPI polarity high +.br +PH set SPI phase high +.br +I2 enable I2C mode +.br +SP enable SPI mode +.br +EN enable BSC peripheral +.br + +.br + +.br +The returned status has the following format + +.br + +.br + +.EX +20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + S S S S S R R R R R T T T T T RB TE RF TF RE TB +.br + +.EE + +.br + +.br +Bits 0-15 are copied unchanged from the BSC FR register. See +pages 165-166 of the Broadcom peripherals document for full +details. + +.br + +.br +SSSSS number of bytes successfully copied to transmit FIFO +.br +RRRRR number of bytes in receieve FIFO +.br +TTTTT number of bytes in transmit FIFO +.br +RB receive busy +.br +TE transmit FIFO empty +.br +RF receive FIFO full +.br +TF transmit FIFO full +.br +RE receive FIFO empty +.br +TB transmit busy +.br + +.br + +.br +The following example shows how to configure the BSC peripheral as +an I2C slave with address 0x13 and send four bytes. + +.br + +.br +\fBExample\fP +.br + +.EX +bsc_xfer_t xfer; +.br + +.br +xfer.control = (0x13<<16) | 0x305; +.br + +.br +memcpy(xfer.txBuf, "ABCD", 4); +.br +xfer.txCnt = 4; +.br + +.br +status = bscXfer(&xfer); +.br + +.br +if (status >= 0) +.br +{ +.br + // process transfer +.br +} +.br + +.EE + +.IP "\fBint bbSPIOpen(unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spiFlags)\fP" +.IP "" 4 +This function selects a set of GPIO for bit banging SPI with +a specified baud rate and mode. + +.br + +.br + +.EX + CS: 0-31 +.br + MISO: 0-31 +.br + MOSI: 0-31 +.br + SCLK: 0-31 +.br + baud: 50-250000 +.br +spiFlags: see below +.br + +.EE + +.br + +.br +spiFlags consists of the least significant 22 bits. + +.br + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m +.br + +.EE + +.br + +.br +mm defines the SPI mode, defaults to 0 + +.br + +.br + +.EX +Mode CPOL CPHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br + +.br +p is 0 if CS is active low (default) and 1 for active high. + +.br + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. + +.br + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. + +.br + +.br +The other bits in flags should be set to zero. + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or +PI_GPIO_IN_USE. + +.br + +.br +If more than one device is connected to the SPI bus (defined by +SCLK, MOSI, and MISO) each must have its own CS. + +.br + +.br +\fBExample\fP +.br + +.EX +bbSPIOpen(10, MISO, MOSI, SCLK, 10000, 0); // device 1 +.br +bbSPIOpen(11, MISO, MOSI, SCLK, 20000, 3); // device 2 +.br + +.EE + +.IP "\fBint bbSPIClose(unsigned CS)\fP" +.IP "" 4 +This function stops bit banging SPI on a set of GPIO +opened with \fBbbSPIOpen\fP. + +.br + +.br + +.EX +CS: 0-31, the CS GPIO used in a prior call to \fBbbSPIOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO. + +.IP "\fBint bbSPIXfer(unsigned CS, char *inBuf, char *outBuf, unsigned count)\fP" +.IP "" 4 +This function executes a bit banged SPI transfer. + +.br + +.br + +.EX + CS: 0-31 (as used in a prior call to \fBbbSPIOpen\fP) +.br + inBuf: pointer to buffer to hold data to be sent +.br +outBuf: pointer to buffer to hold returned data +.br + count: size of data transfer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER. + +.br + +.br +\fBExample\fP +.br + +.EX +// gcc -Wall -pthread -o bbSPIx_test bbSPIx_test.c -lpigpio +.br +// sudo ./bbSPIx_test +.br + +.br + +.br +#include +.br + +.br +#include "pigpio.h" +.br + +.br +#define CE0 5 +.br +#define CE1 6 +.br +#define MISO 13 +.br +#define MOSI 19 +.br +#define SCLK 12 +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int i, count, set_val, read_val; +.br + unsigned char inBuf[3]; +.br + char cmd1[] = {0, 0}; +.br + char cmd2[] = {12, 0}; +.br + char cmd3[] = {1, 128, 0}; +.br + +.br + if (gpioInitialise() < 0) +.br + { +.br + fprintf(stderr, "pigpio initialisation failed.\n"); +.br + return 1; +.br + } +.br + +.br + bbSPIOpen(CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC +.br + bbSPIOpen(CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC +.br + +.br + for (i=0; i<256; i++) +.br + { +.br + cmd1[1] = i; +.br + +.br + count = bbSPIXfer(CE0, cmd1, (char *)inBuf, 2); // > DAC +.br + +.br + if (count == 2) +.br + { +.br + count = bbSPIXfer(CE0, cmd2, (char *)inBuf, 2); // < DAC +.br + +.br + if (count == 2) +.br + { +.br + set_val = inBuf[1]; +.br + +.br + count = bbSPIXfer(CE1, cmd3, (char *)inBuf, 3); // < ADC +.br + +.br + if (count == 3) +.br + { +.br + read_val = ((inBuf[1]&3)<<8) | inBuf[2]; +.br + printf("%d %d\n", set_val, read_val); +.br + } +.br + } +.br + } +.br + } +.br + +.br + bbSPIClose(CE0); +.br + bbSPIClose(CE1); +.br + +.br + gpioTerminate(); +.br + +.br + return 0; +.br +} +.br + +.EE + +.IP "\fBint spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags)\fP" +.IP "" 4 +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +.br + +.br +The Pi has two SPI peripherals: main and auxiliary. + +.br + +.br +The main SPI has two chip selects (channels), the auxiliary has +three. + +.br + +.br +The auxiliary SPI is available on all models but the A and B. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + MISO MOSI SCLK CE0 CE1 CE2 +.br +Main SPI 9 10 11 8 7 - +.br +Aux SPI 19 20 21 18 17 16 +.br + +.br + +.br + +.EX + spiChan: 0-1 (0-2 for the auxiliary SPI) +.br + baud: 32K-125M (values above 30M are unlikely to work) +.br +spiFlags: see below +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +.br + +.br +spiFlags consists of the least significant 22 bits. + +.br + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +.br + +.EE + +.br + +.br +mm defines the SPI mode. + +.br + +.br +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +.br + +.br + +.EX +Mode POL PHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br + +.br +px is 0 if CEx is active low (default) and 1 for active high. + +.br + +.br +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +.br + +.br +A is 0 for the main SPI, 1 for the auxiliary SPI. + +.br + +.br +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +.br + +.br +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +.br + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +.br + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +.br + +.br +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +.br + +.br +The \fBspiRead\fP, \fBspiWrite\fP, and \fBspiXfer\fP functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +.br + +.br +For bits 1-8 there will be one byte per word. +.br +For bits 9-16 there will be two bytes per word. +.br +For bits 17-32 there will be four bytes per word. + +.br + +.br +Multi-byte transfers are made in least significant byte first order. + +.br + +.br +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +.br + +.br +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +.br + +.br +The other bits in flags should be set to zero. + +.IP "\fBint spiClose(unsigned handle)\fP" +.IP "" 4 +This functions closes the SPI device identified by the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspiOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint spiRead(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads count bytes of data from the SPI +device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspiOpen\fP +.br + buf: an array to receive the read data bytes +.br + count: the number of bytes to read +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spiWrite(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspiOpen\fP +.br + buf: the data bytes to write +.br + count: the number of bytes to write +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)\fP" +.IP "" 4 +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspiOpen\fP +.br + txBuf: the data bytes to write +.br + rxBuf: the received data bytes +.br + count: the number of bytes to transfer +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint serOpen(char *sertty, unsigned baud, unsigned serFlags)\fP" +.IP "" 4 +This function opens a serial device at a specified baud rate +and with specified flags. The device name must start with +/dev/tty or /dev/serial. + +.br + +.br + +.EX + sertty: the serial device to open +.br + baud: the baud rate in bits per second, see below +.br +serFlags: 0 +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +.br + +.br +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.IP "\fBint serClose(unsigned handle)\fP" +.IP "" 4 +This function closes the serial device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint serWriteByte(unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This function writes bVal to the serial port associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serReadByte(unsigned handle)\fP" +.IP "" 4 +This function reads a byte from the serial port associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + +.EE + +.br + +.br +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +.br + +.br +If no data is ready PI_SER_READ_NO_DATA is returned. + +.IP "\fBint serWrite(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes from buf to the the serial port +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + buf: the array of bytes to write +.br + count: the number of bytes to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serRead(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads up count bytes from the the serial port +associated with handle and writes them to buf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + buf: an array to receive the read data +.br + count: the maximum number of bytes to read +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0=) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_SER_READ_NO_DATA. + +.br + +.br +If no data is ready zero is returned. + +.IP "\fBint serDataAvailable(unsigned handle)\fP" +.IP "" 4 +This function returns the number of bytes available +to be read from the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserOpen\fP +.br + +.EE + +.br + +.br +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. + +.IP "\fBint gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level)\fP" +.IP "" 4 +This function sends a trigger pulse to a GPIO. The GPIO is set to +level for pulseLen microseconds and then reset to not level. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + pulseLen: 1-100 +.br + level: 0,1 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, +or PI_BAD_PULSELEN. + +.IP "\fBint gpioSetWatchdog(unsigned user_gpio, unsigned timeout)\fP" +.IP "" 4 +Sets a watchdog for a GPIO. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + timeout: 0-60000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT. + +.br + +.br +The watchdog is nominally in milliseconds. + +.br + +.br +One watchdog may be registered per GPIO. + +.br + +.br +The watchdog may be cancelled by setting timeout to 0. + +.br + +.br +Until cancelled a timeout will be reported every timeout milliseconds +after the last GPIO activity. + +.br + +.br +In particular: + +.br + +.br +1) any registered alert function for the GPIO will be called with + the level set to PI_TIMEOUT. + +.br + +.br +2) any notification for the GPIO will have a report written to the + fifo with the flags set to indicate a watchdog timeout. + +.br + +.br +\fBExample\fP +.br + +.EX +void aFunction(int gpio, int level, uint32_t tick) +.br +{ +.br + printf("GPIO %d became %d at %d", gpio, level, tick); +.br +} +.br + +.br +// call aFunction whenever GPIO 4 changes state +.br +gpioSetAlertFunc(4, aFunction); +.br + +.br +// or approximately every 5 millis +.br +gpioSetWatchdog(4, 5); +.br + +.EE + +.IP "\fBint gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active)\fP" +.IP "" 4 +Sets a noise filter on a GPIO. + +.br + +.br +Level changes on the GPIO are ignored until a level which has +been stable for \fBsteady\fP microseconds is detected. Level changes +on the GPIO are then reported for \fBactive\fP microseconds after +which the process repeats. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + steady: 0-300000 +.br + active: 0-1000000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +.br + +.br +This filter affects the GPIO samples returned to callbacks set up +with \fBgpioSetAlertFunc\fP, \fBgpioSetAlertFuncEx\fP, \fBgpioSetGetSamplesFunc\fP, +and \fBgpioSetGetSamplesFuncEx\fP. + +.br + +.br +It does not affect interrupts set up with \fBgpioSetISRFunc\fP, +\fBgpioSetISRFuncEx\fP, or levels read by \fBgpioRead\fP, +\fBgpioRead_Bits_0_31\fP, or \fBgpioRead_Bits_32_53\fP. + +.br + +.br +Level changes before and after the active period may +be reported. Your software must be designed to cope with +such reports. + +.IP "\fBint gpioGlitchFilter(unsigned user_gpio, unsigned steady)\fP" +.IP "" 4 +Sets a glitch filter on a GPIO. + +.br + +.br +Level changes on the GPIO are not reported unless the level +has been stable for at least \fBsteady\fP microseconds. The +level is then reported. Level changes of less than \fBsteady\fP +microseconds are ignored. + +.br + +.br + +.EX +user_gpio: 0-31 +.br + steady: 0-300000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +.br + +.br +This filter affects the GPIO samples returned to callbacks set up +with \fBgpioSetAlertFunc\fP, \fBgpioSetAlertFuncEx\fP, \fBgpioSetGetSamplesFunc\fP, +and \fBgpioSetGetSamplesFuncEx\fP. + +.br + +.br +It does not affect interrupts set up with \fBgpioSetISRFunc\fP, +\fBgpioSetISRFuncEx\fP, or levels read by \fBgpioRead\fP, +\fBgpioRead_Bits_0_31\fP, or \fBgpioRead_Bits_32_53\fP. + +.br + +.br +Each (stable) edge will be timestamped \fBsteady\fP microseconds +after it was first detected. + +.IP "\fBint gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits)\fP" +.IP "" 4 +Registers a function to be called (a callback) every millisecond +with the latest GPIO samples. + +.br + +.br + +.EX + f: the function to call +.br +bits: the GPIO of interest +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.br + +.br +The function is passed a pointer to the samples (an array of +\fBgpioSample_t\fP), and the number of samples. + +.br + +.br +Only one function can be registered. + +.br + +.br +The callback may be cancelled by passing NULL as the function. + +.br + +.br +The samples returned will be the union of bits, plus any active alerts, +plus any active notifications. + +.br + +.br +e.g. if there are alerts for GPIO 7, 8, and 9, notifications for GPIO +8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for GPIO +7, 8, 9, 10, 17, 23, and 24 will be reported. + +.IP "\fBint gpioSetGetSamplesFuncEx(gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) every millisecond +with the latest GPIO samples. + +.br + +.br + +.EX + f: the function to call +.br + bits: the GPIO of interest +.br +userdata: a pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.br + +.br +The function is passed a pointer to the samples (an array of +\fBgpioSample_t\fP), the number of samples, and the userdata pointer. + +.br + +.br +Only one of \fBgpioGetSamplesFunc\fP or \fBgpioGetSamplesFuncEx\fP can be +registered. + +.br + +.br +See \fBgpioSetGetSamplesFunc\fP for further details. + +.IP "\fBint gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f)\fP" +.IP "" 4 +Registers a function to be called (a callback) every millis milliseconds. + +.br + +.br + +.EX + timer: 0-9 +.br +millis: 10-60000 +.br + f: the function to call +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. + +.br + +.br +10 timers are supported numbered 0 to 9. + +.br + +.br +One function may be registered per timer. + +.br + +.br +The timer may be cancelled by passing NULL as the function. + +.br + +.br +\fBExample\fP +.br + +.EX +void bFunction(void) +.br +{ +.br + printf("two seconds have elapsed"); +.br +} +.br + +.br +// call bFunction every 2000 milliseconds +.br +gpioSetTimerFunc(0, 2000, bFunction); +.br + +.EE + +.IP "\fBint gpioSetTimerFuncEx(unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) every millis milliseconds. + +.br + +.br + +.EX + timer: 0-9. +.br + millis: 10-60000 +.br + f: the function to call +.br +userdata: a pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. + +.br + +.br +The function is passed the userdata pointer. + +.br + +.br +Only one of \fBgpioSetTimerFunc\fP or \fBgpioSetTimerFuncEx\fP can be +registered per timer. + +.br + +.br +See \fBgpioSetTimerFunc\fP for further details. + +.IP "\fBpthread_t *gpioStartThread(gpioThreadFunc_t f, void *userdata)\fP" +.IP "" 4 +Starts a new thread of execution with f as the main routine. + +.br + +.br + +.EX + f: the main function for the new thread +.br +userdata: a pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns a pointer to pthread_t if OK, otherwise NULL. + +.br + +.br +The function is passed the single argument arg. + +.br + +.br +The thread can be cancelled by passing the pointer to pthread_t to +\fBgpioStopThread\fP. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +void *myfunc(void *arg) +.br +{ +.br + while (1) +.br + { +.br + printf("%s", arg); +.br + sleep(1); +.br + } +.br +} +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + pthread_t *p1, *p2, *p3; +.br + +.br + if (gpioInitialise() < 0) return 1; +.br + +.br + p1 = gpioStartThread(myfunc, "thread 1"); sleep(3); +.br + +.br + p2 = gpioStartThread(myfunc, "thread 2"); sleep(3); +.br + +.br + p3 = gpioStartThread(myfunc, "thread 3"); sleep(3); +.br + +.br + gpioStopThread(p3); sleep(3); +.br + +.br + gpioStopThread(p2); sleep(3); +.br + +.br + gpioStopThread(p1); sleep(3); +.br + +.br + gpioTerminate(); +.br +} +.br + +.EE + +.IP "\fBvoid gpioStopThread(pthread_t *pth)\fP" +.IP "" 4 +Cancels the thread pointed at by pth. + +.br + +.br + +.EX +pth: a thread pointer returned by \fBgpioStartThread\fP +.br + +.EE + +.br + +.br +No value is returned. + +.br + +.br +The thread to be stopped should have been started with \fBgpioStartThread\fP. + +.IP "\fBint gpioStoreScript(char *script)\fP" +.IP "" 4 +This function stores a null terminated script for later execution. + +.br + +.br +See \fBhttp://abyz.me.uk/rpi/pigpio/pigs.html#Scripts\fP for details. + +.br + +.br + +.EX +script: the text of the script +.br + +.EE + +.br + +.br +The function returns a script id if the script is valid, +otherwise PI_BAD_SCRIPT. + +.IP "\fBint gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param)\fP" +.IP "" 4 +This function runs a stored script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + numPar: 0-10, the number of parameters +.br + param: an array of parameters +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param)\fP" +.IP "" 4 +This function runs a stored script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + numPar: 0-10, the number of parameters +.br + param: an array of parameters +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param)\fP" +.IP "" 4 +This function sets the parameters of a script. The script may or +may not be running. The first numPar parameters of the script are +overwritten with the new values. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + numPar: 0-10, the number of parameters +.br + param: an array of parameters +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint gpioScriptStatus(unsigned script_id, uint32_t *param)\fP" +.IP "" 4 +This function returns the run status of a stored script as well as +the current values of parameters 0 to 9. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + param: an array to hold the returned 10 parameters +.br + +.EE + +.br + +.br +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +.br + +.br +The run status may be + +.br + +.br + +.EX +PI_SCRIPT_INITING +.br +PI_SCRIPT_HALTED +.br +PI_SCRIPT_RUNNING +.br +PI_SCRIPT_WAITING +.br +PI_SCRIPT_FAILED +.br + +.EE + +.br + +.br +The current value of script parameters 0 to 9 are returned in param. + +.IP "\fBint gpioStopScript(unsigned script_id)\fP" +.IP "" 4 +This function stops a running script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint gpioDeleteScript(unsigned script_id)\fP" +.IP "" 4 +This function deletes a stored script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBgpioStoreScript\fP +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f)\fP" +.IP "" 4 +Registers a function to be called (a callback) when a signal occurs. + +.br + +.br + +.EX +signum: 0-63 +.br + f: the callback function +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_SIGNUM. + +.br + +.br +The function is passed the signal number. + +.br + +.br +One function may be registered per signal. + +.br + +.br +The callback may be cancelled by passing NULL. + +.br + +.br +By default all signals are treated as fatal and cause the library +to call gpioTerminate and then exit. + +.IP "\fBint gpioSetSignalFuncEx(unsigned signum, gpioSignalFuncEx_t f, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) when a signal occurs. + +.br + +.br + +.EX + signum: 0-63 +.br + f: the callback function +.br +userdata: a pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_SIGNUM. + +.br + +.br +The function is passed the signal number and the userdata pointer. + +.br + +.br +Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be +registered per signal. + +.br + +.br +See gpioSetSignalFunc for further details. + +.IP "\fBuint32_t gpioRead_Bits_0_31(void)\fP" +.IP "" 4 +Returns the current level of GPIO 0-31. + +.IP "\fBuint32_t gpioRead_Bits_32_53(void)\fP" +.IP "" 4 +Returns the current level of GPIO 32-53. + +.IP "\fBint gpioWrite_Bits_0_31_Clear(uint32_t bits)\fP" +.IP "" 4 +Clears GPIO 0-31 if the corresponding bit in bits is set. + +.br + +.br + +.EX +bits: a bit mask of GPIO to clear +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.br + +.br +\fBExample\fP +.br + +.EX +// To clear (set to 0) GPIO 4, 7, and 15 +.br +gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) ); +.br + +.EE + +.IP "\fBint gpioWrite_Bits_32_53_Clear(uint32_t bits)\fP" +.IP "" 4 +Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +.br + +.br + +.EX +bits: a bit mask of GPIO to clear +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.IP "\fBint gpioWrite_Bits_0_31_Set(uint32_t bits)\fP" +.IP "" 4 +Sets GPIO 0-31 if the corresponding bit in bits is set. + +.br + +.br + +.EX +bits: a bit mask of GPIO to set +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.IP "\fBint gpioWrite_Bits_32_53_Set(uint32_t bits)\fP" +.IP "" 4 +Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +.br + +.br + +.EX +bits: a bit mask of GPIO to set +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.br + +.br +\fBExample\fP +.br + +.EX +// To set (set to 1) GPIO 32, 40, and 53 +.br +gpioWrite_Bits_32_53_Set((1<<(32-32)) | (1<<(40-32)) | (1<<(53-32))); +.br + +.EE + +.IP "\fBint gpioHardwareClock(unsigned gpio, unsigned clkfreq)\fP" +.IP "" 4 +Starts a hardware clock on a GPIO at the specified frequency. +Frequencies above 30MHz are unlikely to work. + +.br + +.br + +.EX + gpio: see description +.br +clkfreq: 0 (off) or 4689-250000000 (250M) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HCLK_GPIO, +PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS. + +.br + +.br +The same clock is available on multiple GPIO. The latest +frequency setting will be used by all GPIO which share a clock. + +.br + +.br +The GPIO must be one of the following. + +.br + +.br + +.EX +4 clock 0 All models +.br +5 clock 1 All models but A and B (reserved for system use) +.br +6 clock 2 All models but A and B +.br +20 clock 0 All models but A and B +.br +21 clock 1 All models but A and Rev.2 B (reserved for system use) +.br + +.br +32 clock 0 Compute module only +.br +34 clock 0 Compute module only +.br +42 clock 1 Compute module only (reserved for system use) +.br +43 clock 2 Compute module only +.br +44 clock 1 Compute module only (reserved for system use) +.br + +.EE + +.br + +.br +Access to clock 1 is protected by a password as its use will likely +crash the Pi. The password is given by or'ing 0x5A000000 with the +GPIO number. + +.IP "\fBint gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty)\fP" +.IP "" 4 +Starts hardware PWM on a GPIO at the specified frequency and dutycycle. +Frequencies above 30MHz are unlikely to work. + +.br + +.br +NOTE: Any waveform started by \fBgpioWaveTxSend\fP, or +\fBgpioWaveChain\fP will be cancelled. + +.br + +.br +This function is only valid if the pigpio main clock is PCM. The +main clock defaults to PCM but may be overridden by a call to +\fBgpioCfgClock\fP. + +.br + +.br + +.EX + gpio: see description +.br +PWMfreq: 0 (off) or 1-125000000 (125M) +.br +PWMduty: 0 (off) to 1000000 (1M)(fully on) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HPWM_GPIO, +PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, or PI_HPWM_ILLEGAL. + +.br + +.br +The same PWM channel is available on multiple GPIO. The latest +frequency and dutycycle setting will be used by all GPIO which +share a PWM channel. + +.br + +.br +The GPIO must be one of the following. + +.br + +.br + +.EX +12 PWM channel 0 All models but A and B +.br +13 PWM channel 1 All models but A and B +.br +18 PWM channel 0 All models +.br +19 PWM channel 1 All models but A and B +.br + +.br +40 PWM channel 0 Compute module only +.br +41 PWM channel 1 Compute module only +.br +45 PWM channel 1 Compute module only +.br +52 PWM channel 0 Compute module only +.br +53 PWM channel 1 Compute module only +.br + +.EE + +.br + +.br +The actual number of steps beween off and fully on is the +integral part of 250 million divided by PWMfreq. + +.br + +.br +The actual frequency set is 250 million / steps. + +.br + +.br +There will only be a million steps for a PWMfreq of 250. +Lower frequencies will have more steps and higher +frequencies will have fewer steps. PWMduty is +automatically scaled to take this into account. + +.IP "\fBint gpioTime(unsigned timetype, int *seconds, int *micros)\fP" +.IP "" 4 +Updates the seconds and micros variables with the current time. + +.br + +.br + +.EX +timetype: 0 (relative), 1 (absolute) +.br + seconds: a pointer to an int to hold seconds +.br + micros: a pointer to an int to hold microseconds +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_TIMETYPE. + +.br + +.br +If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the +number of seconds and microseconds since the epoch (1st January 1970). + +.br + +.br +If timetype is PI_TIME_RELATIVE updates seconds and micros with the +number of seconds and microseconds since the library was initialised. + +.br + +.br +\fBExample\fP +.br + +.EX +int secs, mics; +.br + +.br +// print the number of seconds since the library was started +.br +gpioTime(PI_TIME_RELATIVE, &secs, &mics); +.br +printf("library started %d.%03d seconds ago", secs, mics/1000); +.br + +.EE + +.IP "\fBint gpioSleep(unsigned timetype, int seconds, int micros)\fP" +.IP "" 4 +Sleeps for the number of seconds and microseconds specified by seconds +and micros. + +.br + +.br + +.EX +timetype: 0 (relative), 1 (absolute) +.br + seconds: seconds to sleep +.br + micros: microseconds to sleep +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS, +or PI_BAD_MICROS. + +.br + +.br +If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds +and microseconds since the epoch (1st January 1970) has elapsed. System +clock changes are taken into account. + +.br + +.br +If timetype is PI_TIME_RELATIVE the sleep is for the specified number +of seconds and microseconds. System clock changes do not effect the +sleep length. + +.br + +.br +For short delays (say, 50 microseonds or less) use \fBgpioDelay\fP. + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds +.br + +.br +gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 0.1 seconds +.br + +.br +gpioSleep(PI_TIME_RELATIVE, 60, 0); // sleep for one minute +.br + +.EE + +.IP "\fBuint32_t gpioDelay(uint32_t micros)\fP" +.IP "" 4 +Delays for at least the number of microseconds specified by micros. + +.br + +.br + +.EX +micros: the number of microseconds to sleep +.br + +.EE + +.br + +.br +Returns the actual length of the delay in microseconds. + +.br + +.br +Delays of 100 microseconds or less use busy waits. + +.IP "\fBuint32_t gpioTick(void)\fP" +.IP "" 4 +Returns the current system tick. + +.br + +.br +Tick is the number of microseconds since system boot. + +.br + +.br +As tick is an unsigned 32 bit quantity it wraps around after +2^32 microseconds, which is approximately 1 hour 12 minutes. + +.br + +.br +You don't need to worry about the wrap around as long as you +take a tick (uint32_t) from another tick, i.e. the following +code will always provide the correct difference. + +.br + +.br +\fBExample\fP +.br + +.EX +uint32_t startTick, endTick; +.br +int diffTick; +.br + +.br +startTick = gpioTick(); +.br + +.br +// do some processing +.br + +.br +endTick = gpioTick(); +.br + +.br +diffTick = endTick - startTick; +.br + +.br +printf("some processing took %d microseconds", diffTick); +.br + +.EE + +.IP "\fBunsigned gpioHardwareRevision(void)\fP" +.IP "" 4 +Returns the hardware revision. + +.br + +.br +If the hardware revision can not be found or is not a valid hexadecimal +number the function returns 0. + +.br + +.br +The hardware revision is the last few characters on the Revision line of +/proc/cpuinfo. + +.br + +.br +The revision number can be used to determine the assignment of GPIO +to pins (see \fBgpio\fP). + +.br + +.br +There are at least three types of board. + +.br + +.br +Type 1 boards have hardware revision numbers of 2 and 3. + +.br + +.br +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. + +.br + +.br +Type 3 boards have hardware revision numbers of 16 or greater. + +.br + +.br +for "Revision : 0002" the function returns 2. +.br +for "Revision : 000f" the function returns 15. +.br +for "Revision : 000g" the function returns 0. + +.IP "\fBunsigned gpioVersion(void)\fP" +.IP "" 4 +Returns the pigpio version. + +.IP "\fBint gpioGetPad(unsigned pad)\fP" +.IP "" 4 +This function returns the pad drive strength in mA. + +.br + +.br + +.EX +pad: 0-2, the pad to get +.br + +.EE + +.br + +.br +Returns the pad drive strength if OK, otherwise PI_BAD_PAD. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +strength = gpioGetPad(1); // get pad 1 strength +.br + +.EE + +.IP "\fBint gpioSetPad(unsigned pad, unsigned padStrength)\fP" +.IP "" 4 +This function sets the pad drive strength in mA. + +.br + +.br + +.EX + pad: 0-2, the pad to set +.br +padStrength: 1-16 mA +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +gpioSetPad(0, 16); // set pad 0 strength to 16 mA +.br + +.EE + +.IP "\fBint eventMonitor(unsigned handle, uint32_t bits)\fP" +.IP "" 4 +This function selects the events to be reported on a previously +opened handle. + +.br + +.br + +.EX +handle: >=0, as returned by \fBgpioNotifyOpen\fP +.br + bits: a bit mask indicating the events of interest +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +A report is sent each time an event is triggered providing the +corresponding bit in bits is set. + +.br + +.br +See \fBgpioNotifyBegin\fP for the notification format. + +.br + +.br +\fBExample\fP +.br + +.EX +// Start reporting events 3, 6, and 7. +.br + +.br +// bit 76543210 +.br +// (0xC8 = 0b11001000) +.br + +.br +eventMonitor(h, 0xC8); +.br + +.EE + +.br + +.br + +.IP "\fBint eventSetFunc(unsigned event, eventFunc_t f)\fP" +.IP "" 4 +Registers a function to be called (a callback) when the specified +event occurs. + +.br + +.br + +.EX +event: 0-31 +.br + f: the callback function +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +.br + +.br +One function may be registered per event. + +.br + +.br +The function is passed the event, and the tick. + +.br + +.br +The callback may be cancelled by passing NULL as the function. + +.IP "\fBint eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata)\fP" +.IP "" 4 +Registers a function to be called (a callback) when the specified +event occurs. + +.br + +.br + +.EX + event: 0-31 +.br + f: the callback function +.br +userdata: pointer to arbitrary user data +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +.br + +.br +One function may be registered per event. + +.br + +.br +The function is passed the event, the tick, and the ueserdata pointer. + +.br + +.br +The callback may be cancelled by passing NULL as the function. + +.br + +.br +Only one of \fBeventSetFunc\fP or \fBeventSetFuncEx\fP can be +registered per event. + +.IP "\fBint eventTrigger(unsigned event)\fP" +.IP "" 4 +This function signals the occurrence of an event. + +.br + +.br + +.EX +event: 0-31, the event +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +.br + +.br +An event is a signal used to inform one or more consumers +to start an action. Each consumer which has registered an interest +in the event (e.g. by calling \fBeventSetFunc\fP) will be informed by +a callback. + +.br + +.br +One event, PI_EVENT_BSC (31) is predefined. This event is +auto generated on BSC slave activity. + +.br + +.br +The meaning of other events is arbitrary. + +.br + +.br +Note that other than its id and its tick there is no data associated +with an event. + +.IP "\fBint shell(char *scriptName, char *scriptString)\fP" +.IP "" 4 +This function uses the system call to execute a shell script +with the given string as its parameter. + +.br + +.br + +.EX + scriptName: the name of the script, only alphanumeric characters, +.br + '-' and '_' are allowed in the name +.br +scriptString: the string to pass to the script +.br + +.EE + +.br + +.br +The exit status of the system call is returned if OK, otherwise +PI_BAD_SHELL_STATUS. + +.br + +.br +scriptName must exist in /opt/pigpio/cgi and must be executable. + +.br + +.br +The returned exit status is normally 256 times that set by the +shell script exit function. If the script can't be found 32512 will +be returned. + +.br + +.br +The following table gives some example returned statuses. + +.br + +.br +Script exit status Returned system call status +.br +1 256 +.br +5 1280 +.br +10 2560 +.br +200 51200 +.br +script not found 32512 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +// pass two parameters, hello and world +.br +status = shell("scr1", "hello world"); +.br + +.br +// pass three parameters, hello, string with spaces, and world +.br +status = shell("scr1", "hello 'string with spaces' world"); +.br + +.br +// pass one parameter, hello string with spaces world +.br +status = shell("scr1", "\"hello string with spaces world\""); +.br + +.EE + +.IP "\fBint fileOpen(char *file, unsigned mode)\fP" +.IP "" 4 +This function returns a handle to a file opened in a specified mode. + +.br + +.br + +.EX +file: the file to open +.br +mode: the file open mode +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS, +PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR. + +.br + +.br +File + +.br + +.br +A file may only be opened if permission is granted by an entry in +/opt/pigpio/access. This is intended to allow remote access to files +in a more or less controlled manner. + +.br + +.br +Each entry in /opt/pigpio/access takes the form of a file path +which may contain wildcards followed by a single letter permission. +The permission may be R for read, W for write, U for read/write, +and N for no access. + +.br + +.br +Where more than one entry matches a file the most specific rule +applies. If no entry matches a file then access is denied. + +.br + +.br +Suppose /opt/pigpio/access contains the following entries + +.br + +.br + +.EX +/home/* n +.br +/home/pi/shared/dir_1/* w +.br +/home/pi/shared/dir_2/* r +.br +/home/pi/shared/dir_3/* u +.br +/home/pi/shared/dir_1/file.txt n +.br + +.EE + +.br + +.br +Files may be written in directory dir_1 with the exception +of file.txt. + +.br + +.br +Files may be read in directory dir_2. + +.br + +.br +Files may be read and written in directory dir_3. + +.br + +.br +If a directory allows read, write, or read/write access then files may +be created in that directory. + +.br + +.br +In an attempt to prevent risky permissions the following paths are +ignored in /opt/pigpio/access. + +.br + +.br + +.EX +a path containing .. +.br +a path containing only wildcards (*?) +.br +a path containing less than two non-wildcard parts +.br + +.EE + +.br + +.br +Mode + +.br + +.br +The mode may have the following values. + +.br + +.br +Macro Value Meaning +.br +PI_FILE_READ 1 open file for reading +.br +PI_FILE_WRITE 2 open file for writing +.br +PI_FILE_RW 3 open file for reading and writing +.br + +.br + +.br +The following values may be or'd into the mode. + +.br + +.br +Macro Value Meaning +.br +PI_FILE_APPEND 4 Writes append data to the end of the file +.br +PI_FILE_CREATE 8 The file is created if it doesn't exist +.br +PI_FILE_TRUNC 16 The file is truncated +.br + +.br + +.br +Newly created files are owned by root with permissions owner read and write. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int handle, c; +.br + char buf[60000]; +.br + +.br + if (gpioInitialise() < 0) return 1; +.br + +.br + // assumes /opt/pigpio/access contains the following line +.br + // /ram/*.c r +.br + +.br + handle = fileOpen("/ram/pigpio.c", PI_FILE_READ); +.br + +.br + if (handle >= 0) +.br + { +.br + while ((c=fileRead(handle, buf, sizeof(buf)-1))) +.br + { +.br + buf[c] = 0; +.br + printf("%s", buf); +.br + } +.br + +.br + fileClose(handle); +.br + } +.br + +.br + gpioTerminate(); +.br +} +.br + +.EE + +.IP "\fBint fileClose(unsigned handle)\fP" +.IP "" 4 +This function closes the file associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBfileOpen\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +\fBExample\fP +.br + +.EX +fileClose(h); +.br + +.EE + +.IP "\fBint fileWrite(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes from buf to the the file +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBfileOpen\fP +.br + buf: the array of bytes to write +.br + count: the number of bytes to write +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, +PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE. + +.br + +.br +\fBExample\fP +.br + +.EX +status = fileWrite(h, buf, count); +.br +if (status == 0) +.br +{ +.br + // okay +.br +} +.br +else +.br +{ +.br + // error +.br +} +.br + +.EE + +.IP "\fBint fileRead(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads up to count bytes from the the file +associated with handle and writes them to buf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBfileOpen\fP +.br + buf: an array to receive the read data +.br + count: the maximum number of bytes to read +.br + +.EE + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE. + +.br + +.br +\fBExample\fP +.br + +.EX +if (fileRead(h, buf, sizeof(buf)) > 0) +.br +{ +.br + // process read data +.br +} +.br + +.EE + +.IP "\fBint fileSeek(unsigned handle, int32_t seekOffset, int seekFrom)\fP" +.IP "" 4 +This function seeks to a position within the file associated +with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBfileOpen\fP +.br +seekOffset: the number of bytes to move. Positive offsets +.br + move forward, negative offsets backwards. +.br + seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1), +.br + or PI_FROM_END (2) +.br + +.EE + +.br + +.br +Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK. + +.br + +.br +\fBExample\fP +.br + +.EX +fileSeek(0, 20, PI_FROM_START); // Seek to start plus 20 +.br + +.br +size = fileSeek(0, 0, PI_FROM_END); // Seek to end, return size +.br + +.br +pos = fileSeek(0, 0, PI_FROM_CURRENT); // Return current position +.br + +.EE + +.IP "\fBint fileList(char *fpat, char *buf, unsigned count)\fP" +.IP "" 4 +This function returns a list of files which match a pattern. The +pattern may contain wildcards. + +.br + +.br + +.EX + fpat: file pattern to match +.br + buf: an array to receive the matching file names +.br +count: the maximum number of bytes to read +.br + +.EE + +.br + +.br +Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS, +or PI_NO_FILE_MATCH. + +.br + +.br +The pattern must match an entry in /opt/pigpio/access. The pattern +may contain wildcards. See \fBfileOpen\fP. + +.br + +.br +NOTE + +.br + +.br +The returned value is not the number of files, it is the number +of bytes in the buffer. The file names are separated by newline +characters. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int c; +.br + char buf[1000]; +.br + +.br + if (gpioInitialise() < 0) return 1; +.br + +.br + // assumes /opt/pigpio/access contains the following line +.br + // /ram/*.c r +.br + +.br + c = fileList("/ram/p*.c", buf, sizeof(buf)); +.br + +.br + if (c >= 0) +.br + { +.br + // terminate string +.br + buf[c] = 0; +.br + printf("%s", buf); +.br + } +.br + +.br + gpioTerminate(); +.br +} +.br + +.EE + +.IP "\fBint gpioCfgBufferSize(unsigned cfgMillis)\fP" +.IP "" 4 +Configures pigpio to buffer cfgMillis milliseconds of GPIO samples. + +.br + +.br +This function is only effective if called before \fBgpioInitialise\fP. + +.br + +.br + +.EX +cfgMillis: 100-10000 +.br + +.EE + +.br + +.br +The default setting is 120 milliseconds. + +.br + +.br +The intention is to allow for bursts of data and protection against +other processes hogging cpu time. + +.br + +.br +I haven't seen a process locked out for more than 100 milliseconds. + +.br + +.br +Making the buffer bigger uses a LOT of memory at the more frequent +sampling rates as shown in the following table in MBs. + +.br + +.br + +.EX + buffer milliseconds +.br + 120 250 500 1sec 2sec 4sec 8sec +.br + +.br + 1 16 31 55 107 --- --- --- +.br + 2 10 18 31 55 107 --- --- +.br +sample 4 8 12 18 31 55 107 --- +.br + rate 5 8 10 14 24 45 87 --- +.br + (us) 8 6 8 12 18 31 55 107 +.br + 10 6 8 10 14 24 45 87 +.br + +.EE + +.IP "\fBint gpioCfgClock(unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource)\fP" +.IP "" 4 +Configures pigpio to use a particular sample rate timed by a specified +peripheral. + +.br + +.br +This function is only effective if called before \fBgpioInitialise\fP. + +.br + +.br + +.EX + cfgMicros: 1, 2, 4, 5, 8, 10 +.br +cfgPeripheral: 0 (PWM), 1 (PCM) +.br + cfgSource: deprecated, value is ignored +.br + +.EE + +.br + +.br +The timings are provided by the specified peripheral (PWM or PCM). + +.br + +.br +The default setting is 5 microseconds using the PCM peripheral. + +.br + +.br +The approximate CPU percentage used for each sample rate is: + +.br + +.br + +.EX +sample cpu +.br + rate % +.br + +.br + 1 25 +.br + 2 16 +.br + 4 11 +.br + 5 10 +.br + 8 15 +.br + 10 14 +.br + +.EE + +.br + +.br +A sample rate of 5 microseconds seeems to be the sweet spot. + +.IP "\fBint gpioCfgDMAchannel(unsigned DMAchannel)\fP" +.IP "" 4 +Configures pigpio to use the specified DMA channel. + +.br + +.br +This function is only effective if called before \fBgpioInitialise\fP. + +.br + +.br + +.EX +DMAchannel: 0-14 +.br + +.EE + +.br + +.br +The default setting is to use channel 14. + +.IP "\fBint gpioCfgDMAchannels(unsigned primaryChannel, unsigned secondaryChannel)\fP" +.IP "" 4 +Configures pigpio to use the specified DMA channels. + +.br + +.br +This function is only effective if called before \fBgpioInitialise\fP. + +.br + +.br + +.EX + primaryChannel: 0-14 +.br +secondaryChannel: 0-14 +.br + +.EE + +.br + +.br +The default setting is to use channel 14 for the primary channel and +channel 6 for the secondary channel. + +.br + +.br +The secondary channel is only used for the transmission of waves. + +.br + +.br +If possible use one of channels 0 to 6 for the secondary channel +(a full channel). + +.br + +.br +A full channel only requires one DMA control block regardless of the +length of a pulse delay. Channels 7 to 14 (lite channels) require +one DMA control block for each 16383 microseconds of delay. I.e. +a 10 second pulse delay requires one control block on a full channel +and 611 control blocks on a lite channel. + +.IP "\fBint gpioCfgPermissions(uint64_t updateMask)\fP" +.IP "" 4 +Configures pigpio to restrict GPIO updates via the socket or pipe +interfaces to the GPIO specified by the mask. Programs directly +calling the pigpio library (i.e. linked with -lpigpio are not +affected). A GPIO update is a write to a GPIO or a GPIO mode +change or any function which would force such an action. + +.br + +.br +This function is only effective if called before \fBgpioInitialise\fP. + +.br + +.br + +.EX +updateMask: bit (1<=0 +.br +arg2: >=0 +.br +argx: extra (byte) arguments +.br +argc: number of extra arguments +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.IP "\fBint gpioCustom2(unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)\fP" +.IP "" 4 +This function is available for user customisation. + +.br + +.br +It differs from gpioCustom1 in that it returns an array of bytes +rather than just an integer. + +.br + +.br +The returned value is an integer indicating the number of returned bytes. + +.EX + arg1: >=0 +.br + argx: extra (byte) arguments +.br + argc: number of extra arguments +.br +retBuf: buffer for returned bytes +.br +retMax: maximum number of bytes to return +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.br + +.br +The number of returned bytes must be retMax or less. + +.IP "\fBint rawWaveAddSPI(rawSPI_t *spi, unsigned offset, unsigned spiSS, char *buf, unsigned spiTxBits, unsigned spiBitFirst, unsigned spiBitLast, unsigned spiBits)\fP" +.IP "" 4 +This function adds a waveform representing SPI data to the +existing waveform (if any). + +.br + +.br + +.EX + spi: a pointer to a spi object +.br + offset: microseconds from the start of the waveform +.br + spiSS: the slave select GPIO +.br + buf: the bits to transmit, most significant bit first +.br + spiTxBits: the number of bits to write +.br +spiBitFirst: the first bit to read +.br + spiBitLast: the last bit to read +.br + spiBits: the number of bits to transfer +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. + +.br + +.br +Not intended for general use. + +.IP "\fBint rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses)\fP" +.IP "" 4 +This function adds a number of pulses to the current waveform. + +.br + +.br + +.EX +numPulses: the number of pulses +.br + pulses: the array containing the pulses +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +.br + +.br +The advantage of this function over gpioWaveAddGeneric is that it +allows the setting of the flags field. + +.br + +.br +The pulses are interleaved in time order within the existing waveform +(if any). + +.br + +.br +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +.br + +.br +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. + +.br + +.br +Not intended for general use. + +.IP "\fBunsigned rawWaveCB(void)\fP" +.IP "" 4 +Returns the number of the cb being currently output. + +.br + +.br +Not intended for general use. + +.IP "\fBrawCbs_t *rawWaveCBAdr(int cbNum)\fP" +.IP "" 4 +Return the (Linux) address of contol block cbNum. + +.br + +.br + +.EX +cbNum: the cb of interest +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBuint32_t rawWaveGetOOL(int pos)\fP" +.IP "" 4 +Gets the OOL parameter stored at pos. + +.br + +.br + +.EX +pos: the position of interest. +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBvoid rawWaveSetOOL(int pos, uint32_t lVal)\fP" +.IP "" 4 +Sets the OOL parameter stored at pos to value. + +.br + +.br + +.EX + pos: the position of interest +.br +lVal: the value to write +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBuint32_t rawWaveGetOut(int pos)\fP" +.IP "" 4 +Gets the wave output parameter stored at pos. + +.br + +.br +DEPRECATED: use rawWaveGetOOL instead. + +.br + +.br + +.EX +pos: the position of interest. +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBvoid rawWaveSetOut(int pos, uint32_t lVal)\fP" +.IP "" 4 +Sets the wave output parameter stored at pos to value. + +.br + +.br +DEPRECATED: use rawWaveSetOOL instead. + +.br + +.br + +.EX + pos: the position of interest +.br +lVal: the value to write +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBuint32_t rawWaveGetIn(int pos)\fP" +.IP "" 4 +Gets the wave input value parameter stored at pos. + +.br + +.br +DEPRECATED: use rawWaveGetOOL instead. + +.br + +.br + +.EX +pos: the position of interest +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBvoid rawWaveSetIn(int pos, uint32_t lVal)\fP" +.IP "" 4 +Sets the wave input value stored at pos to value. + +.br + +.br +DEPRECATED: use rawWaveSetOOL instead. + +.br + +.br + +.EX + pos: the position of interest +.br +lVal: the value to write +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBrawWaveInfo_t rawWaveInfo(int wave_id)\fP" +.IP "" 4 +Gets details about the wave with id wave_id. + +.br + +.br + +.EX +wave_id: the wave of interest +.br + +.EE + +.br + +.br +Not intended for general use. + +.IP "\fBint getBitInBytes(int bitPos, char *buf, int numBits)\fP" +.IP "" 4 +Returns the value of the bit bitPos bits from the start of buf. Returns +0 if bitPos is greater than or equal to numBits. + +.br + +.br + +.EX + bitPos: bit index from the start of buf +.br + buf: array of bits +.br +numBits: number of valid bits in buf +.br + +.EE + +.br + +.br + +.IP "\fBvoid putBitInBytes(int bitPos, char *buf, int bit)\fP" +.IP "" 4 +Sets the bit bitPos bits from the start of buf to bit. + +.br + +.br + +.EX +bitPos: bit index from the start of buf +.br + buf: array of bits +.br + bit: 0-1, value to set +.br + +.EE + +.br + +.br + +.IP "\fBdouble time_time(void)\fP" +.IP "" 4 +Return the current time in seconds since the Epoch. + +.IP "\fBvoid time_sleep(double seconds)\fP" +.IP "" 4 +Delay execution for a given number of seconds + +.br + +.br + +.EX +seconds: the number of seconds to sleep +.br + +.EE + +.IP "\fBvoid rawDumpWave(void)\fP" +.IP "" 4 +Used to print a readable version of the current waveform to stderr. + +.br + +.br +Not intended for general use. + +.IP "\fBvoid rawDumpScript(unsigned script_id)\fP" +.IP "" 4 +Used to print a readable version of a script to stderr. + +.br + +.br + +.EX +script_id: >=0, a script_id returned by \fBgpioStoreScript\fP +.br + +.EE + +.br + +.br +Not intended for general use. +.SH PARAMETERS + +.br + +.br + +.IP "\fBactive\fP: 0-1000000" 0 + +.br + +.br +The number of microseconds level changes are reported for once +a noise filter has been triggered (by \fBsteady\fP microseconds of +a stable level). + +.br + +.br + +.IP "\fBarg1\fP" 0 + +.br + +.br +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBarg2\fP" 0 + +.br + +.br +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBargc\fP" 0 +The count of bytes passed to a user customised function. + +.br + +.br + +.IP "\fB*argx\fP" 0 +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +.br + +.br + +.IP "\fBbaud\fP" 0 +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +.br + +.br + +.IP "\fBbit\fP" 0 +A value of 0 or 1. + +.br + +.br + +.IP "\fBbitPos\fP" 0 +A bit position within a byte or word. The least significant bit is +position 0. + +.br + +.br + +.IP "\fBbits\fP" 0 +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +.br + +.br +A convenient way to set bit n is to or in (1<=0" 0 + +.br + +.br +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + +.br + +.br + +.IP "\fBgpio\fP" 0 + +.br + +.br +A Broadcom numbered GPIO, in the range 0-53. + +.br + +.br +There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through +GPIO53. + +.br + +.br +They are split into two banks. Bank 1 consists of GPIO0 through +GPIO31. Bank 2 consists of GPIO32 through GPIO53. + +.br + +.br +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +.br + +.br +See \fBgpioHardwareRevision\fP. + +.br + +.br +The user GPIO are marked with an X in the following table. + +.br + +.br + +.EX + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +.br +Type 1 X X - - X - - X X X X X - - X X +.br +Type 2 - - X X X - - X X X X X - - X X +.br +Type 3 X X X X X X X X X X X X X X +.br + +.br + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +.br +Type 1 - X X - - X X X X X - - - - - - +.br +Type 2 - X X - - - X X X X - X X X X X +.br +Type 3 X X X X X X X X X X X X - - - - +.br + +.EE + +.br + +.br + +.IP "\fBgpioAlertFunc_t\fP" 0 + +.EX +typedef void (*gpioAlertFunc_t) (int gpio, int level, uint32_t tick); +.br + +.EE + +.br + +.br + +.IP "\fBgpioAlertFuncEx_t\fP" 0 + +.EX +typedef void (*eventFuncEx_t) +.br + (int event, int level, uint32_t tick, void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBgpioCfg*\fP" 0 + +.br + +.br +These functions are only effective if called before \fBgpioInitialise\fP. + +.br + +.br +\fBgpioCfgBufferSize\fP +.br +\fBgpioCfgClock\fP +.br +\fBgpioCfgDMAchannel\fP +.br +\fBgpioCfgDMAchannels\fP +.br +\fBgpioCfgPermissions\fP +.br +\fBgpioCfgInterfaces\fP +.br +\fBgpioCfgSocketPort\fP +.br +\fBgpioCfgMemAlloc\fP + +.br + +.br + +.IP "\fBgpioGetSamplesFunc_t\fP" 0 + +.EX +typedef void (*gpioGetSamplesFunc_t) +.br + (const gpioSample_t *samples, int numSamples); +.br + +.EE + +.br + +.br + +.IP "\fBgpioGetSamplesFuncEx_t\fP" 0 + +.EX +typedef void (*gpioGetSamplesFuncEx_t) +.br + (const gpioSample_t *samples, int numSamples, void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBgpioISRFunc_t\fP" 0 + +.EX +typedef void (*gpioISRFunc_t) +.br + (int gpio, int level, uint32_t tick); +.br + +.EE + +.br + +.br + +.IP "\fBgpioISRFuncEx_t\fP" 0 + +.EX +typedef void (*gpioISRFuncEx_t) +.br + (int gpio, int level, uint32_t tick, void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBgpioPulse_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint32_t gpioOn; +.br + uint32_t gpioOff; +.br + uint32_t usDelay; +.br +} gpioPulse_t; +.br + +.EE + +.br + +.br + +.IP "\fBgpioSample_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint32_t tick; +.br + uint32_t level; +.br +} gpioSample_t; +.br + +.EE + +.br + +.br + +.IP "\fBgpioSignalFunc_t\fP" 0 + +.EX +typedef void (*gpioSignalFunc_t) (int signum); +.br + +.EE + +.br + +.br + +.IP "\fBgpioSignalFuncEx_t\fP" 0 + +.EX +typedef void (*gpioSignalFuncEx_t) (int signum, void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBgpioThreadFunc_t\fP" 0 + +.EX +typedef void *(gpioThreadFunc_t) (void *); +.br + +.EE + +.br + +.br + +.IP "\fBgpioTimerFunc_t\fP" 0 + +.EX +typedef void (*gpioTimerFunc_t) (void); +.br + +.EE + +.br + +.br + +.IP "\fBgpioTimerFuncEx_t\fP" 0 + +.EX +typedef void (*gpioTimerFuncEx_t) (void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBgpioWaveAdd*\fP" 0 + +.br + +.br +One of + +.br + +.br +\fBgpioWaveAddNew\fP +.br +\fBgpioWaveAddGeneric\fP +.br +\fBgpioWaveAddSerial\fP + +.br + +.br + +.IP "\fBhandle\fP: >=0" 0 + +.br + +.br +A number referencing an object opened by one of + +.br + +.br +\fBfileOpen\fP +.br +\fBgpioNotifyOpen\fP +.br +\fBi2cOpen\fP +.br +\fBserOpen\fP +.br +\fBspiOpen\fP + +.br + +.br + +.IP "\fBi2cAddr\fP: 0-0x7F" 0 +The address of a device on the I2C bus. + +.br + +.br + +.IP "\fBi2cBus\fP: >=0" 0 + +.br + +.br +An I2C bus number. + +.br + +.br + +.IP "\fBi2cFlags\fP: 0" 0 + +.br + +.br +Flags which modify an I2C open command. None are currently defined. + +.br + +.br + +.IP "\fBi2cReg\fP: 0-255" 0 + +.br + +.br +A register of an I2C device. + +.br + +.br + +.IP "\fBifFlags\fP: 0-3" 0 + +.EX +PI_DISABLE_FIFO_IF 1 +.br +PI_DISABLE_SOCK_IF 2 +.br + +.EE + +.br + +.br + +.IP "\fB*inBuf\fP" 0 +A buffer used to pass data to a function. + +.br + +.br + +.IP "\fBinLen\fP" 0 +The number of bytes of data in a buffer. + +.br + +.br + +.IP "\fBint\fP" 0 +A whole number, negative or positive. + +.br + +.br + +.IP "\fBint32_t\fP" 0 +A 32-bit signed value. + +.br + +.br + +.IP "\fBinvert\fP" 0 +A flag used to set normal or inverted bit bang serial data level logic. + +.br + +.br + +.IP "\fBlevel\fP" 0 +The level of a GPIO. Low or High. + +.br + +.br + +.EX +PI_OFF 0 +.br +PI_ON 1 +.br + +.br +PI_CLEAR 0 +.br +PI_SET 1 +.br + +.br +PI_LOW 0 +.br +PI_HIGH 1 +.br + +.EE + +.br + +.br +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See \fBgpioSetWatchdog\fP. + +.br + +.br + +.EX +PI_TIMEOUT 2 +.br + +.EE + +.br + +.br + +.br + +.br + +.IP "\fBlVal\fP: 0-4294967295 (Hex 0x0-0xFFFFFFFF, Octal 0-37777777777)" 0 + +.br + +.br +A 32-bit word value. + +.br + +.br + +.IP "\fBmemAllocMode\fP: 0-2" 0 + +.br + +.br +The DMA memory allocation mode. + +.br + +.br + +.EX +PI_MEM_ALLOC_AUTO 0 +.br +PI_MEM_ALLOC_PAGEMAP 1 +.br +PI_MEM_ALLOC_MAILBOX 2 +.br + +.EE + +.br + +.br + +.IP "\fB*micros\fP" 0 + +.br + +.br +A value representing microseconds. + +.br + +.br + +.IP "\fBmicros\fP" 0 + +.br + +.br +A value representing microseconds. + +.br + +.br + +.IP "\fBmillis\fP" 0 + +.br + +.br +A value representing milliseconds. + +.br + +.br + +.IP "\fBMISO\fP" 0 +The GPIO used for the MISO signal when bit banging SPI. + +.br + +.br + +.IP "\fBmode\fP" 0 + +.br + +.br +1. The operational mode of a GPIO, normally INPUT or OUTPUT. + +.br + +.br + +.EX +PI_INPUT 0 +.br +PI_OUTPUT 1 +.br +PI_ALT0 4 +.br +PI_ALT1 5 +.br +PI_ALT2 6 +.br +PI_ALT3 7 +.br +PI_ALT4 3 +.br +PI_ALT5 2 +.br + +.EE + +.br + +.br +2. A file open mode. + +.br + +.br + +.EX +PI_FILE_READ 1 +.br +PI_FILE_WRITE 2 +.br +PI_FILE_RW 3 +.br + +.EE + +.br + +.br +The following values can be or'd into the mode. + +.br + +.br + +.EX +PI_FILE_APPEND 4 +.br +PI_FILE_CREATE 8 +.br +PI_FILE_TRUNC 16 +.br + +.EE + +.br + +.br + +.IP "\fBMOSI\fP" 0 +The GPIO used for the MOSI signal when bit banging SPI. + +.br + +.br + +.IP "\fBnumBits\fP" 0 + +.br + +.br +The number of bits stored in a buffer. + +.br + +.br + +.IP "\fBnumBytes\fP" 0 +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +.br + +.br + +.IP "\fBnumPar\fP: 0-10" 0 +The number of parameters passed to a script. + +.br + +.br + +.IP "\fBnumPulses\fP" 0 +The number of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBnumSegs\fP" 0 +The number of segments in a combined I2C transaction. + +.br + +.br + +.IP "\fBnumSockAddr\fP" 0 +The number of network addresses allowed to use the socket interface. + +.br + +.br +0 means all addresses allowed. + +.br + +.br + +.IP "\fBoffset\fP" 0 +The associated data starts this number of microseconds from the start of +the waveform. + +.br + +.br + +.IP "\fB*outBuf\fP" 0 +A buffer used to return data from a function. + +.br + +.br + +.IP "\fBoutLen\fP" 0 +The size in bytes of an output buffer. + +.br + +.br + +.IP "\fBpad\fP: 0-2" 0 +A set of GPIO which share common drivers. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br + +.IP "\fBpadStrength\fP: 1-16" 0 +The mA which may be drawn from each GPIO whilst still guaranteeing the +high and low levels. + +.br + +.br + +.IP "\fB*param\fP" 0 +An array of script parameters. + +.br + +.br + +.IP "\fBpi_i2c_msg_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint16_t addr; // slave address +.br + uint16_t flags; +.br + uint16_t len; // msg length +.br + uint8_t *buf; // pointer to msg data +.br +} pi_i2c_msg_t; +.br + +.EE + +.br + +.br + +.IP "\fBport\fP: 1024-32000" 0 +The port used to bind to the pigpio socket. Defaults to 8888. + +.br + +.br + +.IP "\fBpos\fP" 0 +The position of an item. + +.br + +.br + +.IP "\fBprimaryChannel\fP: 0-14" 0 +The DMA channel used to time the sampling of GPIO and to time servo and +PWM pulses. + +.br + +.br + +.IP "\fB*pth\fP" 0 + +.br + +.br +A thread identifier, returned by \fBgpioStartThread\fP. + +.br + +.br + +.IP "\fBpthread_t\fP" 0 + +.br + +.br +A thread identifier. + +.br + +.br + +.IP "\fBpud\fP: 0-2" 0 + +.br + +.br +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. + +.br + +.br + +.EX +PI_PUD_OFF 0 +.br +PI_PUD_DOWN 1 +.br +PI_PUD_UP 2 +.br + +.EE + +.br + +.br + +.IP "\fBpulseLen\fP" 0 + +.br + +.br +1-100, the length of a trigger pulse in microseconds. + +.br + +.br + +.IP "\fB*pulses\fP" 0 + +.br + +.br +An array of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBpulsewidth\fP: 0, 500-2500" 0 + +.EX +PI_SERVO_OFF 0 +.br +PI_MIN_SERVO_PULSEWIDTH 500 +.br +PI_MAX_SERVO_PULSEWIDTH 2500 +.br + +.EE + +.br + +.br + +.IP "\fBPWMduty\fP: 0-1000000 (1M)" 0 +The hardware PWM dutycycle. + +.br + +.br + +.EX +PI_HW_PWM_RANGE 1000000 +.br + +.EE + +.br + +.br + +.IP "\fBPWMfreq\fP: 5-250K" 0 +The hardware PWM frequency. + +.br + +.br + +.EX +PI_HW_PWM_MIN_FREQ 1 +.br +PI_HW_PWM_MAX_FREQ 125000000 +.br + +.EE + +.br + +.br + +.IP "\fBrange\fP: 25-40000" 0 + +.EX +PI_MIN_DUTYCYCLE_RANGE 25 +.br +PI_MAX_DUTYCYCLE_RANGE 40000 +.br + +.EE + +.br + +.br + +.IP "\fBrawCbs_t\fP" 0 + +.EX +typedef struct // linux/arch/arm/mach-bcm2708/include/mach/dma.h +.br +{ +.br + unsigned long info; +.br + unsigned long src; +.br + unsigned long dst; +.br + unsigned long length; +.br + unsigned long stride; +.br + unsigned long next; +.br + unsigned long pad[2]; +.br +} rawCbs_t; +.br + +.EE + +.br + +.br + +.IP "\fBrawSPI_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + int clk; // GPIO for clock +.br + int mosi; // GPIO for MOSI +.br + int miso; // GPIO for MISO +.br + int ss_pol; // slave select off state +.br + int ss_us; // delay after slave select +.br + int clk_pol; // clock off state +.br + int clk_pha; // clock phase +.br + int clk_us; // clock micros +.br +} rawSPI_t; +.br + +.EE + +.br + +.br + +.IP "\fBrawWave_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint32_t gpioOn; +.br + uint32_t gpioOff; +.br + uint32_t usDelay; +.br + uint32_t flags; +.br +} rawWave_t; +.br + +.EE + +.br + +.br + +.IP "\fBrawWaveInfo_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint16_t botCB; // first CB used by wave +.br + uint16_t topCB; // last CB used by wave +.br + uint16_t botOOL; // last OOL used by wave +.br + uint16_t topOOL; // first OOL used by wave +.br + uint16_t deleted; +.br + uint16_t numCB; +.br + uint16_t numBOOL; +.br + uint16_t numTOOL; +.br +} rawWaveInfo_t; +.br + +.EE + +.br + +.br + +.IP "\fB*retBuf\fP" 0 + +.br + +.br +A buffer to hold a number of bytes returned to a used customised function, + +.br + +.br + +.IP "\fBretMax\fP" 0 + +.br + +.br +The maximum number of bytes a user customised function should return. + +.br + +.br + +.IP "\fB*rxBuf\fP" 0 + +.br + +.br +A pointer to a buffer to receive data. + +.br + +.br + +.IP "\fBSCL\fP" 0 +The user GPIO to use for the clock when bit banging I2C. + +.br + +.br + +.IP "\fBSCLK\fP" 0 +The GPIO used for the SCLK signal when bit banging SPI. + +.br + +.br + +.IP "\fB*script\fP" 0 +A pointer to the text of a script. + +.br + +.br + +.IP "\fBscript_id\fP" 0 +An id of a stored script as returned by \fBgpioStoreScript\fP. + +.br + +.br + +.IP "\fB*scriptName\fP" 0 +The name of a \fBshell\fP script to be executed. The script must be present in +/opt/pigpio/cgi and must have execute permission. + +.br + +.br + +.IP "\fB*scriptString\fP" 0 +The string to be passed to a \fBshell\fP script to be executed. + +.br + +.br + +.IP "\fBSDA\fP" 0 +The user GPIO to use for data when bit banging I2C. + +.br + +.br + +.IP "\fBsecondaryChannel\fP: 0-6" 0 + +.br + +.br +The DMA channel used to time output waveforms. + +.br + +.br + +.IP "\fB*seconds\fP" 0 + +.br + +.br +A pointer to a uint32_t to store the second component of +a returned time. + +.br + +.br + +.IP "\fBseconds\fP" 0 +The number of seconds. + +.br + +.br + +.IP "\fBseekFrom\fP" 0 + +.br + +.br + +.EX +PI_FROM_START 0 +.br +PI_FROM_CURRENT 1 +.br +PI_FROM_END 2 +.br + +.EE + +.br + +.br + +.IP "\fBseekOffset\fP" 0 +The number of bytes to move forward (positive) or backwards (negative) +from the seek position (start, current, or end of file). + +.br + +.br + +.IP "\fB*segs\fP" 0 +An array of segments which make up a combined I2C transaction. + +.br + +.br + +.IP "\fBserFlags\fP" 0 +Flags which modify a serial open command. None are currently defined. + +.br + +.br + +.IP "\fB*sertty\fP" 0 +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +.br + +.br + +.IP "\fBsetting\fP" 0 +A value used to set a flag, 0 for false, non-zero for true. + +.br + +.br + +.IP "\fBsignum\fP: 0-63" 0 + +.EX +PI_MIN_SIGNUM 0 +.br +PI_MAX_SIGNUM 63 +.br + +.EE + +.br + +.br + +.IP "\fBsize_t\fP" 0 + +.br + +.br +A standard type used to indicate the size of an object in bytes. + +.br + +.br + +.IP "\fB*sockAddr\fP" 0 +An array of network addresses allowed to use the socket interface encoded +as 32 bit numbers. + +.br + +.br +E.g. address 192.168.1.66 would be encoded as 0x4201a8c0. + +.br + +.br + +.IP "\fB*spi\fP" 0 +A pointer to a \fBrawSPI_t\fP structure. + +.br + +.br + +.IP "\fBspiBitFirst\fP" 0 +GPIO reads are made from spiBitFirst to spiBitLast. + +.br + +.br + +.IP "\fBspiBitLast\fP" 0 + +.br + +.br +GPIO reads are made from spiBitFirst to spiBitLast. + +.br + +.br + +.IP "\fBspiBits\fP" 0 +The number of bits to transfer in a raw SPI transaction. + +.br + +.br + +.IP "\fBspiChan\fP" 0 +A SPI channel, 0-2. + +.br + +.br + +.IP "\fBspiFlags\fP" 0 +See \fBspiOpen\fP and \fBbbSPIOpen\fP. + +.br + +.br + +.IP "\fBspiSS\fP" 0 +The SPI slave select GPIO in a raw SPI transaction. + +.br + +.br + +.IP "\fBspiTxBits\fP" 0 +The number of bits to transfer dring a raw SPI transaction + +.br + +.br + +.IP "\fBsteady\fP: 0-300000" 0 + +.br + +.br +The number of microseconds level changes must be stable for +before reporting the level changed (\fBgpioGlitchFilter\fP) or triggering +the active part of a noise filter (\fBgpioNoiseFilter\fP). + +.br + +.br + +.IP "\fBstop_bits\fP: 2-8" 0 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +.br + +.br + +.EX +PI_MIN_WAVE_HALFSTOPBITS 2 +.br +PI_MAX_WAVE_HALFSTOPBITS 8 +.br + +.EE + +.br + +.br + +.IP "\fB*str\fP" 0 +An array of characters. + +.br + +.br + +.IP "\fBtimeout\fP" 0 +A GPIO level change timeout in milliseconds. + +.br + +.br +\fBgpioSetWatchdog\fP + +.EX +PI_MIN_WDOG_TIMEOUT 0 +.br +PI_MAX_WDOG_TIMEOUT 60000 +.br + +.EE + +.br + +.br +\fBgpioSetISRFunc\fP and \fBgpioSetISRFuncEx\fP + +.EX +<=0 cancel timeout +.br +>0 timeout after specified milliseconds +.br + +.EE + +.br + +.br + +.IP "\fBtimer\fP" 0 + +.EX +PI_MIN_TIMER 0 +.br +PI_MAX_TIMER 9 +.br + +.EE + +.br + +.br + +.IP "\fBtimetype\fP" 0 + +.EX +PI_TIME_RELATIVE 0 +.br +PI_TIME_ABSOLUTE 1 +.br + +.EE + +.br + +.br + +.IP "\fB*txBuf\fP" 0 + +.br + +.br +An array of bytes to transmit. + +.br + +.br + +.IP "\fBuint32_t\fP: 0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)" 0 + +.br + +.br +A 32-bit unsigned value. + +.br + +.br + +.IP "\fBuint64_t\fP: 0-(2^64)-1" 0 + +.br + +.br +A 64-bit unsigned value. + +.br + +.br + +.IP "\fBunsigned\fP" 0 + +.br + +.br +A whole number >= 0. + +.br + +.br + +.IP "\fBupdateMask\fP" 0 + +.br + +.br +A 64 bit mask indicating which GPIO may be written to by the user. + +.br + +.br +If GPIO#n may be written then bit (1< 4 +.br +#define PI_BAD_CHANNEL -27 // DMA channel not 0-14 +.br +#define PI_BAD_PRIM_CHANNEL -27 // DMA primary channel not 0-14 +.br +#define PI_BAD_SOCKET_PORT -28 // socket port not 1024-32000 +.br +#define PI_BAD_FIFO_COMMAND -29 // unrecognized fifo command +.br +#define PI_BAD_SECO_CHANNEL -30 // DMA secondary channel not 0-6 +.br +#define PI_NOT_INITIALISED -31 // function called before gpioInitialise +.br +#define PI_INITIALISED -32 // function called after gpioInitialise +.br +#define PI_BAD_WAVE_MODE -33 // waveform mode not 0-3 +.br +#define PI_BAD_CFG_INTERNAL -34 // bad parameter in gpioCfgInternals call +.br +#define PI_BAD_WAVE_BAUD -35 // baud rate not 50-250K(RX)/50-1M(TX) +.br +#define PI_TOO_MANY_PULSES -36 // waveform has too many pulses +.br +#define PI_TOO_MANY_CHARS -37 // waveform has too many chars +.br +#define PI_NOT_SERIAL_GPIO -38 // no bit bang serial read on GPIO +.br +#define PI_BAD_SERIAL_STRUC -39 // bad (null) serial structure parameter +.br +#define PI_BAD_SERIAL_BUF -40 // bad (null) serial buf parameter +.br +#define PI_NOT_PERMITTED -41 // GPIO operation not permitted +.br +#define PI_SOME_PERMITTED -42 // one or more GPIO not permitted +.br +#define PI_BAD_WVSC_COMMND -43 // bad WVSC subcommand +.br +#define PI_BAD_WVSM_COMMND -44 // bad WVSM subcommand +.br +#define PI_BAD_WVSP_COMMND -45 // bad WVSP subcommand +.br +#define PI_BAD_PULSELEN -46 // trigger pulse length not 1-100 +.br +#define PI_BAD_SCRIPT -47 // invalid script +.br +#define PI_BAD_SCRIPT_ID -48 // unknown script id +.br +#define PI_BAD_SER_OFFSET -49 // add serial data offset > 30 minutes +.br +#define PI_GPIO_IN_USE -50 // GPIO already in use +.br +#define PI_BAD_SERIAL_COUNT -51 // must read at least a byte at a time +.br +#define PI_BAD_PARAM_NUM -52 // script parameter id not 0-9 +.br +#define PI_DUP_TAG -53 // script has duplicate tag +.br +#define PI_TOO_MANY_TAGS -54 // script has too many tags +.br +#define PI_BAD_SCRIPT_CMD -55 // illegal script command +.br +#define PI_BAD_VAR_NUM -56 // script variable id not 0-149 +.br +#define PI_NO_SCRIPT_ROOM -57 // no more room for scripts +.br +#define PI_NO_MEMORY -58 // can't allocate temporary memory +.br +#define PI_SOCK_READ_FAILED -59 // socket read failed +.br +#define PI_SOCK_WRIT_FAILED -60 // socket write failed +.br +#define PI_TOO_MANY_PARAM -61 // too many script parameters (> 10) +.br +#define PI_NOT_HALTED -62 // DEPRECATED +.br +#define PI_SCRIPT_NOT_READY -62 // script initialising +.br +#define PI_BAD_TAG -63 // script has unresolved tag +.br +#define PI_BAD_MICS_DELAY -64 // bad MICS delay (too large) +.br +#define PI_BAD_MILS_DELAY -65 // bad MILS delay (too large) +.br +#define PI_BAD_WAVE_ID -66 // non existent wave id +.br +#define PI_TOO_MANY_CBS -67 // No more CBs for waveform +.br +#define PI_TOO_MANY_OOL -68 // No more OOL for waveform +.br +#define PI_EMPTY_WAVEFORM -69 // attempt to create an empty waveform +.br +#define PI_NO_WAVEFORM_ID -70 // no more waveforms +.br +#define PI_I2C_OPEN_FAILED -71 // can't open I2C device +.br +#define PI_SER_OPEN_FAILED -72 // can't open serial device +.br +#define PI_SPI_OPEN_FAILED -73 // can't open SPI device +.br +#define PI_BAD_I2C_BUS -74 // bad I2C bus +.br +#define PI_BAD_I2C_ADDR -75 // bad I2C address +.br +#define PI_BAD_SPI_CHANNEL -76 // bad SPI channel +.br +#define PI_BAD_FLAGS -77 // bad i2c/spi/ser open flags +.br +#define PI_BAD_SPI_SPEED -78 // bad SPI speed +.br +#define PI_BAD_SER_DEVICE -79 // bad serial device name +.br +#define PI_BAD_SER_SPEED -80 // bad serial baud rate +.br +#define PI_BAD_PARAM -81 // bad i2c/spi/ser parameter +.br +#define PI_I2C_WRITE_FAILED -82 // i2c write failed +.br +#define PI_I2C_READ_FAILED -83 // i2c read failed +.br +#define PI_BAD_SPI_COUNT -84 // bad SPI count +.br +#define PI_SER_WRITE_FAILED -85 // ser write failed +.br +#define PI_SER_READ_FAILED -86 // ser read failed +.br +#define PI_SER_READ_NO_DATA -87 // ser read no data available +.br +#define PI_UNKNOWN_COMMAND -88 // unknown command +.br +#define PI_SPI_XFER_FAILED -89 // spi xfer/read/write failed +.br +#define PI_BAD_POINTER -90 // bad (NULL) pointer +.br +#define PI_NO_AUX_SPI -91 // no auxiliary SPI on Pi A or B +.br +#define PI_NOT_PWM_GPIO -92 // GPIO is not in use for PWM +.br +#define PI_NOT_SERVO_GPIO -93 // GPIO is not in use for servo pulses +.br +#define PI_NOT_HCLK_GPIO -94 // GPIO has no hardware clock +.br +#define PI_NOT_HPWM_GPIO -95 // GPIO has no hardware PWM +.br +#define PI_BAD_HPWM_FREQ -96 // hardware PWM frequency not 1-125M +.br +#define PI_BAD_HPWM_DUTY -97 // hardware PWM dutycycle not 0-1M +.br +#define PI_BAD_HCLK_FREQ -98 // hardware clock frequency not 4689-250M +.br +#define PI_BAD_HCLK_PASS -99 // need password to use hardware clock 1 +.br +#define PI_HPWM_ILLEGAL -100 // illegal, PWM in use for main clock +.br +#define PI_BAD_DATABITS -101 // serial data bits not 1-32 +.br +#define PI_BAD_STOPBITS -102 // serial (half) stop bits not 2-8 +.br +#define PI_MSG_TOOBIG -103 // socket/pipe message too big +.br +#define PI_BAD_MALLOC_MODE -104 // bad memory allocation mode +.br +#define PI_TOO_MANY_SEGS -105 // too many I2C transaction segments +.br +#define PI_BAD_I2C_SEG -106 // an I2C transaction segment failed +.br +#define PI_BAD_SMBUS_CMD -107 // SMBus command not supported by driver +.br +#define PI_NOT_I2C_GPIO -108 // no bit bang I2C in progress on GPIO +.br +#define PI_BAD_I2C_WLEN -109 // bad I2C write length +.br +#define PI_BAD_I2C_RLEN -110 // bad I2C read length +.br +#define PI_BAD_I2C_CMD -111 // bad I2C command +.br +#define PI_BAD_I2C_BAUD -112 // bad I2C baud rate, not 50-500k +.br +#define PI_CHAIN_LOOP_CNT -113 // bad chain loop count +.br +#define PI_BAD_CHAIN_LOOP -114 // empty chain loop +.br +#define PI_CHAIN_COUNTER -115 // too many chain counters +.br +#define PI_BAD_CHAIN_CMD -116 // bad chain command +.br +#define PI_BAD_CHAIN_DELAY -117 // bad chain delay micros +.br +#define PI_CHAIN_NESTING -118 // chain counters nested too deeply +.br +#define PI_CHAIN_TOO_BIG -119 // chain is too long +.br +#define PI_DEPRECATED -120 // deprecated function removed +.br +#define PI_BAD_SER_INVERT -121 // bit bang serial invert not 0 or 1 +.br +#define PI_BAD_EDGE -122 // bad ISR edge value, not 0-2 +.br +#define PI_BAD_ISR_INIT -123 // bad ISR initialisation +.br +#define PI_BAD_FOREVER -124 // loop forever must be last command +.br +#define PI_BAD_FILTER -125 // bad filter parameter +.br +#define PI_BAD_PAD -126 // bad pad number +.br +#define PI_BAD_STRENGTH -127 // bad pad drive strength +.br +#define PI_FIL_OPEN_FAILED -128 // file open failed +.br +#define PI_BAD_FILE_MODE -129 // bad file mode +.br +#define PI_BAD_FILE_FLAG -130 // bad file flag +.br +#define PI_BAD_FILE_READ -131 // bad file read +.br +#define PI_BAD_FILE_WRITE -132 // bad file write +.br +#define PI_FILE_NOT_ROPEN -133 // file not open for read +.br +#define PI_FILE_NOT_WOPEN -134 // file not open for write +.br +#define PI_BAD_FILE_SEEK -135 // bad file seek +.br +#define PI_NO_FILE_MATCH -136 // no files match pattern +.br +#define PI_NO_FILE_ACCESS -137 // no permission to access file +.br +#define PI_FILE_IS_A_DIR -138 // file is a directory +.br +#define PI_BAD_SHELL_STATUS -139 // bad shell return status +.br +#define PI_BAD_SCRIPT_NAME -140 // bad script name +.br +#define PI_BAD_SPI_BAUD -141 // bad SPI baud rate, not 50-500k +.br +#define PI_NOT_SPI_GPIO -142 // no bit bang SPI in progress on GPIO +.br +#define PI_BAD_EVENT_ID -143 // bad event id +.br +#define PI_CMD_INTERRUPTED -144 // Used by Python +.br + +.br +#define PI_PIGIF_ERR_0 -2000 +.br +#define PI_PIGIF_ERR_99 -2099 +.br + +.br +#define PI_CUSTOM_ERR_0 -3000 +.br +#define PI_CUSTOM_ERR_999 -3999 +.br + +.br + +.EE +.SH Defaults + +.EX + +.br +#define PI_DEFAULT_BUFFER_MILLIS 120 +.br +#define PI_DEFAULT_CLK_MICROS 5 +.br +#define PI_DEFAULT_CLK_PERIPHERAL PI_CLOCK_PCM +.br +#define PI_DEFAULT_IF_FLAGS 0 +.br +#define PI_DEFAULT_FOREGROUND 0 +.br +#define PI_DEFAULT_DMA_CHANNEL 14 +.br +#define PI_DEFAULT_DMA_PRIMARY_CHANNEL 14 +.br +#define PI_DEFAULT_DMA_SECONDARY_CHANNEL 6 +.br +#define PI_DEFAULT_SOCKET_PORT 8888 +.br +#define PI_DEFAULT_SOCKET_PORT_STR "8888" +.br +#define PI_DEFAULT_SOCKET_ADDR_STR "127.0.0.1" +.br +#define PI_DEFAULT_UPDATE_MASK_UNKNOWN 0x0000000FFFFFFCLL +.br +#define PI_DEFAULT_UPDATE_MASK_B1 0x03E7CF93 +.br +#define PI_DEFAULT_UPDATE_MASK_A_B2 0xFBC7CF9C +.br +#define PI_DEFAULT_UPDATE_MASK_APLUS_BPLUS 0x0080480FFFFFFCLL +.br +#define PI_DEFAULT_UPDATE_MASK_ZERO 0x0080000FFFFFFCLL +.br +#define PI_DEFAULT_UPDATE_MASK_PI2B 0x0080480FFFFFFCLL +.br +#define PI_DEFAULT_UPDATE_MASK_PI3B 0x0000000FFFFFFCLL +.br +#define PI_DEFAULT_UPDATE_MASK_COMPUTE 0x00FFFFFFFFFFFFLL +.br +#define PI_DEFAULT_MEM_ALLOC_MODE PI_MEM_ALLOC_AUTO +.br + +.br +#define PI_DEFAULT_CFG_INTERNALS 0 +.br + +.br + +.EE + +.SH SEE ALSO + +pigpiod(1), pig2vcd(1), pigs(1), pigpiod_if(3), pigpiod_if2(3) +.SH AUTHOR + +joan@abyz.me.uk diff --git a/thirdparty/PIGPIO/pigpio.c b/thirdparty/PIGPIO/pigpio.c new file mode 100644 index 0000000000..b63b4a8954 --- /dev/null +++ b/thirdparty/PIGPIO/pigpio.c @@ -0,0 +1,13577 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* pigpio version 68 */ + +/* include ------------------------------------------------------- */ + +#define _GNU_SOURCE + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "pigpio.h" + +#include "command.h" + + +/* --------------------------------------------------------------- */ + +/* + 0 GPFSEL0 GPIO Function Select 0 + 1 GPFSEL1 GPIO Function Select 1 + 2 GPFSEL2 GPIO Function Select 2 + 3 GPFSEL3 GPIO Function Select 3 + 4 GPFSEL4 GPIO Function Select 4 + 5 GPFSEL5 GPIO Function Select 5 + 6 - Reserved + 7 GPSET0 GPIO Pin Output Set 0 + 8 GPSET1 GPIO Pin Output Set 1 + 9 - Reserved +10 GPCLR0 GPIO Pin Output Clear 0 +11 GPCLR1 GPIO Pin Output Clear 1 +12 - Reserved +13 GPLEV0 GPIO Pin Level 0 +14 GPLEV1 GPIO Pin Level 1 +15 - Reserved +16 GPEDS0 GPIO Pin Event Detect Status 0 +17 GPEDS1 GPIO Pin Event Detect Status 1 +18 - Reserved +19 GPREN0 GPIO Pin Rising Edge Detect Enable 0 +20 GPREN1 GPIO Pin Rising Edge Detect Enable 1 +21 - Reserved +22 GPFEN0 GPIO Pin Falling Edge Detect Enable 0 +23 GPFEN1 GPIO Pin Falling Edge Detect Enable 1 +24 - Reserved +25 GPHEN0 GPIO Pin High Detect Enable 0 +26 GPHEN1 GPIO Pin High Detect Enable 1 +27 - Reserved +28 GPLEN0 GPIO Pin Low Detect Enable 0 +29 GPLEN1 GPIO Pin Low Detect Enable 1 +30 - Reserved +31 GPAREN0 GPIO Pin Async. Rising Edge Detect 0 +32 GPAREN1 GPIO Pin Async. Rising Edge Detect 1 +33 - Reserved +34 GPAFEN0 GPIO Pin Async. Falling Edge Detect 0 +35 GPAFEN1 GPIO Pin Async. Falling Edge Detect 1 +36 - Reserved +37 GPPUD GPIO Pin Pull-up/down Enable +38 GPPUDCLK0 GPIO Pin Pull-up/down Enable Clock 0 +39 GPPUDCLK1 GPIO Pin Pull-up/down Enable Clock 1 +40 - Reserved +41 - Test +*/ + +/* +0 CS DMA Channel 0 Control and Status +1 CPI_ONBLK_AD DMA Channel 0 Control Block Address +2 TI DMA Channel 0 CB Word 0 (Transfer Information) +3 SOURCE_AD DMA Channel 0 CB Word 1 (Source Address) +4 DEST_AD DMA Channel 0 CB Word 2 (Destination Address) +5 TXFR_LEN DMA Channel 0 CB Word 3 (Transfer Length) +6 STRIDE DMA Channel 0 CB Word 4 (2D Stride) +7 NEXTCPI_ONBK DMA Channel 0 CB Word 5 (Next CB Address) +8 DEBUG DMA Channel 0 Debug +*/ + +/* +DEBUG register bits + +bit 2 READ_ERROR + + Slave Read Response Error RW 0x0 + + Set if the read operation returned an error value on + the read response bus. It can be cleared by writing + a 1. + +bit 1 FIFO_ERROR + + Fifo Error RW 0x0 + + Set if the optional read Fifo records an error + condition. It can be cleared by writing a 1. + +bit 0 READ_LAST_NOT_SET_ERROR + + Read Last Not Set Error RW 0x0 + + If the AXI read last signal was not set when + expected, then this error bit will be set. It can be + cleared by writing a 1. +*/ + +/* +0 CTL PWM Control +1 STA PWM Status +2 DMAC PWM DMA Configuration +4 RNG1 PWM Channel 1 Range +5 DAT1 PWM Channel 1 Data +6 FIF1 PWM FIFO Input +8 RNG2 PWM Channel 2 Range +9 DAT2 PWM Channel 2 Data +*/ + +/* +0 PCM_CS PCM Control and Status +1 PCM_FIFO PCM FIFO Data +2 PCM_MODE PCM Mode +3 PCM_RXC PCM Receive Configuration +4 PCM_TXC PCM Transmit Configuration +5 PCM_DREQ PCM DMA Request Level +6 PCM_INTEN PCM Interrupt Enables +7 PCM_INTSTC PCM Interrupt Status & Clear +8 PCM_GRAY PCM Gray Mode Control +*/ + +/* +0 CS System Timer Control/Status +1 CLO System Timer Counter Lower 32 bits +2 CHI System Timer Counter Higher 32 bits +3 C0 System Timer Compare 0 +4 C1 System Timer Compare 1 +5 C2 System Timer Compare 2 +6 C3 System Timer Compare 3 +*/ + +/* define -------------------------------------------------------- */ + +#define THOUSAND 1000 +#define MILLION 1000000 +#define BILLION 1000000000 + +#define BANK (gpio>>5) + +#define BIT (1<<(gpio&0x1F)) + +#ifndef EMBEDDED_IN_VM +#define DBG(level, format, arg...) DO_DBG(level, format, ## arg) +#else +#define DBG(level, format, arg...) +#endif + +#define DO_DBG(level, format, arg...) \ + { \ + if ((gpioCfg.dbgLevel >= level) && \ + (!(gpioCfg.internals & PI_CFG_NOSIGHANDLER))) \ + fprintf(stderr, "%s %s: " format "\n" , \ + myTimeStamp(), __FUNCTION__ , ## arg); \ + } + +#ifndef DISABLE_SER_CHECK_INITED +#define SER_CHECK_INITED CHECK_INITED +#else +#define SER_CHECK_INITED +#endif + +#define CHECK_INITED \ + do \ + { \ + if (!libInitialised) \ + { \ + DBG(DBG_ALWAYS, \ + "pigpio uninitialised, call gpioInitialise()"); \ + return PI_NOT_INITIALISED; \ + } \ + } \ + while (0) + +#define CHECK_INITED_RET_NULL_PTR \ + do \ + { \ + if (!libInitialised) \ + { \ + DBG(DBG_ALWAYS, \ + "pigpio uninitialised, call gpioInitialise()"); \ + return (NULL); \ + } \ + } \ + while (0) + +#define CHECK_INITED_RET_NIL \ + do \ + { \ + if (!libInitialised) \ + { \ + DBG(DBG_ALWAYS, \ + "pigpio uninitialised, call gpioInitialise()"); \ + } \ + } \ + while (0) + +#define CHECK_NOT_INITED \ + do \ + { \ + if (libInitialised) \ + { \ + DBG(DBG_ALWAYS, \ + "pigpio initialised, call gpioTerminate()"); \ + return PI_INITIALISED; \ + } \ + } \ + while (0) + +#define SOFT_ERROR(x, format, arg...) \ + do \ + { \ + DBG(DBG_ALWAYS, format, ## arg); \ + return x; \ + } \ + while (0) + +#define TIMER_ADD(a, b, result) \ + do \ + { \ + (result)->tv_sec = (a)->tv_sec + (b)->tv_sec; \ + (result)->tv_nsec = (a)->tv_nsec + (b)->tv_nsec; \ + if ((result)->tv_nsec >= BILLION) \ + { \ + ++(result)->tv_sec; \ + (result)->tv_nsec -= BILLION; \ + } \ + } \ + while (0) + +#define TIMER_SUB(a, b, result) \ + do \ + { \ + (result)->tv_sec = (a)->tv_sec - (b)->tv_sec; \ + (result)->tv_nsec = (a)->tv_nsec - (b)->tv_nsec; \ + if ((result)->tv_nsec < 0) \ + { \ + --(result)->tv_sec; \ + (result)->tv_nsec += BILLION; \ + } \ + } \ + while (0) + +#define PI_PERI_BUS 0x7E000000 + +#define AUX_BASE (pi_peri_phys + 0x00215000) +#define BSCS_BASE (pi_peri_phys + 0x00214000) +#define CLK_BASE (pi_peri_phys + 0x00101000) +#define DMA_BASE (pi_peri_phys + 0x00007000) +#define DMA15_BASE (pi_peri_phys + 0x00E05000) +#define GPIO_BASE (pi_peri_phys + 0x00200000) +#define PADS_BASE (pi_peri_phys + 0x00100000) +#define PCM_BASE (pi_peri_phys + 0x00203000) +#define PWM_BASE (pi_peri_phys + 0x0020C000) +#define SPI_BASE (pi_peri_phys + 0x00204000) +#define SYST_BASE (pi_peri_phys + 0x00003000) + +#define AUX_LEN 0xD8 +#define BSCS_LEN 0x40 +#define CLK_LEN 0xA8 +#define DMA_LEN 0x1000 /* allow access to all channels */ +#define GPIO_LEN 0xB4 +#define PADS_LEN 0x38 +#define PCM_LEN 0x24 +#define PWM_LEN 0x28 +#define SPI_LEN 0x18 +#define SYST_LEN 0x1C + +#define DMA_ENABLE (0xFF0/4) + +#define GPFSEL0 0 + +#define GPSET0 7 +#define GPSET1 8 + +#define GPCLR0 10 +#define GPCLR1 11 + +#define GPLEV0 13 +#define GPLEV1 14 + +#define GPEDS0 16 +#define GPEDS1 17 + +#define GPREN0 19 +#define GPREN1 20 +#define GPFEN0 22 +#define GPFEN1 23 +#define GPHEN0 25 +#define GPHEN1 26 +#define GPLEN0 28 +#define GPLEN1 29 +#define GPAREN0 31 +#define GPAREN1 32 +#define GPAFEN0 34 +#define GPAFEN1 35 + +#define GPPUD 37 +#define GPPUDCLK0 38 +#define GPPUDCLK1 39 + +#define DMA_CS 0 +#define DMA_CONBLK_AD 1 +#define DMA_DEBUG 8 + +/* DMA CS Control and Status bits */ +#define DMA_CHANNEL_RESET (1<<31) +#define DMA_WAIT_ON_WRITES (1<<28) +#define DMA_PANIC_PRIORITY(x) ((x)<<20) +#define DMA_PRIORITY(x) ((x)<<16) +#define DMA_INTERRUPT_STATUS (1<< 2) +#define DMA_END_FLAG (1<< 1) +#define DMA_ACTIVATE (1<< 0) + +/* DMA control block "info" field bits */ +#define DMA_NO_WIDE_BURSTS (1<<26) +#define DMA_PERIPHERAL_MAPPING(x) ((x)<<16) +#define DMA_BURST_LENGTH(x) ((x)<<12) +#define DMA_SRC_IGNORE (1<<11) +#define DMA_SRC_DREQ (1<<10) +#define DMA_SRC_WIDTH (1<< 9) +#define DMA_SRC_INC (1<< 8) +#define DMA_DEST_IGNORE (1<< 7) +#define DMA_DEST_DREQ (1<< 6) +#define DMA_DEST_WIDTH (1<< 5) +#define DMA_DEST_INC (1<< 4) +#define DMA_WAIT_RESP (1<< 3) + +#define DMA_DEBUG_READ_ERR (1<<2) +#define DMA_DEBUG_FIFO_ERR (1<<1) +#define DMA_DEBUG_RD_LST_NOT_SET_ERR (1<<0) + +#define DMA_LITE_FIRST 7 +#define DMA_LITE_MAX 0xfffc + +#define PWM_CTL 0 +#define PWM_STA 1 +#define PWM_DMAC 2 +#define PWM_RNG1 4 +#define PWM_DAT1 5 +#define PWM_FIFO 6 +#define PWM_RNG2 8 +#define PWM_DAT2 9 + +#define PWM_CTL_MSEN2 (1<<15) +#define PWM_CTL_PWEN2 (1<<8) +#define PWM_CTL_MSEN1 (1<<7) +#define PWM_CTL_CLRF1 (1<<6) +#define PWM_CTL_USEF1 (1<<5) +#define PWM_CTL_MODE1 (1<<1) +#define PWM_CTL_PWEN1 (1<<0) + +#define PWM_DMAC_ENAB (1 <<31) +#define PWM_DMAC_PANIC(x) ((x)<< 8) +#define PWM_DMAC_DREQ(x) (x) + +#define PCM_CS 0 +#define PCM_FIFO 1 +#define PCM_MODE 2 +#define PCM_RXC 3 +#define PCM_TXC 4 +#define PCM_DREQ 5 +#define PCM_INTEN 6 +#define PCM_INTSTC 7 +#define PCM_GRAY 8 + +#define PCM_CS_STBY (1 <<25) +#define PCM_CS_SYNC (1 <<24) +#define PCM_CS_RXSEX (1 <<23) +#define PCM_CS_RXERR (1 <<16) +#define PCM_CS_TXERR (1 <<15) +#define PCM_CS_DMAEN (1 <<9) +#define PCM_CS_RXTHR(x) ((x)<<7) +#define PCM_CS_TXTHR(x) ((x)<<5) +#define PCM_CS_RXCLR (1 <<4) +#define PCM_CS_TXCLR (1 <<3) +#define PCM_CS_TXON (1 <<2) +#define PCM_CS_RXON (1 <<1) +#define PCM_CS_EN (1 <<0) + +#define PCM_MODE_CLK_DIS (1 <<28) +#define PCM_MODE_PDMN (1 <<27) +#define PCM_MODE_PDME (1 <<26) +#define PCM_MODE_FRXP (1 <<25) +#define PCM_MODE_FTXP (1 <<24) +#define PCM_MODE_CLKM (1 <<23) +#define PCM_MODE_CLKI (1 <<22) +#define PCM_MODE_FSM (1 <<21) +#define PCM_MODE_FSI (1 <<20) +#define PCM_MODE_FLEN(x) ((x)<<10) +#define PCM_MODE_FSLEN(x) ((x)<< 0) + +#define PCM_RXC_CH1WEX (1 <<31) +#define PCM_RXC_CH1EN (1 <<30) +#define PCM_RXC_CH1POS(x) ((x)<<20) +#define PCM_RXC_CH1WID(x) ((x)<<16) +#define PCM_RXC_CH2WEX (1 <<15) +#define PCM_RXC_CH2EN (1 <<14) +#define PCM_RXC_CH2POS(x) ((x)<< 4) +#define PCM_RXC_CH2WID(x) ((x)<< 0) + +#define PCM_TXC_CH1WEX (1 <<31) +#define PCM_TXC_CH1EN (1 <<30) +#define PCM_TXC_CH1POS(x) ((x)<<20) +#define PCM_TXC_CH1WID(x) ((x)<<16) +#define PCM_TXC_CH2WEX (1 <<15) +#define PCM_TXC_CH2EN (1 <<14) +#define PCM_TXC_CH2POS(x) ((x)<< 4) +#define PCM_TXC_CH2WID(x) ((x)<< 0) + +#define PCM_DREQ_TX_PANIC(x) ((x)<<24) +#define PCM_DREQ_RX_PANIC(x) ((x)<<16) +#define PCM_DREQ_TX_REQ_L(x) ((x)<< 8) +#define PCM_DREQ_RX_REQ_L(x) ((x)<< 0) + +#define PCM_INTEN_RXERR (1<<3) +#define PCM_INTEN_TXERR (1<<2) +#define PCM_INTEN_RXR (1<<1) +#define PCM_INTEN_TXW (1<<0) + +#define PCM_INTSTC_RXERR (1<<3) +#define PCM_INTSTC_TXERR (1<<2) +#define PCM_INTSTC_RXR (1<<1) +#define PCM_INTSTC_TXW (1<<0) + +#define PCM_GRAY_FLUSH (1<<2) +#define PCM_GRAY_CLR (1<<1) +#define PCM_GRAY_EN (1<<0) + +#define BCM_PASSWD (0x5A<<24) + +#define CLK_CTL_MASH(x)((x)<<9) +#define CLK_CTL_BUSY (1 <<7) +#define CLK_CTL_KILL (1 <<5) +#define CLK_CTL_ENAB (1 <<4) +#define CLK_CTL_SRC(x) ((x)<<0) + +#define CLK_SRCS 2 + +#define CLK_CTL_SRC_OSC 1 +#define CLK_CTL_SRC_PLLD 6 + +#define CLK_OSC_FREQ 19200000 +#define CLK_PLLD_FREQ 500000000 + +#define CLK_DIV_DIVI(x) ((x)<<12) +#define CLK_DIV_DIVF(x) ((x)<< 0) + +#define CLK_GP0_CTL 28 +#define CLK_GP0_DIV 29 +#define CLK_GP1_CTL 30 +#define CLK_GP1_DIV 31 +#define CLK_GP2_CTL 32 +#define CLK_GP2_DIV 33 + +#define CLK_PCMCTL 38 +#define CLK_PCMDIV 39 + +#define CLK_PWMCTL 40 +#define CLK_PWMDIV 41 + +#define SYST_CS 0 +#define SYST_CLO 1 +#define SYST_CHI 2 + +/* SPI */ + +#define SPI_CS 0 +#define SPI_FIFO 1 +#define SPI_CLK 2 +#define SPI_DLEN 3 +#define SPI_LTOH 4 +#define SPI_DC 5 + +#define SPI_CS_LEN_LONG (1<<25) +#define SPI_CS_DMA_LEN (1<<24) +#define SPI_CS_CSPOLS(x) ((x)<<21) +#define SPI_CS_RXF (1<<20) +#define SPI_CS_RXR (1<<19) +#define SPI_CS_TXD (1<<18) +#define SPI_CS_RXD (1<<17) +#define SPI_CS_DONE (1<<16) +#define SPI_CS_LEN (1<<13) +#define SPI_CS_REN (1<<12) +#define SPI_CS_ADCS (1<<11) +#define SPI_CS_INTR (1<<10) +#define SPI_CS_INTD (1<<9) +#define SPI_CS_DMAEN (1<<8) +#define SPI_CS_TA (1<<7) +#define SPI_CS_CSPOL(x) ((x)<<6) +#define SPI_CS_CLEAR(x) ((x)<<4) +#define SPI_CS_MODE(x) ((x)<<2) +#define SPI_CS_CS(x) ((x)<<0) + +#define SPI_DC_RPANIC(x) ((x)<<24) +#define SPI_DC_RDREQ(x) ((x)<<16) +#define SPI_DC_TPANIC(x) ((x)<<8) +#define SPI_DC_TDREQ(x) ((x)<<0) + +#define SPI_MODE0 0 +#define SPI_MODE1 1 +#define SPI_MODE2 2 +#define SPI_MODE3 3 + +#define SPI_CS0 0 +#define SPI_CS1 1 +#define SPI_CS2 2 + +/* standard SPI gpios (ALT0) */ + +#define PI_SPI_CE0 8 +#define PI_SPI_CE1 7 +#define PI_SPI_SCLK 11 +#define PI_SPI_MISO 9 +#define PI_SPI_MOSI 10 + +/* auxiliary SPI gpios (ALT4) */ + +#define PI_ASPI_CE0 18 +#define PI_ASPI_CE1 17 +#define PI_ASPI_CE2 16 +#define PI_ASPI_MISO 19 +#define PI_ASPI_MOSI 20 +#define PI_ASPI_SCLK 21 + +/* AUX */ + +#define AUX_IRQ 0 +#define AUX_ENABLES 1 + +#define AUX_MU_IO_REG 16 +#define AUX_MU_IER_REG 17 +#define AUX_MU_IIR_REG 18 +#define AUX_MU_LCR_REG 19 +#define AUX_MU_MCR_REG 20 +#define AUX_MU_LSR_REG 21 +#define AUX_MU_MSR_REG 22 +#define AUX_MU_SCRATCH 23 +#define AUX_MU_CNTL_REG 24 +#define AUX_MU_STAT_REG 25 +#define AUX_MU_BAUD_REG 26 + +#define AUX_SPI0_CNTL0_REG 32 +#define AUX_SPI0_CNTL1_REG 33 +#define AUX_SPI0_STAT_REG 34 +#define AUX_SPI0_PEEK_REG 35 + +#define AUX_SPI0_IO_REG 40 +#define AUX_SPI0_TX_HOLD 44 + +#define AUX_SPI1_CNTL0_REG 48 +#define AUX_SPI1_CNTL1_REG 49 +#define AUX_SPI1_STAT_REG 50 +#define AUX_SPI1_PEEK_REG 51 + +#define AUX_SPI1_IO_REG 56 +#define AUX_SPI1_TX_HOLD 60 + +#define AUXENB_SPI2 (1<<2) +#define AUXENB_SPI1 (1<<1) +#define AUXENB_UART (1<<0) + +#define AUXSPI_CNTL0_SPEED(x) ((x)<<20) +#define AUXSPI_CNTL0_CS(x) ((x)<<17) +#define AUXSPI_CNTL0_POSTINP (1<<16) +#define AUXSPI_CNTL0_VAR_CS (1<<15) +#define AUXSPI_CNTL0_VAR_WIDTH (1<<14) +#define AUXSPI_CNTL0_DOUT_HOLD(x) ((x)<<12) +#define AUXSPI_CNTL0_ENABLE (1<<11) +#define AUXSPI_CNTL0_IN_RISING(x) ((x)<<10) +#define AUXSPI_CNTL0_CLR_FIFOS (1<<9) +#define AUXSPI_CNTL0_OUT_RISING(x) ((x)<<8) +#define AUXSPI_CNTL0_INVERT_CLK(x) ((x)<<7) +#define AUXSPI_CNTL0_MSB_FIRST(x) ((x)<<6) +#define AUXSPI_CNTL0_SHIFT_LEN(x) ((x)<<0) + +#define AUXSPI_CNTL1_CS_HIGH(x) ((x)<<8) +#define AUXSPI_CNTL1_TX_IRQ (1<<7) +#define AUXSPI_CNTL1_DONE_IRQ (1<<6) +#define AUXSPI_CNTL1_MSB_FIRST(x)((x)<<1) +#define AUXSPI_CNTL1_KEEP_INPUT (1<<0) + +#define AUXSPI_STAT_TX_FIFO(x) ((x)<<28) +#define AUXSPI_STAT_RX_FIFO(x) ((x)<<20) +#define AUXSPI_STAT_TX_FULL (1<<10) +#define AUXSPI_STAT_TX_EMPTY (1<<9) +#define AUXSPI_STAT_RX_EMPTY (1<<7) +#define AUXSPI_STAT_BUSY (1<<6) +#define AUXSPI_STAT_BITS(x) ((x)<<0) + +/* --------------------------------------------------------------- */ + +#define NORMAL_DMA (DMA_NO_WIDE_BURSTS | DMA_WAIT_RESP) + +#define TIMED_DMA(x) (DMA_DEST_DREQ | DMA_PERIPHERAL_MAPPING(x)) + +#define PCM_TIMER (((PCM_BASE + PCM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS) +#define PWM_TIMER (((PWM_BASE + PWM_FIFO*4) & 0x00ffffff) | PI_PERI_BUS) + +#define DBG_MIN_LEVEL 0 +#define DBG_ALWAYS 0 +#define DBG_STARTUP 1 +#define DBG_DMACBS 2 +#define DBG_SCRIPT 3 +#define DBG_USER 4 +#define DBG_INTERNAL 5 +#define DBG_SLOW_TICK 6 +#define DBG_FAST_TICK 7 +#define DBG_MAX_LEVEL 8 + +#define GPIO_UNDEFINED 0 +#define GPIO_WRITE 1 +#define GPIO_PWM 2 +#define GPIO_SERVO 3 +#define GPIO_HW_CLK 4 +#define GPIO_HW_PWM 5 +#define GPIO_SPI 6 +#define GPIO_I2C 7 + +#define STACK_SIZE (256*1024) + +#define PAGE_SIZE 4096 + +#define PWM_FREQS 18 + +#define CYCLES_PER_BLOCK 80 +#define PULSE_PER_CYCLE 25 + +#define PAGES_PER_BLOCK 53 + +#define CBS_PER_IPAGE 117 +#define LVS_PER_IPAGE 38 +#define OFF_PER_IPAGE 38 +#define TCK_PER_IPAGE 2 +#define ON_PER_IPAGE 2 +#define PAD_PER_IPAGE 7 + +#define CBS_PER_OPAGE 118 +#define OOL_PER_OPAGE 79 + +/* +Wave Count Block + +Assumes two counters per block. Each counter 4 * 16 (16^4=65536) + 0 CB [13] 13*8 104 CBs for counter 0 + 104 CB [13] 13*8 104 CBs for counter 1 + 208 CB [60] 60*8 480 CBs reserved to construct wave + 688 OOL [60] 60*1 60 OOL reserved to construct wave + 748 OOL[136] 136*1 136 OOL for counter 0 + 884 OOL[136] 136*1 136 OOL for counter 1 +1020 pad [4] 4*1 4 spare +*/ + +#define WCB_CNT_PER_PAGE 2 +#define WCB_COUNTERS (WCB_CNT_PER_PAGE * PI_WAVE_COUNT_PAGES) +#define WCB_CNT_CBS 13 +#define WCB_CNT_OOL 68 +#define WCB_COUNTER_OOL (WCB_CNT_PER_PAGE * WCB_CNT_OOL) +#define WCB_COUNTER_CBS (WCB_CNT_PER_PAGE * WCB_CNT_CBS) +#define WCB_CHAIN_CBS 60 +#define WCB_CHAIN_OOL 60 + +#define CBS_PER_CYCLE ((PULSE_PER_CYCLE*3)+2) + +#define NUM_CBS (CBS_PER_CYCLE * bufferCycles) + +#define SUPERCYCLE 800 +#define SUPERLEVEL 20000 + +#define BLOCK_SIZE (PAGES_PER_BLOCK*PAGE_SIZE) + +#define DMAI_PAGES (PAGES_PER_BLOCK * bufferBlocks) + +#define DMAO_PAGES (PAGES_PER_BLOCK * PI_WAVE_BLOCKS) + +#define NUM_WAVE_OOL (DMAO_PAGES * OOL_PER_OPAGE) +#define NUM_WAVE_CBS (DMAO_PAGES * CBS_PER_OPAGE) + +#define TICKSLOTS 50 + +#define PI_I2C_CLOSED 0 +#define PI_I2C_RESERVED 1 +#define PI_I2C_OPENED 2 + +#define PI_SPI_CLOSED 0 +#define PI_SPI_RESERVED 1 +#define PI_SPI_OPENED 2 + +#define PI_SER_CLOSED 0 +#define PI_SER_RESERVED 1 +#define PI_SER_OPENED 2 + +#define PI_FILE_CLOSED 0 +#define PI_FILE_RESERVED 1 +#define PI_FILE_OPENED 2 + +#define PI_NOTIFY_CLOSED 0 +#define PI_NOTIFY_RESERVED 1 +#define PI_NOTIFY_CLOSING 2 +#define PI_NOTIFY_OPENED 3 +#define PI_NOTIFY_RUNNING 4 +#define PI_NOTIFY_PAUSED 5 + +#define PI_WFRX_NONE 0 +#define PI_WFRX_SERIAL 1 +#define PI_WFRX_I2C_SDA 2 +#define PI_WFRX_I2C_SCL 3 +#define PI_WFRX_SPI_SCLK 4 +#define PI_WFRX_SPI_MISO 5 +#define PI_WFRX_SPI_MOSI 6 +#define PI_WFRX_SPI_CS 7 + +#define PI_WF_MICROS 1 + +#define BPD 4 + +#define MAX_REPORT 250 +#define MAX_SAMPLE 4000 + +#define DEFAULT_PWM_IDX 5 + +#define MAX_EMITS (PIPE_BUF / sizeof(gpioReport_t)) + +#define SRX_BUF_SIZE 8192 + +#define PI_I2C_RETRIES 0x0701 +#define PI_I2C_TIMEOUT 0x0702 +#define PI_I2C_SLAVE 0x0703 +#define PI_I2C_FUNCS 0x0705 +#define PI_I2C_RDWR 0x0707 +#define PI_I2C_SMBUS 0x0720 + +#define PI_I2C_SMBUS_READ 1 +#define PI_I2C_SMBUS_WRITE 0 + +#define PI_I2C_SMBUS_QUICK 0 +#define PI_I2C_SMBUS_BYTE 1 +#define PI_I2C_SMBUS_BYTE_DATA 2 +#define PI_I2C_SMBUS_WORD_DATA 3 +#define PI_I2C_SMBUS_PROC_CALL 4 +#define PI_I2C_SMBUS_BLOCK_DATA 5 +#define PI_I2C_SMBUS_I2C_BLOCK_BROKEN 6 +#define PI_I2C_SMBUS_BLOCK_PROC_CALL 7 +#define PI_I2C_SMBUS_I2C_BLOCK_DATA 8 + +#define PI_I2C_SMBUS_BLOCK_MAX 32 +#define PI_I2C_SMBUS_I2C_BLOCK_MAX 32 + +#define PI_I2C_FUNC_SMBUS_QUICK 0x00010000 +#define PI_I2C_FUNC_SMBUS_READ_BYTE 0x00020000 +#define PI_I2C_FUNC_SMBUS_WRITE_BYTE 0x00040000 +#define PI_I2C_FUNC_SMBUS_READ_BYTE_DATA 0x00080000 +#define PI_I2C_FUNC_SMBUS_WRITE_BYTE_DATA 0x00100000 +#define PI_I2C_FUNC_SMBUS_READ_WORD_DATA 0x00200000 +#define PI_I2C_FUNC_SMBUS_WRITE_WORD_DATA 0x00400000 +#define PI_I2C_FUNC_SMBUS_PROC_CALL 0x00800000 +#define PI_I2C_FUNC_SMBUS_READ_BLOCK_DATA 0x01000000 +#define PI_I2C_FUNC_SMBUS_WRITE_BLOCK_DATA 0x02000000 +#define PI_I2C_FUNC_SMBUS_READ_I2C_BLOCK 0x04000000 +#define PI_I2C_FUNC_SMBUS_WRITE_I2C_BLOCK 0x08000000 + +#define PI_MASH_MAX_FREQ 23800000 + +#define FLUSH_PAGES 1024 + +#define MB_DEV_MAJOR 100 + +#define MB_IOCTL _IOWR(MB_DEV_MAJOR, 0, char *) + +#define MB_DEV1 "/dev/vcio" +#define MB_DEV2 "/dev/pigpio-mb" + +#define BUS_TO_PHYS(x) ((x)&~0xC0000000) + +#define MB_END_TAG 0 +#define MB_PROCESS_REQUEST 0 + +#define MB_ALLOCATE_MEMORY_TAG 0x3000C +#define MB_LOCK_MEMORY_TAG 0x3000D +#define MB_UNLOCK_MEMORY_TAG 0x3000E +#define MB_RELEASE_MEMORY_TAG 0x3000F + +#define PI_SCRIPT_FREE 0 +#define PI_SCRIPT_RESERVED 1 +#define PI_SCRIPT_IN_USE 2 +#define PI_SCRIPT_DYING 3 + +#define PI_SCRIPT_HALT 0 +#define PI_SCRIPT_RUN 1 +#define PI_SCRIPT_DELETE 2 + +#define PI_SCRIPT_STACK_SIZE 256 + +#define PI_SPI_FLAGS_CHANNEL(x) ((x&7)<<29) + +#define PI_SPI_FLAGS_GET_CHANNEL(x) (((x)>>29)&7) +#define PI_SPI_FLAGS_GET_BITLEN(x) (((x)>>16)&63) +#define PI_SPI_FLAGS_GET_RX_LSB(x) (((x)>>15)&1) +#define PI_SPI_FLAGS_GET_TX_LSB(x) (((x)>>14)&1) +#define PI_SPI_FLAGS_GET_3WREN(x) (((x)>>10)&15) +#define PI_SPI_FLAGS_GET_3WIRE(x) (((x)>>9)&1) +#define PI_SPI_FLAGS_GET_AUX_SPI(x) (((x)>>8)&1) +#define PI_SPI_FLAGS_GET_RESVD(x) (((x)>>5)&7) +#define PI_SPI_FLAGS_GET_CSPOLS(x) (((x)>>2)&7) +#define PI_SPI_FLAGS_GET_MODE(x) ((x)&3) + +#define PI_SPI_FLAGS_GET_CPHA(x) ((x)&1) +#define PI_SPI_FLAGS_GET_CPOL(x) ((x)&2) +#define PI_SPI_FLAGS_GET_CSPOL(x) ((x)&4) + +#define PI_STARTING 0 +#define PI_RUNNING 1 +#define PI_ENDING 2 + +#define PI_THREAD_NONE 0 +#define PI_THREAD_STARTED 1 +#define PI_THREAD_RUNNING 2 + +#define PI_MAX_PATH 512 + +/* typedef ------------------------------------------------------- */ + +typedef void (*callbk_t) (); + +typedef struct +{ + rawCbs_t cb [128]; +} dmaPage_t; + +typedef struct +{ + rawCbs_t cb [CBS_PER_IPAGE]; + uint32_t level [LVS_PER_IPAGE]; + uint32_t gpioOff [OFF_PER_IPAGE]; + uint32_t tick [TCK_PER_IPAGE]; + uint32_t gpioOn [ON_PER_IPAGE]; + uint32_t periphData; + uint32_t pad [PAD_PER_IPAGE]; +} dmaIPage_t; + +typedef struct +{ + rawCbs_t cb [CBS_PER_OPAGE]; + uint32_t OOL [OOL_PER_OPAGE]; + uint32_t periphData; +} dmaOPage_t; + +typedef struct +{ + uint8_t is; + uint8_t pad; + uint16_t width; + uint16_t range; /* dutycycles specified by 0 .. range */ + uint16_t freqIdx; + uint16_t deferOff; + uint16_t deferRng; +} gpioInfo_t; + +typedef struct +{ + callbk_t func; + unsigned ex; + void *userdata; + + int wdSteadyUs; + uint32_t wdTick; + uint32_t wdLBitV; + + int nfSteadyUs; + int nfActiveUs; + int nfActive; + uint32_t nfTick1; + uint32_t nfTick2; + uint32_t nfLBitV; + uint32_t nfRBitV; + + uint32_t gfSteadyUs; + uint32_t gfTick; + uint32_t gfLBitV; + uint32_t gfRBitV; + +} gpioAlert_t; + +typedef struct +{ + callbk_t func; + unsigned ex; + void *userdata; + int ignore; + int fired; +} eventAlert_t; + +typedef struct +{ + unsigned gpio; + pthread_t *pth; + callbk_t func; + unsigned edge; + int timeout; + unsigned ex; + void *userdata; + int inited; +} gpioISR_t; + +typedef struct +{ + callbk_t func; + unsigned ex; + void *userdata; +} gpioSignal_t; + +typedef struct +{ + callbk_t func; + unsigned ex; + void *userdata; + uint32_t bits; +} gpioGetSamples_t; + +typedef struct +{ + callbk_t func; + unsigned ex; + void *userdata; + unsigned id; + unsigned running; + unsigned millis; + pthread_t pthId; +} gpioTimer_t; + +typedef struct +{ + unsigned id; + unsigned state; + unsigned request; + unsigned run_state; + uint32_t waitBits; + uint32_t eventBits; + uint32_t changedBits; + pthread_t *pthIdp; + pthread_mutex_t pthMutex; + pthread_cond_t pthCond; + cmdScript_t script; +} gpioScript_t; + + +typedef struct +{ + uint16_t valid; + uint16_t servoIdx; +} clkCfg_t; + +typedef struct +{ + uint16_t seqno; + uint16_t state; + uint32_t bits; + uint32_t eventBits; + uint32_t lastReportTick; + int fd; + int pipe; + int max_emits; +} gpioNotify_t; + +typedef struct +{ + uint16_t state; + int16_t fd; + uint32_t mode; +} fileInfo_t; + +typedef struct +{ + uint16_t state; + int16_t fd; + uint32_t addr; + uint32_t flags; + uint32_t funcs; +} i2cInfo_t; + +typedef struct +{ + uint16_t state; + int16_t fd; + uint32_t flags; +} serInfo_t; + +typedef struct +{ + uint16_t state; + unsigned speed; + uint32_t flags; +} spiInfo_t; + +typedef struct +{ + uint32_t alertTicks; + uint32_t lateTicks; + uint32_t moreToDo; + uint32_t diffTick[TICKSLOTS]; + uint32_t cbTicks; + uint32_t cbCalls; + uint32_t maxEmit; + uint32_t emitFrags; + uint32_t maxSamples; + uint32_t numSamples; + uint32_t DMARestarts; + uint32_t dmaInitCbsCount; + uint32_t goodPipeWrite; + uint32_t shortPipeWrite; + uint32_t wouldBlockPipeWrite; +} gpioStats_t; + +typedef struct +{ + unsigned bufferMilliseconds; + unsigned clockMicros; + unsigned clockPeriph; + unsigned DMAprimaryChannel; + unsigned DMAsecondaryChannel; + unsigned socketPort; + unsigned ifFlags; + unsigned memAllocMode; + unsigned dbgLevel; + unsigned alertFreq; + uint32_t internals; + /* + 0-3: dbgLevel + 4-7: alertFreq + */ +} gpioCfg_t; + +typedef struct +{ + uint32_t micros; + uint32_t highMicros; + uint32_t maxMicros; + uint32_t pulses; + uint32_t highPulses; + uint32_t maxPulses; + uint32_t cbs; + uint32_t highCbs; + uint32_t maxCbs; +} wfStats_t; + +typedef struct +{ + char *buf; + uint32_t bufSize; + int readPos; + int writePos; + uint32_t fullBit; /* nanoseconds */ + uint32_t halfBit; /* nanoseconds */ + int timeout; /* millisconds */ + uint32_t startBitTick; /* microseconds */ + uint32_t nextBitDiff; /* nanoseconds */ + int bit; + uint32_t data; + int bytes; /* 1, 2, 4 */ + int level; + int dataBits; /* 1-32 */ + int invert; /* 0, 1 */ +} wfRxSerial_t; + +typedef struct +{ + int SDA; + int SCL; + int delay; + int SDAMode; + int SCLMode; + int started; +} wfRxI2C_t; + +typedef struct +{ + int CS; + int MISO; + int MOSI; + int SCLK; + int usage; + int delay; + int spiFlags; + int MISOMode; + int MOSIMode; + int CSMode; + int SCLKMode; +} wfRxSPI_t; + +typedef struct +{ + int mode; + int gpio; + uint32_t baud; + pthread_mutex_t mutex; + union + { + wfRxSerial_t s; + wfRxI2C_t I; + wfRxSPI_t S; + }; +} wfRx_t; + +union my_smbus_data +{ + uint8_t byte; + uint16_t word; + uint8_t block[PI_I2C_SMBUS_BLOCK_MAX + 2]; +}; + +struct my_smbus_ioctl_data +{ + uint8_t read_write; + uint8_t command; + uint32_t size; + union my_smbus_data *data; +}; + +typedef struct +{ + pi_i2c_msg_t *msgs; /* pointers to pi_i2c_msgs */ + uint32_t nmsgs; /* number of pi_i2c_msgs */ +} my_i2c_rdwr_ioctl_data_t; + +typedef struct +{ + unsigned div; + unsigned frac; + unsigned clock; +} clkInf_t; + +typedef struct +{ + unsigned handle; /* mbAllocateMemory() */ + uintptr_t bus_addr; /* mbLockMemory() */ + uintptr_t *virtual_addr; /* mbMapMem() */ + unsigned size; /* in bytes */ +} DMAMem_t; + +/* global -------------------------------------------------------- */ + +/* initialise once then preserve */ + +static volatile uint32_t piCores = 0; +static volatile uint32_t pi_peri_phys = 0x20000000; +static volatile uint32_t pi_dram_bus = 0x40000000; +static volatile uint32_t pi_mem_flag = 0x0C; + +static int libInitialised = 0; + +/* initialise every gpioInitialise */ + +static struct timespec libStarted; + +static uint32_t sockNetAddr[MAX_CONNECT_ADDRESSES]; + +static int numSockNetAddr = 0; + +static uint32_t reportedLevel = 0; + +static int waveClockInited = 0; +static int PWMClockInited = 0; + +static volatile gpioStats_t gpioStats; + +static int gpioMaskSet = 0; + +/* initialise if not libInitialised */ + +static uint64_t gpioMask; + +static rawWave_t wf[3][PI_WAVE_MAX_PULSES]; + +static int wfc[3]={0, 0, 0}; + +static int wfcur=0; + +static wfStats_t wfStats= +{ + 0, 0, PI_WAVE_MAX_MICROS, + 0, 0, PI_WAVE_MAX_PULSES, + 0, 0, (DMAO_PAGES * CBS_PER_OPAGE) +}; + +static rawWaveInfo_t waveInfo[PI_MAX_WAVES]; + +static wfRx_t wfRx[PI_MAX_USER_GPIO+1]; + +static int waveOutBotCB = PI_WAVE_COUNT_PAGES*CBS_PER_OPAGE; +static int waveOutBotOOL = PI_WAVE_COUNT_PAGES*OOL_PER_OPAGE; +static int waveOutTopOOL = NUM_WAVE_OOL; +static int waveOutCount = 0; + +static uint32_t *waveEndPtr = NULL; + +static volatile uint32_t alertBits = 0; +static volatile uint32_t monitorBits = 0; +static volatile uint32_t notifyBits = 0; +static volatile uint32_t scriptBits = 0; +static volatile uint32_t gFilterBits = 0; +static volatile uint32_t nFilterBits = 0; +static volatile uint32_t wdogBits = 0; + +static volatile uint32_t scriptEventBits = 0; + +static volatile int runState = PI_STARTING; + +static int pthAlertRunning = PI_THREAD_NONE; +static int pthFifoRunning = PI_THREAD_NONE; +static int pthSocketRunning = PI_THREAD_NONE; + +static gpioAlert_t gpioAlert [PI_MAX_USER_GPIO+1]; + +static eventAlert_t eventAlert [PI_MAX_EVENT+1]; + +static gpioISR_t gpioISR [PI_MAX_GPIO+1]; + +static gpioGetSamples_t gpioGetSamples; + +static gpioInfo_t gpioInfo [PI_MAX_GPIO+1]; + +static gpioNotify_t gpioNotify [PI_NOTIFY_SLOTS]; + +static fileInfo_t fileInfo [PI_FILE_SLOTS]; +static i2cInfo_t i2cInfo [PI_I2C_SLOTS]; +static serInfo_t serInfo [PI_SER_SLOTS]; +static spiInfo_t spiInfo [PI_SPI_SLOTS]; + +static gpioScript_t gpioScript [PI_MAX_SCRIPTS]; + +static gpioSignal_t gpioSignal [PI_MAX_SIGNUM+1]; + +static gpioTimer_t gpioTimer [PI_MAX_TIMER+1]; + +static int pwmFreq[PWM_FREQS]; + +/* reset after gpioTerminated */ + +/* resources which must be released on gpioTerminate */ + +static FILE * inpFifo = NULL; +static FILE * outFifo = NULL; + +static int fdLock = -1; +static int fdMem = -1; +static int fdSock = -1; +static int fdPmap = -1; +static int fdMbox = -1; + +static DMAMem_t *dmaMboxBlk = MAP_FAILED; +static uintptr_t * * dmaPMapBlk = MAP_FAILED; +static dmaPage_t * * dmaVirt = MAP_FAILED; +static dmaPage_t * * dmaBus = MAP_FAILED; + +static dmaIPage_t * * dmaIVirt = MAP_FAILED; +static dmaIPage_t * * dmaIBus = MAP_FAILED; + +static dmaOPage_t * * dmaOVirt = MAP_FAILED; +static dmaOPage_t * * dmaOBus = MAP_FAILED; + +static volatile uint32_t * auxReg = MAP_FAILED; +static volatile uint32_t * bscsReg = MAP_FAILED; +static volatile uint32_t * clkReg = MAP_FAILED; +static volatile uint32_t * dmaReg = MAP_FAILED; +static volatile uint32_t * gpioReg = MAP_FAILED; +static volatile uint32_t * padsReg = MAP_FAILED; +static volatile uint32_t * pcmReg = MAP_FAILED; +static volatile uint32_t * pwmReg = MAP_FAILED; +static volatile uint32_t * spiReg = MAP_FAILED; +static volatile uint32_t * systReg = MAP_FAILED; + +static volatile uint32_t * dmaIn = MAP_FAILED; +static volatile uint32_t * dmaOut = MAP_FAILED; + +static uint32_t hw_clk_freq[3]; +static uint32_t hw_pwm_freq[2]; +static uint32_t hw_pwm_duty[2]; +static uint32_t hw_pwm_real_range[2]; + +static volatile gpioCfg_t gpioCfg = +{ + PI_DEFAULT_BUFFER_MILLIS, + PI_DEFAULT_CLK_MICROS, + PI_DEFAULT_CLK_PERIPHERAL, + PI_DEFAULT_DMA_PRIMARY_CHANNEL, + PI_DEFAULT_DMA_SECONDARY_CHANNEL, + PI_DEFAULT_SOCKET_PORT, + PI_DEFAULT_IF_FLAGS, + PI_DEFAULT_MEM_ALLOC_MODE, + 0, /* dbgLevel */ + 0, /* alertFreq */ + 0, /* internals */ +}; + +/* no initialisation required */ + +static unsigned bufferBlocks; /* number of blocks in buffer */ +static unsigned bufferCycles; /* number of cycles */ + +static pthread_t pthAlert; +static pthread_t pthFifo; +static pthread_t pthSocket; + +static uint32_t spi_dummy; + +static unsigned old_mode_ce0; +static unsigned old_mode_ce1; +static unsigned old_mode_sclk; +static unsigned old_mode_miso; +static unsigned old_mode_mosi; + +static uint32_t old_spi_cs; +static uint32_t old_spi_clk; + +static unsigned old_mode_ace0; +static unsigned old_mode_ace1; +static unsigned old_mode_ace2; +static unsigned old_mode_asclk; +static unsigned old_mode_amiso; +static unsigned old_mode_amosi; + +static uint32_t old_spi_cntl0; +static uint32_t old_spi_cntl1; + +static uint32_t bscFR; + +/* const --------------------------------------------------------- */ + +static const uint8_t clkDef[PI_MAX_GPIO + 1] = +{ + /* 0 1 2 3 4 5 6 7 8 9 */ + /* 0 */ 0x00, 0x00, 0x00, 0x00, 0x84, 0x94, 0xA4, 0x00, 0x00, 0x00, + /* 1 */ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 2 */ 0x82, 0x92, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 3 */ 0x00, 0x00, 0x84, 0x00, 0x84, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 4 */ 0x00, 0x00, 0x94, 0xA4, 0x94, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 5 */ 0x00, 0x00, 0x00, 0x00, +}; + +/* + 7 6 5 4 3 2 1 0 + V . C C . M M M + + V: 0 no clock, 1 has a clock +CC: 00 CLK0, 01 CLK1, 10 CLK2 + M: 100 ALT0, 010 ALT5 + + gpio4 GPCLK0 ALT0 + gpio5 GPCLK1 ALT0 B+ and compute module only (reserved for system use) + gpio6 GPCLK2 ALT0 B+ and compute module only + gpio20 GPCLK0 ALT5 B+ and compute module only + gpio21 GPCLK1 ALT5 Not available on Rev.2 B (reserved for system use) + + gpio32 GPCLK0 ALT0 Compute module only + gpio34 GPCLK0 ALT0 Compute module only + gpio42 GPCLK1 ALT0 Compute module only (reserved for system use) + gpio43 GPCLK2 ALT0 Compute module only + gpio44 GPCLK1 ALT0 Compute module only (reserved for system use) +*/ + +static const uint8_t PWMDef[PI_MAX_GPIO + 1] = +{ + /* 0 1 2 3 4 5 6 7 8 9 */ + /* 0 */ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 1 */ 0x00, 0x00, 0x84, 0x94, 0x00, 0x00, 0x00, 0x00, 0x82, 0x92, + /* 2 */ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 3 */ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* 4 */ 0x84, 0x94, 0x00, 0x00, 0x00, 0x94, 0x00, 0x00, 0x00, 0x00, + /* 5 */ 0x00, 0x00, 0x85, 0x95, +}; + +/* + 7 6 5 4 3 2 1 0 + V . . P . M M M + + V: 0 no PWM, 1 has a PWM + P: 0 PWM0, 1 PWM1 + M: 010 ALT5, 100 ALT0, 101 ALT1 + + gpio12 pwm0 ALT0 + gpio13 pwm1 ALT0 + gpio18 pwm0 ALT5 + gpio19 pwm1 ALT5 + gpio40 pwm0 ALT0 + gpio41 pwm1 ALT0 + gpio45 pwm1 ALT0 + gpio52 pwm0 ALT1 + gpio53 pwm1 ALT1 +*/ + +static const clkCfg_t clkCfg[]= +{ + /* valid servo */ + { 0, 0}, /* 0 */ + { 1, 17}, /* 1 */ + { 1, 16}, /* 2 */ + { 0, 0}, /* 3 */ + { 1, 15}, /* 4 */ + { 1, 14}, /* 5 */ + { 0, 0}, /* 6 */ + { 0, 0}, /* 7 */ + { 1, 13}, /* 8 */ + { 0, 0}, /* 9 */ + { 1, 12}, /* 10 */ +}; + +static const uint16_t pwmCycles[PWM_FREQS]= + { 1, 2, 4, 5, 8, 10, 16, 20, 25, + 32, 40, 50, 80, 100, 160, 200, 400, 800}; + +static const uint16_t pwmRealRange[PWM_FREQS]= + { 25, 50, 100, 125, 200, 250, 400, 500, 625, + 800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000}; + +/* prototype ----------------------------------------------------- */ + +static void intNotifyBits(void); + +static void intScriptBits(void); + +static void intScriptEventBits(void); + +static int gpioNotifyOpenInBand(int fd); + +static void initHWClk + (int clkCtl, int clkDiv, int clkSrc, int divI, int divF, int MASH); + +static void initDMAgo(volatile uint32_t *dmaAddr, uint32_t cbAddr); + +int gpioWaveTxStart(unsigned wave_mode); /* deprecated */ + +static void closeOrphanedNotifications(int slot, int fd); + + +/* ======================================================================= */ + +int myScriptNameValid(char *name) +{ + int i, c, len, valid; + + len = strlen(name); + + valid = 1; + + for (i=0; i 40) c = 40; else c = count; + + for (i=0; ibyte+1, (char*)data)); + + args.read_write = rw; + args.command = cmd; + args.size = size; + args.data = data; + + return ioctl(fd, PI_I2C_SMBUS, &args); +} + +/* ----------------------------------------------------------------------- */ + +static void myGpioSetMode(unsigned gpio, unsigned mode) +{ + int reg, shift; + + reg = gpio/10; + shift = (gpio%10) * 3; + + gpioReg[reg] = (gpioReg[reg] & ~(7<level[slot]; + + return level; +} + +/* ----------------------------------------------------------------------- */ + +static int myI2CGetPar(char *inBuf, int *inPos, int inLen, int *esc) +{ + int bytes; + + if (*esc) bytes = 2; else bytes = 1; + + *esc = 0; + + if (*inPos <= (inLen - bytes)) + { + if (bytes == 1) + { + return inBuf[(*inPos)++]; + } + else + { + (*inPos) += 2; + return inBuf[*inPos-2] + (inBuf[*inPos-1]<<8); + } + } + return -1; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t myGetTick(int pos) +{ + uint32_t tick; + int page, slot; + + myTckPageSlot(pos, &page, &slot); + + tick = dmaIVirt[page]->tick[slot]; + + return tick; +} + +static int myPermit(unsigned gpio) +{ + if (gpio <= PI_MAX_GPIO) + { + if (gpioMask & ((uint64_t)(1)<>32; + + res = gpioWrite_Bits_32_53_Clear(p[1]&mask); + + if ((mask | p[1]) != mask) + { + DBG(DBG_USER, + "gpioWrite_Bits_32_53_Clear: bad bits %08X (permissions %08X)", + p[1], mask); + res = PI_SOME_PERMITTED; + } + break; + + case PI_CMD_BI2CC: + res = bbI2CClose(p[1]); + break; + + case PI_CMD_BI2CO: + memcpy(&p[4], buf, 4); + res = bbI2COpen(p[1], p[2], p[4]); + break; + + case PI_CMD_BI2CZ: + /* use half buffer for write, half buffer for read */ + if (p[3] > (bufSize/2)) p[3] = bufSize/2; + res = bbI2CZip(p[1], buf, p[3], buf+(bufSize/2), bufSize/2); + if (res > 0) + { + memcpy(buf, buf+(bufSize/2), res); + } + break; + + case PI_CMD_BSCX: + xfer.control = p[1]; + if (p[3] > BSC_FIFO_SIZE) p[3] = BSC_FIFO_SIZE; + xfer.txCnt = p[3]; + if (p[3]) memcpy(&xfer.txBuf, buf, p[3]); + res = bscXfer(&xfer); + if (res >= 0) + { + memcpy(buf, &res, 4); + res = 4 + xfer.rxCnt; + if (res > 4) memcpy(buf+4, &xfer.rxBuf, res-4); + } + break; + + case PI_CMD_BSPIO: + + memcpy(&tmp1, buf+ 0, 4); // MISO + memcpy(&tmp2, buf+ 4, 4); // MOSI + memcpy(&tmp3, buf+ 8, 4); // SCLK + memcpy(&tmp4, buf+12, 4); // baud + memcpy(&tmp5, buf+16, 4); // flags + + if (!myPermit(p[1])) + { + DBG(DBG_USER, + "bbSPIOpen: gpio %d, no permission to update CS", p[1]); + res = PI_NOT_PERMITTED; + } + + if (!myPermit(tmp1)) + { + DBG(DBG_USER, + "bbSPIOpen: gpio %d, no permission to update MISO", tmp1); + res = PI_NOT_PERMITTED; + } + + if (!myPermit(tmp2)) + { + DBG(DBG_USER, + "bbSPIOpen: gpio %d, no permission to update MOSI", tmp2); + res = PI_NOT_PERMITTED; + } + + if (!myPermit(tmp3)) + { + DBG(DBG_USER, + "bbSPIOpen: gpio %d, no permission to update SCLK", tmp3); + res = PI_NOT_PERMITTED; + } + + if (!res) res = bbSPIOpen(p[1], tmp1, tmp2, tmp3, tmp4, tmp5); + break; + + case PI_CMD_BSPIC: + res = bbSPIClose(p[1]); + break; + + case PI_CMD_BSPIX: + if (p[3] > bufSize) p[3] = bufSize; + res = bbSPIXfer(p[1], buf, buf, p[3]); + break; + + case PI_CMD_BR1: res = gpioRead_Bits_0_31(); break; + + case PI_CMD_BR2: res = gpioRead_Bits_32_53(); break; + + case PI_CMD_BS1: + mask = gpioMask; + + res = gpioWrite_Bits_0_31_Set(p[1]&mask); + + if ((mask | p[1]) != mask) + { + DBG(DBG_USER, + "gpioWrite_Bits_0_31_Set: bad bits %08X (permissions %08X)", + p[1], mask); + res = PI_SOME_PERMITTED; + } + break; + + case PI_CMD_BS2: + mask = gpioMask>>32; + + res = gpioWrite_Bits_32_53_Set(p[1]&mask); + + if ((mask | p[1]) != mask) + { + DBG(DBG_USER, + "gpioWrite_Bits_32_53_Set: bad bits %08X (permissions %08X)", + p[1], mask); + res = PI_SOME_PERMITTED; + } + break; + + case PI_CMD_CF1: + res = gpioCustom1(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_CF2: + /* a couple of extra precautions for untrusted code */ + if (p[2] > bufSize) p[2] = bufSize; + res = gpioCustom2(p[1], buf, p[3], buf, p[2]); + if (res > p[2]) res = p[2]; + break; + + case PI_CMD_CGI: res = gpioCfgGetInternals(); break; + + case PI_CMD_CSI: res = gpioCfgSetInternals(p[1]); break; + + case PI_CMD_EVM: res = eventMonitor(p[1], p[2]); break; + + case PI_CMD_EVT: res = eventTrigger(p[1]); break; + + case PI_CMD_FC: res = fileClose(p[1]); break; + + case PI_CMD_FG: + res = gpioGlitchFilter(p[1], p[2]); + break; + + case PI_CMD_FL: + if (p[1] > bufSize) p[1] = bufSize; + res = fileList(buf, buf, p[1]); + break; + + case PI_CMD_FN: + memcpy(&p[4], buf, 4); + res = gpioNoiseFilter(p[1], p[2], p[4]); + break; + + case PI_CMD_FO: res = fileOpen(buf, p[1]); break; + + case PI_CMD_FR: + if (p[2] > bufSize) p[2] = bufSize; + res = fileRead(p[1], buf, p[2]); + break; + + case PI_CMD_FS: + memcpy(&p[4], buf, 4); + res = fileSeek(p[1], p[2], p[4]); + break; + + case PI_CMD_FW: res = fileWrite(p[1], buf, p[3]); break; + + case PI_CMD_GDC: res = gpioGetPWMdutycycle(p[1]); break; + + case PI_CMD_GPW: res = gpioGetServoPulsewidth(p[1]); break; + + case PI_CMD_HC: + /* special case to allow password in upper byte */ + if (myPermit(p[1]&0xFFFFFF)) res = gpioHardwareClock(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioHardwareClock: gpio %d, no permission to update", + p[1] & 0xFFFFFF); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_HELP: break; + + case PI_CMD_HP: + if (myPermit(p[1])) + { + memcpy(&p[4], buf, 4); + res = gpioHardwarePWM(p[1], p[2], p[4]); + } + else + { + DBG(DBG_USER, + "gpioHardwarePWM: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_HWVER: res = gpioHardwareRevision(); break; + + + + case PI_CMD_I2CC: res = i2cClose(p[1]); break; + + case PI_CMD_I2CO: + memcpy(&p[4], buf, 4); + res = i2cOpen(p[1], p[2], p[4]); + break; + + case PI_CMD_I2CPC: + memcpy(&p[4], buf, 4); + res = i2cProcessCall(p[1], p[2], p[4]); + break; + + case PI_CMD_I2CPK: + res = i2cBlockProcessCall(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_I2CRB: res = i2cReadByteData(p[1], p[2]); break; + + case PI_CMD_I2CRD: + if (p[2] > bufSize) p[2] = bufSize; + res = i2cReadDevice(p[1], buf, p[2]); + break; + + case PI_CMD_I2CRI: + memcpy(&p[4], buf, 4); + res = i2cReadI2CBlockData(p[1], p[2], buf, p[4]); + break; + + case PI_CMD_I2CRK: + res = i2cReadBlockData(p[1], p[2], buf); + break; + + case PI_CMD_I2CRS: res = i2cReadByte(p[1]); break; + + case PI_CMD_I2CRW: res = i2cReadWordData(p[1], p[2]); break; + + case PI_CMD_I2CWB: + memcpy(&p[4], buf, 4); + res = i2cWriteByteData(p[1], p[2], p[4]); + break; + + case PI_CMD_I2CWD: + res = i2cWriteDevice(p[1], buf, p[3]); + break; + + case PI_CMD_I2CWI: + res = i2cWriteI2CBlockData(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_I2CWK: + res = i2cWriteBlockData(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_I2CWQ: res = i2cWriteQuick(p[1], p[2]); break; + + case PI_CMD_I2CWS: res = i2cWriteByte(p[1], p[2]); break; + + case PI_CMD_I2CWW: + memcpy(&p[4], buf, 4); + res = i2cWriteWordData(p[1], p[2], p[4]); + break; + + case PI_CMD_I2CZ: + /* use half buffer for write, half buffer for read */ + if (p[3] > (bufSize/2)) p[3] = bufSize/2; + res = i2cZip(p[1], buf, p[3], buf+(bufSize/2), bufSize/2); + if (res > 0) + { + memcpy(buf, buf+(bufSize/2), res); + } + break; + + case PI_CMD_MICS: + if (p[1] <= PI_MAX_MICS_DELAY) myGpioDelay(p[1]); + else res = PI_BAD_MICS_DELAY; + break; + + case PI_CMD_MILS: + if (p[1] <= PI_MAX_MILS_DELAY) myGpioDelay(p[1] * 1000); + else res = PI_BAD_MILS_DELAY; + break; + + case PI_CMD_MODEG: res = gpioGetMode(p[1]); break; + + case PI_CMD_MODES: + if (myPermit(p[1])) res = gpioSetMode(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioSetMode: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_NB: res = gpioNotifyBegin(p[1], p[2]); break; + + case PI_CMD_NC: res = gpioNotifyClose(p[1]); break; + + case PI_CMD_NO: res = gpioNotifyOpen(); break; + + case PI_CMD_NP: res = gpioNotifyPause(p[1]); break; + + case PI_CMD_PADG: res = gpioGetPad(p[1]); break; + + case PI_CMD_PADS: res = gpioSetPad(p[1], p[2]); break; + + case PI_CMD_PFG: res = gpioGetPWMfrequency(p[1]); break; + + case PI_CMD_PFS: + if (myPermit(p[1])) res = gpioSetPWMfrequency(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioSetPWMfrequency: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_PIGPV: res = gpioVersion(); break; + + case PI_CMD_PRG: res = gpioGetPWMrange(p[1]); break; + + case PI_CMD_PROC: + res = gpioStoreScript(buf); + break; + + case PI_CMD_PROCD: res = gpioDeleteScript(p[1]); break; + + case PI_CMD_PROCP: + res = gpioScriptStatus(p[1], (uint32_t *)buf); + break; + + case PI_CMD_PROCR: + res = gpioRunScript(p[1], p[3]/4, (uint32_t *)buf); + break; + + case PI_CMD_PROCS: res = gpioStopScript(p[1]); break; + + case PI_CMD_PROCU: + res = gpioUpdateScript(p[1], p[3]/4, (uint32_t *)buf); + break; + + case PI_CMD_PRRG: res = gpioGetPWMrealRange(p[1]); break; + + case PI_CMD_PRS: + if (myPermit(p[1])) res = gpioSetPWMrange(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioSetPWMrange: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_PUD: + if (myPermit(p[1])) res = gpioSetPullUpDown(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioSetPullUpDown: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_PWM: + if (myPermit(p[1])) res = gpioPWM(p[1], p[2]); + else + { + DBG(DBG_USER, "gpioPWM: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_READ: res = gpioRead(p[1]); break; + + case PI_CMD_SERVO: + if (myPermit(p[1])) res = gpioServo(p[1], p[2]); + else + { + DBG(DBG_USER, + "gpioServo: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + + + case PI_CMD_SERRB: res = serReadByte(p[1]); break; + + case PI_CMD_SERWB: res = serWriteByte(p[1], p[2]); break; + + case PI_CMD_SERC: res = serClose(p[1]); break; + + case PI_CMD_SERDA: res = serDataAvailable(p[1]); break; + + case PI_CMD_SERO: res = serOpen(buf, p[1], p[2]); break; + + case PI_CMD_SERR: + if (p[2] > bufSize) p[2] = bufSize; + res = serRead(p[1], buf, p[2]); + break; + + case PI_CMD_SERW: res = serWrite(p[1], buf, p[3]); break; + + + case PI_CMD_SHELL: + res = shell(buf, buf+p[1]+1); + break; + + + case PI_CMD_SLR: + if (p[2] > bufSize) p[2] = bufSize; + res = gpioSerialRead(p[1], buf, p[2]); + break; + + case PI_CMD_SLRC: res = gpioSerialReadClose(p[1]); break; + + case PI_CMD_SLRO: + memcpy(&p[4], buf, 4); + res = gpioSerialReadOpen(p[1], p[2], p[4]); break; + + case PI_CMD_SLRI: res = gpioSerialReadInvert(p[1], p[2]); break; + + case PI_CMD_SPIC: + res = spiClose(p[1]); + break; + + case PI_CMD_SPIO: + memcpy(&p[4], buf, 4); + res = spiOpen(p[1], p[2], p[4]); + break; + + case PI_CMD_SPIR: + if (p[2] > bufSize) p[2] = bufSize; + res = spiRead(p[1], buf, p[2]); + break; + + case PI_CMD_SPIW: + if (p[3] > bufSize) p[3] = bufSize; + res = spiWrite(p[1], buf, p[3]); + break; + + case PI_CMD_SPIX: + if (p[3] > bufSize) p[3] = bufSize; + res = spiXfer(p[1], buf, buf, p[3]); + break; + + case PI_CMD_TICK: res = gpioTick(); break; + + case PI_CMD_TRIG: + if (myPermit(p[1])) + { + memcpy(&p[4], buf, 4); + res = gpioTrigger(p[1], p[2], p[4]); + } + else + { + DBG(DBG_USER, + "gpioTrigger: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_WDOG: res = gpioSetWatchdog(p[1], p[2]); break; + + case PI_CMD_WRITE: + if (myPermit(p[1])) res = gpioWrite(p[1], p[2]); + else + { + DBG(DBG_USER, "gpioWrite: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + + + case PI_CMD_WVAG: + + /* need to mask off any non permitted gpios */ + + mask = gpioMask; + pulse = (gpioPulse_t *)buf; + j = p[3]/sizeof(gpioPulse_t); + masked = 0; + + for (i=0; i= 0)) res = PI_SOME_PERMITTED; + + break; + + case PI_CMD_WVAS: + if (myPermit(p[1])) + { + memcpy(&tmp1, buf, 4); /* databits */ + memcpy(&tmp2, buf+4, 4); /* stophalfbits */ + memcpy(&tmp3, buf+8, 4); /* offset */ + res = gpioWaveAddSerial + (p[1], p[2], tmp1, tmp2, tmp3, p[3]-12, buf+12); + } + else + { + DBG( + DBG_USER, + "gpioWaveAddSerial: gpio %d, no permission to update", p[1]); + res = PI_NOT_PERMITTED; + } + break; + + case PI_CMD_WVBSY: res = gpioWaveTxBusy(); break; + + case PI_CMD_WVCHA: + if (p[3] > bufSize) p[3] = bufSize; + res = gpioWaveChain(buf, p[3]); + break; + + + case PI_CMD_WVCLR: res = gpioWaveClear(); break; + + case PI_CMD_WVCRE: res = gpioWaveCreate(); break; + + case PI_CMD_WVDEL: res = gpioWaveDelete(p[1]); break; + + case PI_CMD_WVGO: res = gpioWaveTxStart(PI_WAVE_MODE_ONE_SHOT); break; + + case PI_CMD_WVGOR: res = gpioWaveTxStart(PI_WAVE_MODE_REPEAT); break; + + case PI_CMD_WVHLT: res = gpioWaveTxStop(); break; + + case PI_CMD_WVNEW: res = gpioWaveAddNew(); break; + + case PI_CMD_WVSC: + switch(p[1]) + { + case 0: res = gpioWaveGetCbs(); break; + case 1: res = gpioWaveGetHighCbs(); break; + case 2: res = gpioWaveGetMaxCbs(); break; + default: res = PI_BAD_WVSC_COMMND; + } + break; + + case PI_CMD_WVSM: + switch(p[1]) + { + case 0: res = gpioWaveGetMicros(); break; + case 1: res = gpioWaveGetHighMicros(); break; + case 2: res = gpioWaveGetMaxMicros(); break; + default: res = PI_BAD_WVSM_COMMND; + } + break; + + case PI_CMD_WVSP: + switch(p[1]) + { + case 0: res = gpioWaveGetPulses(); break; + case 1: res = gpioWaveGetHighPulses(); break; + case 2: res = gpioWaveGetMaxPulses(); break; + default: res = PI_BAD_WVSP_COMMND; + } + break; + + case PI_CMD_WVTAT: res = gpioWaveTxAt(); break; + + case PI_CMD_WVTX: + res = gpioWaveTxSend(p[1], PI_WAVE_MODE_ONE_SHOT); break; + + case PI_CMD_WVTXM: + res = gpioWaveTxSend(p[1], p[2]); break; + + case PI_CMD_WVTXR: + res = gpioWaveTxSend(p[1], PI_WAVE_MODE_REPEAT); break; + + default: + res = PI_UNKNOWN_COMMAND; + break; + } + + return res; +} + +/* ----------------------------------------------------------------------- */ + +static void mySetGpioOff(unsigned gpio, int pos) +{ + int page, slot; + + myOffPageSlot(pos, &page, &slot); + + dmaIVirt[page]->gpioOff[slot] |= (1<gpioOff[slot] &= ~(1<gpioOn[slot] |= (1<gpioOn[slot] &= ~(1< oldOff) + { + for (i=0; i oldOff) + { + for (i=0; ihandle) + { + mbUnmapMem(DMAMemP->virtual_addr, DMAMemP->size); + mbUnlockMemory(fdMbox, DMAMemP->handle); + mbReleaseMemory(fdMbox, DMAMemP->handle); + DMAMemP->handle = 0; + } +} + +static int mbDMAAlloc(DMAMem_t *DMAMemP, unsigned size, uint32_t pi_mem_flag) +{ + DMAMemP->size = size; + + DMAMemP->handle = + mbAllocateMemory(fdMbox, size, PAGE_SIZE, pi_mem_flag); + + if (DMAMemP->handle) + { + DMAMemP->bus_addr = mbLockMemory(fdMbox, DMAMemP->handle); + + DMAMemP->virtual_addr = + mbMapMem(BUS_TO_PHYS(DMAMemP->bus_addr), size); + + return 1; + } + return 0; +} + + +/* ======================================================================= */ + +rawCbs_t * rawWaveCBAdr(int cbNum) +{ + int page, slot; + + page = cbNum/CBS_PER_OPAGE; + slot = cbNum%CBS_PER_OPAGE; + + return &dmaOVirt[page]->cb[slot]; +} + + +/* ----------------------------------------------------------------------- */ + +static uint32_t waveCbPOadr(int pos) +{ + int page, slot; + + page = pos/CBS_PER_OPAGE; + slot = pos%CBS_PER_OPAGE; + + return (uint32_t) &dmaOBus[page]->cb[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static void waveOOLPageSlot(int pos, int *page, int *slot) +{ + *page = pos/OOL_PER_OPAGE; + *slot = pos%OOL_PER_OPAGE; +} + + +/* ----------------------------------------------------------------------- */ + +static void waveSetOOL(int pos, uint32_t OOL) +{ + int page, slot; + + waveOOLPageSlot(pos, &page, &slot); + + dmaOVirt[page]->OOL[slot] = OOL; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t waveOOLPOadr(int pos) +{ + int page, slot; + + waveOOLPageSlot(pos, &page, &slot); + + return (uint32_t) &dmaOBus[page]->OOL[slot]; +} + + +/* ----------------------------------------------------------------------- */ + +static void waveBitDelay + (unsigned baud, unsigned bits, unsigned stops, unsigned *bitDelay) +{ + unsigned fullBit, last, diff, t, i; + + /* scaled 1000X */ + + fullBit = 1000000000 / baud; + last = 0; + + for (i=0; i<=bits; i++) + { + t = (((i+1)*fullBit)+500)/1000; + diff = t - last; + last = t; + bitDelay[i] = diff; + } + + t = (((bits+1)*fullBit) + ((stops*fullBit)/2) + 500)/1000; + diff = t - last; + bitDelay[i] = diff; +} + +static int waveDelayCBs(uint32_t delay) +{ + uint32_t cbs; + + if (!delay) return 0; + if (gpioCfg.DMAsecondaryChannel < DMA_LITE_FIRST) return 1; + cbs = BPD * delay / DMA_LITE_MAX; + if ((BPD * delay) % DMA_LITE_MAX) cbs++; + return cbs; +} + +/* ----------------------------------------------------------------------- */ + +static void waveCBsOOLs(int *numCBs, int *numBOOLs, int *numTOOLs) +{ + int numCB=0, numBOOL=0, numTOOL=0; + + unsigned i; + + unsigned numWaves; + + rawWave_t *waves; + + numWaves = wfc[wfcur]; + waves = wf [wfcur]; + + /* delay cb at start of DMA */ + + numCB++; + + for (i=0; iinfo = NORMAL_DMA | TIMED_DMA(2); + p->dst = PCM_TIMER; + } + else + { + p->info = NORMAL_DMA | TIMED_DMA(5); + p->dst = PWM_TIMER; + } + + p->src = (uint32_t) (&dmaOBus[0]->periphData); + p->length = BPD * 20 / PI_WF_MICROS; /* 20 micros delay */ + p->next = waveCbPOadr(botCB); + + repeatCB = botCB; + + for (i=0; iinfo = NORMAL_DMA; + p->src = waveOOLPOadr(botOOL++); + p->dst = ((GPIO_BASE + (GPSET0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->length = 4; + p->next = waveCbPOadr(botCB); + } + + if (waves[i].gpioOff) + { + waveSetOOL(botOOL, waves[i].gpioOff); + + p = rawWaveCBAdr(botCB++); + + p->info = NORMAL_DMA; + p->src = waveOOLPOadr(botOOL++); + p->dst = ((GPIO_BASE + (GPCLR0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->length = 4; + p->next = waveCbPOadr(botCB); + } + + if (waves[i].flags & WAVE_FLAG_READ) + { + p = rawWaveCBAdr(botCB++); + + p->info = NORMAL_DMA; + p->src = ((GPIO_BASE + (GPLEV0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->dst = waveOOLPOadr(--topOOL); + p->length = 4; + p->next = waveCbPOadr(botCB); + } + + if (waves[i].flags & WAVE_FLAG_TICK) + { + p = rawWaveCBAdr(botCB++); + + p->info = NORMAL_DMA; + p->src = ((SYST_BASE + (SYST_CLO*4)) & 0x00ffffff) | PI_PERI_BUS; + p->dst = waveOOLPOadr(--topOOL); + p->length = 4; + p->next = waveCbPOadr(botCB); + } + + if (waves[i].usDelay) + { + delayLeft = waves[i].usDelay; + + delayCBs = waveDelayCBs(delayLeft); + + for (dcb=0; dcbinfo = NORMAL_DMA | TIMED_DMA(2); + p->dst = PCM_TIMER; + } + else + { + p->info = NORMAL_DMA | TIMED_DMA(5); + p->dst = PWM_TIMER; + } + + p->src = (uint32_t) (&dmaOBus[0]->periphData); + + p->length = BPD * delayLeft / PI_WF_MICROS; + + if ((gpioCfg.DMAsecondaryChannel >= DMA_LITE_FIRST) && + (p->length > DMA_LITE_MAX)) + { + p->length = DMA_LITE_MAX; + } + + delayLeft -= (p->length / BPD); + + p->next = waveCbPOadr(botCB); + } + } + } + + if (p != NULL) + { + if (wave_mode == PI_WAVE_MODE_ONE_SHOT) + p->next = 0; + else p->next = waveCbPOadr(repeatCB); + } + + status = botCB - *CB; + + *CB = botCB; + *BOOL = botOOL; + *TOOL = topOOL; + + return status; +} + +/* ----------------------------------------------------------------------- */ + +static void waveRxSerial(wfRx_t *w, int level, uint32_t tick) +{ + int diffTicks, lastLevel; + int newWritePos; + + level = level ^ w->s.invert; + + if (w->s.bit >= 0) + { + diffTicks = tick - w->s.startBitTick; + + if (level != PI_TIMEOUT) + { + w->s.level = level; + lastLevel = !level; + } + else lastLevel = w->s.level; + + while ((w->s.bit <= w->s.dataBits) && + (diffTicks > (w->s.nextBitDiff/1000))) + { + if (w->s.bit) + { + if (lastLevel) w->s.data |= (1<<(w->s.bit-1)); + } + else w->s.data = 0; + + ++(w->s.bit); + + w->s.nextBitDiff += w->s.fullBit; + } + + if (w->s.bit > w->s.dataBits) + { + memcpy(w->s.buf + w->s.writePos, &w->s.data, w->s.bytes); + + /* don't let writePos catch readPos */ + + newWritePos = (w->s.writePos + w->s.bytes) % (w->s.bufSize); + + if (newWritePos != w->s.readPos) w->s.writePos = newWritePos; + + if (level == 0) + { + gpioSetWatchdog(w->gpio, w->s.timeout); + w->s.bit = 0; + w->s.startBitTick = tick; + w->s.nextBitDiff = w->s.halfBit; + } + else + { + w->s.bit = -1; + gpioSetWatchdog(w->gpio, 0); + } + } + } + else + { + /* start bit if high->low */ + + if (level == 0) + { + gpioSetWatchdog(w->gpio, w->s.timeout); + w->s.level = 0; + w->s.bit = 0; + w->s.startBitTick = tick; + w->s.nextBitDiff = w->s.halfBit; + } + } +} + + +/* ----------------------------------------------------------------------- */ + +static void waveRxBit(int gpio, int level, uint32_t tick) +{ + switch (wfRx[gpio].mode) + { + case PI_WFRX_SERIAL: + waveRxSerial(&wfRx[gpio], level, tick); + } +} + + +/* ----------------------------------------------------------------------- */ + +int rawWaveAddGeneric(unsigned numIn1, rawWave_t *in1) +{ + unsigned inPos1=0, inPos2=0, outPos=0, level = NUM_WAVE_OOL; + + unsigned cbs=0; + + unsigned numIn2, numOut; + + uint32_t tNow, tNext1, tNext2, tDelay; + + rawWave_t *in2, *out; + + numIn2 = wfc[wfcur]; + in2 = wf[wfcur]; + + numOut = PI_WAVE_MAX_PULSES; + out = wf[1-wfcur]; + + tNow = 0; + + if (!numIn1) tNext1 = -1; else tNext1 = 0; + if (!numIn2) tNext2 = -1; else tNext2 = 0; + + while (((inPos1= numIn1) tNext1 = -1; + if (inPos2 >= numIn2) tNext2 = -1; + + } + + if ((outPos < numOut) && (outPos < level)) + { + wfStats.micros = tNow; + + if (tNow > wfStats.highMicros) wfStats.highMicros = tNow; + + wfStats.pulses = outPos; + + if (outPos > wfStats.highPulses) wfStats.highPulses = outPos; + + wfStats.cbs = cbs; + + if (cbs > wfStats.highCbs) wfStats.highCbs = cbs; + + wfc[1-wfcur] = outPos; + wfcur = 1 - wfcur; + + return outPos; + } + else return PI_TOO_MANY_PULSES; +} + +/* ======================================================================= */ + +int i2cWriteQuick(unsigned handle, unsigned bit) +{ + int status; + + DBG(DBG_USER, "handle=%d bit=%d", handle, bit); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_QUICK) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (bit > 1) + SOFT_ERROR(PI_BAD_PARAM, "bad bit (%d)", bit); + + status = my_smbus_access( + i2cInfo[handle].fd, bit, 0, PI_I2C_SMBUS_QUICK, NULL); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + +int i2cReadByte(unsigned handle) +{ + union my_smbus_data data; + int status; + + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_READ_BYTE) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + status = my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, 0, PI_I2C_SMBUS_BYTE, &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + + return 0xFF & data.byte; +} + + +int i2cWriteByte(unsigned handle, unsigned bVal) +{ + int status; + + DBG(DBG_USER, "handle=%d bVal=%d", handle, bVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_WRITE_BYTE) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad bVal (%d)", bVal); + + status = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + bVal, + PI_I2C_SMBUS_BYTE, + NULL); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + + +int i2cReadByteData(unsigned handle, unsigned reg) +{ + union my_smbus_data data; + int status; + + DBG(DBG_USER, "handle=%d reg=%d", handle, reg); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_READ_BYTE_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + status = my_smbus_access(i2cInfo[handle].fd, + PI_I2C_SMBUS_READ, reg, PI_I2C_SMBUS_BYTE_DATA, &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + + return 0xFF & data.byte; +} + + +int i2cWriteByteData(unsigned handle, unsigned reg, unsigned bVal) +{ + union my_smbus_data data; + + int status; + + DBG(DBG_USER, "handle=%d reg=%d bVal=%d", handle, reg, bVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_WRITE_BYTE_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad bVal (%d)", bVal); + + data.byte = bVal; + + status = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_BYTE_DATA, + &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + + +int i2cReadWordData(unsigned handle, unsigned reg) +{ + union my_smbus_data data; + int status; + + DBG(DBG_USER, "handle=%d reg=%d", handle, reg); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_READ_WORD_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + status = (my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_READ, + reg, + PI_I2C_SMBUS_WORD_DATA, + &data)); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + + return 0xFFFF & data.word; +} + + +int i2cWriteWordData(unsigned handle, unsigned reg, unsigned wVal) +{ + union my_smbus_data data; + + int status; + + DBG(DBG_USER, "handle=%d reg=%d wVal=%d", handle, reg, wVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_WRITE_WORD_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (wVal > 0xFFFF) + SOFT_ERROR(PI_BAD_PARAM, "bad wVal (%d)", wVal); + + data.word = wVal; + + status = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_WORD_DATA, + &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + + +int i2cProcessCall(unsigned handle, unsigned reg, unsigned wVal) +{ + union my_smbus_data data; + int status; + + DBG(DBG_USER, "handle=%d reg=%d wVal=%d", handle, reg, wVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_PROC_CALL) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (wVal > 0xFFFF) + SOFT_ERROR(PI_BAD_PARAM, "bad wVal (%d)", wVal); + + data.word = wVal; + + status = (my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, PI_I2C_SMBUS_PROC_CALL, + &data)); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + + return 0xFFFF & data.word; +} + + +int i2cReadBlockData(unsigned handle, unsigned reg, char *buf) +{ + union my_smbus_data data; + + int i, status; + + DBG(DBG_USER, "handle=%d reg=%d buf=%08X", handle, reg, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_READ_BLOCK_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + status = (my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_READ, + reg, + PI_I2C_SMBUS_BLOCK_DATA, + &data)); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + else + { + if (data.block[0] <= PI_I2C_SMBUS_BLOCK_MAX) + { + for (i=0; i= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_WRITE_BLOCK_DATA) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + data.block[0] = count; + + status = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_BLOCK_DATA, + &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + + +int i2cBlockProcessCall( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + union my_smbus_data data; + + int i, status; + + DBG(DBG_USER, "handle=%d reg=%d count=%d [%s]", + handle, reg, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_PROC_CALL) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + data.block[0] = count; + + status = (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_WRITE, reg, + PI_I2C_SMBUS_BLOCK_PROC_CALL, &data)); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + else + { + if (data.block[0] <= PI_I2C_SMBUS_BLOCK_MAX) + { + for (i=0; i= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_READ_I2C_BLOCK) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + if (count == 32) + size = PI_I2C_SMBUS_I2C_BLOCK_BROKEN; + else + size = PI_I2C_SMBUS_I2C_BLOCK_DATA; + + data.block[0] = count; + + status = (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, reg, size, &data)); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_READ_FAILED; + } + else + { + if (data.block[0] <= PI_I2C_SMBUS_I2C_BLOCK_MAX) + { + for (i=0; i= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((i2cInfo[handle].funcs & PI_I2C_FUNC_SMBUS_WRITE_I2C_BLOCK) == 0) + SOFT_ERROR(PI_BAD_SMBUS_CMD, "SMBUS command not supported by driver"); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + + data.block[0] = count; + + status = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_I2C_BLOCK_BROKEN, + &data); + + if (status < 0) + { + DBG(DBG_USER, "error=%d (%m)", status); + return PI_I2C_WRITE_FAILED; + } + + return status; +} + +int i2cWriteDevice(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_I2C_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + bytes = write(i2cInfo[handle].fd, buf, count); + + if (bytes != count) + { + DBG(DBG_USER, "error=%d (%m)", bytes); + return PI_I2C_WRITE_FAILED; + } + + return 0; +} + +int i2cReadDevice(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + DBG(DBG_USER, "handle=%d count=%d buf=%08X", + handle, count, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_I2C_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + bytes = read(i2cInfo[handle].fd, buf, count); + + if (bytes != count) + { + DBG(DBG_USER, "error=%d (%m)", bytes); + return PI_I2C_READ_FAILED; + } + + return bytes; +} + +int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags) +{ + static pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; + char dev[32]; + int i, slot, fd; + uint32_t funcs; + + DBG(DBG_USER, "i2cBus=%d i2cAddr=%d flags=0x%X", + i2cBus, i2cAddr, i2cFlags); + + CHECK_INITED; + + if (i2cAddr > PI_MAX_I2C_ADDR) + SOFT_ERROR(PI_BAD_I2C_ADDR, "bad I2C address (%d)", i2cAddr); + + if (i2cFlags) + SOFT_ERROR(PI_BAD_FLAGS, "bad flags (0x%X)", i2cFlags); + + slot = -1; + + pthread_mutex_lock(&mutex); + + for (i=0; i= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].fd >= 0) close(i2cInfo[handle].fd); + + i2cInfo[handle].fd = -1; + i2cInfo[handle].state = PI_I2C_CLOSED; + + return 0; +} + +void i2cSwitchCombined(int setting) +{ + int fd; + + DBG(DBG_USER, "setting=%d", setting); + + fd = open(PI_I2C_COMBINED, O_WRONLY); + + if (fd >= 0) + { + if (setting) + { + if (write(fd, "1\n", 2) == -1) { /* ignore errors */ } + } + else + { + if (write(fd, "0\n", 2) == -1) { /* ignore errors */ } + } + + close(fd); + } +} + +int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs) +{ + int retval; + my_i2c_rdwr_ioctl_data_t rdwr; + + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (segs == NULL) + SOFT_ERROR(PI_BAD_POINTER, "null segments"); + + if (numSegs > PI_I2C_RDRW_IOCTL_MAX_MSGS) + SOFT_ERROR(PI_TOO_MANY_SEGS, "too many segments (%d)", numSegs); + + rdwr.msgs = segs; + rdwr.nmsgs = numSegs; + + retval = ioctl(i2cInfo[handle].fd, PI_I2C_RDWR, &rdwr); + + if (retval >= 0) return retval; + else return PI_BAD_I2C_SEG; +} + +int i2cZip( + unsigned handle, + char *inBuf, unsigned inLen, char *outBuf, unsigned outLen) +{ + int numSegs, inPos, outPos, status, bytes, flags, addr; + int esc, setesc; + pi_i2c_msg_t segs[PI_I2C_RDRW_IOCTL_MAX_MSGS]; + + DBG(DBG_USER, "handle=%d inBuf=%s outBuf=%08X len=%d", + handle, myBuf2Str(inLen, (char *)inBuf), (int)outBuf, outLen); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!inBuf || !inLen) + SOFT_ERROR(PI_BAD_POINTER, "input buffer can't be NULL"); + + if (!outBuf && outLen) + SOFT_ERROR(PI_BAD_POINTER, "output buffer can't be NULL"); + + numSegs = 0; + + inPos = 0; + outPos = 0; + status = 0; + + addr = i2cInfo[handle].addr; + flags = 0; + esc = 0; + setesc = 0; + + while (!status && (inPos < inLen)) + { + DBG(DBG_INTERNAL, "status=%d inpos=%d inlen=%d cmd=%d addr=%d flags=%x", + status, inPos, inLen, inBuf[inPos], addr, flags); + + switch (inBuf[inPos++]) + { + case PI_I2C_END: + status = 1; + break; + + case PI_I2C_COMBINED_ON: + /* Run prior transactions before setting combined flag */ + if (numSegs) + { + status = i2cSegments(handle, segs, numSegs); + if (status >= 0) status = 0; /* continue */ + numSegs = 0; + } + i2cSwitchCombined(1); + break; + + case PI_I2C_COMBINED_OFF: + /* Run prior transactions before clearing combined flag */ + if (numSegs) + { + status = i2cSegments(handle, segs, numSegs); + if (status >= 0) status = 0; /* continue */ + numSegs = 0; + } + i2cSwitchCombined(0); + break; + + case PI_I2C_ADDR: + addr = myI2CGetPar(inBuf, &inPos, inLen, &esc); + if (addr < 0) status = PI_BAD_I2C_CMD; + break; + + case PI_I2C_FLAGS: + /* cheat to force two byte flags */ + esc = 1; + flags = myI2CGetPar(inBuf, &inPos, inLen, &esc); + if (flags < 0) status = PI_BAD_I2C_CMD; + break; + + case PI_I2C_ESC: + setesc = 1; + break; + + case PI_I2C_READ: + + bytes = myI2CGetPar(inBuf, &inPos, inLen, &esc); + + if (bytes >= 0) + { + if ((bytes + outPos) < outLen) + { + segs[numSegs].addr = addr; + segs[numSegs].flags = (flags|1); + segs[numSegs].len = bytes; + segs[numSegs].buf = (uint8_t *)(outBuf + outPos); + outPos += bytes; + numSegs++; + if (numSegs >= PI_I2C_RDRW_IOCTL_MAX_MSGS) + { + status = i2cSegments(handle, segs, numSegs); + if (status >= 0) status = 0; /* continue */ + numSegs = 0; + } + } + else status = PI_BAD_I2C_RLEN; + } + else status = PI_BAD_I2C_RLEN; + break; + + case PI_I2C_WRITE: + + bytes = myI2CGetPar(inBuf, &inPos, inLen, &esc); + + if (bytes >= 0) + { + if ((bytes + inPos) < inLen) + { + segs[numSegs].addr = addr; + segs[numSegs].flags = (flags&0xfffe); + segs[numSegs].len = bytes; + segs[numSegs].buf = (uint8_t *)(inBuf + inPos); + inPos += bytes; + numSegs++; + if (numSegs >= PI_I2C_RDRW_IOCTL_MAX_MSGS) + { + status = i2cSegments(handle, segs, numSegs); + if (status >= 0) status = 0; /* continue */ + numSegs = 0; + } + } + else status = PI_BAD_I2C_WLEN; + } + else status = PI_BAD_I2C_WLEN; + break; + + default: + status = PI_BAD_I2C_CMD; + } + + if (setesc) esc = 1; else esc = 0; + + setesc = 0; + } + + if (status >= 0) + { + if (numSegs) status = i2cSegments(handle, segs, numSegs); + } + + if (status >= 0) status = outPos; + + return status; +} + +/* ======================================================================= */ + +/*SPI */ + +static uint32_t _spiTXBits(char *buf, int pos, int bitlen, int msbf) +{ + uint32_t bits=0; + + if (buf) + { + if (bitlen <= 8) bits = *((( uint8_t*)buf)+pos); + else if (bitlen <= 16) bits = *(((uint16_t*)buf)+pos); + else bits = *(((uint32_t*)buf)+pos); + + if (msbf) bits <<= (32-bitlen); + } + + return bits; +} + +static void _spiRXBits( + char *buf, int pos, int bitlen, int msbf, uint32_t bits) +{ + if (buf) + { + if (!msbf) bits >>= (32-bitlen); + + if (bitlen <= 8) *((( uint8_t*)buf)+pos) = bits; + else if (bitlen <= 16) *(((uint16_t*)buf)+pos) = bits; + else *(((uint32_t*)buf)+pos) = bits; + } +} + +static void spiACS(int channel, int on) +{ + int gpio; + + switch (channel) + { + case 0: gpio = PI_ASPI_CE0; break; + case 1: gpio = PI_ASPI_CE1; break; + default: gpio = PI_ASPI_CE2; break; + } + myGpioWrite(gpio, on); +} + +static void spiGoA( + unsigned speed, /* bits per second */ + uint32_t flags, /* flags */ + char *txBuf, /* tx buffer */ + char *rxBuf, /* rx buffer */ + unsigned count) /* number of bytes */ +{ + int cs; + char bit_ir[4] = {1, 0, 0, 1}; /* read on rising edge */ + char bit_or[4] = {0, 1, 1, 0}; /* write on rising edge */ + char bit_ic[4] = {0, 0, 1, 1}; /* invert clock */ + + int mode, bitlen, txmsbf, rxmsbf, channel; + unsigned txCnt=0; + unsigned rxCnt=0; + uint32_t spiDefaults; + uint32_t statusReg; + int txFull, rxEmpty; + + channel = PI_SPI_FLAGS_GET_CHANNEL(flags); + mode = PI_SPI_FLAGS_GET_MODE (flags); + + bitlen = PI_SPI_FLAGS_GET_BITLEN (flags); + + if (!bitlen) bitlen = 8; + + /* correct count for word size */ + + if (bitlen > 8) count /= 2; + if (bitlen > 16) count /= 2; + + txmsbf = !PI_SPI_FLAGS_GET_TX_LSB (flags); + rxmsbf = !PI_SPI_FLAGS_GET_RX_LSB (flags); + + cs = PI_SPI_FLAGS_GET_CSPOLS(flags) & (1<>28)&15) > 2); + + if (rxCnt < count) + { + if (!rxEmpty) + { + _spiRXBits( + rxBuf, rxCnt++, bitlen, rxmsbf, auxReg[AUX_SPI0_IO_REG]); + } + } + + if (txCnt < count) + { + if (!txFull) + { + if (txCnt != (count-1)) + { + auxReg[AUX_SPI0_TX_HOLD] = + _spiTXBits(txBuf, txCnt++, bitlen, txmsbf); + } + else + { + auxReg[AUX_SPI0_IO_REG] = + _spiTXBits(txBuf, txCnt++, bitlen, txmsbf); + } + } + } + } + + while ((auxReg[AUX_SPI0_STAT_REG] & AUXSPI_STAT_BUSY)) ; + + spiACS(channel, !cs); +} + +static void spiGoS( + unsigned speed, + uint32_t flags, + char *txBuf, + char *rxBuf, + unsigned count) +{ + unsigned txCnt=0; + unsigned rxCnt=0; + unsigned cnt, cnt4w, cnt3w; + uint32_t spiDefaults; + unsigned mode, channel, cspol, cspols, flag3w, ren3w; + + channel = PI_SPI_FLAGS_GET_CHANNEL(flags); + mode = PI_SPI_FLAGS_GET_MODE (flags); + cspols = PI_SPI_FLAGS_GET_CSPOLS(flags); + cspol = (cspols>>channel) & 1; + flag3w = PI_SPI_FLAGS_GET_3WIRE(flags); + ren3w = PI_SPI_FLAGS_GET_3WREN(flags); + + spiDefaults = SPI_CS_MODE(mode) | + SPI_CS_CSPOLS(cspols) | + SPI_CS_CS(channel) | + SPI_CS_CSPOL(cspol) | + SPI_CS_CLEAR(3); + + spiReg[SPI_DLEN] = 2; /* undocumented, stops inter-byte gap */ + + spiReg[SPI_CS] = spiDefaults; /* stop */ + + if (!count) return; + + if (flag3w) + { + if (ren3w < count) + { + cnt4w = ren3w; + cnt3w = count - ren3w; + } + else + { + cnt4w = count; + cnt3w = 0; + } + } + else + { + cnt4w = count; + cnt3w = 0; + } + + spiReg[SPI_CLK] = 250000000/speed; + + spiReg[SPI_CS] = spiDefaults | SPI_CS_TA; /* start */ + + cnt = cnt4w; + + while((txCnt < cnt) || (rxCnt < cnt)) + { + while((rxCnt < cnt) && ((spiReg[SPI_CS] & SPI_CS_RXD))) + { + if (rxBuf) rxBuf[rxCnt] = spiReg[SPI_FIFO]; + else spi_dummy = spiReg[SPI_FIFO]; + rxCnt++; + } + + while((txCnt < cnt) && ((spiReg[SPI_CS] & SPI_CS_TXD))) + { + if (txBuf) spiReg[SPI_FIFO] = txBuf[txCnt]; + else spiReg[SPI_FIFO] = 0; + txCnt++; + } + } + + while (!(spiReg[SPI_CS] & SPI_CS_DONE)) ; + + /* now switch to 3-wire bus */ + + cnt += cnt3w; + + spiReg[SPI_CS] |= SPI_CS_REN; + + while((txCnt < cnt) || (rxCnt < cnt)) + { + while((rxCnt < cnt) && ((spiReg[SPI_CS] & SPI_CS_RXD))) + { + if (rxBuf) rxBuf[rxCnt] = spiReg[SPI_FIFO]; + else spi_dummy = spiReg[SPI_FIFO]; + rxCnt++; + } + + while((txCnt < cnt) && ((spiReg[SPI_CS] & SPI_CS_TXD))) + { + if (txBuf) spiReg[SPI_FIFO] = txBuf[txCnt]; + else spiReg[SPI_FIFO] = 0; + txCnt++; + } + } + + while (!(spiReg[SPI_CS] & SPI_CS_DONE)) ; + + spiReg[SPI_CS] = spiDefaults; /* stop */ +} + +static void spiGo( + unsigned speed, + uint32_t flags, + char *txBuf, + char *rxBuf, + unsigned count) +{ + static pthread_mutex_t main_mutex = PTHREAD_MUTEX_INITIALIZER; + static pthread_mutex_t aux_mutex = PTHREAD_MUTEX_INITIALIZER; + + if (PI_SPI_FLAGS_GET_AUX_SPI(flags)) + { + pthread_mutex_lock(&aux_mutex); + spiGoA(speed, flags, txBuf, rxBuf, count); + pthread_mutex_unlock(&aux_mutex); + } + else + { + pthread_mutex_lock(&main_mutex); + spiGoS(speed, flags, txBuf, rxBuf, count); + pthread_mutex_unlock(&main_mutex); + } +} + +static int spiAnyOpen(uint32_t flags) +{ + int i, aux; + + aux = PI_SPI_FLAGS_GET_AUX_SPI(flags); + + for (i=0; i= i) + SOFT_ERROR(PI_BAD_SPI_CHANNEL, "bad spiChan (%d)", spiChan); + + if ((baud < PI_SPI_MIN_BAUD) || (baud > PI_SPI_MAX_BAUD)) + SOFT_ERROR(PI_BAD_SPI_SPEED, "bad baud (%d)", baud); + + if (spiFlags > (1<<22)) + SOFT_ERROR(PI_BAD_FLAGS, "bad spiFlags (0x%X)", spiFlags); + + if (!spiAnyOpen(spiFlags)) /* initialise on first open */ + { + spiInit(spiFlags); + spiGo(baud, spiFlags, NULL, NULL, 0); + } + + slot = -1; + + pthread_mutex_lock(&mutex); + + for (i=0; i= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + spiInfo[handle].state = PI_I2C_CLOSED; + + if (!spiAnyOpen(spiInfo[handle].flags)) + spiTerm(spiInfo[handle].flags); /* terminate on last close */ + + return 0; +} + +int spiRead(unsigned handle, char *buf, unsigned count) +{ + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (count > PI_MAX_SPI_DEVICE_COUNT) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spiGo(spiInfo[handle].speed, spiInfo[handle].flags, NULL, buf, count); + + return count; +} + +int spiWrite(unsigned handle, char *buf, unsigned count) +{ + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (count > PI_MAX_SPI_DEVICE_COUNT) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spiGo(spiInfo[handle].speed, spiInfo[handle].flags, buf, NULL, count); + + return count; +} + +int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count) +{ + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, txBuf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (count > PI_MAX_SPI_DEVICE_COUNT) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spiGo(spiInfo[handle].speed, spiInfo[handle].flags, txBuf, rxBuf, count); + + return count; +} + +/* ======================================================================= */ + + +int serOpen(char *tty, unsigned serBaud, unsigned serFlags) +{ + static pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; + struct termios new; + int speed; + int fd; + int i, slot; + + DBG(DBG_USER, "tty=%s serBaud=%d serFlags=0x%X", tty, serBaud, serFlags); + + SER_CHECK_INITED; + + if (strncmp("/dev/tty", tty, 8) && strncmp("/dev/serial", tty, 11)) + SOFT_ERROR(PI_BAD_SER_DEVICE, "bad device (%s)", tty); + + switch (serBaud) + { + case 50: speed = B50; break; + case 75: speed = B75; break; + case 110: speed = B110; break; + case 134: speed = B134; break; + case 150: speed = B150; break; + case 200: speed = B200; break; + case 300: speed = B300; break; + case 600: speed = B600; break; + case 1200: speed = B1200; break; + case 1800: speed = B1800; break; + case 2400: speed = B2400; break; + case 4800: speed = B4800; break; + case 9600: speed = B9600; break; + case 19200: speed = B19200; break; + case 38400: speed = B38400; break; + case 57600: speed = B57600; break; + case 115200: speed = B115200; break; + case 230400: speed = B230400; break; + + default: + SOFT_ERROR(PI_BAD_SER_SPEED, "bad speed (%d)", serBaud); + } + + if (serFlags) + SOFT_ERROR(PI_BAD_FLAGS, "bad flags (0x%X)", serFlags); + + slot = -1; + + pthread_mutex_lock(&mutex); + + for (i=0; i= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].fd >= 0) close(serInfo[handle].fd); + + serInfo[handle].fd = -1; + serInfo[handle].state = PI_SER_CLOSED; + + return 0; +} + +int serWriteByte(unsigned handle, unsigned bVal) +{ + char c; + + DBG(DBG_USER, "handle=%d bVal=%d", handle, bVal); + + SER_CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad parameter (%d)", bVal); + + c = bVal; + + if (write(serInfo[handle].fd, &c, 1) != 1) + return PI_SER_WRITE_FAILED; + else + return 0; +} + +int serReadByte(unsigned handle) +{ + int r; + char x; + + DBG(DBG_USER, "handle=%d", handle); + + SER_CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + r = read(serInfo[handle].fd, &x, 1); + + if (r == 1) + return ((int)x) & 0xFF; + + else if (r == 0) + return PI_SER_READ_NO_DATA; + + else if ((r == -1) && (errno == EAGAIN)) + return PI_SER_READ_NO_DATA; + + else + return PI_SER_READ_FAILED; +} + +int serWrite(unsigned handle, char *buf, unsigned count) +{ + int written=0, wrote=0; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + SER_CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + while ((written != count) && (wrote >= 0)) + { + wrote = write(serInfo[handle].fd, buf+written, count-written); + + if (wrote >= 0) + { + written += wrote; + + if (written != count) time_sleep(0.05); + } + } + + if (written != count) + return PI_SER_WRITE_FAILED; + else + return 0; +} + +int serRead(unsigned handle, char *buf, unsigned count) +{ + int r; + + DBG(DBG_USER, "handle=%d count=%d buf=0x%X", handle, count, (unsigned)buf); + + SER_CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + r = read(serInfo[handle].fd, buf, count); + + if (r == -1) + { + if (errno == EAGAIN) + return PI_SER_READ_NO_DATA; + else + return PI_SER_READ_FAILED; + } + else + { + if (r < count) buf[r] = 0; + return r; + } +} + +int serDataAvailable(unsigned handle) +{ + int result; + + DBG(DBG_USER, "handle=%d", handle); + + SER_CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (ioctl(serInfo[handle].fd, FIONREAD, &result) == -1) return 0; + + return result; +} + +/* ======================================================================= */ + +static int chooseBestClock + (clkInf_t *clkInf, unsigned f, unsigned numc, unsigned *cf) +{ + int c, valid, offby, offby2, best_offby; + uint32_t div; + uint64_t frac; + + valid = 0; + best_offby = 0; + + for (c=0; c 1) && (div < 4096)) + { + if (f < PI_MASH_MAX_FREQ) + { + frac = cf[c] - (div * f); + frac = (frac * 4096) / f; + offby = cf[c] - (div * f) - ((frac * f) / 4096); + if (frac < 4095) + { + offby2 = cf[c] - (div * f) - (((frac+1) * f) / 4096); + if (offby2 < 0) offby2 = -offby2; + if (offby2 < offby) + { + offby = offby2; + frac++; + } + } + } + else + { + frac = 0; + offby = cf[c] - (div * f); + if (div < 4095) + { + offby2 = cf[c] - ((div+1) * f); + if (offby2 < 0) offby2 = -offby2; + if (offby2 < offby) + { + offby = offby2; + div++; + } + } + } + + if ((!valid) || (offby <= best_offby)) + { + valid = 1; + clkInf->div = div; + clkInf->frac = frac; + clkInf->clock = c; + best_offby = offby; + } + } + } + return valid; +} + +/* ======================================================================= */ + +static rawCbs_t * dmaCB2adr(int pos) +{ + int page, slot; + + page = pos/CBS_PER_IPAGE; + slot = pos%CBS_PER_IPAGE; + + return &dmaIVirt[page]->cb[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static void dmaCbPrint(int pos) +{ + rawCbs_t * p; + + p = dmaCB2adr(pos); + + fprintf(stderr, "i=%x s=%x d=%x len=%x s=%x nxt=%x\n", + p->info, p->src, p->dst, p->length, p->stride, p->next); +} + +/* ----------------------------------------------------------------------- */ + +static unsigned dmaNowAtICB(void) +{ + unsigned cb; + static unsigned lastPage=0; + unsigned page; + uint32_t cbAddr; + uint32_t startTick, endTick; + + startTick = systReg[SYST_CLO]; + + cbAddr = dmaIn[DMA_CONBLK_AD]; + + page = lastPage; + + /* which page are we dma'ing? */ + + while (1) + { + cb = (cbAddr - ((int)dmaIBus[page])) / 32; + + if (cb < CBS_PER_IPAGE) + { + endTick = systReg[SYST_CLO]; + + if (endTick != startTick) + gpioStats.cbTicks += (endTick - startTick); + + gpioStats.cbCalls++; + + lastPage = page; + + return (page*CBS_PER_IPAGE) + cb; + } + + if (page++ >= DMAI_PAGES) page=0; + + if (page == lastPage) break; + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +static int dmaNowAtOCB(void) +{ + unsigned cb; + unsigned page; + uint32_t cbAddr; + + cbAddr = dmaOut[DMA_CONBLK_AD]; + + if (!cbAddr) return -PI_NO_TX_WAVE; + + page = 0; + + /* which page are we dma'ing? */ + + while (1) + { + cb = (cbAddr - ((int)dmaOBus[page])) / 32; + + if (cb < CBS_PER_OPAGE) return (page*CBS_PER_OPAGE) + cb; + + if (page++ >= DMAO_PAGES) break; + } + + /* Try twice */ + + cbAddr = dmaOut[DMA_CONBLK_AD]; + + if (!cbAddr) return -PI_NO_TX_WAVE; + + page = 0; + + /* which page are we dma'ing? */ + + while (1) + { + cb = (cbAddr - ((int)dmaOBus[page])) / 32; + + if (cb < CBS_PER_OPAGE) return (page*CBS_PER_OPAGE) + cb; + + if (page++ >= DMAO_PAGES) break; + } + + return -PI_WAVE_NOT_FOUND; +} + +/* ----------------------------------------------------------------------- */ + +unsigned rawWaveCB(void) +{ + unsigned cb; + static unsigned lastPage=0; + unsigned page; + uint32_t cbAddr; + + cbAddr = dmaOut[DMA_CONBLK_AD]; + + if (!cbAddr) return -1; + + page = lastPage; + + /* which page are we dma'ing? */ + + while (1) + { + cb = (cbAddr - ((int)dmaOBus[page])) / 32; + + if (cb < CBS_PER_OPAGE) + { + lastPage = page; + + return (page*CBS_PER_OPAGE) + cb; + } + + if (page++ >= DMAO_PAGES) page=0; + + if (page == lastPage) break; + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +static unsigned dmaCurrentSlot(unsigned pos) +{ + unsigned cycle=0, slot=0, tmp; + + cycle = (pos/CBS_PER_CYCLE); + tmp = (pos%CBS_PER_CYCLE); + + if (tmp > 2) slot = ((tmp-2)/3); + + return (cycle*PULSE_PER_CYCLE)+slot; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaPwmDataAdr(int pos) +{ + return (uint32_t) &dmaIBus[pos]->periphData; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaGpioOnAdr(int pos) +{ + int page, slot; + + page = pos/ON_PER_IPAGE; + slot = pos%ON_PER_IPAGE; + + return (uint32_t) &dmaIBus[page]->gpioOn[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaGpioOffAdr(int pos) +{ + int page, slot; + + myOffPageSlot(pos, &page, &slot); + + return (uint32_t) &dmaIBus[page]->gpioOff[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaTickAdr(int pos) +{ + int page, slot; + + myTckPageSlot(pos, &page, &slot); + + return (uint32_t) &dmaIBus[page]->tick[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaReadLevelsAdr(int pos) +{ + int page, slot; + + myLvsPageSlot(pos, &page, &slot); + + return (uint32_t) &dmaIBus[page]->level[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t dmaCbAdr(int pos) +{ + int page, slot; + + page = (pos/CBS_PER_IPAGE); + slot = (pos%CBS_PER_IPAGE); + + return (uint32_t) &dmaIBus[page]->cb[slot]; +} + +/* ----------------------------------------------------------------------- */ + +static void dmaGpioOnCb(int b, int pos) +{ + rawCbs_t * p; + + p = dmaCB2adr(b); + + p->info = NORMAL_DMA; + p->src = dmaGpioOnAdr(pos); + p->dst = ((GPIO_BASE + (GPSET0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->length = 4; + p->next = dmaCbAdr(b+1); +} + +/* ----------------------------------------------------------------------- */ + +static void dmaTickCb(int b, int pos) +{ + rawCbs_t * p; + + p = dmaCB2adr(b); + + p->info = NORMAL_DMA; + p->src = ((SYST_BASE + (SYST_CLO*4)) & 0x00ffffff) | PI_PERI_BUS; + p->dst = dmaTickAdr(pos); + p->length = 4; + p->next = dmaCbAdr(b+1); +} + +/* ----------------------------------------------------------------------- */ + +static void dmaGpioOffCb(int b, int pos) +{ + rawCbs_t * p; + + p = dmaCB2adr(b); + + p->info = NORMAL_DMA; + p->src = dmaGpioOffAdr(pos); + p->dst = ((GPIO_BASE + (GPCLR0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->length = 4; + p->next = dmaCbAdr(b+1); +} + +/* ----------------------------------------------------------------------- */ + +static void dmaReadLevelsCb(int b, int pos) +{ + rawCbs_t * p; + + p = dmaCB2adr(b); + + p->info = NORMAL_DMA; + p->src = ((GPIO_BASE + (GPLEV0*4)) & 0x00ffffff) | PI_PERI_BUS; + p->dst = dmaReadLevelsAdr(pos); + p->length = 4; + p->next = dmaCbAdr(b+1); +} + +/* ----------------------------------------------------------------------- */ + +static void dmaDelayCb(int b) +{ + rawCbs_t * p; + + p = dmaCB2adr(b); + + if (gpioCfg.clockPeriph == PI_CLOCK_PCM) + { + p->info = NORMAL_DMA | TIMED_DMA(2); + p->dst = PCM_TIMER; + } + else + { + p->info = NORMAL_DMA | TIMED_DMA(5); + p->dst = PWM_TIMER; + } + + p->src = dmaPwmDataAdr(b%DMAI_PAGES); + p->length = 4; + p->next = dmaCbAdr(b+1); +} + +/* ----------------------------------------------------------------------- */ + +static void dmaInitCbs(void) +{ + int b, pulse, level, cycle; + + rawCbs_t * p; + + /* set up the DMA control blocks */ + + DBG(DBG_STARTUP, ""); + + gpioStats.dmaInitCbsCount++; + + b = -1; + level = 0; + + for (cycle=0; cyclenext = dmaCbAdr(0); + + DBG(DBG_STARTUP, "DMA page type count = %d", sizeof(dmaIPage_t)); + + DBG(DBG_STARTUP, "%d control blocks (exp=%d)", b+1, NUM_CBS); +} + +/* ======================================================================= */ + + +static void sigHandler(int signum) +{ + if ((signum >= PI_MIN_SIGNUM) && (signum <= PI_MAX_SIGNUM)) + { + if (gpioSignal[signum].func) + { + if (gpioSignal[signum].ex) + { + (gpioSignal[signum].func)(signum, gpioSignal[signum].userdata); + } + else + { + (gpioSignal[signum].func)(signum); + } + } + else + { + switch(signum) + { + case SIGUSR1: + + if (gpioCfg.dbgLevel > DBG_MIN_LEVEL) --gpioCfg.dbgLevel; + else gpioCfg.dbgLevel = DBG_MIN_LEVEL; + DBG(DBG_USER, "Debug level %d\n", gpioCfg.dbgLevel); + break; + + case SIGUSR2: + if (gpioCfg.dbgLevel < DBG_MAX_LEVEL) ++gpioCfg.dbgLevel; + else gpioCfg.dbgLevel = DBG_MAX_LEVEL; + DBG(DBG_USER, "Debug level %d\n", gpioCfg.dbgLevel); + break; + + case SIGPIPE: + case SIGWINCH: + DBG(DBG_USER, "signal %d ignored", signum); + break; + + case SIGCHLD: + /* Used to notify threads of events */ + break; + + default: + DBG(DBG_ALWAYS, "Unhandled signal %d, terminating\n", signum); + gpioTerminate(); + exit(-1); + } + } + } + else + { + /* exit */ + + DBG(DBG_ALWAYS, "Unhandled signal %d, terminating\n", signum); + gpioTerminate(); + exit(-1); + } +} + +/* ----------------------------------------------------------------------- */ + +static void sigSetHandler(void) +{ + int i; + struct sigaction new; + + for (i=PI_MIN_SIGNUM; i<=PI_MAX_SIGNUM; i++) + { + + memset(&new, 0, sizeof(new)); + new.sa_handler = sigHandler; + + sigaction(i, &new, NULL); + } +} + +/* + freq mics net + 0 1000 1000 900 + 1 4000 250 225 + 2 3750 266 240 + 3 3500 285 257 + 4 3250 307 276 + 5 3000 333 300 + 6 2750 363 327 + 7 2500 400 360 + 8 2250 444 400 + 9 2000 500 450 +10 1750 571 514 +11 1500 666 600 +12 1250 800 720 +13 1000 1000 900 +14 750 1333 1200 +15 500 2000 1800 +*/ + +unsigned alert_delays[]= +{ + 900000, 225000, 240000, 257142, 276923, 300000, 327272, 360000, + 400000, 450000, 514285, 600000, 720000, 900000, 1200000, 1800000 +}; + +/* ======================================================================= */ + +static void alertGlitchFilter(gpioSample_t *sample, int numSamples) +{ + int i, j, diff; + uint32_t steadyUs, changedTick, RBitV, LBitV; + uint32_t bit, bitV; + + for (i=0; i<=PI_MAX_USER_GPIO; i++) + { + bit = (1<= steadyUs) + { + /* Level stable for steady period. */ + RBitV = bitV; + } + else + { + /* Keep reporting old level. */ + + sample[j].level ^= bit; + } + } + + } + + gpioAlert[i].gfRBitV = RBitV; + gpioAlert[i].gfLBitV = LBitV; + gpioAlert[i].gfTick = changedTick; + } + } +} + +static void alertNoiseFilter(gpioSample_t *sample, int numSamples) +{ + int i, j, diff; + uint32_t LBitV; + uint32_t bit, bitV; + uint32_t nowTick; + + for (i=0; i<=PI_MAX_USER_GPIO; i++) + { + bit = (1<= 0) + { + /* Stop reporting gpio changes */ + + gpioAlert[i].nfActive = 0; + gpioAlert[i].nfTick1 = nowTick; + } + } + else /* waiting for steady us */ + { + if (bitV != LBitV) + { + diff = nowTick - gpioAlert[i].nfTick1; + gpioAlert[i].nfTick1 = nowTick; + + if (diff >= gpioAlert[i].nfSteadyUs) + { + /* Start reporting gpio changes */ + + gpioAlert[i].nfRBitV = LBitV; + gpioAlert[i].nfActive = 1; + gpioAlert[i].nfTick2 = + nowTick + gpioAlert[i].nfActiveUs; + } + } + } + + if (!gpioAlert[i].nfActive) + { + if (bitV != gpioAlert[i].nfRBitV) + sample[j].level ^= bit; + } + + LBitV = bitV; + } + + gpioAlert[i].nfLBitV = LBitV; + + } + } +} + +static void alertEmit( + gpioSample_t *sample, int numSamples, uint32_t changedBits, uint32_t eTick) +{ + uint32_t oldLevel, newLevel; + int32_t diff; + int emit, seqno, emitted; + uint32_t changes, bits, timeoutBits, eventBits; + int d; + int b, n, v; + int err; + int max_emits; + char fifo[32]; + /* ensure space for maximum number of watchdog and event notifications */ + gpioReport_t report[MAX_REPORT+PI_MAX_USER_GPIO+1+PI_MAX_EVENT+1]; + + if (changedBits) + { + if (gpioGetSamples.func) + { + if (gpioGetSamples.ex) + { + (gpioGetSamples.func) + (sample, numSamples, gpioGetSamples.userdata); + } + else + { + (gpioGetSamples.func)(sample, numSamples); + } + } + } + + eventBits = 0; + + if (bscFR != (bscsReg[BSC_FR]&0xffff)) + { + bscFR = bscsReg[BSC_FR]&0xffff; + eventAlert[PI_EVENT_BSC].fired = 1; + } + + for (b=0; b<=PI_MAX_EVENT; b++) + { + if (eventAlert[b].fired && (!eventAlert[b].ignore)) + { + eventBits |= (1<= gpioAlert[b].wdSteadyUs) + { + timeoutBits |= (1<= PI_NOTIFY_OPENED) + { + bits = gpioNotify[n].bits; + + emit = 0; + + seqno = gpioNotify[n].seqno; + + if (gpioNotify[n].state == PI_NOTIFY_RUNNING) + { + /* check to see if any bits have changed for this + notification. + + bits is the set of notification bits + changedBits is the set of changed bits + */ + + if (changedBits & bits) + { + oldLevel = reportedLevel & bits; + + for (d=0; d 60000000) + { + if (numSamples) + newLevel = sample[numSamples-1].level; + else + newLevel = reportedLevel; + + report[emit].seqno = seqno; + report[emit].flags = PI_NTFY_FLAGS_ALIVE; + report[emit].tick = eTick; + report[emit].level = newLevel; + + emit++; + seqno++; + } + } + + if (emit) + { + DBG(DBG_FAST_TICK, "notification %d (%d reports, %x-%x)", + n, emit, report[0].seqno, report[emit-1].seqno); + gpioNotify[n].lastReportTick = eTick; + max_emits = gpioNotify[n].max_emits; + + if (emit > gpioStats.maxEmit) gpioStats.maxEmit = emit; + + emitted = 0; + + while (emit > 0) + { + if (emit > max_emits) + { + gpioStats.emitFrags++; + + err = write(gpioNotify[n].fd, + report+emitted, + max_emits*sizeof(gpioReport_t)); + + if (err != (max_emits*sizeof(gpioReport_t))) + { + if (err < 0) + { + if ((errno != EAGAIN) && (errno != EWOULDBLOCK)) + { + /* serious error, no point continuing */ + + DBG(DBG_ALWAYS, "fd=%d err=%d errno=%d", + gpioNotify[n].fd, err, errno); + + DBG(DBG_ALWAYS, "%s", strerror(errno)); + + gpioNotify[n].bits = 0; + gpioNotify[n].state = PI_NOTIFY_CLOSING; + intNotifyBits(); + break; + } + else gpioStats.wouldBlockPipeWrite++; + } + else + { + gpioStats.shortPipeWrite++; + DBG(DBG_ALWAYS, "emitted %d, asked for %d", + err/sizeof(gpioReport_t), max_emits); + } + } + else + { + gpioStats.goodPipeWrite++; + } + + emitted += max_emits; + emit -= max_emits; + } + else + { + err = write(gpioNotify[n].fd, + report+emitted, + emit*sizeof(gpioReport_t)); + + if (err != (emit*sizeof(gpioReport_t))) + { + if (err < 0) + { + if ((errno != EAGAIN) && (errno != EWOULDBLOCK)) + { + DBG(DBG_ALWAYS, "fd=%d err=%d errno=%d", + gpioNotify[n].fd, err, errno); + + DBG(DBG_ALWAYS, "%s", strerror(errno)); + + /* serious error, no point continuing */ + gpioNotify[n].bits = 0; + gpioNotify[n].state = PI_NOTIFY_CLOSING; + intNotifyBits(); + break; + } + else gpioStats.wouldBlockPipeWrite++; + } + else + { + gpioStats.shortPipeWrite++; + DBG(DBG_ALWAYS, "emitted %d, asked for %d", + err/sizeof(gpioReport_t), emit); + } + } + else + { + gpioStats.goodPipeWrite++; + } + + emitted += emit; + emit = 0; + } + } + + gpioNotify[n].seqno = seqno; + } + } + } + + if (changedBits & scriptBits) + { + for (n=0; n= PULSE_PER_CYCLE) + { + pulse = 0; + + if (++cycle >= bufferCycles) + { + cycle = 0; + oldSlot = 0; + } + + expected = sTick; + + sTick = myGetTick(cycle); + + if (stickInited) + { + diff = sTick - expected; + + if (abs(diff) > minDiff) + { + ft = sample[numSamples-PULSE_PER_CYCLE].tick; + + ticks = sTick - ft; + + for (i=1; i= TICKSLOTS) + { + gpioStats.diffTick[TICKSLOTS-1]++; + } + + else gpioStats.diffTick[diff]++; + } + else + { + stickInited = 1; + numSamples = 0; + if (!(gpioCfg.ifFlags & PI_DISABLE_ALERT)) + { + pthAlertRunning = PI_THREAD_RUNNING; + } + } + } + } + + if (oldSlot == newSlot) moreToDo = 0; else moreToDo = 1; + + /* Apply glitch filter */ + + if (numSamples && gFilterBits) alertGlitchFilter(sample, numSamples); + + /* Apply noise filter */ + + if (numSamples && nFilterBits) alertNoiseFilter(sample, numSamples); + + /* Compact samples */ + + changedBits = 0; + oldLevel &= monitorBits; + reports = 0; + totalSamples = 0; + + for (rp=0; rp= MAX_REPORT) + { + totalSamples += reports; + + /* Rebase watchdog timeouts */ + if (wdogBits) alertWdogCheck(sample, reports); + + gpioStats.numSamples += reports; + + alertEmit(sample, reports, changedBits, sample[rp].tick); + + changedBits = 0; + reports = 0; + } + } + } + + if (reports) + { + totalSamples += reports; + + /* Rebase watchdog timeouts */ + if (wdogBits) alertWdogCheck(sample, reports); + + gpioStats.numSamples += reports; + } + + alertEmit(sample, reports, changedBits, sTick); + reportedLevel = sample[numSamples -1].level; + + if (totalSamples > gpioStats.maxSamples) + gpioStats.maxSamples = numSamples; + + req.tv_sec = 0; + req.tv_nsec = alert_delays[(gpioCfg.internals>>PI_CFG_ALERT_FREQ)&15]; + + if (moreToDo) + { + gpioStats.moreToDo++; + } + else + { + gpioStats.alertTicks++; + + while (nanosleep(&req, &rem)) + { + req.tv_sec = rem.tv_sec; + req.tv_nsec = rem.tv_nsec; + } + } + } + + return 0; +} + +/* ======================================================================= */ + +static int scrPop(gpioScript_t *s, int *SP, int *S) +{ + if ((*SP) > 0) + { + return S[--(*SP)]; + } + else + { + s->run_state = PI_SCRIPT_FAILED; + DBG(DBG_ALWAYS, "script %d too many pops", s->id); + return 0; + } +} + +/* ----------------------------------------------------------------------- */ + +static void scrPush(gpioScript_t *s, int *SP, int *S, int val) +{ + if ((*SP) < PI_SCRIPT_STACK_SIZE) + { + S[(*SP)++] = val; + } + else + { + s->run_state = PI_SCRIPT_FAILED; + DBG(DBG_ALWAYS, "script %d too many pushes", s->id); + } +} + +/* ----------------------------------------------------------------------- */ + +static void scrSwap(int *v1, int *v2) +{ + int t; + + t=*v1; *v1=*v2; *v2= t; +} + +/* ----------------------------------------------------------------------- */ + +static int scrEvtWait(gpioScript_t *s, uint32_t bits) +{ + pthread_mutex_lock(&s->pthMutex); + + if (s->request == PI_SCRIPT_RUN) + { + s->run_state = PI_SCRIPT_WAITING; + s->eventBits = bits; + intScriptEventBits(); + + pthread_cond_wait(&s->pthCond, &s->pthMutex); + + s->waitBits = 0; + intScriptEventBits(); + s->run_state = PI_SCRIPT_RUNNING; + } + + pthread_mutex_unlock(&s->pthMutex); + + return s->changedBits; +} + +/* ----------------------------------------------------------------------- */ + +static int scrWait(gpioScript_t *s, uint32_t bits) +{ + pthread_mutex_lock(&s->pthMutex); + + if (s->request == PI_SCRIPT_RUN) + { + s->run_state = PI_SCRIPT_WAITING; + s->waitBits = bits; + intScriptBits(); + + pthread_cond_wait(&s->pthCond, &s->pthMutex); + + s->waitBits = 0; + intScriptBits(); + s->run_state = PI_SCRIPT_RUNNING; + } + + pthread_mutex_unlock(&s->pthMutex); + + return s->changedBits; +} + +/* ----------------------------------------------------------------------- */ + +static int scrSys(char *cmd, uint32_t p1, uint32_t p2) +{ + char buf[1024]; + int status; + + if (!myScriptNameValid(cmd)) + SOFT_ERROR(PI_BAD_SCRIPT_NAME, "bad script name (%s)", cmd); + + snprintf(buf, sizeof(buf), "/opt/pigpio/cgi/%s %u %u", cmd, p1, p2); + + DBG(DBG_USER, "%s", buf); + + status = system(buf); + + if (status < 0) status = PI_BAD_SHELL_STATUS; + + return status; +} + +/* ----------------------------------------------------------------------- */ + +static void *pthScript(void *x) +{ + gpioScript_t *s; + cmdInstr_t instr; + int p1, p2, p1o, p2o, p3o, *t1, *t2; + int PC, A, F, SP; + int S[PI_SCRIPT_STACK_SIZE]; + char buf[CMD_MAX_EXTENSION]; + + + S[0] = 0; /* to prevent compiler warning */ + + s = x; + + while ((volatile int)s->request != PI_SCRIPT_DELETE) + { + pthread_mutex_lock(&s->pthMutex); + s->run_state = PI_SCRIPT_HALTED; + pthread_cond_wait(&s->pthCond, &s->pthMutex); + pthread_mutex_unlock(&s->pthMutex); + + s->run_state = PI_SCRIPT_RUNNING; + + A = 0; + F = 0; + PC = 0; + SP = 0; + + while (((volatile int)s->request == PI_SCRIPT_RUN ) && + (s->run_state == PI_SCRIPT_RUNNING)) + { + instr = s->script.instr[PC]; + + p1o = instr.p[1]; + p2o = instr.p[2]; + + if (instr.opt[1] == CMD_VAR) instr.p[1] = s->script.var[p1o]; + else if (instr.opt[1] == CMD_PAR) instr.p[1] = s->script.par[p1o]; + + if (instr.opt[2] == CMD_VAR) instr.p[2] = s->script.var[p2o]; + else if (instr.opt[2] == CMD_PAR) instr.p[2] = s->script.par[p2o]; +/* + fprintf(stderr, "PC=%d cmd=%d p1o=%d p1=%d p2o=%d p2=%d\n", + PC, instr.p[0], p1o, instr.p[1], p2o, instr.p[2]); + fflush(stderr); +*/ + if (instr.p[0] < PI_CMD_SCRIPT) + { + if (instr.p[3]) + { + if ((instr.p[3] == sizeof(int)) && ((instr.opt[3] == CMD_VAR) || (instr.opt[3] == CMD_PAR))) + { + /* Hack to allow register use in 3rd parameter */ + memcpy((char*)&p3o, (char *)instr.p[4], sizeof(int)); + if (instr.opt[3] == CMD_VAR) memcpy(buf, (char *)&(s->script.var[p3o]), sizeof(int)); + else memcpy(buf, (char *)&(s->script.par[p3o]), sizeof(int)); + } + else + { + memcpy(buf, (char *)instr.p[4], instr.p[3]); + } + } + + A = myDoCommand(instr.p, sizeof(buf)-1, buf); + + F = A; + + PC++; + } + else + { + p1 = instr.p[1]; + p2 = instr.p[2]; + + switch (instr.p[0]) + { + case PI_CMD_ADD: A+=p1; F=A; PC++; break; + + case PI_CMD_AND: A&=p1; F=A; PC++; break; + + case PI_CMD_CALL: scrPush(s, &SP, S, PC+1); PC = p1; break; + + case PI_CMD_CMP: F=A-p1; PC++; break; + + case PI_CMD_DCR: + if (instr.opt[1] == CMD_PAR) + {--s->script.par[p1o]; F=s->script.par[p1o];} + else + {--s->script.var[p1o]; F=s->script.var[p1o];} + PC++; + break; + + case PI_CMD_DCRA: --A; F=A; PC++; break; + + case PI_CMD_DIV: A/=p1; F=A; PC++; break; + + case PI_CMD_HALT: s->run_state = PI_SCRIPT_HALTED; break; + + case PI_CMD_EVTWT: A=scrEvtWait(s, p1); F=A; PC++; break; + + case PI_CMD_INR: + if (instr.opt[1] == CMD_PAR) + {++s->script.par[p1o]; F=s->script.par[p1o];} + else + {++s->script.var[p1o]; F=s->script.var[p1o];} + PC++; + break; + + case PI_CMD_INRA: ++A; F=A; PC++; break; + + case PI_CMD_JM: if (F<0) PC=p1; else PC++; break; + + case PI_CMD_JMP: PC=p1; break; + + case PI_CMD_JNZ: if (F) PC=p1; else PC++; break; + + case PI_CMD_JP: if (F>=0) PC=p1; else PC++; break; + + case PI_CMD_JZ: if (!F) PC=p1; else PC++; break; + + case PI_CMD_LD: + if (instr.opt[1] == CMD_PAR) s->script.par[p1o]=p2; + else s->script.var[p1o]=p2; + PC++; + break; + + case PI_CMD_LDA: A=p1; PC++; break; + + case PI_CMD_LDAB: + if ((p1 >= 0) && (p1 < sizeof(buf))) A = buf[p1]; + PC++; + break; + + case PI_CMD_MLT: A*=p1; F=A; PC++; break; + + case PI_CMD_MOD: A%=p1; F=A; PC++; break; + + case PI_CMD_OR: A|=p1; F=A; PC++; break; + + case PI_CMD_POP: + if (instr.opt[1] == CMD_PAR) + s->script.par[p1o]=scrPop(s, &SP, S); + else + s->script.var[p1o]=scrPop(s, &SP, S); + PC++; + break; + + case PI_CMD_POPA: A=scrPop(s, &SP, S); PC++; break; + + case PI_CMD_PUSH: + if (instr.opt[1] == CMD_PAR) + scrPush(s, &SP, S, s->script.par[p1o]); + else + scrPush(s, &SP, S, s->script.var[p1o]); + PC++; + break; + + case PI_CMD_PUSHA: scrPush(s, &SP, S, A); PC++; break; + + case PI_CMD_RET: PC=scrPop(s, &SP, S); break; + + case PI_CMD_RL: + if (instr.opt[1] == CMD_PAR) + {s->script.par[p1o]<<=p2; F=s->script.par[p1o];} + else + {s->script.var[p1o]<<=p2; F=s->script.var[p1o];} + PC++; + break; + + case PI_CMD_RLA: A<<=p1; F=A; PC++; break; + + case PI_CMD_RR: + if (instr.opt[1] == CMD_PAR) + {s->script.par[p1o]>>=p2; F=s->script.par[p1o];} + else + {s->script.var[p1o]>>=p2; F=s->script.var[p1o];} + PC++; + break; + + case PI_CMD_RRA: A>>=p1; F=A; PC++; break; + + case PI_CMD_STA: + if (instr.opt[1] == CMD_PAR) s->script.par[p1o]=A; + else s->script.var[p1o]=A; + PC++; + break; + + case PI_CMD_STAB: + if ((p1 >= 0) && (p1 < sizeof(buf))) buf[p1] = A; + PC++; + break; + + case PI_CMD_SUB: A-=p1; F=A; PC++; break; + + case PI_CMD_SYS: + A=scrSys((char*)instr.p[4], A, *(gpioReg + GPLEV0)); + F=A; + PC++; + break; + + case PI_CMD_WAIT: A=scrWait(s, p1); F=A; PC++; break; + + case PI_CMD_X: + if (instr.opt[1] == CMD_PAR) t1 = &s->script.par[p1o]; + else t1 = &s->script.var[p1o]; + + if (instr.opt[2] == CMD_PAR) t2 = &s->script.par[p2o]; + else t2 = &s->script.var[p2o]; + + scrSwap(t1, t2); + PC++; + break; + + case PI_CMD_XA: + if (instr.opt[1] == CMD_PAR) + scrSwap(&s->script.par[p1o], &A); + else + scrSwap(&s->script.var[p1o], &A); + PC++; + break; + + case PI_CMD_XOR: A^=p1; F=A; PC++; break; + + } + } + + if (PC >= s->script.instrs) s->run_state = PI_SCRIPT_HALTED; + + } + + if ((volatile int)s->request == PI_SCRIPT_HALT) + s->run_state = PI_SCRIPT_HALTED; + + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +static void * pthTimerTick(void *x) +{ + gpioTimer_t *tp; + struct timespec req, rem; + + tp = x; + + while (1) + { + req.tv_sec = tp->millis / THOUSAND; + req.tv_nsec = (tp->millis % THOUSAND) * THOUSAND * THOUSAND; + + while (nanosleep(&req, &rem)) + { + req.tv_sec = rem.tv_sec; + req.tv_nsec = rem.tv_nsec; + } + + if (tp->ex) (tp->func)(tp->userdata); + else (tp->func)(); + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + + +static void * pthFifoThread(void *x) +{ + char buf[CMD_MAX_EXTENSION]; + int idx, flags, len, res, i; + uint32_t p[CMD_P_ARR]; + cmdCtlParse_t ctl; + uint32_t *param; + char v[CMD_MAX_EXTENSION]; + + myCreatePipe(PI_INPFIFO, 0662); + + if ((inpFifo = fopen(PI_INPFIFO, "r+")) == NULL) + SOFT_ERROR((void*)PI_INIT_FAILED, "fopen %s failed(%m)", PI_INPFIFO); + + myCreatePipe(PI_OUTFIFO, 0664); + + if ((outFifo = fopen(PI_OUTFIFO, "w+")) == NULL) + SOFT_ERROR((void*)PI_INIT_FAILED, "fopen %s failed (%m)", PI_OUTFIFO); + + /* set outFifo non-blocking */ + + flags = fcntl(fileno(outFifo), F_GETFL, 0); + fcntl(fileno(outFifo), F_SETFL, flags | O_NONBLOCK); + + /* don't start until DMA started */ + + spinWhileStarting(); + + while (1) + { + if (fgets(buf, sizeof(buf), inpFifo) == NULL) + SOFT_ERROR((void*)PI_INIT_FAILED, "fifo fgets failed (%m)"); + + len = strlen(buf); + + if (len) + { + --len; + buf[len] = 0; /* replace terminating */ + } + + ctl.eaten = 0; + idx = 0; + + while (((ctl.eaten)= 0)) + { + if ((idx=cmdParse(buf, p, CMD_MAX_EXTENSION, v, &ctl)) >= 0) + { + /* make sure extensions are null terminated */ + + v[p[3]] = 0; + + res = myDoCommand(p, sizeof(v)-1, v); + + switch (cmdInfo[idx].rv) + { + case 0: + fprintf(outFifo, "%d\n", res); + break; + + case 1: + fprintf(outFifo, "%d\n", res); + break; + + case 2: + fprintf(outFifo, "%d\n", res); + break; + + case 3: + fprintf(outFifo, "%08X\n", res); + break; + + case 4: + fprintf(outFifo, "%u\n", res); + break; + + case 5: + fprintf(outFifo, "%s", cmdUsage); + break; + + case 6: + fprintf(outFifo, "%d", res); + if (res > 0) + { + for (i=0; i= 0) + { + memcpy(buf, &p[3], 4); + p[3] = 4 + (4*PI_MAX_SCRIPT_PARAMS); + } + break; + + default: + p[3] = myDoCommand(p, sizeof(buf)-1, buf); + } + + if (write(sock, p, 16) == -1) { /* ignore errors */ } + + switch (p[0]) + { + /* extensions */ + + case PI_CMD_BI2CZ: + case PI_CMD_BSCX: + case PI_CMD_CF2: + case PI_CMD_FL: + case PI_CMD_FR: + case PI_CMD_I2CPK: + case PI_CMD_I2CRD: + case PI_CMD_I2CRI: + case PI_CMD_I2CRK: + case PI_CMD_I2CZ: + case PI_CMD_PROCP: + case PI_CMD_SERR: + case PI_CMD_SLR: + case PI_CMD_SPIX: + case PI_CMD_SPIR: + case PI_CMD_BSPIX: + + if (((int)p[3]) > 0) + { + if (write(sock, buf, p[3]) == 1) { /* ignore errors */ } + } + break; + + default: + break; + } + } + + closeOrphanedNotifications(-1, sock); + + close(sock); + + DBG(DBG_ALWAYS, "Socket %d closed", sock); + + return 0; +} + +static int addrAllowed(struct sockaddr *saddr) +{ + int i; + uint32_t addr; + + if (!numSockNetAddr) return 1; + + // FIXME: add IPv6 whitelisting support + if (saddr->sa_family != AF_INET) return 0; + + addr = ((struct sockaddr_in *) saddr)->sin_addr.s_addr; + + for (i=0; i= 0) + { + pthread_t thr; + + fdC = accept(fdSock, (struct sockaddr *)&client, (socklen_t*)&c); + + closeOrphanedNotifications(-1, fdC); + + if (addrAllowed((struct sockaddr *)&client)) + { + DBG(DBG_ALWAYS, "Connection accepted on socket %d", fdC); + + sock = malloc(sizeof(int)); + + *sock = fdC; + + /* Enable tcp_keepalive */ + int optval = 1; + socklen_t optlen = sizeof(optval); + + if (setsockopt(fdC, SOL_SOCKET, SO_KEEPALIVE, &optval, optlen) < 0) { + DBG(0, "setsockopt() fail, closing socket %d", fdC); + close(fdC); + } + + DBG(DBG_ALWAYS, "SO_KEEPALIVE enabled on socket %d\n", fdC); + + if (pthread_create + (&thr, &attr, pthSocketThreadHandler, (void*) sock) < 0) + SOFT_ERROR((void*)PI_INIT_FAILED, + "socket pthread_create failed (%m)"); + } + else + { + DBG(DBG_ALWAYS, "Connection rejected, closing"); + close(fdC); + } + } + + if (fdC < 0) + SOFT_ERROR((void*)PI_INIT_FAILED, "accept failed (%m)"); + + return 0; +} + +/* ======================================================================= */ + +static void initCheckLockFile(void) +{ + int fd; + int count; + int pid; + int err; + int delete; + char str[20]; + + fd = open(PI_LOCKFILE, O_RDONLY); + + if (fd != -1) + { + DBG(DBG_STARTUP, "lock file exists"); + delete = 1; + + count = read(fd, str, sizeof(str)-1); + + if (count) + { + pid = atoi(str); + err = kill(pid, 0); + if (!err) delete = 0; /* process still exists */ + DBG(DBG_STARTUP, "lock file pid=%d err=%d", pid, err); + } + + close(fd); + DBG(DBG_STARTUP, "lock file delete=%d", delete); + + if (delete) unlink(PI_LOCKFILE); + } +} + +static int initGrabLockFile(void) +{ + int fd; + int lockResult; + char pidStr[20]; + + initCheckLockFile(); + + /* try to grab the lock file */ + + fd = open(PI_LOCKFILE, O_WRONLY|O_CREAT|O_EXCL|O_TRUNC, 0644); + + if (fd != -1) + { + lockResult = flock(fd, LOCK_EX|LOCK_NB); + + if(lockResult == 0) + { + sprintf(pidStr, "%d\n", (int)getpid()); + + if (write(fd, pidStr, strlen(pidStr)) == -1) + { + /* ignore errors */ + } + } + else + { + close(fd); + return -1; + } + } + + return fd; +} + +/* ----------------------------------------------------------------------- */ + +static uint32_t * initMapMem(int fd, uint32_t addr, uint32_t len) +{ + return (uint32_t *) mmap(0, len, + PROT_READ|PROT_WRITE|PROT_EXEC, + MAP_SHARED|MAP_LOCKED, + fd, addr); +} + +/* ----------------------------------------------------------------------- */ + +static int initCheckPermitted(void) +{ + DBG(DBG_STARTUP, ""); + + if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC) ) < 0) + { + DBG(DBG_ALWAYS, + "\n" \ + "+---------------------------------------------------------+\n" \ + "|Sorry, you don't have permission to run this program. |\n" \ + "|Try running as root, e.g. precede the command with sudo. |\n" \ + "+---------------------------------------------------------+\n\n"); + return -1; + } + return 0; +} + +/* ----------------------------------------------------------------------- */ + +static int initPeripherals(void) +{ + uint32_t dmaBase; + + DBG(DBG_STARTUP, ""); + + gpioReg = initMapMem(fdMem, GPIO_BASE, GPIO_LEN); + + if (gpioReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap gpio failed (%m)"); + + /* dma channels 0-14 share one page, 15 has another */ + + if (gpioCfg.DMAprimaryChannel < 15) + { + dmaBase = DMA_BASE; + } + else dmaBase = DMA15_BASE; + + dmaReg = initMapMem(fdMem, dmaBase, DMA_LEN); + + if (dmaReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap dma failed (%m)"); + + if (gpioCfg.DMAprimaryChannel < 15) + { + dmaIn = dmaReg + (gpioCfg.DMAprimaryChannel * 0x40); + dmaOut = dmaReg + (gpioCfg.DMAsecondaryChannel * 0x40); + } + + DBG(DBG_STARTUP, "DMA #%d @ %08X @ %08X", + gpioCfg.DMAprimaryChannel, dmaBase, (uint32_t)dmaIn); + + DBG(DBG_STARTUP, "debug reg is %08X", dmaIn[DMA_DEBUG]); + + clkReg = initMapMem(fdMem, CLK_BASE, CLK_LEN); + + if (clkReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap clk failed (%m)"); + + systReg = initMapMem(fdMem, SYST_BASE, SYST_LEN); + + if (systReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap syst failed (%m)"); + + spiReg = initMapMem(fdMem, SPI_BASE, SPI_LEN); + + if (spiReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap spi failed (%m)"); + + pwmReg = initMapMem(fdMem, PWM_BASE, PWM_LEN); + + if (pwmReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap pwm failed (%m)"); + + pcmReg = initMapMem(fdMem, PCM_BASE, PCM_LEN); + + if (pcmReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap pcm failed (%m)"); + + auxReg = initMapMem(fdMem, AUX_BASE, AUX_LEN); + + if (auxReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap aux failed (%m)"); + + padsReg = initMapMem(fdMem, PADS_BASE, PADS_LEN); + + if (padsReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap pads failed (%m)"); + + bscsReg = initMapMem(fdMem, BSCS_BASE, BSCS_LEN); + + if (bscsReg == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap bscs failed (%m)"); + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +static int initZaps + (int pmapFd, void *virtualBase, int basePage, int pages) +{ + int n; + long index; + off_t offset; + ssize_t t; + uint32_t physical; + int status; + uint32_t pageAdr; + unsigned long long pa; + + DBG(DBG_STARTUP, ""); + + status = 0; + + pageAdr = (uint32_t) dmaVirt[basePage]; + + index = ((uint32_t)virtualBase / PAGE_SIZE) * 8; + + offset = lseek(pmapFd, index, SEEK_SET); + + if (offset != index) + SOFT_ERROR(PI_INIT_FAILED, "lseek pagemap failed (%m)"); + + for (n=0; n PI_DEFAULT_BUFFER_MILLIS))) + { + /* pagemap allocation of DMA memory */ + + dmaPMapBlk = mmap( + 0, (bufferBlocks+PI_WAVE_BLOCKS)*sizeof(dmaPage_t *), + PROT_READ|PROT_WRITE, + MAP_PRIVATE|MAP_ANONYMOUS|MAP_LOCKED, + -1, 0); + + if (dmaPMapBlk == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "pagemap mmap block failed (%m)"); + + fdPmap = open("/proc/self/pagemap", O_RDONLY); + + if (fdPmap < 0) + SOFT_ERROR(PI_INIT_FAILED, "pagemap open failed(%m)"); + + for (i=0; i<(bufferBlocks+PI_WAVE_BLOCKS); i++) + { + status = initPagemapBlock(i); + if (status < 0) + { + close(fdPmap); + return status; + } + } + + close(fdPmap); + + DBG(DBG_STARTUP, "dmaPMapBlk=%08X dmaIn=%08X", + (uint32_t)dmaPMapBlk, (uint32_t)dmaIn); + } + else + { + /* mailbox allocation of DMA memory */ + + dmaMboxBlk = mmap( + 0, (bufferBlocks+PI_WAVE_BLOCKS)*sizeof(DMAMem_t), + PROT_READ|PROT_WRITE, + MAP_PRIVATE|MAP_ANONYMOUS|MAP_LOCKED, + -1, 0); + + if (dmaMboxBlk == MAP_FAILED) + SOFT_ERROR(PI_INIT_FAILED, "mmap mbox block failed (%m)"); + + fdMbox = mbOpen(); + + if (fdMbox < 0) + SOFT_ERROR(PI_INIT_FAILED, "mbox open failed(%m)"); + + for (i=0; i<(bufferBlocks+PI_WAVE_BLOCKS); i++) + { + status = initMboxBlock(i); + if (status < 0) + { + mbClose(fdMbox); + return status; + } + } + + mbClose(fdMbox); + + DBG(DBG_STARTUP, "dmaMboxBlk=%08X dmaIn=%08X", + (uint32_t)dmaMboxBlk, (uint32_t)dmaIn); + } + + DBG(DBG_STARTUP, + "gpioReg=%08X pwmReg=%08X pcmReg=%08X clkReg=%08X auxReg=%08X", + (uint32_t)gpioReg, (uint32_t)pwmReg, + (uint32_t)pcmReg, (uint32_t)clkReg, (uint32_t)auxReg); + + for (i=0; i= DBG_DMACBS) + { + fprintf(stderr, "*** INPUT DMA CONTROL BLOCKS ***\n"); + for (i=0; iperiphData = 1; + + /* enable PWM DMA, raise panic and dreq thresholds to 15 */ + + pwmReg[PWM_DMAC] = PWM_DMAC_ENAB | + PWM_DMAC_PANIC(15) | + PWM_DMAC_DREQ(15); + + myGpioDelay(10); + + /* clear PWM fifo */ + + pwmReg[PWM_CTL] = PWM_CTL_CLRF1; + + myGpioDelay(10); + + /* enable PWM channel 1 and use fifo */ + + pwmReg[PWM_CTL] = PWM_CTL_USEF1 | PWM_CTL_MODE1 | PWM_CTL_PWEN1; +} + +/* ----------------------------------------------------------------------- */ + +static void initPCM(unsigned bits) +{ + DBG(DBG_STARTUP, "bits=%d", bits); + + /* disable PCM so we can modify the regs */ + + pcmReg[PCM_CS] = 0; + + myGpioDelay(1000); + + pcmReg[PCM_FIFO] = 0; + pcmReg[PCM_MODE] = 0; + pcmReg[PCM_RXC] = 0; + pcmReg[PCM_TXC] = 0; + pcmReg[PCM_DREQ] = 0; + pcmReg[PCM_INTEN] = 0; + pcmReg[PCM_INTSTC] = 0; + pcmReg[PCM_GRAY] = 0; + + myGpioDelay(1000); + + pcmReg[PCM_MODE] = PCM_MODE_FLEN(bits-1); /* # bits in frame */ + + /* enable channel 1 with # bits width */ + + pcmReg[PCM_TXC] = PCM_TXC_CH1EN | PCM_TXC_CH1WID(bits-8); + + pcmReg[PCM_CS] |= PCM_CS_STBY; /* clear standby */ + + myGpioDelay(1000); + + pcmReg[PCM_CS] |= PCM_CS_TXCLR; /* clear TX FIFO */ + + pcmReg[PCM_CS] |= PCM_CS_DMAEN; /* enable DREQ */ + + pcmReg[PCM_DREQ] = PCM_DREQ_TX_PANIC(16) | PCM_DREQ_TX_REQ_L(30); + + pcmReg[PCM_INTSTC] = 0b1111; /* clear status bits */ + + /* enable PCM */ + + pcmReg[PCM_CS] |= PCM_CS_EN; + + /* enable tx */ + + pcmReg[PCM_CS] |= PCM_CS_TXON; + + dmaIVirt[0]->periphData = 0x0F; +} + +/* ----------------------------------------------------------------------- */ + +static void initHWClk + (int clkCtl, int clkDiv, int clkSrc, int divI, int divF, int MASH) +{ + DBG(DBG_INTERNAL, "ctl=%d div=%d src=%d /I=%d /f=%d M=%d", + clkCtl, clkDiv, clkSrc, divI, divF, MASH); + + /* kill the clock if busy, anything else isn't reliable */ + + if (clkReg[clkCtl] & CLK_CTL_BUSY) + { + do + { + clkReg[clkCtl] = BCM_PASSWD | CLK_CTL_KILL; + } + while (clkReg[clkCtl] & CLK_CTL_BUSY); + } + + clkReg[clkDiv] = (BCM_PASSWD | CLK_DIV_DIVI(divI) | CLK_DIV_DIVF(divF)); + + usleep(10); + + clkReg[clkCtl] = (BCM_PASSWD | CLK_CTL_MASH(MASH) | CLK_CTL_SRC(clkSrc)); + + usleep(10); + + clkReg[clkCtl] |= (BCM_PASSWD | CLK_CTL_ENAB); +} + +static void initClock(int mainClock) +{ + const unsigned BITS=10; + int clockPWM; + unsigned clkCtl, clkDiv, clkSrc, clkDivI, clkDivF, clkMash, clkBits; + char *per; + unsigned micros; + + DBG(DBG_STARTUP, "mainClock=%d", mainClock); + + if (mainClock) micros = gpioCfg.clockMicros; + else micros = PI_WF_MICROS; + + clockPWM = mainClock ^ (gpioCfg.clockPeriph == PI_CLOCK_PCM); + + if (clockPWM) + { + clkCtl = CLK_PWMCTL; + clkDiv = CLK_PWMDIV; + per = "PWM"; + } + else + { + clkCtl = CLK_PCMCTL; + clkDiv = CLK_PCMDIV; + per = "PCM"; + } + + clkSrc = CLK_CTL_SRC_PLLD; + clkDivI = 50 * micros; /* 10 MHz - 1 MHz */ + clkBits = BITS; /* 10/BITS MHz - 1/BITS MHz */ + clkDivF = 0; + clkMash = 0; + + DBG(DBG_STARTUP, "%s PLLD divi=%d divf=%d mash=%d bits=%d", + per, clkDivI, clkDivF, clkMash, clkBits); + + initHWClk(clkCtl, clkDiv, clkSrc, clkDivI, clkDivF, clkMash); + + if (clockPWM) initPWM(BITS); + else initPCM(BITS); + + myGpioDelay(2000); +} + +/* ----------------------------------------------------------------------- */ + +static void initDMAgo(volatile uint32_t *dmaAddr, uint32_t cbAddr) +{ + DBG(DBG_STARTUP, ""); + + dmaAddr[DMA_CS] = DMA_CHANNEL_RESET; + + dmaAddr[DMA_CS] = DMA_INTERRUPT_STATUS | DMA_END_FLAG; + + dmaAddr[DMA_CONBLK_AD] = cbAddr; + + /* clear READ/FIFO/READ_LAST_NOT_SET error bits */ + + dmaAddr[DMA_DEBUG] = DMA_DEBUG_READ_ERR | + DMA_DEBUG_FIFO_ERR | + DMA_DEBUG_RD_LST_NOT_SET_ERR; + + + dmaAddr[DMA_CS] = DMA_WAIT_ON_WRITES | + DMA_PANIC_PRIORITY(8) | + DMA_PRIORITY(8) | + DMA_ACTIVATE; +} + +/* ----------------------------------------------------------------------- */ + +static void initClearGlobals(void) +{ + int i; + + DBG(DBG_STARTUP, ""); + + alertBits = 0; + monitorBits = 0; + notifyBits = 0; + scriptBits = 0; + gFilterBits = 0; + nFilterBits = 0; + wdogBits = 0; + + pthAlertRunning = PI_THREAD_NONE; + pthFifoRunning = PI_THREAD_NONE; + pthSocketRunning = PI_THREAD_NONE; + + wfc[0] = 0; + wfc[1] = 0; + wfc[2] = 0; + + wfcur=0; + + wfStats.micros = 0; + wfStats.highMicros = 0; + wfStats.maxMicros = PI_WAVE_MAX_MICROS; + + wfStats.pulses = 0; + wfStats.highPulses = 0; + wfStats.maxPulses = PI_WAVE_MAX_PULSES; + + wfStats.cbs = 0; + wfStats.highCbs = 0; + wfStats.maxCbs = (PI_WAVE_BLOCKS * PAGES_PER_BLOCK * CBS_PER_OPAGE); + + gpioGetSamples.func = NULL; + gpioGetSamples.ex = 0; + gpioGetSamples.userdata = NULL; + gpioGetSamples.bits = 0; + + for (i=0; i<=PI_MAX_USER_GPIO; i++) + { + wfRx[i].mode = PI_WFRX_NONE; + pthread_mutex_init(&wfRx[i].mutex, NULL); + gpioAlert[i].func = NULL; + } + + for (i=0; i<=PI_MAX_GPIO; i++) + { + gpioInfo [i].is = GPIO_UNDEFINED; + gpioInfo [i].width = 0; + gpioInfo [i].range = PI_DEFAULT_DUTYCYCLE_RANGE; + gpioInfo [i].freqIdx = DEFAULT_PWM_IDX; + } + + for (i=0; i> 4) & 0xFF; + + /* model + 0=A 1=B + 2=A+ 3=B+ + 4=Pi2B + 5=Alpha + 6=Compute Module + 7=Unknown + 8=Pi3B + 9=Zero + */ + if (model < 2) gpioMask = PI_DEFAULT_UPDATE_MASK_A_B2; + else if (model < 4) gpioMask = PI_DEFAULT_UPDATE_MASK_APLUS_BPLUS; + else if (model == 4) gpioMask = PI_DEFAULT_UPDATE_MASK_PI2B; + else if (model == 6) gpioMask = PI_DEFAULT_UPDATE_MASK_COMPUTE; + else if (model == 8) gpioMask = PI_DEFAULT_UPDATE_MASK_PI3B; + else if (model == 9) gpioMask = PI_DEFAULT_UPDATE_MASK_ZERO; + else gpioMask = PI_DEFAULT_UPDATE_MASK_UNKNOWN; + } + + gpioMaskSet = 1; + } + +#ifndef EMBEDDED_IN_VM + if (!(gpioCfg.internals & PI_CFG_NOSIGHANDLER)) + sigSetHandler(); +#endif + + if (initPeripherals() < 0) return PI_INIT_FAILED; + + if (initAllocDMAMem() < 0) return PI_INIT_FAILED; + + /* done with /dev/mem */ + + if (fdMem != -1) + { + close(fdMem); + fdMem = -1; + } + + param.sched_priority = sched_get_priority_max(SCHED_FIFO); + + if (gpioCfg.internals & PI_CFG_RT_PRIORITY) + sched_setscheduler(0, SCHED_FIFO, ¶m); + + initClock(1); /* initialise main clock */ + + atexit(gpioTerminate); + + if (pthread_attr_init(&pthAttr)) + SOFT_ERROR(PI_INIT_FAILED, "pthread_attr_init failed (%m)"); + + if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE)) + SOFT_ERROR(PI_INIT_FAILED, "pthread_attr_setstacksize failed (%m)"); + + if (!(gpioCfg.ifFlags & PI_DISABLE_ALERT)) + { + if (pthread_create(&pthAlert, &pthAttr, pthAlertThread, &i)) + SOFT_ERROR(PI_INIT_FAILED, "pthread_create alert failed (%m)"); + + pthAlertRunning = PI_THREAD_STARTED; + } + + if (!(gpioCfg.ifFlags & PI_DISABLE_FIFO_IF)) + { + if (pthread_create(&pthFifo, &pthAttr, pthFifoThread, &i)) + SOFT_ERROR(PI_INIT_FAILED, "pthread_create fifo failed (%m)"); + + pthFifoRunning = PI_THREAD_STARTED; + } + + if (!(gpioCfg.ifFlags & PI_DISABLE_SOCK_IF)) + { + portStr = getenv(PI_ENVPORT); + if (portStr) port = atoi(portStr); else port = gpioCfg.socketPort; + + // Accept connections on IPv6, unless we have an IPv4-only whitelist + if (!numSockNetAddr) + { + fdSock = socket(AF_INET6, SOCK_STREAM , 0); + + if (fdSock != -1) + { + bzero((char *)&server6, sizeof(server6)); + server6.sin6_family = AF_INET6; + if (gpioCfg.ifFlags & PI_LOCALHOST_SOCK_IF) + { + server6.sin6_addr = in6addr_loopback; + } + else + { + server6.sin6_addr = in6addr_any; + } + server6.sin6_port = htons(port); + + int opt; + setsockopt(fdSock, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt)); + if (bind(fdSock,(struct sockaddr *)&server6, sizeof(server6)) < 0) + SOFT_ERROR(PI_INIT_FAILED, "bind to port %d failed (%m)", port); + } + } + + if (numSockNetAddr || fdSock == -1) + { + fdSock = socket(AF_INET , SOCK_STREAM , 0); + + if (fdSock == -1) + SOFT_ERROR(PI_INIT_FAILED, "socket failed (%m)"); + else + { + int opt; + setsockopt(fdSock, SOL_SOCKET, SO_REUSEADDR, &opt, sizeof(opt)); + } + server.sin_family = AF_INET; + if (gpioCfg.ifFlags & PI_LOCALHOST_SOCK_IF) + { + server.sin_addr.s_addr = htonl(INADDR_LOOPBACK); + } + else + { + server.sin_addr.s_addr = htonl(INADDR_ANY); + } + server.sin_port = htons(port); + + if (bind(fdSock,(struct sockaddr *)&server , sizeof(server)) < 0) + SOFT_ERROR(PI_INIT_FAILED, "bind to port %d failed (%m)", port); + } + + if (pthread_create(&pthSocket, &pthAttr, pthSocketThread, &i)) + SOFT_ERROR(PI_INIT_FAILED, "pthread_create socket failed (%m)"); + + pthSocketRunning = PI_THREAD_STARTED; + } + + myGpioDelay(1000); + + dmaInitCbs(); + + flushMemory(); + + initDMAgo((uint32_t *)dmaIn, (uint32_t)dmaIBus[0]); + + return PIGPIO_VERSION; +} + + +/* ======================================================================= */ + +int getBitInBytes(int bitPos, char *buf, int numBits) +{ + int bitp, bufp; + + if (bitPos < numBits) + { + bufp = bitPos / 8; + bitp = 7 - (bitPos % 8); + if (buf[bufp] & (1<= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot(pos, &page, &slot); + return (dmaOVirt[page]->OOL[slot]); + } + + return -1; +} + +/* ----------------------------------------------------------------------- */ + +void rawWaveSetOOL(int pos, uint32_t value) +{ + int page, slot; + + if ((pos >= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot(pos, &page, &slot); + dmaOVirt[page]->OOL[slot] = value; + } +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t rawWaveGetOut(int pos) +{ + int page, slot; + + if ((pos >= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot(pos, &page, &slot); + return (dmaOVirt[page]->OOL[slot]); + } + + return -1; +} + +/* ----------------------------------------------------------------------- */ + +void rawWaveSetOut(int pos, uint32_t value) +{ + int page, slot; + + if ((pos >= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot(pos, &page, &slot); + dmaOVirt[page]->OOL[slot] = value; + } +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t rawWaveGetIn(int pos) +{ + int page, slot; + + if ((pos >= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot((NUM_WAVE_OOL-1)-pos, &page, &slot); + return (dmaOVirt[page]->OOL[slot]); + } + + return -1; +} + +/* ----------------------------------------------------------------------- */ + +void rawWaveSetIn(int pos, uint32_t value) +{ + int page, slot; + + if ((pos >= 0) && (pos < NUM_WAVE_OOL)) + { + waveOOLPageSlot((NUM_WAVE_OOL-1)-pos, &page, &slot); + dmaOVirt[page]->OOL[slot] = value; + } +} + +/* ----------------------------------------------------------------------- */ + +rawWaveInfo_t rawWaveInfo(int wave_id) +{ + rawWaveInfo_t dummy = {0, 0, 0, 0, 0, 0, 0, 0}; + + if ((wave_id >=0) && (wave_id < PI_MAX_WAVES)) return waveInfo[wave_id]; + else return dummy; +} + +/* ----------------------------------------------------------------------- */ + +double time_time(void) +{ + struct timeval tv; + double t; + + gettimeofday(&tv, 0); + + t = (double)tv.tv_sec + ((double)tv.tv_usec / 1E6); + + return t; +} + +/* ----------------------------------------------------------------------- */ + +void time_sleep(double seconds) +{ + struct timespec ts, rem; + + if (seconds > 0.0) + { + ts.tv_sec = seconds; + ts.tv_nsec = (seconds-(double)ts.tv_sec) * 1E9; + + while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem)) + { + /* copy remaining time to ts */ + ts.tv_sec = rem.tv_sec; + ts.tv_nsec = rem.tv_nsec; + } + } +} + +/* ----------------------------------------------------------------------- */ + +void rawDumpWave(void) +{ + int i; + + unsigned numWaves, t; + + rawWave_t *waves; + + numWaves = wfc[wfcur]; + waves = wf [wfcur]; + + t = 0; + + for (i=0; i= PI_MAX_SCRIPTS) return; + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + + for (i=0; i> 4) & 3; + + if (pwm == 0) pwmReg[PWM_CTL] &= (~PWM_CTL_PWEN1); + else pwmReg[PWM_CTL] &= (~PWM_CTL_PWEN2); + + gpioInfo[i].width = 0; + gpioInfo[i].is = GPIO_UNDEFINED; + } + } +} + +/* ----------------------------------------------------------------------- */ + +int gpioSetMode(unsigned gpio, unsigned mode) +{ + int reg, shift, old_mode; + + DBG(DBG_USER, "gpio=%d mode=%d", gpio, mode); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (mode > PI_ALT3) + SOFT_ERROR(PI_BAD_MODE, "gpio %d, bad mode (%d)", gpio, mode); + + reg = gpio/10; + shift = (gpio%10) * 3; + + old_mode = (gpioReg[reg] >> shift) & 7; + + if (mode != old_mode) + { + switchFunctionOff(gpio); + + gpioInfo[gpio].is = GPIO_UNDEFINED; + } + + gpioReg[reg] = (gpioReg[reg] & ~(7< PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + reg = gpio/10; + shift = (gpio%10) * 3; + + return (gpioReg[reg] >> shift) & 7; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetPullUpDown(unsigned gpio, unsigned pud) +{ + DBG(DBG_USER, "gpio=%d pud=%d", gpio, pud); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (pud > PI_PUD_UP) + SOFT_ERROR(PI_BAD_PUD, "gpio %d, bad pud (%d)", gpio, pud); + + *(gpioReg + GPPUD) = pud; + + myGpioDelay(1); + + *(gpioReg + GPPUDCLK0 + BANK) = BIT; + + myGpioDelay(1); + + *(gpioReg + GPPUD) = 0; + + *(gpioReg + GPPUDCLK0 + BANK) = 0; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioRead(unsigned gpio) +{ + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if ((*(gpioReg + GPLEV0 + BANK) & BIT) != 0) return PI_ON; + else return PI_OFF; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWrite(unsigned gpio, unsigned level) +{ + DBG(DBG_USER, "gpio=%d level=%d", gpio, level); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (level > PI_ON) + SOFT_ERROR(PI_BAD_LEVEL, "gpio %d, bad level (%d)", gpio, level); + + if (gpio <= PI_MAX_GPIO) + { + if (gpioInfo[gpio].is != GPIO_WRITE) + { + /* stop a glitch between setting mode then level */ + if (level == PI_OFF) *(gpioReg + GPCLR0 + BANK) = BIT; + else *(gpioReg + GPSET0 + BANK) = BIT; + + switchFunctionOff(gpio); + + gpioInfo[gpio].is = GPIO_WRITE; + } + } + + myGpioSetMode(gpio, PI_OUTPUT); + + if (level == PI_OFF) *(gpioReg + GPCLR0 + BANK) = BIT; + else *(gpioReg + GPSET0 + BANK) = BIT; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioPWM(unsigned gpio, unsigned val) +{ + DBG(DBG_USER, "gpio=%d dutycycle=%d", gpio, val); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (val > gpioInfo[gpio].range) + SOFT_ERROR(PI_BAD_DUTYCYCLE, "gpio %d, bad dutycycle (%d)", gpio, val); + + if (gpioInfo[gpio].is != GPIO_PWM) + { + switchFunctionOff(gpio); + + gpioInfo[gpio].is = GPIO_PWM; + + if (!val) myGpioWrite(gpio, 0); + } + + myGpioSetMode(gpio, PI_OUTPUT); + + myGpioSetPwm(gpio, gpioInfo[gpio].width, val); + + gpioInfo[gpio].width=val; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioGetPWMdutycycle(unsigned gpio) +{ + unsigned pwm; + + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + switch (gpioInfo[gpio].is) + { + case GPIO_PWM: + return gpioInfo[gpio].width; + + case GPIO_HW_PWM: + pwm = (PWMDef[gpio] >> 4) & 3; + return hw_pwm_duty[pwm]; + + case GPIO_HW_CLK: + return PI_HW_PWM_RANGE/2; + + default: + SOFT_ERROR(PI_NOT_PWM_GPIO, "not a PWM gpio (%d)", gpio); + } +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetPWMrange(unsigned gpio, unsigned range) +{ + int oldWidth, newWidth; + + DBG(DBG_USER, "gpio=%d range=%d", gpio, range); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if ((range < PI_MIN_DUTYCYCLE_RANGE) || (range > PI_MAX_DUTYCYCLE_RANGE)) + SOFT_ERROR(PI_BAD_DUTYRANGE, "gpio %d, bad range (%d)", gpio, range); + + oldWidth = gpioInfo[gpio].width; + + if (oldWidth) + { + if (gpioInfo[gpio].is == GPIO_PWM) + { + newWidth = (range * oldWidth) / gpioInfo[gpio].range; + + myGpioSetPwm(gpio, oldWidth, 0); + gpioInfo[gpio].range = range; + gpioInfo[gpio].width = newWidth; + myGpioSetPwm(gpio, 0, newWidth); + } + } + + gpioInfo[gpio].range = range; + + /* return the actual range for the current gpio frequency */ + + return pwmRealRange[gpioInfo[gpio].freqIdx]; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioGetPWMrange(unsigned gpio) +{ + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + switch (gpioInfo[gpio].is) + { + case GPIO_HW_PWM: + case GPIO_HW_CLK: + return PI_HW_PWM_RANGE; + + default: + return gpioInfo[gpio].range; + } +} + + +/* ----------------------------------------------------------------------- */ + +int gpioGetPWMrealRange(unsigned gpio) +{ + unsigned pwm; + + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + switch (gpioInfo[gpio].is) + { + case GPIO_HW_PWM: + pwm = (PWMDef[gpio] >> 4) & 3; + return hw_pwm_real_range[pwm]; + + case GPIO_HW_CLK: + return PI_HW_PWM_RANGE; + + default: + return pwmRealRange[gpioInfo[gpio].freqIdx]; + } +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetPWMfrequency(unsigned gpio, unsigned frequency) +{ + int i, width; + unsigned diff, best, idx; + + DBG(DBG_USER, "gpio=%d frequency=%d", gpio, frequency); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (frequency > pwmFreq[0]) idx = 0; + else if (frequency < pwmFreq[PWM_FREQS-1]) idx = PWM_FREQS-1; + else + { + best = 100000; /* impossibly high frequency difference */ + idx = 0; + + for (i=0; i pwmFreq[i]) diff = frequency - pwmFreq[i]; + else diff = pwmFreq[i] - frequency; + + if (diff < best) + { + best = diff; + idx = i; + } + } + } + + width = gpioInfo[gpio].width; + + if (width) + { + if (gpioInfo[gpio].is == GPIO_PWM) + { + myGpioSetPwm(gpio, width, 0); + gpioInfo[gpio].freqIdx = idx; + myGpioSetPwm(gpio, 0, width); + } + } + + gpioInfo[gpio].freqIdx = idx; + + return pwmFreq[idx]; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioGetPWMfrequency(unsigned gpio) +{ + unsigned pwm, clock; + + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + switch (gpioInfo[gpio].is) + { + case GPIO_HW_PWM: + pwm = (PWMDef[gpio] >> 4) & 3; + return hw_pwm_freq[pwm]; + + case GPIO_HW_CLK: + clock = (clkDef[gpio] >> 4) & 3; + return hw_clk_freq[clock]; + + default: + return pwmFreq[gpioInfo[gpio].freqIdx]; + } +} + + +/* ----------------------------------------------------------------------- */ + +int gpioServo(unsigned gpio, unsigned val) +{ + DBG(DBG_USER, "gpio=%d pulsewidth=%d", gpio, val); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if ((val!=PI_SERVO_OFF) && (valPI_MAX_SERVO_PULSEWIDTH) + SOFT_ERROR(PI_BAD_PULSEWIDTH, + "gpio %d, bad pulsewidth (%d)", gpio, val); + + if (gpioInfo[gpio].is != GPIO_SERVO) + { + switchFunctionOff(gpio); + + gpioInfo[gpio].is = GPIO_SERVO; + + if (!val) myGpioWrite(gpio, 0); + } + + myGpioSetMode(gpio, PI_OUTPUT); + + myGpioSetServo(gpio, gpioInfo[gpio].width, val); + + gpioInfo[gpio].width=val; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioGetServoPulsewidth(unsigned gpio) +{ + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (gpioInfo[gpio].is != GPIO_SERVO) + SOFT_ERROR(PI_NOT_SERVO_GPIO, "not a servo gpio (%d)", gpio); + + return gpioInfo[gpio].width; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWaveClear(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + wfc[0] = 0; + wfc[1] = 0; + wfc[2] = 0; + + wfcur = 0; + + wfStats.micros = 0; + wfStats.pulses = 0; + wfStats.cbs = 0; + + waveOutBotCB = PI_WAVE_COUNT_PAGES*CBS_PER_OPAGE; + waveOutBotOOL = PI_WAVE_COUNT_PAGES*OOL_PER_OPAGE; + waveOutTopOOL = NUM_WAVE_OOL; + + waveOutCount = 0; + + waveEndPtr = NULL; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveAddNew(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + wfc[0] = 0; + wfc[1] = 0; + wfc[2] = 0; + + wfcur = 0; + + wfStats.micros = 0; + wfStats.pulses = 0; + wfStats.cbs = 0; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses) +{ + int p; + + DBG(DBG_USER, "numPulses=%u pulses=%08X", numPulses, (uint32_t)pulses); + + CHECK_INITED; + + if (numPulses > PI_WAVE_MAX_PULSES) + SOFT_ERROR(PI_TOO_MANY_PULSES, "bad number of pulses (%d)", numPulses); + + if (!pulses) SOFT_ERROR(PI_BAD_POINTER, "bad (NULL) pulses pointer"); + + for (p=0; p PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if ((baud < PI_WAVE_MIN_BAUD) || (baud > PI_WAVE_MAX_BAUD)) + SOFT_ERROR(PI_BAD_WAVE_BAUD, "bad baud rate (%d)", baud); + + if ((data_bits < PI_MIN_WAVE_DATABITS) || + (data_bits > PI_MAX_WAVE_DATABITS)) + SOFT_ERROR(PI_BAD_DATABITS, "bad number of databits (%d)", data_bits); + + if ((stop_bits < PI_MIN_WAVE_HALFSTOPBITS) || + (stop_bits > PI_MAX_WAVE_HALFSTOPBITS)) + SOFT_ERROR(PI_BAD_STOPBITS, + "bad number of (half) stop bits (%d)", stop_bits); + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (numBytes > PI_WAVE_MAX_CHARS) + SOFT_ERROR(PI_TOO_MANY_CHARS, "too many chars (%d)", numBytes); + + if (offset > PI_WAVE_MAX_MICROS) + SOFT_ERROR(PI_BAD_SER_OFFSET, "offset too large (%d)", offset); + + if (data_bits > 8) numBytes /= 2; + if (data_bits > 16) numBytes /= 2; + + if (!numBytes) return 0; + + waveBitDelay(baud, data_bits, stop_bits, bitDelay); + + p = 0; + + wf[2][p].gpioOn = (1< bitDelay[0]) wf[2][p].usDelay = offset; + else wf[2][p].usDelay = bitDelay[0]; + + for (i=0; i PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", spiSS); + + /* + CPOL CPHA + 0 0 read rising/write falling + 0 1 read falling/write rising + 1 0 read falling/write rising + 1 1 read rising/write falling + */ + + if (spi->clk_pol) {rising_edge[0] = 0; rising_edge[1] = 1;} + else {rising_edge[0] = 1; rising_edge[1] = 0;} + + if (spi->clk_pha) {read_cycle[0] = 0; read_cycle[1] = 1;} + else {read_cycle[0] = 1; read_cycle[1] = 0;} + + p = 0; + + if (offset) + { + wf[2][p].gpioOn = 0; + wf[2][p].gpioOff = 0; + wf[2][p].flags = 0; + wf[2][p].usDelay = offset; + p++; + } + + on_bits = 0; + off_bits = 0; + + tx_bit_pos = 0; + + /* preset initial mosi bit */ + + if (getBitInBytes(tx_bit_pos, buf, spiTxBits)) + { + on_bits |= (1<<(spi->mosi)); + dbv = 1; + } + else + { + off_bits |= (1<<(spi->mosi)); + dbv = 0; + } + + if (!spi->clk_pha) tx_bit_pos ++; + + if (spi->ss_pol) off_bits |= (1<clk_pol) on_bits |= (1<<(spi->clk)); + else off_bits |= (1<<(spi->clk)); + + wf[2][p].gpioOn = on_bits; + wf[2][p].gpioOff = off_bits; + wf[2][p].flags = 0; + + if (spi->clk_us > spi->ss_us) wf[2][p].usDelay = spi->clk_us; + else wf[2][p].usDelay = spi->ss_us; + + p++; + + for (bit=1; bit<=spiBits; bit++) + { + for (halfbit=0; halfbit<2; halfbit++) + { + wf[2][p].usDelay = spi->clk_us; + wf[2][p].flags = 0; + + on_bits = 0; + off_bits = 0; + + if (read_cycle[halfbit]) + { + if ((bit>=spiBitFirst) && (bit<=spiBitLast)) + wf[2][p].flags = WAVE_FLAG_READ; + } + else + { + if (getBitInBytes(tx_bit_pos, buf, spiTxBits)) + { + if (!dbv) on_bits |= (1<<(spi->mosi)); + dbv = 1; + } + else + { + if (dbv) off_bits |= (1<<(spi->mosi)); + dbv = 0; + } + + ++tx_bit_pos; + } + + if (rising_edge[halfbit]) on_bits |= (1<<(spi->clk)); + else off_bits |= (1<<(spi->clk)); + + wf[2][p].gpioOn = on_bits; + wf[2][p].gpioOff = off_bits; + + p++; + } + } + + on_bits = 0; + off_bits = 0; + + if (spi->ss_pol) on_bits |= (1<= NUM_WAVE_CBS) + return PI_TOO_MANY_CBS; + + if ((numBOOL+waveOutBotOOL) >= (waveOutTopOOL-numTOOL)) + return PI_TOO_MANY_OOL; + + if (wid >= PI_MAX_WAVES) + return PI_NO_WAVEFORM_ID; + + wid = waveOutCount++; + + waveInfo[wid].botCB = waveOutBotCB; + waveInfo[wid].topCB = waveOutBotCB + numCB -1; + waveInfo[wid].botOOL = waveOutBotOOL; + waveInfo[wid].topOOL = waveOutTopOOL; + waveInfo[wid].numCB = numCB; + waveInfo[wid].numBOOL = numBOOL; + waveInfo[wid].numTOOL = numTOOL; + + waveOutBotCB += numCB; + waveOutBotOOL += numBOOL; + waveOutTopOOL -= numTOOL; + } + + /* Must be room if got this far. */ + + CB = waveInfo[wid].botCB; + BOOL = waveInfo[wid].botOOL; + TOOL = waveInfo[wid].topOOL; + + wave2Cbs(PI_WAVE_MODE_ONE_SHOT, &CB, &BOOL, &TOOL); + + /* Sanity check. */ + + if ( (numCB != (CB-waveInfo[wid].botCB)) || + (numBOOL != (BOOL-waveInfo[wid].botOOL)) || + (numTOOL != (waveInfo[wid].topOOL-TOOL)) ) + { + DBG(DBG_ALWAYS, "ERROR wid=%d CBs %d=%d BOOL %d=%d TOOL %d=%d", wid, + numCB, CB-waveInfo[wid].botCB, + numBOOL, BOOL-waveInfo[wid].botOOL, + numTOOL, waveInfo[wid].topOOL-TOOL); + } + + waveInfo[wid].deleted = 0; + + /* Consume waves. */ + + wfc[0] = 0; + wfc[1] = 0; + wfc[2] = 0; + + wfcur = 0; + + return wid; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveDelete(unsigned wave_id) +{ + DBG(DBG_USER, "wave id=%d", wave_id); + + CHECK_INITED; + + if ((wave_id >= waveOutCount) || waveInfo[wave_id].deleted) + SOFT_ERROR(PI_BAD_WAVE_ID, "bad wave id (%d)", wave_id); + + waveInfo[wave_id].deleted = 1; + + if (wave_id == (waveOutCount-1)) + { + /* top wave deleted, garbage collect any other deleted waves */ + + while ((wave_id > 0) && (waveInfo[wave_id-1].deleted)) --wave_id; + + waveOutBotCB = waveInfo[wave_id].botCB; + waveOutBotOOL = waveInfo[wave_id].botOOL; + waveOutTopOOL = waveInfo[wave_id].topOOL; + + waveOutCount = wave_id; + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveTxStart(unsigned wave_mode) +{ + /* This function is deprecated and has been removed. */ + + CHECK_INITED; + + SOFT_ERROR(PI_DEPRECATED, "deprected function removed"); +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode) +{ + rawCbs_t *p=NULL; + + DBG(DBG_USER, "wave_id=%d wave_mode=%d", wave_id, wave_mode); + + CHECK_INITED; + + if ((wave_id >= waveOutCount) || waveInfo[wave_id].deleted) + SOFT_ERROR(PI_BAD_WAVE_ID, "bad wave id (%d)", wave_id); + + if (wave_mode > PI_WAVE_MODE_REPEAT_SYNC) + SOFT_ERROR(PI_BAD_WAVE_MODE, "bad wave mode (%d)", wave_mode); + + if (!waveClockInited) + { + stopHardwarePWM(); + initClock(0); /* initialise secondary clock */ + waveClockInited = 1; + PWMClockInited = 0; + } + + if (wave_mode < PI_WAVE_MODE_ONE_SHOT_SYNC) + { + dmaOut[DMA_CS] = DMA_CHANNEL_RESET; + dmaOut[DMA_CONBLK_AD] = 0; + } + + p = rawWaveCBAdr(waveInfo[wave_id].topCB); + + if ((wave_mode & 1) == PI_WAVE_MODE_ONE_SHOT) + p->next = 0; + else + p->next = waveCbPOadr(waveInfo[wave_id].botCB+1); + + if (waveEndPtr && (wave_mode > PI_WAVE_MODE_REPEAT)) + { + *waveEndPtr = waveCbPOadr(waveInfo[wave_id].botCB+1); + + if (!dmaOut[DMA_CONBLK_AD]) + { + initDMAgo((uint32_t *)dmaOut, waveCbPOadr(waveInfo[wave_id].botCB)); + } + } + else + { + initDMAgo((uint32_t *)dmaOut, waveCbPOadr(waveInfo[wave_id].botCB)); + } + + waveEndPtr = &p->next; + + /* for compatability with the deprecated gpioWaveTxStart return the + number of cbs + */ + return (waveInfo[wave_id].topCB - waveInfo[wave_id].botCB) + 1; +} + + +/* ----------------------------------------------------------------------- */ + +static int chainGetCB(int n) +{ + int block, index; + + if (n < (WCB_CHAIN_CBS * PI_WAVE_COUNT_PAGES)) + { + block = n / WCB_CHAIN_CBS; + index = n % WCB_CHAIN_CBS; + return (block*CBS_PER_OPAGE) + WCB_COUNTER_CBS + index; + } + return -1; +} + +static void chainSetVal(int n, uint32_t val) +{ + int block, index; + uint32_t *p; + + if (n < (WCB_CHAIN_OOL * PI_WAVE_COUNT_PAGES)) + { + block = n / WCB_CHAIN_OOL; + index = n % WCB_CHAIN_OOL; + p = (uint32_t *) dmaOVirt[block] + (WCB_COUNTER_CBS+WCB_CHAIN_CBS) * 8; + p[index] = val; + } +} + +static uint32_t chainGetValPadr(int n) +{ + int block, index; + uint32_t *p; + + if (n < (WCB_CHAIN_OOL * PI_WAVE_COUNT_PAGES)) + { + block = n / WCB_CHAIN_OOL; + index = n % WCB_CHAIN_OOL; + p = (uint32_t *) dmaOBus[block] + (WCB_COUNTER_CBS+WCB_CHAIN_CBS) * 8; + return (uint32_t) (p + index); + } + return 0; +} + +static uint32_t chainGetCntVal(int counter, int slot) +{ + uint32_t *p; + int page, offset; + page = counter / 2; + offset = (counter % 2 ? WCB_COUNTER_OOL : 0); + p = (uint32_t *) dmaOVirt[page] + (WCB_COUNTER_CBS+WCB_CHAIN_CBS) * 8; + return p[WCB_CHAIN_OOL+ offset + slot]; +} + +static void chainSetCntVal(int counter, int slot, uint32_t value) +{ + uint32_t *p; + int page, offset; + page = counter / 2; + offset = (counter % 2 ? WCB_COUNTER_OOL : 0); + p = (uint32_t *) dmaOVirt[page] + (WCB_COUNTER_CBS+WCB_CHAIN_CBS) * 8; + p[WCB_CHAIN_OOL + offset + slot] = value; +} + +static uint32_t chainGetCntValPadr(int counter, int slot) +{ + uint32_t *p; + int page, offset; + page = counter / 2; + offset = (counter % 2 ? WCB_COUNTER_OOL : 0); + p = (uint32_t *) dmaOBus[page] + (WCB_COUNTER_CBS+WCB_CHAIN_CBS) * 8; + return (uint32_t)(p + WCB_CHAIN_OOL + offset + slot); +} + +static int chainGetCntCB(int counter) +{ + int page, offset; + page = counter / 2; + offset = (counter % 2 ? WCB_CNT_CBS : 0); + return ((page * CBS_PER_OPAGE) + offset); +} + +static void chainMakeCounter( + unsigned counter, + unsigned blklen, + unsigned blocks, + unsigned count, + uint32_t repeat, + uint32_t next) +{ + rawCbs_t *p=NULL; + + int b, baseCB, dig; + uint32_t nxt; + + int botCB; + + botCB = chainGetCntCB(counter); + + baseCB = botCB; + + /* set up all the OOLs */ + for (b=0; b < (blocks*(blklen+1)); b++) chainSetCntVal(counter, b, repeat); + + for (b=0; binfo = NORMAL_DMA; + + p->src = chainGetCntValPadr(counter, b*(blklen+1)); + p->dst = (waveCbPOadr(botCB+1) + 20); + + p->length = 4; + p->next = waveCbPOadr(botCB); + + /* copy BOTTOM to TOP */ + + p = rawWaveCBAdr(botCB++); + + p->info = NORMAL_DMA; + + p->src = chainGetCntValPadr(counter, b*(blklen+1)); + p->dst = chainGetCntValPadr(counter, (b*(blklen+1))+blklen); + + p->length = 4; + p->next = waveCbPOadr(botCB); + + /* shift all down one */ + + p = rawWaveCBAdr(botCB++); + + p->info = NORMAL_DMA|DMA_SRC_INC|DMA_DEST_INC; + + p->src = chainGetCntValPadr(counter, ((b*(blklen+1))+1)); + p->dst = chainGetCntValPadr(counter, ((b*(blklen+1))+0)); + + p->length = blklen*4; + p->next = repeat; + } + + /* reset the counter */ + + p = rawWaveCBAdr(botCB); + + p->info = NORMAL_DMA|DMA_SRC_INC|DMA_DEST_INC; + + p->src = chainGetCntValPadr(counter, blocks*(blklen+1)); + p->dst = chainGetCntValPadr(counter, 0); + + p->length = blocks*(blklen+1)*4; + p->next = next; + + b = 0; + + while (count && (binfo = NORMAL_DMA | TIMED_DMA(2); + p->dst = PCM_TIMER; + } + else + { + p->info = NORMAL_DMA | TIMED_DMA(5); + p->dst = PWM_TIMER; + } + + p->src = (uint32_t) (&dmaOBus[0]->periphData); + p->length = BPD * 20 / PI_WF_MICROS; /* 20 micros delay */ + p->next = waveCbPOadr(chainGetCB(cb)); + + counters = 0; + wid = -1; + + i = 0; + + while (i bufSize) + SOFT_ERROR(PI_BAD_CHAIN_CMD, + "incomplete chain command (at %d)", i); + + cmd = buf[i+1]; + + if (cmd == 0) /* loop begin */ + { + if (stk_lev >= (sizeof(stk_pos)/sizeof(int))) + SOFT_ERROR(PI_CHAIN_NESTING, + "chain counters nested too deep (at %d)", i); + + stk_pos[stk_lev++] = cb; + + i += 2; + } + else if (cmd == 1) /* loop end */ + { + if (counters >= WCB_COUNTERS) + SOFT_ERROR(PI_CHAIN_COUNTER, + "too many chain counters (at %d)", i); + + if ((i+4) > bufSize) + SOFT_ERROR(PI_BAD_CHAIN_CMD, + "incomplete chain command (at %d)", i); + + loop = 0; + if (--stk_lev >= 0) loop = stk_pos[stk_lev]; + + if ((loop < 1) || (loop == cb)) + SOFT_ERROR(PI_BAD_CHAIN_LOOP, + "empty chain loop (at %d)", i); + + cycles = ((unsigned)buf[i+3] << 8) + (unsigned)buf[i+2]; + + i += 4; + + if (cycles > PI_MAX_WAVE_CYCLES) + SOFT_ERROR(PI_CHAIN_LOOP_CNT, + "bad chain loop count (%d)", cycles); + + if (cycles == 0) + { + /* Skip the complete loop block. Change + the next pointing to the start of the + loop block to the current cb. + */ + p = rawWaveCBAdr(chainGetCB(loop)); + p->next = waveCbPOadr(chainGetCB(cb)); + } + else if (cycles == 1) + { + /* Nothing to do, no need for a counter. */ + } + else + { + chaincb = chainGetCB(cb++); + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + p = rawWaveCBAdr(chaincb); + + repeat = waveCbPOadr(chainGetCB(loop)); + + /* Need to check next cb as well. */ + + chaincb = chainGetCB(cb); + + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + next = waveCbPOadr(chainGetCB(cb)); + + /* dummy src and dest */ + p->info = NORMAL_DMA; + p->src = (uint32_t) (&dmaOBus[0]->periphData); + p->dst = (uint32_t) (&dmaOBus[0]->periphData); + p->length = 4; + p->next = waveCbPOadr(chainGetCntCB(counters)); + + chainMakeCounter(counters, blklen, blocks, + cycles-1, repeat, next); + + counters++; + } + } + else if (cmd == 2) /* delay us */ + { + if ((i+4) > bufSize) + SOFT_ERROR(PI_BAD_CHAIN_CMD, + "incomplete chain command (at %d)", i); + + cycles = ((unsigned)buf[i+3] << 8) + (unsigned)buf[i+2]; + + i += 4; + + if (cycles > PI_MAX_WAVE_DELAY) + SOFT_ERROR(PI_BAD_CHAIN_DELAY, + "bad chain delay micros (%d)", cycles); + + if (cycles) + { + delayLeft = cycles; + delayCBs = waveDelayCBs(delayLeft); + for (dcb=0; dcbinfo = NORMAL_DMA | TIMED_DMA(2); + p->dst = PCM_TIMER; + } + else + { + p->info = NORMAL_DMA | TIMED_DMA(5); + p->dst = PWM_TIMER; + } + + p->src = (uint32_t) (&dmaOBus[0]->periphData); + + p->length = BPD * delayLeft / PI_WF_MICROS; + + if ((gpioCfg.DMAsecondaryChannel >= DMA_LITE_FIRST) && + (p->length > DMA_LITE_MAX)) + { + p->length = DMA_LITE_MAX; + } + + delayLeft -= (p->length / BPD); + + p->next = waveCbPOadr(chainGetCB(cb)); + } + } + } + else if (cmd == 3) /* repeat loop forever */ + { + i += 2; + + loop = 0; + if (--stk_lev >= 0) loop = stk_pos[stk_lev]; + + if ((loop < 1) || (loop == cb)) + SOFT_ERROR(PI_BAD_CHAIN_LOOP, + "empty chain loop (at %d)", i); + + chaincb = chainGetCB(cb++); + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + if (i < bufSize) + SOFT_ERROR(PI_BAD_FOREVER, + "loop forever must be last command"); + + p = rawWaveCBAdr(chaincb); + + /* dummy src and dest */ + p->info = NORMAL_DMA; + p->src = (uint32_t) (&dmaOBus[0]->periphData); + p->dst = (uint32_t) (&dmaOBus[0]->periphData); + p->length = 4; + p->next = waveCbPOadr(chainGetCB(loop)); + endPtr = &p->next; + } + else + SOFT_ERROR(PI_BAD_CHAIN_CMD, + "unknown chain command (255 %d)", cmd); + } + else if ((wid >= waveOutCount) || waveInfo[wid].deleted) + SOFT_ERROR(PI_BAD_WAVE_ID, "undefined wave (%d)", wid); + else + { + chaincb = chainGetCB(cb++); + + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + p = rawWaveCBAdr(chaincb); + + chaincb = chainGetCB(cb); + + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + chainSetVal(cb-1, waveCbPOadr(chaincb)); + + /* patch next of wid topCB to next cb */ + + p->info = NORMAL_DMA; + p->src = chainGetValPadr(cb-1); /* this next */ + p->dst = waveCbPOadr(waveInfo[wid].topCB) + 20; /* wid next */ + p->length = 4; + p->next = waveCbPOadr(waveInfo[wid].botCB+1); + + i += 1; + } + } + + chaincb = chainGetCB(cb++); + + if (chaincb < 0) + SOFT_ERROR(PI_CHAIN_TOO_BIG, "chain is too long (%d)", cb); + + p = rawWaveCBAdr(chaincb); + + p->info = NORMAL_DMA; + p->src = (uint32_t) (&dmaOBus[0]->periphData); + p->dst = (uint32_t) (&dmaOBus[0]->periphData); + p->length = 4; + p->next = 0; + + if (!endPtr) endPtr = &p->next; + + initDMAgo((uint32_t *)dmaOut, waveCbPOadr(chainGetCB(0))); + + waveEndPtr = endPtr; + + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int gpioWaveTxBusy(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + if (dmaOut[DMA_CONBLK_AD]) + return 1; + else + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int gpioWaveTxAt(void) +{ + int i, cb; + + DBG(DBG_USER, ""); + + CHECK_INITED; + + cb = dmaNowAtOCB(); + + if (cb < 0) return -cb; + + for (i=0; i= waveInfo[i].botCB) && + (cb <= waveInfo[i].topCB) ) return i; + } + + return PI_WAVE_NOT_FOUND; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveTxStop(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + dmaOut[DMA_CS] = DMA_CHANNEL_RESET; + dmaOut[DMA_CONBLK_AD] = 0; + + waveEndPtr = NULL; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetMicros(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.micros; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetHighMicros(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.highMicros; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetMaxMicros(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.maxMicros; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetPulses(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.pulses; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetHighPulses(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.highPulses; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetMaxPulses(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.maxPulses; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetCbs(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.cbs; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetHighCbs(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.highCbs; +} + +/* ----------------------------------------------------------------------- */ + +int gpioWaveGetMaxCbs(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return wfStats.maxCbs; +} + +/* ----------------------------------------------------------------------- */ + +static int read_SDA(wfRx_t *w) +{ + myGpioSetMode(w->I.SDA, PI_INPUT); + return myGpioRead(w->I.SDA); +} + +static void set_SDA(wfRx_t *w) +{ + myGpioSetMode(w->I.SDA, PI_INPUT); +} + +static void clear_SDA(wfRx_t *w) +{ + myGpioSetMode(w->I.SDA, PI_OUTPUT); + myGpioWrite(w->I.SDA, 0); +} + +static void clear_SCL(wfRx_t *w) +{ + myGpioSetMode(w->I.SCL, PI_OUTPUT); + myGpioWrite(w->I.SCL, 0); +} + +static void I2C_delay(wfRx_t *w) +{ + myGpioDelay(w->I.delay); +} + +static void I2C_clock_stretch(wfRx_t *w) +{ + uint32_t now, max_stretch=100000; + + myGpioSetMode(w->I.SCL, PI_INPUT); + now = gpioTick(); + while ((myGpioRead(w->I.SCL) == 0) && ((gpioTick()-now) < max_stretch)); +} + +static void I2CStart(wfRx_t *w) +{ + if (w->I.started) + { + set_SDA(w); + I2C_delay(w); + I2C_clock_stretch(w); + I2C_delay(w); + } + + clear_SDA(w); + I2C_delay(w); + clear_SCL(w); + I2C_delay(w); + + w->I.started = 1; +} + +static void I2CStop(wfRx_t *w) +{ + clear_SDA(w); + I2C_delay(w); + I2C_clock_stretch(w); + I2C_delay(w); + set_SDA(w); + I2C_delay(w); + + w->I.started = 0; +} + +static void I2CPutBit(wfRx_t *w, int bit) +{ + if (bit) set_SDA(w); + else clear_SDA(w); + + I2C_delay(w); + I2C_clock_stretch(w); + I2C_delay(w); + clear_SCL(w); +} + +static int I2CGetBit(wfRx_t *w) +{ + int bit; + + set_SDA(w); /* let SDA float */ + I2C_delay(w); + I2C_clock_stretch(w); + bit = read_SDA(w); + I2C_delay(w); + clear_SCL(w); + + return bit; +} + +static int I2CPutByte(wfRx_t *w, int byte) +{ + int bit, nack; + + for(bit=0; bit<8; bit++) + { + I2CPutBit(w, byte & 0x80); + byte <<= 1; + } + + nack = I2CGetBit(w); + + return nack; +} + +static uint8_t I2CGetByte(wfRx_t *w, int nack) +{ + int bit, byte=0; + + for (bit=0; bit<8; bit++) + { + byte = (byte << 1) | I2CGetBit(w); + } + + I2CPutBit(w, nack); + + return byte; +} + +/*-------------------------------------------------------------------------*/ + +int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud) +{ + DBG(DBG_USER, "SDA=%d SCL=%d baud=%d", SDA, SCL, baud); + + CHECK_INITED; + + if (SDA > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad SDA (%d)", SDA); + + if (SCL > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad SCL (%d)", SCL); + + if ((baud < PI_BB_I2C_MIN_BAUD) || (baud > PI_BB_I2C_MAX_BAUD)) + SOFT_ERROR(PI_BAD_I2C_BAUD, + "SDA %d, bad baud rate (%d)", SDA, baud); + + if (wfRx[SDA].mode != PI_WFRX_NONE) + SOFT_ERROR(PI_GPIO_IN_USE, "gpio %d is already being used", SDA); + + if ((wfRx[SCL].mode != PI_WFRX_NONE) || (SCL == SDA)) + SOFT_ERROR(PI_GPIO_IN_USE, "gpio %d is already being used", SCL); + + wfRx[SDA].gpio = SDA; + wfRx[SDA].mode = PI_WFRX_I2C_SDA; + wfRx[SDA].baud = baud; + + wfRx[SDA].I.started = 0; + wfRx[SDA].I.SDA = SDA; + wfRx[SDA].I.SCL = SCL; + wfRx[SDA].I.delay = 500000 / baud; + wfRx[SDA].I.SDAMode = gpioGetMode(SDA); + wfRx[SDA].I.SCLMode = gpioGetMode(SCL); + + wfRx[SCL].gpio = SCL; + wfRx[SCL].mode = PI_WFRX_I2C_SCL; + + myGpioSetMode(SDA, PI_INPUT); + myGpioSetMode(SCL, PI_INPUT); + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int bbI2CClose(unsigned SDA) +{ + DBG(DBG_USER, "SDA=%d", SDA); + + CHECK_INITED; + + if (SDA > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", SDA); + + switch(wfRx[SDA].mode) + { + case PI_WFRX_I2C_SDA: + + myGpioSetMode(wfRx[SDA].I.SDA, wfRx[SDA].I.SDAMode); + myGpioSetMode(wfRx[SDA].I.SCL, wfRx[SDA].I.SCLMode); + + wfRx[wfRx[SDA].I.SDA].mode = PI_WFRX_NONE; + wfRx[wfRx[SDA].I.SCL].mode = PI_WFRX_NONE; + + break; + + default: + + SOFT_ERROR(PI_NOT_I2C_GPIO, "no I2C on gpio (%d)", SDA); + + break; + + } + + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int bbI2CZip( + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen) +{ + int i, ack, inPos, outPos, status, bytes; + int addr, flags, esc, setesc; + wfRx_t *w; + + DBG(DBG_USER, "gpio=%d inBuf=%s outBuf=%08X len=%d", + SDA, myBuf2Str(inLen, (char *)inBuf), (int)outBuf, outLen); + + CHECK_INITED; + + if (SDA > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", SDA); + + if (wfRx[SDA].mode != PI_WFRX_I2C_SDA) + SOFT_ERROR(PI_NOT_I2C_GPIO, "no I2C on gpio (%d)", SDA); + + if (!inBuf || !inLen) + SOFT_ERROR(PI_BAD_POINTER, "input buffer can't be NULL"); + + if (!outBuf && outLen) + SOFT_ERROR(PI_BAD_POINTER, "output buffer can't be NULL"); + + w = &wfRx[SDA]; + + inPos = 0; + outPos = 0; + status = 0; + + addr = 0; + flags = 0; + esc = 0; + setesc = 0; + + wfRx_lock(SDA); + + while (!status && (inPos < inLen)) + { + DBG(DBG_INTERNAL, "status=%d inpos=%d inlen=%d cmd=%d addr=%d flags=%x", + status, inPos, inLen, inBuf[inPos], addr, flags); + + switch (inBuf[inPos++]) + { + case PI_I2C_END: + status = 1; + break; + + case PI_I2C_START: + I2CStart(w); + break; + + case PI_I2C_STOP: + I2CStop(w); + break; + + case PI_I2C_ADDR: + addr = myI2CGetPar(inBuf, &inPos, inLen, &esc); + if (addr < 0) status = PI_BAD_I2C_CMD; + break; + + case PI_I2C_FLAGS: + /* cheat to force two byte flags */ + esc = 1; + flags = myI2CGetPar(inBuf, &inPos, inLen, &esc); + if (flags < 0) status = PI_BAD_I2C_CMD; + break; + + case PI_I2C_ESC: + setesc = 1; + break; + + case PI_I2C_READ: + + bytes = myI2CGetPar(inBuf, &inPos, inLen, &esc); + + if (bytes >= 0) ack = I2CPutByte(w, (addr<<1)|1); + + if (bytes > 0) + { + if (!ack) + { + if ((bytes + outPos) <= outLen) + { + for (i=0; i<(bytes-1); i++) + { + outBuf[outPos++] = I2CGetByte(w, 0); + } + outBuf[outPos++] = I2CGetByte(w, 1); + } + else status = PI_BAD_I2C_RLEN; + } + else status = PI_I2C_READ_FAILED; + } + else status = PI_BAD_I2C_CMD; + break; + + case PI_I2C_WRITE: + + bytes = myI2CGetPar(inBuf, &inPos, inLen, &esc); + + if (bytes >= 0) ack = I2CPutByte(w, addr<<1); + + if (bytes > 0) + { + if (!ack) + { + if ((bytes + inPos) <= inLen) + { + for (i=0; i<(bytes-1); i++) + { + ack = I2CPutByte(w, inBuf[inPos++]); + if (ack) status = PI_I2C_WRITE_FAILED; + } + ack = I2CPutByte(w, inBuf[inPos++]); + } + else status = PI_BAD_I2C_WLEN; + } else status = PI_I2C_WRITE_FAILED; + } + else status = PI_BAD_I2C_CMD; + break; + + default: + status = PI_BAD_I2C_CMD; + } + + if (setesc) esc = 1; else esc = 0; + + setesc = 0; + } + + wfRx_unlock(SDA); + + if (status >= 0) status = outPos; + + return status; +} + +/* ----------------------------------------------------------------------- */ + +void bscInit(int mode) +{ + bscsReg[BSC_CR]=0; /* clear device */ + bscsReg[BSC_RSR]=0; /* clear underrun and overrun errors */ + bscsReg[BSC_SLV]=0; /* clear I2C slave address */ + bscsReg[BSC_IMSC]=0xf; /* mask off all interrupts */ + bscsReg[BSC_ICR]=0x0f; /* clear all interrupts */ + + gpioSetMode(BSC_SDA_MOSI, PI_ALT3); + gpioSetMode(BSC_SCL_SCLK, PI_ALT3); + + if (mode > 1) /* SPI uses all GPIO */ + { + gpioSetMode(BSC_MISO, PI_ALT3); + gpioSetMode(BSC_CE_N, PI_ALT3); + } +} + +void bscTerm(int mode) +{ + bscsReg[BSC_CR] = 0; /* clear device */ + bscsReg[BSC_RSR]=0; /* clear underrun and overrun errors */ + bscsReg[BSC_SLV]=0; /* clear I2C slave address */ + + gpioSetMode(BSC_SDA_MOSI, PI_INPUT); + gpioSetMode(BSC_SCL_SCLK, PI_INPUT); + + if (mode > 1) + { + gpioSetMode(BSC_MISO, PI_INPUT); + gpioSetMode(BSC_CE_N, PI_INPUT); + } +} + +int bscXfer(bsc_xfer_t *xfer) +{ + static int bscMode = 0; + + int copied=0; + int active, mode; + + DBG(DBG_USER, "control=0x%X (sa=0x%X, cr=0x%X) tx=%d [%s]", + xfer->control, + ((xfer->control)>>16) & 127, + (xfer->control) & 0x3fff, + xfer->txCnt, + myBuf2Str(xfer->txCnt, (char *)xfer->txBuf)); + + CHECK_INITED; + + eventAlert[PI_EVENT_BSC].ignore = 1; + + if (xfer->control) + { + /* + bscMode (0=None, 1=I2C, 2=SPI) tracks which GPIO have been + set to BSC mode + */ + if (xfer->control & 2) mode = 2; /* SPI */ + else mode = 1; /* assume I2C */ + + if (mode > bscMode) + { + bscInit(bscMode); + bscMode = mode; + } + } + else + { + if (bscMode) bscTerm(bscMode); + bscMode = 0; + return 0; /* leave ignore set */ + } + + xfer->rxCnt = 0; + + bscsReg[BSC_SLV] = ((xfer->control)>>16) & 127; + bscsReg[BSC_CR] = (xfer->control) & 0x3fff; + bscsReg[BSC_RSR]=0; /* clear underrun and overrun errors */ + + active = 1; + + while (active) + { + active = 0; + + while ((copied < xfer->txCnt) && + (!(bscsReg[BSC_FR] & BSC_FR_TXFF))) + { + bscsReg[BSC_DR] = xfer->txBuf[copied++]; + active = 1; + } + + while ((xfer->rxCnt < BSC_FIFO_SIZE) && + (!(bscsReg[BSC_FR] & BSC_FR_RXFE))) + { + xfer->rxBuf[xfer->rxCnt++] = bscsReg[BSC_DR]; + active = 1; + } + + if (!active) + { + active = bscsReg[BSC_FR] & (BSC_FR_RXBUSY | BSC_FR_TXBUSY); + } + + if (active) myGpioSleep(0, 20); + } + + bscFR = bscsReg[BSC_FR] & 0xffff; + + eventAlert[PI_EVENT_BSC].ignore = 0; + + return (copied<<16) | bscFR; +} + +/* ----------------------------------------------------------------------- */ + +static void set_CS(wfRx_t *w) +{ + myGpioWrite(w->S.CS, PI_SPI_FLAGS_GET_CSPOL(w->S.spiFlags)); +} + +static void clear_CS(wfRx_t *w) +{ + myGpioWrite(w->S.CS, !PI_SPI_FLAGS_GET_CSPOL(w->S.spiFlags)); +} + +static void set_SCLK(wfRx_t *w) +{ + myGpioWrite(w->S.SCLK, !PI_SPI_FLAGS_GET_CPOL(w->S.spiFlags)); +} + +static void clear_SCLK(wfRx_t *w) +{ + myGpioWrite(w->S.SCLK, PI_SPI_FLAGS_GET_CPOL(w->S.spiFlags)); +} + +static void SPI_delay(wfRx_t *w) +{ + myGpioDelay(w->S.delay); +} + +static void bbSPIStart(wfRx_t *w) +{ + clear_SCLK(w); + + SPI_delay(w); + + set_CS(w); + + SPI_delay(w); +} + +static void bbSPIStop(wfRx_t *w) +{ + SPI_delay(w); + + clear_CS(w); + + SPI_delay(w); + + clear_SCLK(w); +} + +static uint8_t bbSPIXferByte(wfRx_t *w, char txByte) +{ + uint8_t bit, rxByte=0; + + if (PI_SPI_FLAGS_GET_CPHA(w->S.spiFlags)) + { + /* + CPHA = 1 + write on set clock + read on clear clock + */ + + for (bit=0; bit<8; bit++) + { + set_SCLK(w); + + if (PI_SPI_FLAGS_GET_TX_LSB(w->S.spiFlags)) + { + myGpioWrite(w->S.MOSI, txByte & 0x01); + txByte >>= 1; + } + else + { + myGpioWrite(w->S.MOSI, txByte & 0x80); + txByte <<= 1; + } + + SPI_delay(w); + + clear_SCLK(w); + + if (PI_SPI_FLAGS_GET_RX_LSB(w->S.spiFlags)) + { + rxByte = (rxByte >> 1) | myGpioRead(w->S.MISO) << 7; + } + else + { + rxByte = (rxByte << 1) | myGpioRead(w->S.MISO); + } + + SPI_delay(w); + } + } + else + { + /* + CPHA = 0 + read on set clock + write on clear clock + */ + + for (bit=0; bit<8; bit++) + { + if (PI_SPI_FLAGS_GET_TX_LSB(w->S.spiFlags)) + { + myGpioWrite(w->S.MOSI, txByte & 0x01); + txByte >>= 1; + } + else + { + myGpioWrite(w->S.MOSI, txByte & 0x80); + txByte <<= 1; + } + + SPI_delay(w); + + set_SCLK(w); + + if (PI_SPI_FLAGS_GET_RX_LSB(w->S.spiFlags)) + { + rxByte = (rxByte >> 1) | myGpioRead(w->S.MISO) << 7; + } + else + { + rxByte = (rxByte << 1) | myGpioRead(w->S.MISO); + } + + SPI_delay(w); + + clear_SCLK(w); + } + } + + return rxByte; +} + +/*-------------------------------------------------------------------------*/ + +int bbSPIOpen( + unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, + unsigned baud, unsigned spiFlags) +{ + int valid; + uint32_t bits; + + DBG(DBG_USER, "CS=%d MISO=%d MOSI=%d SCLK=%d baud=%d flags=%d", + CS, MISO, MOSI, SCLK, baud, spiFlags); + + CHECK_INITED; + + if (CS > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad CS (%d)", CS); + + if (MISO > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad MISO (%d)", MISO); + + if (MOSI > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad MOSI (%d)", MOSI); + + if (SCLK > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad SCLK (%d)", SCLK); + + if ((baud < PI_BB_SPI_MIN_BAUD) || (baud > PI_BB_SPI_MAX_BAUD)) + SOFT_ERROR(PI_BAD_SPI_BAUD, "CS %d, bad baud (%d)", CS, baud); + + if (wfRx[CS].mode != PI_WFRX_NONE) + SOFT_ERROR(PI_GPIO_IN_USE, + "CS %d is already being used, mode %d", CS, wfRx[CS].mode); + + valid = 0; + + /* check all GPIO unique */ + + bits = (1< PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", CS); + + switch(wfRx[CS].mode) + { + case PI_WFRX_SPI_CS: + + myGpioSetMode(wfRx[CS].S.CS, wfRx[CS].S.CSMode); + wfRx[CS].mode = PI_WFRX_NONE; + + SCLK = wfRx[CS].S.SCLK; + + if (--wfRx[SCLK].S.usage <= 0) + { + myGpioSetMode(wfRx[SCLK].S.MISO, wfRx[SCLK].S.MISOMode); + myGpioSetMode(wfRx[SCLK].S.MOSI, wfRx[SCLK].S.MOSIMode); + myGpioSetMode(wfRx[SCLK].S.SCLK, wfRx[SCLK].S.SCLKMode); + + wfRx[wfRx[SCLK].S.MISO].mode = PI_WFRX_NONE; + wfRx[wfRx[SCLK].S.MOSI].mode = PI_WFRX_NONE; + wfRx[wfRx[SCLK].S.SCLK].mode = PI_WFRX_NONE; + } + + break; + + default: + + SOFT_ERROR(PI_NOT_SPI_GPIO, "no SPI on gpio (%d)", CS); + + break; + + } + + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int bbSPIXfer( + unsigned CS, + char *inBuf, + char *outBuf, + unsigned count) +{ + int SCLK; + int pos; + wfRx_t *w; + + DBG(DBG_USER, "CS=%d inBuf=%s outBuf=%08X count=%d", + CS, myBuf2Str(count, (char *)inBuf), (int)outBuf, count); + + CHECK_INITED; + + if (CS > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", CS); + + if (wfRx[CS].mode != PI_WFRX_SPI_CS) + SOFT_ERROR(PI_NOT_SPI_GPIO, "no SPI on gpio (%d)", CS); + + if (!inBuf || !count) + SOFT_ERROR(PI_BAD_POINTER, "input buffer can't be NULL"); + + if (!outBuf && count) + SOFT_ERROR(PI_BAD_POINTER, "output buffer can't be NULL"); + + SCLK = wfRx[CS].S.SCLK; + + wfRx[SCLK].S.CS = CS; + wfRx[SCLK].baud = wfRx[CS].baud; + wfRx[SCLK].S.delay = wfRx[CS].S.delay; + wfRx[SCLK].S.spiFlags = wfRx[CS].S.spiFlags; + + w = &wfRx[SCLK]; + + wfRx_lock(SCLK); + + bbSPIStart(w); + + for (pos=0; pos < count; pos++) + { + outBuf[pos] = bbSPIXferByte(w, inBuf[pos]); + } + + bbSPIStop(w); + + wfRx_unlock(SCLK); + + return count; +} + +/*-------------------------------------------------------------------------*/ + +int gpioSerialReadOpen(unsigned gpio, unsigned baud, unsigned data_bits) +{ + int bitTime, timeout; + + DBG(DBG_USER, "gpio=%d baud=%d data_bits=%d", gpio, baud, data_bits); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if ((baud < PI_BB_SER_MIN_BAUD) || (baud > PI_BB_SER_MAX_BAUD)) + SOFT_ERROR(PI_BAD_WAVE_BAUD, + "gpio %d, bad baud rate (%d)", gpio, baud); + + if ((data_bits < PI_MIN_WAVE_DATABITS) || + (data_bits > PI_MAX_WAVE_DATABITS)) + SOFT_ERROR(PI_BAD_DATABITS, + "gpio %d, bad data bits (%d)", gpio, data_bits); + + if (wfRx[gpio].mode != PI_WFRX_NONE) + SOFT_ERROR(PI_GPIO_IN_USE, "gpio %d is already being used", gpio); + + bitTime = (1000 * MILLION) / baud; /* nanos */ + + timeout = ((data_bits+2) * bitTime)/MILLION; /* millis */ + + if (timeout < 1) timeout = 1; + + wfRx[gpio].gpio = gpio; + wfRx[gpio].mode = PI_WFRX_SERIAL; + wfRx[gpio].baud = baud; + + wfRx[gpio].s.buf = malloc(SRX_BUF_SIZE); + wfRx[gpio].s.bufSize = SRX_BUF_SIZE; + wfRx[gpio].s.timeout = timeout; + wfRx[gpio].s.fullBit = bitTime; /* nanos */ + wfRx[gpio].s.halfBit = (bitTime/2)+500; /* nanos (500 for rounding) */ + wfRx[gpio].s.readPos = 0; + wfRx[gpio].s.writePos = 0; + wfRx[gpio].s.bit = -1; + wfRx[gpio].s.dataBits = data_bits; + wfRx[gpio].s.invert = PI_BB_SER_NORMAL; + + if (data_bits < 9) wfRx[gpio].s.bytes = 1; + else if (data_bits < 17) wfRx[gpio].s.bytes = 2; + else wfRx[gpio].s.bytes = 4; + + gpioSetAlertFunc(gpio, waveRxBit); + + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int gpioSerialReadInvert(unsigned gpio, unsigned invert) +{ + DBG(DBG_USER, "gpio=%d invert=%d", gpio, invert); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (wfRx[gpio].mode != PI_WFRX_SERIAL) + SOFT_ERROR(PI_NOT_SERIAL_GPIO, "no serial read on gpio (%d)", gpio); + + if ((invert < PI_BB_SER_NORMAL) || + (invert > PI_BB_SER_INVERT)) + SOFT_ERROR(PI_BAD_SER_INVERT, + "bad invert level for gpio %d (%d)", gpio, invert); + + wfRx[gpio].s.invert = invert; + + return 0; +} + +/*-------------------------------------------------------------------------*/ + +int gpioSerialRead(unsigned gpio, void *buf, size_t bufSize) +{ + unsigned bytes=0, wpos; + volatile wfRx_t *w; + + DBG(DBG_USER, "gpio=%d buf=%08X bufSize=%d", gpio, (int)buf, bufSize); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (bufSize == 0) + SOFT_ERROR(PI_BAD_SERIAL_COUNT, "buffer size can't be zero"); + + if (wfRx[gpio].mode != PI_WFRX_SERIAL) + SOFT_ERROR(PI_NOT_SERIAL_GPIO, "no serial read on gpio (%d)", gpio); + + w = &wfRx[gpio]; + + if (w->s.readPos != w->s.writePos) + { + wpos = w->s.writePos; + + if (wpos > w->s.readPos) bytes = wpos - w->s.readPos; + else bytes = w->s.bufSize - w->s.readPos; + + if (bytes > bufSize) bytes = bufSize; + + /* copy in multiples of the data size in bytes */ + + bytes = (bytes / w->s.bytes) * w->s.bytes; + + if (buf) memcpy(buf, w->s.buf+w->s.readPos, bytes); + + w->s.readPos += bytes; + + if (w->s.readPos >= w->s.bufSize) w->s.readPos = 0; + } + return bytes; +} + + +/*-------------------------------------------------------------------------*/ + +int gpioSerialReadClose(unsigned gpio) +{ + DBG(DBG_USER, "gpio=%d", gpio); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + switch(wfRx[gpio].mode) + { + case PI_WFRX_NONE: + + SOFT_ERROR(PI_NOT_SERIAL_GPIO, "no serial read on gpio (%d)", gpio); + + break; + + case PI_WFRX_SERIAL: + + free(wfRx[gpio].s.buf); + + gpioSetWatchdog(gpio, 0); /* switch off timeouts */ + + gpioSetAlertFunc(gpio, NULL); /* cancel alert */ + + wfRx[gpio].mode = PI_WFRX_NONE; + + break; + } + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +static int intEventSetFunc( + unsigned event, + void * f, + int user, + void * userdata) +{ + DBG(DBG_INTERNAL, "event=%d function=%08X, user=%d, userdata=%08X", + event, (uint32_t)f, user, (uint32_t)userdata); + + eventAlert[event].ex = user; + eventAlert[event].userdata = userdata; + + eventAlert[event].func = f; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int eventSetFunc(unsigned event, eventFunc_t f) +{ + DBG(DBG_USER, "event=%d function=%08X", event, (uint32_t)f); + + CHECK_INITED; + + if (event > PI_MAX_EVENT) + SOFT_ERROR(PI_BAD_EVENT_ID, "bad event (%d)", event); + + intEventSetFunc(event, f, 0, NULL); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata) +{ + DBG(DBG_USER, "event=%d function=%08X userdata=%08X", + event, (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED; + + if (event > PI_MAX_EVENT) + SOFT_ERROR(PI_BAD_EVENT_ID, "bad event (%d)", event); + + intEventSetFunc(event, f, 1, userdata); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int eventMonitor(unsigned handle, uint32_t bits) +{ + DBG(DBG_USER, "handle=%d bits=%08X", handle, bits); + + CHECK_INITED; + + if (handle >= PI_NOTIFY_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (gpioNotify[handle].state <= PI_NOTIFY_CLOSING) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + gpioNotify[handle].eventBits = bits; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int eventTrigger(unsigned event) +{ + DBG(DBG_USER, "event=%d", event); + + CHECK_INITED; + + if (event > PI_MAX_EVENT) + SOFT_ERROR(PI_BAD_EVENT_ID, "bad event (%d)", event); + + eventAlert[event].fired = 1; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +static int intGpioSetAlertFunc( + unsigned gpio, + void * f, + int user, + void * userdata) +{ + DBG(DBG_INTERNAL, "gpio=%d function=%08X, user=%d, userdata=%08X", + gpio, (uint32_t)f, user, (uint32_t)userdata); + + gpioAlert[gpio].ex = user; + gpioAlert[gpio].userdata = userdata; + + gpioAlert[gpio].func = f; + + if (f) + { + alertBits |= BIT; + } + else + { + alertBits &= ~BIT; + } + + monitorBits = alertBits | notifyBits | scriptBits | gpioGetSamples.bits; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioSetAlertFunc(unsigned gpio, gpioAlertFunc_t f) +{ + DBG(DBG_USER, "gpio=%d function=%08X", gpio, (uint32_t)f); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + intGpioSetAlertFunc(gpio, f, 0, NULL); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetAlertFuncEx(unsigned gpio, gpioAlertFuncEx_t f, void *userdata) +{ + DBG(DBG_USER, "gpio=%d function=%08X userdata=%08X", + gpio, (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + intGpioSetAlertFunc(gpio, f, 1, userdata); + + return 0; +} + +static void *pthISRThread(void *x) +{ + gpioISR_t *isr = x; + int fd; + int retval; + uint32_t tick; + int level; + uint32_t levels; + struct pollfd pfd; + char buf[64]; + + DBG(DBG_USER, "gpio=%d edge=%d timeout=%d f=%x u=%d data=%x", + isr->gpio, isr->edge, isr->timeout, (uint32_t)isr->func, + isr->ex, (uint32_t)isr->userdata); + + sprintf(buf, "/sys/class/gpio/gpio%d/value", isr->gpio); + + if ((fd = open(buf, O_RDONLY)) < 0) + { + DBG(DBG_ALWAYS, "gpio %d not exported", isr->gpio); + return NULL; + } + + pfd.fd = fd; + + pfd.events = POLLPRI; + + lseek(fd, 0, SEEK_SET); /* consume any prior interrupt */ + if (read(fd, buf, sizeof buf) == -1) { /* ignore errors */ } + + while (1) + { + retval = poll(&pfd, 1, isr->timeout); /* wait for interrupt */ + + tick = systReg[SYST_CLO]; + + levels = *(gpioReg + GPLEV0); + + if (retval >= 0) + { + lseek(fd, 0, SEEK_SET); /* consume interrupt */ + if (read(fd, buf, sizeof buf) == -1) { /* ignore errors */ } + + if (retval) + { + if (levels & (1<gpio)) level = PI_ON; else level = PI_OFF; + } + else level = PI_TIMEOUT; + + if (isr->ex) (isr->func)(isr->gpio, level, tick, isr->userdata); + else (isr->func)(isr->gpio, level, tick); + } + } + + return NULL; +} + + +/* ----------------------------------------------------------------------- */ + +static int intGpioSetISRFunc( + unsigned gpio, + unsigned edge, + int timeout, + void *f, + int user, + void *userdata) +{ + char buf[64]; + + char *edge_str[]={"rising\n", "falling\n", "both\n"}; + int fd; + int err; + + DBG(DBG_INTERNAL, + "gpio=%d edge=%d timeout=%d function=%08X user=%d userdata=%08X", + gpio, edge, timeout, (uint32_t)f, user, (uint32_t)userdata); + + if (f) + { + if (!gpioISR[gpio].inited) /* export gpio if unexported */ + { + fd = open("/sys/class/gpio/export", O_WRONLY); + if (fd < 0) return PI_BAD_ISR_INIT; + + /* ignore write fail if already exported */ + sprintf(buf, "%d\n", gpio); + err = write(fd, buf, strlen(buf)); + close(fd); + + sprintf(buf, "/sys/class/gpio/gpio%d/direction", gpio); + fd = open(buf, O_WRONLY); + if (fd < 0) return PI_BAD_ISR_INIT; + + err = write(fd, "in\n", 3); + close(fd); + if (err != 3) return PI_BAD_ISR_INIT; + + gpioISR[gpio].gpio = gpio; + gpioISR[gpio].edge = -1; + gpioISR[gpio].timeout = -1; + + gpioISR[gpio].inited = 1; + } + + if (gpioISR[gpio].edge != edge) + { + sprintf(buf, "/sys/class/gpio/gpio%d/edge", gpio); + fd = open(buf, O_WRONLY); + if (fd < 0) return PI_BAD_ISR_INIT; + + err = write(fd, edge_str[edge], strlen(edge_str[edge])); + close(fd); + if (err != strlen(edge_str[edge])) return PI_BAD_ISR_INIT; + + gpioISR[gpio].edge = edge; + + if (gpioISR[gpio].pth != NULL) + pthread_kill(*gpioISR[gpio].pth, SIGCHLD); + } + + if (timeout <= 0) timeout = -1; + if (gpioISR[gpio].timeout != timeout) + { + gpioISR[gpio].timeout = timeout; + + if (gpioISR[gpio].pth != NULL) + pthread_kill(*gpioISR[gpio].pth, SIGCHLD); + } + + gpioISR[gpio].func = f; + gpioISR[gpio].ex = user; + gpioISR[gpio].userdata = userdata; + + if (gpioISR[gpio].pth == NULL) + gpioISR[gpio].pth = gpioStartThread(pthISRThread, &gpioISR[gpio]); + } + else /* null function, delete ISR, unexport gpio */ + { + if (gpioISR[gpio].pth) /* delete any existing ISR */ + { + gpioStopThread(gpioISR[gpio].pth); + gpioISR[gpio].func = NULL; + gpioISR[gpio].pth = NULL; + } + + if (gpioISR[gpio].inited) /* unexport the gpio */ + { + fd = open("/sys/class/gpio/unexport", O_WRONLY); + if (fd < 0) return PI_BAD_ISR_INIT; + sprintf(buf, "%d\n", gpio); + err = write(fd, buf, strlen(buf)); + close(fd); + if (err != strlen(buf)) return PI_BAD_ISR_INIT; + gpioISR[gpio].inited = 0; + } + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioSetISRFunc( + unsigned gpio, + unsigned edge, + int timeout, + gpioISRFunc_t f) +{ + DBG(DBG_USER, "gpio=%d edge=%d timeout=%d function=%08X", + gpio, edge, timeout, (uint32_t)f); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (edge > EITHER_EDGE) + SOFT_ERROR(PI_BAD_EDGE, "bad ISR edge (%d)", edge); + + return intGpioSetISRFunc(gpio, edge, timeout, f, 0, NULL); +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetISRFuncEx( + unsigned gpio, + unsigned edge, + int timeout, + gpioAlertFuncEx_t f, + void *userdata) +{ + DBG(DBG_USER, "gpio=%d edge=%d timeout=%d function=%08X userdata=%08X", + gpio, edge, timeout, (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (edge > EITHER_EDGE) + SOFT_ERROR(PI_BAD_EDGE, "bad ISR edge (%d)", edge); + + return intGpioSetISRFunc(gpio, edge, timeout, f, 1, userdata); +} + +static void closeOrphanedNotifications(int slot, int fd) +{ + int i; + + /* Check for and close any orphaned notifications. */ + + for (i=0; i= PI_NOTIFY_OPENED) && + (gpioNotify[i].fd == fd)) + { + DBG(DBG_USER, "closed orphaned fd=%d (handle=%d)", fd, i); + gpioNotify[i].state = PI_NOTIFY_CLOSED; + intNotifyBits(); + } + } +} + +/* ----------------------------------------------------------------------- */ + +static void notifyMutex(int lock) +{ + static pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; + if (lock) pthread_mutex_lock(&mutex); + else pthread_mutex_unlock(&mutex); +} + +/* ----------------------------------------------------------------------- */ + +int gpioNotifyOpenWithSize(int bufSize) +{ + int i, slot, fd; + char name[32]; + + DBG(DBG_USER, "bufSize=%d", bufSize); + + CHECK_INITED; + + slot = -1; + + notifyMutex(1); + + for (i=0; i= PI_NOTIFY_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (gpioNotify[handle].state <= PI_NOTIFY_CLOSING) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + gpioNotify[handle].bits = bits; + + gpioNotify[handle].state = PI_NOTIFY_RUNNING; + + intNotifyBits(); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioNotifyPause (unsigned handle) +{ + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_NOTIFY_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (gpioNotify[handle].state <= PI_NOTIFY_CLOSING) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + gpioNotify[handle].bits = 0; + + gpioNotify[handle].state = PI_NOTIFY_PAUSED; + + intNotifyBits(); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioNotifyClose(unsigned handle) +{ + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_NOTIFY_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (gpioNotify[handle].state <= PI_NOTIFY_CLOSING) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + gpioNotify[handle].bits = 0; + + gpioNotify[handle].state = PI_NOTIFY_CLOSING; + + intNotifyBits(); + + /* actual close done in alert thread */ + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioTrigger(unsigned gpio, unsigned pulseLen, unsigned level) +{ + DBG(DBG_USER, "gpio=%d pulseLen=%d level=%d", gpio, pulseLen, level); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (level > PI_ON) + SOFT_ERROR(PI_BAD_LEVEL, "gpio %d, bad level (%d)", gpio, level); + + if ((pulseLen > PI_MAX_BUSY_DELAY) || (!pulseLen)) + SOFT_ERROR(PI_BAD_PULSELEN, + "gpio %d, bad pulseLen (%d)", gpio, pulseLen); + + if (level == PI_OFF) *(gpioReg + GPCLR0 + BANK) = BIT; + else *(gpioReg + GPSET0 + BANK) = BIT; + + myGpioDelay(pulseLen); + + if (level != PI_OFF) *(gpioReg + GPCLR0 + BANK) = BIT; + else *(gpioReg + GPSET0 + BANK) = BIT; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetWatchdog(unsigned gpio, unsigned timeout) +{ + DBG(DBG_USER, "gpio=%d timeout=%d", gpio, timeout); + + CHECK_INITED; + + if (gpio > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (timeout > PI_MAX_WDOG_TIMEOUT) + SOFT_ERROR(PI_BAD_WDOG_TIMEOUT, + "gpio %d, bad timeout (%d)", gpio, timeout); + + gpioAlert[gpio].wdTick = systReg[SYST_CLO]; + gpioAlert[gpio].wdSteadyUs = timeout*1000; + + if (timeout) wdogBits |= (1< PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (steady > PI_MAX_STEADY) + SOFT_ERROR(PI_BAD_FILTER, "bad steady (%d)", steady); + + if (active > PI_MAX_ACTIVE) + SOFT_ERROR(PI_BAD_FILTER, "bad active (%d)", active); + + gpioAlert[gpio].nfTick1 = systReg[SYST_CLO]; + gpioAlert[gpio].nfTick2 = gpioAlert[gpio].nfTick1; + gpioAlert[gpio].nfSteadyUs = steady; + gpioAlert[gpio].nfActiveUs = active; + gpioAlert[gpio].nfActive = 0; + + if (steady) nFilterBits |= (1< PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); + + if (steady > PI_MAX_STEADY) + SOFT_ERROR(PI_BAD_FILTER, "bad steady (%d)", steady); + + if (steady) + { + gpioAlert[gpio].gfTick = systReg[SYST_CLO]; + + if (gpioRead_Bits_0_31() & (1< PI_MAX_TIMER) + SOFT_ERROR(PI_BAD_TIMER, "bad timer id (%d)", id); + + if ((millis < PI_MIN_MS) || (millis > PI_MAX_MS)) + SOFT_ERROR(PI_BAD_MS, "timer %d, bad millis (%d)", id, millis); + + intGpioSetTimerFunc(id, millis, f, 0, NULL); + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetTimerFuncEx(unsigned id, unsigned millis, gpioTimerFuncEx_t f, + void * userdata) +{ + DBG(DBG_USER, "id=%d millis=%d function=%08X, userdata=%08X", + id, millis, (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED; + + if (id > PI_MAX_TIMER) + SOFT_ERROR(PI_BAD_TIMER, "bad timer id (%d)", id); + + if ((millis < PI_MIN_MS) || (millis > PI_MAX_MS)) + SOFT_ERROR(PI_BAD_MS, "timer %d, bad millis (%d)", id, millis); + + intGpioSetTimerFunc(id, millis, f, 1, userdata); + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +pthread_t *gpioStartThread(gpioThreadFunc_t f, void *userdata) +{ + pthread_t *pth; + pthread_attr_t pthAttr; + + DBG(DBG_USER, "f=%08X, userdata=%08X", (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED_RET_NULL_PTR; + + pth = malloc(sizeof(pthread_t)); + + if (pth) + { + if (pthread_attr_init(&pthAttr)) + { + free(pth); + SOFT_ERROR(NULL, "pthread_attr_init failed"); + } + + if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE)) + { + free(pth); + SOFT_ERROR(NULL, "pthread_attr_setstacksize failed"); + } + + if (pthread_create(pth, &pthAttr, f, userdata)) + { + free(pth); + SOFT_ERROR(NULL, "pthread_create failed"); + } + } + return pth; +} + +/* ----------------------------------------------------------------------- */ + +void gpioStopThread(pthread_t *pth) +{ + DBG(DBG_USER, "pth=%08X", (uint32_t)pth); + + CHECK_INITED_RET_NIL; + + if (pth) + { + if (pthread_self() == *pth) + { + free(pth); + pthread_exit(NULL); + } + else + { + pthread_cancel(*pth); + pthread_join(*pth, NULL); + free(pth); + } + } +} + +/* ----------------------------------------------------------------------- */ + +int gpioStoreScript(char *script) +{ + static pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; + gpioScript_t *s; + int status, slot, i; + + DBG(DBG_USER, "script=[%s]", script); + + CHECK_INITED; + + slot = -1; + + pthread_mutex_lock(&mutex); + + for (i=0; iscript, 0); + + if (status == 0) + { + s->request = PI_SCRIPT_HALT; + s->run_state = PI_SCRIPT_INITING; + + pthread_cond_init(&s->pthCond, NULL); + pthread_mutex_init(&s->pthMutex, NULL); + + s->id = slot; + + gpioScript[slot].state = PI_SCRIPT_IN_USE; + + s->pthIdp = gpioStartThread(pthScript, s); + + status = slot; + } + else + { + if (s->script.par) free(s->script.par); + s->script.par = NULL; + gpioScript[slot].state = PI_SCRIPT_FREE; + } + + return status; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioRunScript(unsigned script_id, unsigned numParam, uint32_t *param) +{ + int status = 0; + + DBG(DBG_USER, "script_id=%d numParam=%d param=%08X", + script_id, numParam, (uint32_t)param); + + CHECK_INITED; + + if (script_id >= PI_MAX_SCRIPTS) + SOFT_ERROR(PI_BAD_SCRIPT_ID, "bad script id(%d)", script_id); + + if (numParam > PI_MAX_SCRIPT_PARAMS) + SOFT_ERROR(PI_TOO_MANY_PARAM, "bad number of parameters(%d)", numParam); + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + pthread_mutex_lock(&gpioScript[script_id].pthMutex); + + if (gpioScript[script_id].run_state != PI_SCRIPT_INITING) + { + if ((numParam > 0) && (param != 0)) + { + memcpy(gpioScript[script_id].script.par, param, + sizeof(uint32_t) * numParam); + } + + gpioScript[script_id].request = PI_SCRIPT_RUN; + + pthread_cond_signal(&gpioScript[script_id].pthCond); + } + else + { + status = PI_SCRIPT_NOT_READY; + } + + pthread_mutex_unlock(&gpioScript[script_id].pthMutex); + + return status; + } + else + { + return PI_BAD_SCRIPT_ID; + } +} + + +/* ----------------------------------------------------------------------- */ + +int gpioUpdateScript(unsigned script_id, unsigned numParam, uint32_t *param) +{ + DBG(DBG_USER, "script_id=%d numParam=%d param=%08X", + script_id, numParam, (uint32_t)param); + + CHECK_INITED; + + if (script_id >= PI_MAX_SCRIPTS) + SOFT_ERROR(PI_BAD_SCRIPT_ID, "bad script id(%d)", script_id); + + if (numParam > PI_MAX_SCRIPT_PARAMS) + SOFT_ERROR(PI_TOO_MANY_PARAM, "bad number of parameters(%d)", numParam); + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + if ((numParam > 0) && (param != 0)) + { + memcpy(gpioScript[script_id].script.par, param, + sizeof(uint32_t) * numParam); + } + } + else + { + return PI_BAD_SCRIPT_ID; + } + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioScriptStatus(unsigned script_id, uint32_t *param) +{ + DBG(DBG_USER, "script_id=%d param=%08X", script_id, (uint32_t)param); + + CHECK_INITED; + + if (script_id >= PI_MAX_SCRIPTS) + SOFT_ERROR(PI_BAD_SCRIPT_ID, "bad script id(%d)", script_id); + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + if (param != NULL) + { + memcpy(param, gpioScript[script_id].script.par, + sizeof(uint32_t) * PI_MAX_SCRIPT_PARAMS); + } + + return gpioScript[script_id].run_state; + } + else return PI_BAD_SCRIPT_ID; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioStopScript(unsigned script_id) +{ + DBG(DBG_USER, "script_id=%d", script_id); + + CHECK_INITED; + + if (script_id >= PI_MAX_SCRIPTS) + SOFT_ERROR(PI_BAD_SCRIPT_ID, "bad script id(%d)", script_id); + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + pthread_mutex_lock(&gpioScript[script_id].pthMutex); + + gpioScript[script_id].request = PI_SCRIPT_HALT; + + if (gpioScript[script_id].run_state == PI_SCRIPT_WAITING) + { + pthread_cond_signal(&gpioScript[script_id].pthCond); + } + + pthread_mutex_unlock(&gpioScript[script_id].pthMutex); + + return 0; + } + else return PI_BAD_SCRIPT_ID; +} + +/* ----------------------------------------------------------------------- */ + +int gpioDeleteScript(unsigned script_id) +{ + DBG(DBG_USER, "script_id=%d", script_id); + + CHECK_INITED; + + if (script_id >= PI_MAX_SCRIPTS) + SOFT_ERROR(PI_BAD_SCRIPT_ID, "bad script id(%d)", script_id); + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) + { + gpioScript[script_id].state = PI_SCRIPT_DYING; + + pthread_mutex_lock(&gpioScript[script_id].pthMutex); + + gpioScript[script_id].request = PI_SCRIPT_HALT; + + if (gpioScript[script_id].run_state == PI_SCRIPT_WAITING) + { + pthread_cond_signal(&gpioScript[script_id].pthCond); + } + + pthread_mutex_unlock(&gpioScript[script_id].pthMutex); + + while (gpioScript[script_id].run_state == PI_SCRIPT_RUNNING) + { + myGpioSleep(0, 5000); /* give script time to halt */ + } + + gpioStopThread(gpioScript[script_id].pthIdp); + + if (gpioScript[script_id].script.par) + free(gpioScript[script_id].script.par); + + gpioScript[script_id].script.par = NULL; + + gpioScript[script_id].state = PI_SCRIPT_FREE; + + return 0; + } + else return PI_BAD_SCRIPT_ID; +} + + + +/* ----------------------------------------------------------------------- */ + +int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f) +{ + DBG(DBG_USER, "signum=%d function=%08X", signum, (uint32_t)f); + + CHECK_INITED; + + if (signum > PI_MAX_SIGNUM) + SOFT_ERROR(PI_BAD_SIGNUM, "bad signum (%d)", signum); + + gpioSignal[signum].ex = 0; + gpioSignal[signum].userdata = NULL; + + gpioSignal[signum].func = f; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSetSignalFuncEx(unsigned signum, gpioSignalFuncEx_t f, + void *userdata) +{ + DBG(DBG_USER, "signum=%d function=%08X userdata=%08X", + signum, (uint32_t)f, (uint32_t)userdata); + + CHECK_INITED; + + if (signum > PI_MAX_SIGNUM) + SOFT_ERROR(PI_BAD_SIGNUM, "bad signum (%d)", signum); + + gpioSignal[signum].ex = 1; + gpioSignal[signum].userdata = userdata; + + gpioSignal[signum].func = f; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t gpioRead_Bits_0_31(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return (*(gpioReg + GPLEV0)); +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t gpioRead_Bits_32_53(void) +{ + DBG(DBG_USER, ""); + + CHECK_INITED; + + return (*(gpioReg + GPLEV1)); +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWrite_Bits_0_31_Clear(uint32_t bits) +{ + DBG(DBG_USER, "bits=%08X", bits); + + CHECK_INITED; + + *(gpioReg + GPCLR0) = bits; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWrite_Bits_32_53_Clear(uint32_t bits) +{ + DBG(DBG_USER, "bits=%08X", bits); + + CHECK_INITED; + + *(gpioReg + GPCLR1) = bits; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWrite_Bits_0_31_Set(uint32_t bits) +{ + DBG(DBG_USER, "bits=%08X", bits); + + CHECK_INITED; + + *(gpioReg + GPSET0) = bits; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioWrite_Bits_32_53_Set(uint32_t bits) +{ + DBG(DBG_USER, "bits=%08X", bits); + + CHECK_INITED; + + *(gpioReg + GPSET1) = bits; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioHardwareClock(unsigned gpio, unsigned frequency) +{ + int cctl[] = {CLK_GP0_CTL, CLK_GP1_CTL, CLK_GP2_CTL}; + int cdiv[] = {CLK_GP0_DIV, CLK_GP1_DIV, CLK_GP2_DIV}; + int csrc[CLK_SRCS] = {CLK_CTL_SRC_OSC, CLK_CTL_SRC_PLLD}; + uint32_t cfreq[CLK_SRCS]={CLK_OSC_FREQ, CLK_PLLD_FREQ}; + unsigned clock, mode, mash; + int password = 0; + double f; + clkInf_t clkInf={0,0,0}; + + DBG(DBG_USER, "gpio=%d frequency=%d", gpio, frequency); + + CHECK_INITED; + + if ((gpio >> 24) == 0x5A) password = 1; + + gpio &= 0xFFFFFF; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (!clkDef[gpio]) + SOFT_ERROR(PI_NOT_HCLK_GPIO, "bad gpio for clock (%d)", gpio); + + if (((frequency < PI_HW_CLK_MIN_FREQ) || + (frequency > PI_HW_CLK_MAX_FREQ)) && + (frequency)) + SOFT_ERROR(PI_BAD_HCLK_FREQ, + "bad hardware clock frequency (%d)", frequency); + + clock = (clkDef[gpio] >> 4) & 3; + + if ((clock == 1) && (!password)) + SOFT_ERROR(PI_BAD_HCLK_PASS, + "Need password to use clock 1 (%d)", gpio); + + mode = clkDef[gpio] & 7; + mash = frequency < PI_MASH_MAX_FREQ ? 1 : 0; + + if (frequency) + { + if (chooseBestClock(&clkInf, frequency, CLK_SRCS, cfreq)) + { + if (clkInf.frac == 0) mash = 0; + + initHWClk(cctl[clock], cdiv[clock], + csrc[clkInf.clock], clkInf.div, clkInf.frac, mash); + + myGpioSetMode(gpio, mode); + + gpioInfo[gpio].is = GPIO_HW_CLK; + + f = (double) cfreq[clkInf.clock] / + ((double)clkInf.div + ((double)clkInf.frac / 4096.0)); + + hw_clk_freq[clock] = (f + 0.5); + + DBG(DBG_USER, "cf=%d div=%d frac=%d mash=%d", + cfreq[clkInf.clock], clkInf.div, clkInf.frac, mash); + } + else + { + SOFT_ERROR(PI_BAD_HCLK_FREQ, + "bad hardware clock frequency (%d)", frequency); + } + } + else + { + /* frequency 0, stop clock */ + clkReg[cctl[clock]] = BCM_PASSWD | CLK_CTL_KILL; + + if (gpioInfo[gpio].is == GPIO_HW_CLK) + gpioInfo[gpio].is = GPIO_UNDEFINED; + } + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioHardwarePWM( + unsigned gpio, unsigned frequency, unsigned dutycycle) +{ + uint32_t old_PWM_CTL; + unsigned pwm, mode; + uint32_t real_range, real_dutycycle; + + DBG(DBG_USER, "gpio=%d frequency=%d dutycycle=%d", + gpio, frequency, dutycycle); + + CHECK_INITED; + + if (gpio > PI_MAX_GPIO) + SOFT_ERROR(PI_BAD_GPIO, "bad gpio (%d)", gpio); + + if (!PWMDef[gpio]) + SOFT_ERROR(PI_NOT_HPWM_GPIO, "bad gpio for PWM (%d)", gpio); + + if (dutycycle > PI_HW_PWM_RANGE) + SOFT_ERROR(PI_BAD_HPWM_DUTY, "bad PWM dutycycle (%d)", dutycycle); + + if (((frequency < PI_HW_PWM_MIN_FREQ) || + (frequency > PI_HW_PWM_MAX_FREQ)) && + (frequency)) + SOFT_ERROR(PI_BAD_HPWM_FREQ, + "bad hardware PWM frequency (%d)", frequency); + + if (gpioCfg.clockPeriph == PI_CLOCK_PWM) + SOFT_ERROR(PI_HPWM_ILLEGAL, "illegal, PWM in use for main clock"); + + pwm = (PWMDef[gpio] >> 4) & 3; + mode = PWMDef[gpio] & 7; + + if (frequency) + { + real_range = ((double)CLK_PLLD_FREQ / (2.0 * frequency)) + 0.5; + real_dutycycle = ((uint64_t)dutycycle * real_range) / PI_HW_PWM_RANGE; + + /* record the set PWM frequency and dutycycle */ + + hw_pwm_freq[pwm] = + ((double)CLK_PLLD_FREQ / ( 2.0 * real_range)) + 0.5; + + hw_pwm_duty[pwm] = dutycycle; + + hw_pwm_real_range[pwm] = real_range; + + /* Abort any waveform transmission in progress */ + + if (gpioWaveTxBusy()) gpioWaveTxStop(); + + waveClockInited = 0; + + /* preserve channel enable only and mark space mode */ + + old_PWM_CTL = pwmReg[PWM_CTL] & + (PWM_CTL_PWEN1 | PWM_CTL_MSEN1 | PWM_CTL_PWEN2 | PWM_CTL_MSEN2); + + if (!PWMClockInited) + { + pwmReg[PWM_CTL] = 0; + + myGpioDelay(10); + + initHWClk(CLK_PWMCTL, CLK_PWMDIV, CLK_CTL_SRC_PLLD, 2, 0, 0); + + PWMClockInited = 1; + } + + if (pwm == 0) + { + pwmReg[PWM_RNG1] = real_range; + myGpioDelay(10); + pwmReg[PWM_DAT1] = real_dutycycle; + myGpioDelay(10); + + pwmReg[PWM_CTL] = (old_PWM_CTL | PWM_CTL_PWEN1 | PWM_CTL_MSEN1); + } + else + { + pwmReg[PWM_RNG2] = real_range; + myGpioDelay(10); + pwmReg[PWM_DAT2] = real_dutycycle; + myGpioDelay(10); + + pwmReg[PWM_CTL] = (old_PWM_CTL | PWM_CTL_PWEN2 | PWM_CTL_MSEN2); + } + + if (gpioInfo[gpio].is != GPIO_HW_PWM) + { + switchFunctionOff(gpio); + + myGpioSetMode(gpio, mode); + + gpioInfo[gpio].is = GPIO_HW_PWM; + } + } + else + { + /* frequency 0, stop PWM */ + + if (gpioInfo[gpio].is == GPIO_HW_PWM) + { + if (pwm == 0) pwmReg[PWM_CTL] &= (~PWM_CTL_PWEN1); + else pwmReg[PWM_CTL] &= (~PWM_CTL_PWEN2); + + gpioInfo[gpio].is = GPIO_UNDEFINED; + } + } + + return 0; +} + + +int gpioSetPad(unsigned pad, unsigned padStrength) +{ + DBG(DBG_USER, "pad=%d padStrength=%d", pad, padStrength); + + CHECK_INITED; + + if (pad > PI_MAX_PAD) + SOFT_ERROR(PI_BAD_PAD, "bad pad number (%d)", pad); + + if ((padStrength < PI_MIN_PAD_STRENGTH) || + (padStrength > PI_MAX_PAD_STRENGTH)) + SOFT_ERROR(PI_BAD_STRENGTH, "bad pad drive strength (%d)", pad); + + /* 1-16 -> 0-7 */ + + padStrength += 1; + padStrength /= 2; + padStrength -= 1; + + padsReg[11+pad] = BCM_PASSWD | 0x18 | (padStrength & 7) ; + + return 0; +} + +int gpioGetPad(unsigned pad) +{ + int strength; + + DBG(DBG_USER, "pad=%d", pad); + + CHECK_INITED; + + if (pad > PI_MAX_PAD) + SOFT_ERROR(PI_BAD_PAD, "bad pad (%d)", pad); + + strength = padsReg[11+pad] & 7; + + strength *= 2; + strength += 2; + + return strength; +} + +int shell(char *scriptName, char *scriptString) +{ + int status; + char buf[4096]; + + DBG(DBG_USER, "name=%s string=%s", scriptName, scriptString); + + CHECK_INITED; + + if (!myScriptNameValid(scriptName)) + SOFT_ERROR(PI_BAD_SCRIPT_NAME, "bad script name (%s)", scriptName); + + snprintf(buf, sizeof(buf), + "/opt/pigpio/cgi/%s %s", scriptName, scriptString); + + DBG(DBG_USER, "%s", buf); + + status = system(buf); + + if (status < 0) status = PI_BAD_SHELL_STATUS; + + return status; +} + + +int fileApprove(char *filename) +{ + char match[PI_MAX_PATH]; + char buffer[PI_MAX_PATH]; + char line[PI_MAX_PATH]; + char mperm=0; + char perm; + char term; + FILE *f; + + buffer[0] = 0; + match[0] = 0; + + f = fopen("/opt/pigpio/access", "r"); + + if (!f) return PI_FILE_NONE; + + while (!feof(f)) + { + buffer[0] = 0; + perm = 0; + term = 0; + if (fgets(line, sizeof(line), f)) + { + sscanf(line, " %511s %c%c", buffer, &perm, &term); + if (term == 10) + { + if (myPathBad(buffer)) continue; /* disallow risky lines */ + + if (fnmatch(buffer, filename, 0) == 0) + { + if (match[0]) + { + if (fnmatch(match, buffer, 0) == 0) + { + strcpy(match, buffer); + mperm = perm; + } + } + else + { + strcpy(match, buffer); + mperm = perm; + } + } + } + } + } + + fclose(f); + + if (match[0]) + { + switch (toupper(mperm)) + { + case 'R': return PI_FILE_READ; + case 'W': return PI_FILE_WRITE; + case 'U': return PI_FILE_RW; + default : return PI_FILE_NONE; + } + } + + return PI_FILE_NONE; +} + +int fileOpen(char *file, unsigned mode) +{ + static pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER; + int fd=-1; + int i, slot, oflag, omode; + struct stat statbuf; + + DBG(DBG_USER, "file=%s mode=%d", file, mode); + + CHECK_INITED; + + if ( (mode < PI_FILE_MIN) || + (mode > PI_FILE_MAX) || + ((mode & PI_FILE_RW) == 0) ) + SOFT_ERROR(PI_BAD_FILE_MODE, "bad mode (%d)", mode); + + if ((fileApprove(file) & mode) == PI_FILE_NONE) + SOFT_ERROR(PI_NO_FILE_ACCESS, "no permission to access file (%s)", file); + + slot = -1; + + pthread_mutex_lock(&mutex); + + for (i=0; i= PI_FILE_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (fileInfo[handle].state != PI_FILE_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (fileInfo[handle].fd >= 0) close(fileInfo[handle].fd); + + fileInfo[handle].fd = -1; + fileInfo[handle].state = PI_FILE_CLOSED; + + return 0; +} + +int fileWrite(unsigned handle, char *buf, unsigned count) +{ + int w; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_FILE_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (fileInfo[handle].state != PI_FILE_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + if (!(fileInfo[handle].mode & PI_FILE_WRITE)) + SOFT_ERROR(PI_FILE_NOT_WOPEN, "file not opened for write"); + + w = write(fileInfo[handle].fd, buf, count); + + if (w != count) + { + if (w == -1) DBG(DBG_USER, "write failed with errno %d", errno); + + return PI_BAD_FILE_WRITE; + } + return 0; +} + +int fileRead(unsigned handle, char *buf, unsigned count) +{ + int r; + + DBG(DBG_USER, "handle=%d count=%d buf=0x%X", handle, count, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_FILE_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (fileInfo[handle].state != PI_FILE_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + if (!(fileInfo[handle].mode & PI_FILE_READ)) + SOFT_ERROR(PI_FILE_NOT_ROPEN, "file not opened for read"); + + r = read(fileInfo[handle].fd, buf, count); + + if (r == -1) + { + DBG(DBG_USER, "read failed with errno %d", errno); + return PI_BAD_FILE_READ; + } + else + { + buf[r] = 0; + return r; + } +} + + +int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom) +{ + int whence, s; + + DBG(DBG_USER, "handle=%d offset=%d from=%d", + handle, seekOffset, seekFrom); + + CHECK_INITED; + + if (handle >= PI_FILE_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (fileInfo[handle].state != PI_FILE_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + switch (seekFrom) + { + case PI_FROM_START: + whence = SEEK_SET; + break; + + case PI_FROM_CURRENT: + whence = SEEK_CUR; + break; + + case PI_FROM_END: + whence = SEEK_END; + break; + + default: + SOFT_ERROR(PI_BAD_FILE_SEEK, "bad seek from (%d)", seekFrom); + } + + s = lseek(fileInfo[handle].fd, seekOffset, whence); + + if (s == -1) + { + DBG(DBG_USER, "seek failed with errno %d", errno); + return PI_BAD_FILE_SEEK; + } + + return s; +} + +int fileList(char *fpat, char *buf, unsigned count) +{ + int len, bufpos; + glob_t pglob; + int i; + + DBG(DBG_USER, "fpat=%s count=%d buf=%x", fpat, count, (unsigned)buf); + + CHECK_INITED; + + if (fileApprove(fpat) == PI_FILE_NONE) + SOFT_ERROR(PI_NO_FILE_ACCESS, "no permission to access file (%s)", fpat); + + bufpos = 0; + + if (glob(fpat, GLOB_MARK, NULL, &pglob) == 0) + { + for (i=0; i PI_TIME_ABSOLUTE) + SOFT_ERROR(PI_BAD_TIMETYPE, "bad timetype (%d)", timetype); + + if (timetype == PI_TIME_ABSOLUTE) + { + clock_gettime(CLOCK_REALTIME, &ts); + *seconds = ts.tv_sec; + *micros = ts.tv_nsec/1000; + } + else + { + clock_gettime(CLOCK_REALTIME, &ts); + + TIMER_SUB(&ts, &libStarted, &ts); + + *seconds = ts.tv_sec; + *micros = ts.tv_nsec/1000; + } + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioSleep(unsigned timetype, int seconds, int micros) +{ + struct timespec ts, rem; + + DBG(DBG_USER, "timetype=%d seconds=%d micros=%d", + timetype, seconds, micros); + + CHECK_INITED; + + if (timetype > PI_TIME_ABSOLUTE) + SOFT_ERROR(PI_BAD_TIMETYPE, "bad timetype (%d)", timetype); + + if (seconds < 0) + SOFT_ERROR(PI_BAD_SECONDS, "bad seconds (%d)", seconds); + + if ((micros < 0) || (micros > 999999)) + SOFT_ERROR(PI_BAD_MICROS, "bad micros (%d)", micros); + + ts.tv_sec = seconds; + ts.tv_nsec = micros * 1000; + + if (timetype == PI_TIME_ABSOLUTE) + { + while (clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &ts, &rem)); + } + else + { + while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem)) + { + /* copy remaining time to ts */ + ts.tv_sec = rem.tv_sec; + ts.tv_nsec = rem.tv_nsec; + } + } + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t gpioDelay(uint32_t micros) +{ + uint32_t start; + + DBG(DBG_USER, "microseconds=%u", micros); + + CHECK_INITED; + + start = systReg[SYST_CLO]; + + if (micros <= PI_MAX_BUSY_DELAY) + while ((systReg[SYST_CLO] - start) <= micros); + else + gpioSleep(PI_TIME_RELATIVE, (micros/MILLION), (micros%MILLION)); + + return (systReg[SYST_CLO] - start); +} + + +/* ----------------------------------------------------------------------- */ + +uint32_t gpioTick(void) +{ + CHECK_INITED; + + return systReg[SYST_CLO]; +} + + +/* ----------------------------------------------------------------------- */ + +unsigned gpioVersion(void) +{ + DBG(DBG_USER, ""); + + return PIGPIO_VERSION; +} + + +/* ----------------------------------------------------------------------- */ + +/* +2 2 2 2 2 2 1 1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 +5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0 + +W W S M M M B B B B P P P P T T T T T T T T R R R R + +W warranty void if either bit is set + +S 0=old (bits 0-22 are revision number) 1=new (following fields apply) + +M 0=256 1=512 2=1024 + +B 0=Sony 1=Egoman 2=Embest 3=Unknown 4=Embest + +P 0=2835, 1=2836, 2=2837 + +T 0=A 1=B 2=A+ 3=B+ 4=Pi2B 5=Alpha 6=Compute Module 7=Unknown 8=Pi3B 9=Zero + +R PCB board revision + +*/ + +unsigned gpioHardwareRevision(void) +{ + static unsigned rev = 0; + + FILE * filp; + char buf[512]; + char term; + + DBG(DBG_USER, ""); + + if (rev) return rev; + + piCores = 0; + + filp = fopen ("/proc/cpuinfo", "r"); + + if (filp != NULL) + { + while (fgets(buf, sizeof(buf), filp) != NULL) + { + if (piCores == 0) + { + if (!strncasecmp("model name", buf, 10)) + { + if (strstr (buf, "ARMv6") != NULL) + { + piCores = 1; + pi_peri_phys = 0x20000000; + pi_dram_bus = 0x40000000; + pi_mem_flag = 0x0C; + } + else if (strstr (buf, "ARMv7") != NULL) + { + piCores = 4; + pi_peri_phys = 0x3F000000; + pi_dram_bus = 0xC0000000; + pi_mem_flag = 0x04; + } + else if (strstr (buf, "ARMv8") != NULL) + { + piCores = 4; + pi_peri_phys = 0x3F000000; + pi_dram_bus = 0xC0000000; + pi_mem_flag = 0x04; + } + } + } + + if (!strncasecmp("revision\t:", buf, 10)) + { + if (sscanf(buf+10, "%x%c", &rev, &term) == 2) + { + if (term != '\n') rev = 0; + else rev &= 0xFFFFFF; /* mask out warranty bit */ + } + } + } + + fclose(filp); + } + return rev; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgBufferSize(unsigned millis) +{ + DBG(DBG_USER, "millis=%d", millis); + + CHECK_NOT_INITED; + + if ((millis < PI_BUF_MILLIS_MIN) || (millis > PI_BUF_MILLIS_MAX)) + SOFT_ERROR(PI_BAD_BUF_MILLIS, "bad millis (%d)", millis); + + gpioCfg.bufferMilliseconds = millis; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgClock(unsigned micros, unsigned peripheral, unsigned source) +{ + DBG(DBG_USER, "micros=%d peripheral=%d", micros, peripheral); + + CHECK_NOT_INITED; + + if ((micros < 1) || (micros > 10)) + SOFT_ERROR(PI_BAD_CLK_MICROS, "bad micros (%d)", micros); + + if (!clkCfg[micros].valid) + SOFT_ERROR(PI_BAD_CLK_MICROS, "bad micros (%d)", micros); + + if (peripheral > PI_CLOCK_PCM) + SOFT_ERROR(PI_BAD_CLK_PERIPH, "bad peripheral (%d)", peripheral); + + gpioCfg.clockMicros = micros; + gpioCfg.clockPeriph = peripheral; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgDMAchannel(unsigned DMAchannel) +{ + DBG(DBG_USER, "channel=%d", DMAchannel); + + CHECK_NOT_INITED; + + if ((DMAchannel < PI_MIN_DMA_CHANNEL) || (DMAchannel > PI_MAX_DMA_CHANNEL)) + SOFT_ERROR(PI_BAD_CHANNEL, "bad channel (%d)", DMAchannel); + + gpioCfg.DMAprimaryChannel = DMAchannel; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgDMAchannels(unsigned primaryChannel, unsigned secondaryChannel) +{ + DBG(DBG_USER, "primary channel=%d, secondary channel=%d", + primaryChannel, secondaryChannel); + + CHECK_NOT_INITED; + + if (primaryChannel > PI_MAX_DMA_CHANNEL) + SOFT_ERROR(PI_BAD_PRIM_CHANNEL, "bad primary channel (%d)", + primaryChannel); + + if ((secondaryChannel > PI_MAX_DMA_CHANNEL) || + (secondaryChannel == primaryChannel)) + SOFT_ERROR(PI_BAD_SECO_CHANNEL, "bad secondary channel (%d)", + secondaryChannel); + + gpioCfg.DMAprimaryChannel = primaryChannel; + gpioCfg.DMAsecondaryChannel = secondaryChannel; + + return 0; +} + + +/*-------------------------------------------------------------------------*/ + +int gpioCfgPermissions(uint64_t updateMask) +{ + DBG(DBG_USER, "gpio update mask=%llX", updateMask); + + CHECK_NOT_INITED; + + gpioMask = updateMask; + + gpioMaskSet = 1; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgInterfaces(unsigned ifFlags) +{ + DBG(DBG_USER, "ifFlags=%X", ifFlags); + + CHECK_NOT_INITED; + + if (ifFlags > 15) + SOFT_ERROR(PI_BAD_IF_FLAGS, "bad ifFlags (%X)", ifFlags); + + gpioCfg.ifFlags = ifFlags; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioCfgSocketPort(unsigned port) +{ + DBG(DBG_USER, "port=%d", port); + + CHECK_NOT_INITED; + + if ((port < PI_MIN_SOCKET_PORT) || (port > PI_MAX_SOCKET_PORT)) + SOFT_ERROR(PI_BAD_SOCKET_PORT, "bad port (%d)", port); + + gpioCfg.socketPort = port; + + return 0; +} + + +/* ----------------------------------------------------------------------- */ + +int gpioCfgMemAlloc(unsigned memAllocMode) +{ + DBG(DBG_USER, "memAllocMode=%d", memAllocMode); + + CHECK_NOT_INITED; + + if (memAllocMode > PI_MEM_ALLOC_MAILBOX) + SOFT_ERROR( + PI_BAD_MALLOC_MODE, "bad mem alloc mode (%d)", memAllocMode); + + gpioCfg.memAllocMode = memAllocMode; + + return 0; +} + +/* ----------------------------------------------------------------------- */ + +int gpioCfgNetAddr(int numSockAddr, uint32_t *sockAddr) +{ + int i; + + DBG(DBG_USER, "numSockAddr=%d sockAddr=%08X", + numSockAddr, (unsigned)sockAddr); + + CHECK_NOT_INITED; + + if (numSockAddr <= 0) numSockNetAddr = 0; + else + { + if (numSockAddr >= MAX_CONNECT_ADDRESSES) + numSockAddr = MAX_CONNECT_ADDRESSES; + + for (i=0; i>4) & 0xF; + return 0; +} + +int gpioCfgInternals(unsigned cfgWhat, unsigned cfgVal) +{ + int retVal = PI_BAD_CFG_INTERNAL; + + DBG(DBG_USER, "cfgWhat=%u, cfgVal=%d", cfgWhat, cfgVal); + + switch(cfgWhat) + { + case 562484977: + + if (cfgVal) gpioCfg.internals |= PI_CFG_STATS; + else gpioCfg.internals &= (~PI_CFG_STATS); + + DBG(DBG_ALWAYS, "show stats is %u", cfgVal); + + retVal = 0; + + break; + + case 984762879: + + if ((cfgVal >= DBG_ALWAYS) && (cfgVal <= DBG_MAX_LEVEL)) + { + + gpioCfg.dbgLevel = cfgVal; + gpioCfg.internals = (gpioCfg.internals & (~0xF)) | cfgVal; + + DBG(DBG_ALWAYS, "Debug level is %u", cfgVal); + + retVal = 0; + } + + break; + } + + return retVal; +} + + +/* include any user customisations */ + +#include "custom.cext" + diff --git a/thirdparty/PIGPIO/pigpio.h b/thirdparty/PIGPIO/pigpio.h new file mode 100644 index 0000000000..8c79d2c4b8 --- /dev/null +++ b/thirdparty/PIGPIO/pigpio.h @@ -0,0 +1,6461 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +#ifndef PIGPIO_H +#define PIGPIO_H + +#include +#include + +#define PIGPIO_VERSION 68 + +/*TEXT + +pigpio is a C library for the Raspberry which allows control of the GPIO. + +*Features* + +o hardware timed PWM on any of GPIO 0-31 + +o hardware timed servo pulses on any of GPIO 0-31 + +o callbacks when any of GPIO 0-31 change state + +o callbacks at timed intervals + +o reading/writing all of the GPIO in a bank as one operation + +o individually setting GPIO modes, reading and writing + +o notifications when any of GPIO 0-31 change state + +o the construction of output waveforms with microsecond timing + +o rudimentary permission control over GPIO + +o a simple interface to start and stop new threads + +o I2C, SPI, and serial link wrappers + +o creating and running scripts + +*GPIO* + +ALL GPIO are identified by their Broadcom number. + +*Credits* + +The PWM and servo pulses are timed using the DMA and PWM peripherals. + +This use was inspired by Richard Hirst's servoblaster kernel module. + +See [[https://github.com/richardghirst/PiBits/tree/master/ServoBlaster]] + +*Usage* + +Include in your source files. + +Assuming your source is in prog.c use the following command to build and +run the executable. + +. . +gcc -Wall -pthread -o prog prog.c -lpigpio -lrt +sudo ./prog +. . + +For examples of usage see the C programs within the pigpio archive file. + +*Notes* + +All the functions which return an int return < 0 on error. + +[*gpioInitialise*] must be called before all other library functions +with the following exceptions: + +. . +[*gpioCfg**] +[*gpioVersion*] +[*gpioHardwareRevision*] +. . + +If the library is not initialised all but the [*gpioCfg**], +[*gpioVersion*], and [*gpioHardwareRevision*] functions will +return error PI_NOT_INITIALISED. + +If the library is initialised the [*gpioCfg**] functions will return +error PI_INITIALISED. + +TEXT*/ + +/*OVERVIEW + +ESSENTIAL + +gpioInitialise Initialise library +gpioTerminate Stop library + +BEGINNER + +gpioSetMode Set a GPIO mode +gpioGetMode Get a GPIO mode + +gpioSetPullUpDown Set/clear GPIO pull up/down resistor + +gpioRead Read a GPIO +gpioWrite Write a GPIO + +gpioPWM Start/stop PWM pulses on a GPIO +gpioGetPWMdutycycle Get dutycycle setting on a GPIO + +gpioServo Start/stop servo pulses on a GPIO +gpioGetServoPulsewidth Get pulsewidth setting on a GPIO + +gpioDelay Delay for a number of microseconds + +gpioSetAlertFunc Request a GPIO level change callback + +gpioSetTimerFunc Request a regular timed callback + +INTERMEDIATE + +gpioTrigger Send a trigger pulse to a GPIO. + +gpioSetWatchdog Set a watchdog on a GPIO. + +gpioSetPWMrange Configure PWM range for a GPIO +gpioGetPWMrange Get configured PWM range for a GPIO + +gpioSetPWMfrequency Configure PWM frequency for a GPIO +gpioGetPWMfrequency Get configured PWM frequency for a GPIO + +gpioRead_Bits_0_31 Read all GPIO in bank 1 +gpioRead_Bits_32_53 Read all GPIO in bank 2 + +gpioWrite_Bits_0_31_Clear Clear selected GPIO in bank 1 +gpioWrite_Bits_32_53_Clear Clear selected GPIO in bank 2 + +gpioWrite_Bits_0_31_Set Set selected GPIO in bank 1 +gpioWrite_Bits_32_53_Set Set selected GPIO in bank 2 + +gpioStartThread Start a new thread +gpioStopThread Stop a previously started thread + +ADVANCED + +gpioGetPWMrealRange Get underlying PWM range for a GPIO + +gpioSetAlertFuncEx Request a GPIO change callback, extended + +gpioSetISRFunc Request a GPIO interrupt callback +gpioSetISRFuncEx Request a GPIO interrupt callback, extended + +gpioSetSignalFunc Request a signal callback +gpioSetSignalFuncEx Request a signal callback, extended + +gpioSetGetSamplesFunc Requests a GPIO samples callback +gpioSetGetSamplesFuncEx Requests a GPIO samples callback, extended + +gpioSetTimerFuncEx Request a regular timed callback, extended + +gpioNotifyOpen Request a notification handle +gpioNotifyOpenWithSize Request a notification handle with sized pipe +gpioNotifyBegin Start notifications for selected GPIO +gpioNotifyPause Pause notifications +gpioNotifyClose Close a notification + +gpioSerialReadOpen Opens a GPIO for bit bang serial reads +gpioSerialReadInvert Configures normal/inverted for serial reads +gpioSerialRead Reads bit bang serial data from a GPIO +gpioSerialReadClose Closes a GPIO for bit bang serial reads + +gpioHardwareClock Start hardware clock on supported GPIO +gpioHardwarePWM Start hardware PWM on supported GPIO + +gpioGlitchFilter Set a glitch filter on a GPIO +gpioNoiseFilter Set a noise filter on a GPIO + +gpioGetPad Gets a pads drive strength +gpioSetPad Sets a pads drive strength + +shell Executes a shell command + +SCRIPTS + +gpioStoreScript Store a script +gpioRunScript Run a stored script +gpioUpdateScript Set a scripts parameters +gpioScriptStatus Get script status and parameters +gpioStopScript Stop a running script +gpioDeleteScript Delete a stored script + +WAVES + +gpioWaveClear Deletes all waveforms + +gpioWaveAddNew Starts a new waveform +gpioWaveAddGeneric Adds a series of pulses to the waveform +gpioWaveAddSerial Adds serial data to the waveform + +gpioWaveCreate Creates a waveform from added data +gpioWaveDelete Deletes a waveform + +gpioWaveTxSend Transmits a waveform + +gpioWaveChain Transmits a chain of waveforms + +gpioWaveTxAt Returns the current transmitting waveform + +gpioWaveTxBusy Checks to see if the waveform has ended +gpioWaveTxStop Aborts the current waveform + +gpioWaveGetMicros Length in microseconds of the current waveform +gpioWaveGetHighMicros Length of longest waveform so far +gpioWaveGetMaxMicros Absolute maximum allowed micros + +gpioWaveGetPulses Length in pulses of the current waveform +gpioWaveGetHighPulses Length of longest waveform so far +gpioWaveGetMaxPulses Absolute maximum allowed pulses + +gpioWaveGetCbs Length in control blocks of the current waveform +gpioWaveGetHighCbs Length of longest waveform so far +gpioWaveGetMaxCbs Absolute maximum allowed control blocks + +I2C + +i2cOpen Opens an I2C device +i2cClose Closes an I2C device + +i2cWriteQuick SMBus write quick +i2cWriteByte SMBus write byte +i2cReadByte SMBus read byte +i2cWriteByteData SMBus write byte data +i2cWriteWordData SMBus write word data +i2cReadByteData SMBus read byte data +i2cReadWordData SMBus read word data +i2cProcessCall SMBus process call +i2cWriteBlockData SMBus write block data +i2cReadBlockData SMBus read block data +i2cBlockProcessCall SMBus block process call + +i2cWriteI2CBlockData SMBus write I2C block data +i2cReadI2CBlockData SMBus read I2C block data + +i2cReadDevice Reads the raw I2C device +i2cWriteDevice Writes the raw I2C device + +i2cSwitchCombined Sets or clears the combined flag + +i2cSegments Performs multiple I2C transactions + +i2cZip Performs multiple I2C transactions + +bbI2COpen Opens GPIO for bit banging I2C +bbI2CClose Closes GPIO for bit banging I2C +bbI2CZip Performs multiple bit banged I2C transactions + +SPI + +spiOpen Opens a SPI device +spiClose Closes a SPI device + +spiRead Reads bytes from a SPI device +spiWrite Writes bytes to a SPI device +spiXfer Transfers bytes with a SPI device + +bbSPIOpen Opens GPIO for bit banging SPI +bbSPIClose Closes GPIO for bit banging SPI +bbSPIXfer Performs multiple bit banged SPI transactions + +I2C/SPI_SLAVE + +bscXfer I2C/SPI as slave transfer + +SERIAL + +serOpen Opens a serial device +serClose Closes a serial device + +serReadByte Reads a byte from a serial device +serWriteByte Writes a byte to a serial device +serRead Reads bytes from a serial device +serWrite Writes bytes to a serial device + +serDataAvailable Returns number of bytes ready to be read + +FILES + +fileOpen Opens a file +fileClose Closes a file +fileRead Reads bytes from a file +fileWrite Writes bytes to a file +fileSeek Seeks to a position within a file +fileList List files which match a pattern + +EVENTS + +eventMonitor Sets the events to monitor +eventSetFunc Request an event callback +eventSetFuncEx Request an event callback, extended +eventTrigger Trigger an event + +CONFIGURATION + +gpioCfgBufferSize Configure the GPIO sample buffer size +gpioCfgClock Configure the GPIO sample rate +gpioCfgDMAchannel Configure the DMA channel (DEPRECATED) +gpioCfgDMAchannels Configure the DMA channels +gpioCfgPermissions Configure the GPIO access permissions +gpioCfgInterfaces Configure user interfaces +gpioCfgSocketPort Configure socket port +gpioCfgMemAlloc Configure DMA memory allocation mode +gpioCfgNetAddr Configure allowed network addresses + +gpioCfgInternals Configure miscellaneous internals (DEPRECATED) +gpioCfgGetInternals Get internal configuration settings +gpioCfgSetInternals Set internal configuration settings + +CUSTOM + +gpioCustom1 User custom function 1 +gpioCustom2 User custom function 2 + +UTILITIES + +gpioTick Get current tick (microseconds) + +gpioHardwareRevision Get hardware revision +gpioVersion Get the pigpio version + +getBitInBytes Get the value of a bit +putBitInBytes Set the value of a bit + +gpioTime Get current time +gpioSleep Sleep for specified time + +time_sleep Sleeps for a float number of seconds +time_time Float number of seconds since the epoch + +EXPERT + +rawWaveAddSPI Not intended for general use +rawWaveAddGeneric Not intended for general use +rawWaveCB Not intended for general use +rawWaveCBAdr Not intended for general use +rawWaveGetOOL Not intended for general use +rawWaveSetOOL Not intended for general use +rawWaveGetOut Not intended for general use +rawWaveSetOut Not intended for general use +rawWaveGetIn Not intended for general use +rawWaveSetIn Not intended for general use +rawWaveInfo Not intended for general use +rawDumpWave Not intended for general use +rawDumpScript Not intended for general use + +OVERVIEW*/ + +#define PI_INPFIFO "/dev/pigpio" +#define PI_OUTFIFO "/dev/pigout" +#define PI_ERRFIFO "/dev/pigerr" + +#define PI_ENVPORT "PIGPIO_PORT" +#define PI_ENVADDR "PIGPIO_ADDR" + +#define PI_LOCKFILE "/var/run/pigpio.pid" + +#define PI_I2C_COMBINED "/sys/module/i2c_bcm2708/parameters/combined" + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct +{ + uint16_t func; + uint16_t size; +} gpioHeader_t; + +typedef struct +{ + size_t size; + void *ptr; + uint32_t data; +} gpioExtent_t; + +typedef struct +{ + uint32_t tick; + uint32_t level; +} gpioSample_t; + +typedef struct +{ + uint16_t seqno; + uint16_t flags; + uint32_t tick; + uint32_t level; +} gpioReport_t; + +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; + +#define WAVE_FLAG_READ 1 +#define WAVE_FLAG_TICK 2 + +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; + uint32_t flags; +} rawWave_t; + +/* +CBs are used in order from the lowest numbered CB up to +the maximum NUM_WAVE_CBS. + +OOLS are used from the bottom climbing up and from +the top climbing down. + +The GPIO on and off settings climb up from the bottom (botOOL/numBOOL). + +The level and tick read values are stored in descending locations +from the top (topOOL/numTOOL). +*/ + +typedef struct +{ + uint16_t botCB; /* first CB used by wave */ + uint16_t topCB; /* last CB used by wave */ + uint16_t botOOL; /* first bottom OOL used by wave */ + /* botOOL to botOOL + numBOOL - 1 are in use */ + uint16_t topOOL; /* last top OOL used by wave */ + /* topOOL - numTOOL to topOOL are in use.*/ + uint16_t deleted; + uint16_t numCB; + uint16_t numBOOL; + uint16_t numTOOL; +} rawWaveInfo_t; + +typedef struct +{ + int clk; /* GPIO for clock */ + int mosi; /* GPIO for MOSI */ + int miso; /* GPIO for MISO */ + int ss_pol; /* slave select off state */ + int ss_us; /* delay after slave select */ + int clk_pol; /* clock off state */ + int clk_pha; /* clock phase */ + int clk_us; /* clock micros */ +} rawSPI_t; + +typedef struct { /* linux/arch/arm/mach-bcm2708/include/mach/dma.h */ + uint32_t info; + uint32_t src; + uint32_t dst; + uint32_t length; + uint32_t stride; + uint32_t next; + uint32_t pad[2]; +} rawCbs_t; + +typedef struct +{ + uint16_t addr; /* slave address */ + uint16_t flags; + uint16_t len; /* msg length */ + uint8_t *buf; /* pointer to msg data */ +} pi_i2c_msg_t; + +/* BSC FIFO size */ + +#define BSC_FIFO_SIZE 512 + +typedef struct +{ + uint32_t control; /* Write */ + int rxCnt; /* Read only */ + char rxBuf[BSC_FIFO_SIZE]; /* Read only */ + int txCnt; /* Write */ + char txBuf[BSC_FIFO_SIZE]; /* Write */ +} bsc_xfer_t; + + +typedef void (*gpioAlertFunc_t) (int gpio, + int level, + uint32_t tick); + +typedef void (*gpioAlertFuncEx_t) (int gpio, + int level, + uint32_t tick, + void *userdata); + +typedef void (*eventFunc_t) (int event, + uint32_t tick); + +typedef void (*eventFuncEx_t) (int event, + uint32_t tick, + void *userdata); + +typedef void (*gpioISRFunc_t) (int gpio, + int level, + uint32_t tick); + +typedef void (*gpioISRFuncEx_t) (int gpio, + int level, + uint32_t tick, + void *userdata); + +typedef void (*gpioTimerFunc_t) (void); + +typedef void (*gpioTimerFuncEx_t) (void *userdata); + +typedef void (*gpioSignalFunc_t) (int signum); + +typedef void (*gpioSignalFuncEx_t) (int signum, + void *userdata); + +typedef void (*gpioGetSamplesFunc_t) (const gpioSample_t *samples, + int numSamples); + +typedef void (*gpioGetSamplesFuncEx_t) (const gpioSample_t *samples, + int numSamples, + void *userdata); + +typedef void *(gpioThreadFunc_t) (void *); + + +/* gpio: 0-53 */ + +#define PI_MIN_GPIO 0 +#define PI_MAX_GPIO 53 + +/* user_gpio: 0-31 */ + +#define PI_MAX_USER_GPIO 31 + +/* level: 0-1 */ + +#define PI_OFF 0 +#define PI_ON 1 + +#define PI_CLEAR 0 +#define PI_SET 1 + +#define PI_LOW 0 +#define PI_HIGH 1 + +/* level: only reported for GPIO time-out, see gpioSetWatchdog */ + +#define PI_TIMEOUT 2 + +/* mode: 0-7 */ + +#define PI_INPUT 0 +#define PI_OUTPUT 1 +#define PI_ALT0 4 +#define PI_ALT1 5 +#define PI_ALT2 6 +#define PI_ALT3 7 +#define PI_ALT4 3 +#define PI_ALT5 2 + +/* pud: 0-2 */ + +#define PI_PUD_OFF 0 +#define PI_PUD_DOWN 1 +#define PI_PUD_UP 2 + +/* dutycycle: 0-range */ + +#define PI_DEFAULT_DUTYCYCLE_RANGE 255 + +/* range: 25-40000 */ + +#define PI_MIN_DUTYCYCLE_RANGE 25 +#define PI_MAX_DUTYCYCLE_RANGE 40000 + +/* pulsewidth: 0, 500-2500 */ + +#define PI_SERVO_OFF 0 +#define PI_MIN_SERVO_PULSEWIDTH 500 +#define PI_MAX_SERVO_PULSEWIDTH 2500 + +/* hardware PWM */ + +#define PI_HW_PWM_MIN_FREQ 1 +#define PI_HW_PWM_MAX_FREQ 125000000 +#define PI_HW_PWM_RANGE 1000000 + +/* hardware clock */ + +#define PI_HW_CLK_MIN_FREQ 4689 +#define PI_HW_CLK_MAX_FREQ 250000000 + +#define PI_NOTIFY_SLOTS 32 + +#define PI_NTFY_FLAGS_EVENT (1 <<7) +#define PI_NTFY_FLAGS_ALIVE (1 <<6) +#define PI_NTFY_FLAGS_WDOG (1 <<5) +#define PI_NTFY_FLAGS_BIT(x) (((x)<<0)&31) + +#define PI_WAVE_BLOCKS 4 +#define PI_WAVE_MAX_PULSES (PI_WAVE_BLOCKS * 3000) +#define PI_WAVE_MAX_CHARS (PI_WAVE_BLOCKS * 300) + +#define PI_BB_I2C_MIN_BAUD 50 +#define PI_BB_I2C_MAX_BAUD 500000 + +#define PI_BB_SPI_MIN_BAUD 50 +#define PI_BB_SPI_MAX_BAUD 250000 + +#define PI_BB_SER_MIN_BAUD 50 +#define PI_BB_SER_MAX_BAUD 250000 + +#define PI_BB_SER_NORMAL 0 +#define PI_BB_SER_INVERT 1 + +#define PI_WAVE_MIN_BAUD 50 +#define PI_WAVE_MAX_BAUD 1000000 + +#define PI_SPI_MIN_BAUD 32000 +#define PI_SPI_MAX_BAUD 125000000 + +#define PI_MIN_WAVE_DATABITS 1 +#define PI_MAX_WAVE_DATABITS 32 + +#define PI_MIN_WAVE_HALFSTOPBITS 2 +#define PI_MAX_WAVE_HALFSTOPBITS 8 + +#define PI_WAVE_MAX_MICROS (30 * 60 * 1000000) /* half an hour */ + +#define PI_MAX_WAVES 250 + +#define PI_MAX_WAVE_CYCLES 65535 +#define PI_MAX_WAVE_DELAY 65535 + +#define PI_WAVE_COUNT_PAGES 10 + +/* wave tx mode */ + +#define PI_WAVE_MODE_ONE_SHOT 0 +#define PI_WAVE_MODE_REPEAT 1 +#define PI_WAVE_MODE_ONE_SHOT_SYNC 2 +#define PI_WAVE_MODE_REPEAT_SYNC 3 + +/* special wave at return values */ + +#define PI_WAVE_NOT_FOUND 9998 /* Transmitted wave not found. */ +#define PI_NO_TX_WAVE 9999 /* No wave being transmitted. */ + +/* Files, I2C, SPI, SER */ + +#define PI_FILE_SLOTS 16 +#define PI_I2C_SLOTS 64 +#define PI_SPI_SLOTS 32 +#define PI_SER_SLOTS 16 + +#define PI_MAX_I2C_ADDR 0x7F + +#define PI_NUM_AUX_SPI_CHANNEL 3 +#define PI_NUM_STD_SPI_CHANNEL 2 + +#define PI_MAX_I2C_DEVICE_COUNT (1<<16) +#define PI_MAX_SPI_DEVICE_COUNT (1<<16) + +/* max pi_i2c_msg_t per transaction */ + +#define PI_I2C_RDRW_IOCTL_MAX_MSGS 42 + +/* flags for i2cTransaction, pi_i2c_msg_t */ + +#define PI_I2C_M_WR 0x0000 /* write data */ +#define PI_I2C_M_RD 0x0001 /* read data */ +#define PI_I2C_M_TEN 0x0010 /* ten bit chip address */ +#define PI_I2C_M_RECV_LEN 0x0400 /* length will be first received byte */ +#define PI_I2C_M_NO_RD_ACK 0x0800 /* if I2C_FUNC_PROTOCOL_MANGLING */ +#define PI_I2C_M_IGNORE_NAK 0x1000 /* if I2C_FUNC_PROTOCOL_MANGLING */ +#define PI_I2C_M_REV_DIR_ADDR 0x2000 /* if I2C_FUNC_PROTOCOL_MANGLING */ +#define PI_I2C_M_NOSTART 0x4000 /* if I2C_FUNC_PROTOCOL_MANGLING */ + +/* bbI2CZip and i2cZip commands */ + +#define PI_I2C_END 0 +#define PI_I2C_ESC 1 +#define PI_I2C_START 2 +#define PI_I2C_COMBINED_ON 2 +#define PI_I2C_STOP 3 +#define PI_I2C_COMBINED_OFF 3 +#define PI_I2C_ADDR 4 +#define PI_I2C_FLAGS 5 +#define PI_I2C_READ 6 +#define PI_I2C_WRITE 7 + +/* SPI */ + +#define PI_SPI_FLAGS_BITLEN(x) ((x&63)<<16) +#define PI_SPI_FLAGS_RX_LSB(x) ((x&1)<<15) +#define PI_SPI_FLAGS_TX_LSB(x) ((x&1)<<14) +#define PI_SPI_FLAGS_3WREN(x) ((x&15)<<10) +#define PI_SPI_FLAGS_3WIRE(x) ((x&1)<<9) +#define PI_SPI_FLAGS_AUX_SPI(x) ((x&1)<<8) +#define PI_SPI_FLAGS_RESVD(x) ((x&7)<<5) +#define PI_SPI_FLAGS_CSPOLS(x) ((x&7)<<2) +#define PI_SPI_FLAGS_MODE(x) ((x&3)) + +/* BSC registers */ + +#define BSC_DR 0 +#define BSC_RSR 1 +#define BSC_SLV 2 +#define BSC_CR 3 +#define BSC_FR 4 +#define BSC_IFLS 5 +#define BSC_IMSC 6 +#define BSC_RIS 7 +#define BSC_MIS 8 +#define BSC_ICR 9 +#define BSC_DMACR 10 +#define BSC_TDR 11 +#define BSC_GPUSTAT 12 +#define BSC_HCTRL 13 +#define BSC_DEBUG_I2C 14 +#define BSC_DEBUG_SPI 15 + +#define BSC_CR_TESTFIFO 2048 +#define BSC_CR_RXE 512 +#define BSC_CR_TXE 256 +#define BSC_CR_BRK 128 +#define BSC_CR_CPOL 16 +#define BSC_CR_CPHA 8 +#define BSC_CR_I2C 4 +#define BSC_CR_SPI 2 +#define BSC_CR_EN 1 + +#define BSC_FR_RXBUSY 32 +#define BSC_FR_TXFE 16 +#define BSC_FR_RXFF 8 +#define BSC_FR_TXFF 4 +#define BSC_FR_RXFE 2 +#define BSC_FR_TXBUSY 1 + +/* BSC GPIO */ + +#define BSC_SDA_MOSI 18 +#define BSC_SCL_SCLK 19 +#define BSC_MISO 20 +#define BSC_CE_N 21 + +/* Longest busy delay */ + +#define PI_MAX_BUSY_DELAY 100 + +/* timeout: 0-60000 */ + +#define PI_MIN_WDOG_TIMEOUT 0 +#define PI_MAX_WDOG_TIMEOUT 60000 + +/* timer: 0-9 */ + +#define PI_MIN_TIMER 0 +#define PI_MAX_TIMER 9 + +/* millis: 10-60000 */ + +#define PI_MIN_MS 10 +#define PI_MAX_MS 60000 + +#define PI_MAX_SCRIPTS 32 + +#define PI_MAX_SCRIPT_TAGS 50 +#define PI_MAX_SCRIPT_VARS 150 +#define PI_MAX_SCRIPT_PARAMS 10 + +/* script status */ + +#define PI_SCRIPT_INITING 0 +#define PI_SCRIPT_HALTED 1 +#define PI_SCRIPT_RUNNING 2 +#define PI_SCRIPT_WAITING 3 +#define PI_SCRIPT_FAILED 4 + +/* signum: 0-63 */ + +#define PI_MIN_SIGNUM 0 +#define PI_MAX_SIGNUM 63 + +/* timetype: 0-1 */ + +#define PI_TIME_RELATIVE 0 +#define PI_TIME_ABSOLUTE 1 + +#define PI_MAX_MICS_DELAY 1000000 /* 1 second */ +#define PI_MAX_MILS_DELAY 60000 /* 60 seconds */ + +/* cfgMillis */ + +#define PI_BUF_MILLIS_MIN 100 +#define PI_BUF_MILLIS_MAX 10000 + +/* cfgMicros: 1, 2, 4, 5, 8, or 10 */ + +/* cfgPeripheral: 0-1 */ + +#define PI_CLOCK_PWM 0 +#define PI_CLOCK_PCM 1 + +/* DMA channel: 0-14 */ + +#define PI_MIN_DMA_CHANNEL 0 +#define PI_MAX_DMA_CHANNEL 14 + +/* port */ + +#define PI_MIN_SOCKET_PORT 1024 +#define PI_MAX_SOCKET_PORT 32000 + + +/* ifFlags: */ + +#define PI_DISABLE_FIFO_IF 1 +#define PI_DISABLE_SOCK_IF 2 +#define PI_LOCALHOST_SOCK_IF 4 +#define PI_DISABLE_ALERT 8 + +/* memAllocMode */ + +#define PI_MEM_ALLOC_AUTO 0 +#define PI_MEM_ALLOC_PAGEMAP 1 +#define PI_MEM_ALLOC_MAILBOX 2 + +/* filters */ + +#define PI_MAX_STEADY 300000 +#define PI_MAX_ACTIVE 1000000 + +/* gpioCfgInternals */ + +#define PI_CFG_DBG_LEVEL 0 /* bits 0-3 */ +#define PI_CFG_ALERT_FREQ 4 /* bits 4-7 */ +#define PI_CFG_RT_PRIORITY (1<<8) +#define PI_CFG_STATS (1<<9) +#define PI_CFG_NOSIGHANDLER (1<<10) + +#define PI_CFG_ILLEGAL_VAL (1<<11) + + +/* gpioISR */ + +#define RISING_EDGE 0 +#define FALLING_EDGE 1 +#define EITHER_EDGE 2 + + +/* pads */ + +#define PI_MAX_PAD 2 + +#define PI_MIN_PAD_STRENGTH 1 +#define PI_MAX_PAD_STRENGTH 16 + +/* files */ + +#define PI_FILE_NONE 0 +#define PI_FILE_MIN 1 +#define PI_FILE_READ 1 +#define PI_FILE_WRITE 2 +#define PI_FILE_RW 3 +#define PI_FILE_APPEND 4 +#define PI_FILE_CREATE 8 +#define PI_FILE_TRUNC 16 +#define PI_FILE_MAX 31 + +#define PI_FROM_START 0 +#define PI_FROM_CURRENT 1 +#define PI_FROM_END 2 + +/* Allowed socket connect addresses */ + +#define MAX_CONNECT_ADDRESSES 256 + +/* events */ + +#define PI_MAX_EVENT 31 + +/* Event auto generated on BSC slave activity */ + +#define PI_EVENT_BSC 31 + +/*F*/ +int gpioInitialise(void); +/*D +Initialises the library. + +Returns the pigpio version number if OK, otherwise PI_INIT_FAILED. + +gpioInitialise must be called before using the other library functions +with the following exceptions: + +. . +[*gpioCfg**] +[*gpioVersion*] +[*gpioHardwareRevision*] +. . + +... +if (gpioInitialise() < 0) +{ + // pigpio initialisation failed. +} +else +{ + // pigpio initialised okay. +} +... +D*/ + + +/*F*/ +void gpioTerminate(void); +/*D +Terminates the library. + +Returns nothing. + +Call before program exit. + +This function resets the used DMA channels, releases memory, and +terminates any running threads. + +... +gpioTerminate(); +... +D*/ + + +/*F*/ +int gpioSetMode(unsigned gpio, unsigned mode); +/*D +Sets the GPIO mode, typically input or output. + +. . +gpio: 0-53 +mode: 0-7 +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE. + +Arduino style: pinMode. + +... +gpioSetMode(17, PI_INPUT); // Set GPIO17 as input. + +gpioSetMode(18, PI_OUTPUT); // Set GPIO18 as output. + +gpioSetMode(22,PI_ALT0); // Set GPIO22 to alternative mode 0. +... + +See [[http://www.raspberrypi.org/documentation/hardware/raspberrypi/bcm2835/BCM2835-ARM-Peripherals.pdf]] page 102 for an overview of the modes. +D*/ + + +/*F*/ +int gpioGetMode(unsigned gpio); +/*D +Gets the GPIO mode. + +. . +gpio: 0-53 +. . + +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. + +... +if (gpioGetMode(17) != PI_ALT0) +{ + gpioSetMode(17, PI_ALT0); // set GPIO17 to ALT0 +} +... +D*/ + + +/*F*/ +int gpioSetPullUpDown(unsigned gpio, unsigned pud); +/*D +Sets or clears resistor pull ups or downs on the GPIO. + +. . +gpio: 0-53 + pud: 0-2 +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD. + +... +gpioSetPullUpDown(17, PI_PUD_UP); // Sets a pull-up. + +gpioSetPullUpDown(18, PI_PUD_DOWN); // Sets a pull-down. + +gpioSetPullUpDown(23, PI_PUD_OFF); // Clear any pull-ups/downs. +... +D*/ + + +/*F*/ +int gpioRead (unsigned gpio); +/*D +Reads the GPIO level, on or off. + +. . +gpio: 0-53 +. . + +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. + +Arduino style: digitalRead. + +... +printf("GPIO24 is level %d", gpioRead(24)); +... +D*/ + + +/*F*/ +int gpioWrite(unsigned gpio, unsigned level); +/*D +Sets the GPIO level, on or off. + +. . + gpio: 0-53 +level: 0-1 +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL. + +If PWM or servo pulses are active on the GPIO they are switched off. + +Arduino style: digitalWrite + +... +gpioWrite(24, 1); // Set GPIO24 high. +... +D*/ + + +/*F*/ +int gpioPWM(unsigned user_gpio, unsigned dutycycle); +/*D +Starts PWM on the GPIO, dutycycle between 0 (off) and range (fully on). +Range defaults to 255. + +. . +user_gpio: 0-31 +dutycycle: 0-range +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE. + +Arduino style: analogWrite + +This and the servo functionality use the DMA and PWM or PCM peripherals +to control and schedule the pulse lengths and dutycycles. + +The [*gpioSetPWMrange*] function may be used to change the default +range of 255. + +... +gpioPWM(17, 255); // Sets GPIO17 full on. + +gpioPWM(18, 128); // Sets GPIO18 half on. + +gpioPWM(23, 0); // Sets GPIO23 full off. +... +D*/ + + +/*F*/ +int gpioGetPWMdutycycle(unsigned user_gpio); +/*D +Returns the PWM dutycycle setting for the GPIO. + +. . +user_gpio: 0-31 +. . + +Returns between 0 (off) and range (fully on) if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see [*gpioGetPWMrange*]). + +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). + +Normal PWM range defaults to 255. +D*/ + + +/*F*/ +int gpioSetPWMrange(unsigned user_gpio, unsigned range); +/*D +Selects the dutycycle range to be used for the GPIO. Subsequent calls +to gpioPWM will use a dutycycle between 0 (off) and range (fully on). + +. . +user_gpio: 0-31 + range: 25-40000 +. . + +Returns the real range for the given GPIO's frequency if OK, +otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE. + +If PWM is currently active on the GPIO its dutycycle will be scaled +to reflect the new range. + +The real range, the number of steps between fully off and fully +on for each frequency, is given in the following table. + +. . + 25, 50, 100, 125, 200, 250, 400, 500, 625, + 800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000 +. . + +The real value set by [*gpioPWM*] is (dutycycle * real range) / range. + +... +gpioSetPWMrange(24, 2000); // Now 2000 is fully on + // 1000 is half on + // 500 is quarter on, etc. +... +D*/ + + +/*F*/ +int gpioGetPWMrange(unsigned user_gpio); +/*D +Returns the dutycycle range used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +. . +user_gpio: 0-31 +. . + +If a hardware clock or hardware PWM is active on the GPIO +the reported range will be 1000000 (1M). + +... +r = gpioGetPWMrange(23); +... +D*/ + + +/*F*/ +int gpioGetPWMrealRange(unsigned user_gpio); +/*D +Returns the real range used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +. . +user_gpio: 0-31 +. . + +If a hardware clock is active on the GPIO the reported real +range will be 1000000 (1M). + +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +... +rr = gpioGetPWMrealRange(17); +... +D*/ + + +/*F*/ +int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency); +/*D +Sets the frequency in hertz to be used for the GPIO. + +. . +user_gpio: 0-31 +frequency: >=0 +. . + +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO. + +If PWM is currently active on the GPIO it will be +switched off and then back on at the new frequency. + +Each GPIO can be independently set to one of 18 different PWM +frequencies. + +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). + +The frequencies for each sample rate are: + +. . + Hertz + + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 + 1250 1000 800 500 400 250 200 100 50 + + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 + 625 500 400 250 200 125 100 50 25 + + 4: 10000 5000 2500 2000 1250 1000 625 500 400 + 313 250 200 125 100 63 50 25 13 +sample + rate + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 + 250 200 160 100 80 50 40 20 10 + + 8: 5000 2500 1250 1000 625 500 313 250 200 + 156 125 100 63 50 31 25 13 6 + + 10: 4000 2000 1000 800 500 400 250 200 160 + 125 100 80 50 40 25 20 10 5 +. . + +... +gpioSetPWMfrequency(23, 0); // Set GPIO23 to lowest frequency. + +gpioSetPWMfrequency(24, 500); // Set GPIO24 to 500Hz. + +gpioSetPWMfrequency(25, 100000); // Set GPIO25 to highest frequency. +... +D*/ + + +/*F*/ +int gpioGetPWMfrequency(unsigned user_gpio); +/*D +Returns the frequency (in hertz) used for the GPIO if OK, otherwise +PI_BAD_USER_GPIO. + +. . +user_gpio: 0-31 +. . + +For normal PWM the frequency will be that defined for the GPIO by +[*gpioSetPWMfrequency*]. + +If a hardware clock is active on the GPIO the reported frequency +will be that set by [*gpioHardwareClock*]. + +If hardware PWM is active on the GPIO the reported frequency +will be that set by [*gpioHardwarePWM*]. + +... +f = gpioGetPWMfrequency(23); // Get frequency used for GPIO23. +... +D*/ + + +/*F*/ +int gpioServo(unsigned user_gpio, unsigned pulsewidth); +/*D +Starts servo pulses on the GPIO, 0 (off), 500 (most anti-clockwise) to +2500 (most clockwise). + +. . + user_gpio: 0-31 +pulsewidth: 0, 500-2500 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH. + +The range supported by servos varies and should probably be determined +by experiment. A value of 1500 should always be safe and represents +the mid-point of rotation. You can DAMAGE a servo if you command it +to move beyond its limits. + +The following causes an on pulse of 1500 microseconds duration to be +transmitted on GPIO 17 at a rate of 50 times per second. This will +command a servo connected to GPIO 17 to rotate to its mid-point. + +... +gpioServo(17, 1000); // Move servo to safe position anti-clockwise. + +gpioServo(23, 1500); // Move servo to centre position. + +gpioServo(25, 2000); // Move servo to safe position clockwise. +... + +OTHER UPDATE RATES: + +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +. . +PWM Hz 50 100 200 400 500 +1E6/Hz 20000 10000 5000 2500 2000 +. . + +Firstly set the desired PWM frequency using [*gpioSetPWMfrequency*]. + +Then set the PWM range using [*gpioSetPWMrange*] to 1E6/frequency. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +E.g. If you want to update a servo connected to GPIO25 at 400Hz + +. . +gpioSetPWMfrequency(25, 400); + +gpioSetPWMrange(25, 2500); +. . + +Thereafter use the PWM command to move the servo, +e.g. gpioPWM(25, 1500) will set a 1500 us pulse. +D*/ + + +/*F*/ +int gpioGetServoPulsewidth(unsigned user_gpio); +/*D +Returns the servo pulsewidth setting for the GPIO. + +. . +user_gpio: 0-31 +. . + +Returns 0 (off), 500 (most anti-clockwise) to 2500 (most clockwise) +if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. +D*/ + + +/*F*/ +int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f); +/*D +Registers a function to be called (a callback) when the specified +GPIO changes state. + +. . +user_gpio: 0-31 + f: the callback function +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. + +One callback may be registered per GPIO. + +The callback is passed the GPIO, the new level, and the tick. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +level 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes +. . + +The alert may be cancelled by passing NULL as the function. + +The GPIO are sampled at a rate set when the library is started. + +If a value isn't specifically set the default of 5 us is used. + +The number of samples per second is given in the following table. + +. . + samples + per sec + + 1 1,000,000 + 2 500,000 +sample 4 250,000 +rate 5 200,000 +(us) 8 125,000 + 10 100,000 +. . + +Level changes shorter than the sample rate may be missed. + +The thread which calls the alert functions is triggered nominally +1000 times per second. The active alert functions will be called +once per level change since the last time the thread was activated. +i.e. The active alert functions will get all level changes but there +will be a latency. + +The tick value is the time stamp of the sample in microseconds, see +[*gpioTick*] for more details. + +... +void aFunction(int gpio, int level, uint32_t tick) +{ + printf("GPIO %d became %d at %d", gpio, level, tick); +} + +// call aFunction whenever GPIO 4 changes state + +gpioSetAlertFunc(4, aFunction); +... +D*/ + + +/*F*/ +int gpioSetAlertFuncEx( + unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata); +/*D +Registers a function to be called (a callback) when the specified +GPIO changes state. + +. . +user_gpio: 0-31 + f: the callback function + userdata: pointer to arbitrary user data +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. + +One callback may be registered per GPIO. + +The callback is passed the GPIO, the new level, the tick, and +the userdata pointer. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +level 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes + +userdata pointer Pointer to an arbitrary object +. . + +See [*gpioSetAlertFunc*] for further details. + +Only one of [*gpioSetAlertFunc*] or [*gpioSetAlertFuncEx*] can be +registered per GPIO. +D*/ + + +/*F*/ +int gpioSetISRFunc( + unsigned gpio, unsigned edge, int timeout, gpioISRFunc_t f); +/*D +Registers a function to be called (a callback) whenever the specified +GPIO interrupt occurs. + +. . + gpio: 0-53 + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE +timeout: interrupt timeout in milliseconds (<=0 to cancel) + f: the callback function +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE, +or PI_BAD_ISR_INIT. + +One function may be registered per GPIO. + +The function is passed the GPIO, the current level, and the +current tick. The level will be PI_TIMEOUT if the optional +interrupt timeout expires. + +. . +Parameter Value Meaning + +GPIO 0-53 The GPIO which has changed state + +level 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (interrupt timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes +. . + +The underlying Linux sysfs GPIO interface is used to provide +the interrupt services. + +The first time the function is called, with a non-NULL f, the +GPIO is exported, set to be an input, and set to interrupt +on the given edge and timeout. + +Subsequent calls, with a non-NULL f, can vary one or more of the +edge, timeout, or function. + +The ISR may be cancelled by passing a NULL f, in which case the +GPIO is unexported. + +The tick is that read at the time the process was informed of +the interrupt. This will be a variable number of microseconds +after the interrupt occurred. Typically the latency will be of +the order of 50 microseconds. The latency is not guaranteed +and will vary with system load. + +The level is that read at the time the process was informed of +the interrupt, or PI_TIMEOUT if the optional interrupt timeout +expired. It may not be the same as the expected edge as +interrupts happening in rapid succession may be missed by the +kernel (i.e. this mechanism can not be used to capture several +interrupts only a few microseconds apart). +D*/ + + +/*F*/ +int gpioSetISRFuncEx( + unsigned gpio, + unsigned edge, + int timeout, + gpioISRFuncEx_t f, + void *userdata); +/*D +Registers a function to be called (a callback) whenever the specified +GPIO interrupt occurs. + +. . + gpio: 0-53 + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE + timeout: interrupt timeout in milliseconds (<=0 to cancel) + f: the callback function +userdata: pointer to arbitrary user data +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_EDGE, +or PI_BAD_ISR_INIT. + +The function is passed the GPIO, the current level, the +current tick, and the userdata pointer. + +. . +Parameter Value Meaning + +GPIO 0-53 The GPIO which has changed state + +level 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (interrupt timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes + +userdata pointer Pointer to an arbitrary object +. . + +Only one of [*gpioSetISRFunc*] or [*gpioSetISRFuncEx*] can be +registered per GPIO. + +See [*gpioSetISRFunc*] for further details. +D*/ + + +/*F*/ +int gpioNotifyOpen(void); +/*D +This function requests a free notification handle. + +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +A notification is a method for being notified of GPIO state changes +via a pipe or socket. + +Pipe notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). E.g. if the +function returns 15 then the notifications must be read +from /dev/pigpio15. + +Socket notifications are returned to the socket which requested the +handle. + +... +h = gpioNotifyOpen(); + +if (h >= 0) +{ + sprintf(str, "/dev/pigpio%d", h); + + fd = open(str, O_RDONLY); + + if (fd >= 0) + { + // Okay. + } + else + { + // Error. + } +} +else +{ + // Error. +} +... +D*/ + + +/*F*/ +int gpioNotifyOpenWithSize(int bufSize); +/*D +This function requests a free notification handle. + +It differs from [*gpioNotifyOpen*] in that the pipe size may be +specified, whereas [*gpioNotifyOpen*] uses the default pipe size. + +See [*gpioNotifyOpen*] for further details. +D*/ + + +/*F*/ +int gpioNotifyBegin(unsigned handle, uint32_t bits); +/*D +This function starts notifications on a previously opened handle. + +. . +handle: >=0, as returned by [*gpioNotifyOpen*] + bits: a bit mask indicating the GPIO of interest +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +The notification sends state changes for each GPIO whose corresponding +bit in bits is set. + +Each notification occupies 12 bytes in the fifo and has the +following structure. + +. . +typedef struct +{ + uint16_t seqno; + uint16_t flags; + uint32_t tick; + uint32_t level; +} gpioReport_t; +. . + +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +flags: three flags are defined, PI_NTFY_FLAGS_WDOG, +PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT. + +If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags +indicate an event which has been triggered. + +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +level: indicates the level of each GPIO. If bit 1<=0, as returned by [*gpioNotifyOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +Notifications for the handle are suspended until [*gpioNotifyBegin*] +is called again. + +... +gpioNotifyPause(h); +... +D*/ + + +/*F*/ +int gpioNotifyClose(unsigned handle); +/*D +This function stops notifications on a previously opened handle +and releases the handle for reuse. + +. . +handle: >=0, as returned by [*gpioNotifyOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +... +gpioNotifyClose(h); +... +D*/ + + +/*F*/ +int gpioWaveClear(void); +/*D +This function clears all waveforms and any data added by calls to the +[*gpioWaveAdd**] functions. + +Returns 0 if OK. + +... +gpioWaveClear(); +... +D*/ + + +/*F*/ +int gpioWaveAddNew(void); +/*D +This function starts a new empty waveform. + +You wouldn't normally need to call this function as it is automatically +called after a waveform is created with the [*gpioWaveCreate*] function. + +Returns 0 if OK. + +... +gpioWaveAddNew(); +... +D*/ + + +/*F*/ +int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses); +/*D +This function adds a number of pulses to the current waveform. + +. . +numPulses: the number of pulses + pulses: an array of pulses +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +The pulses are interleaved in time order within the existing waveform +(if any). + +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. + +... +// Construct and send a 30 microsecond square wave. + +gpioSetMode(gpio, PI_OUTPUT); + +pulse[0].gpioOn = (1<= 0) +{ + gpioWaveTxSend(wave_id, PI_WAVE_MODE_REPEAT); + + // Transmit for 30 seconds. + + sleep(30); + + gpioWaveTxStop(); +} +else +{ + // Wave create failed. +} +... +D*/ + + +/*F*/ +int gpioWaveAddSerial + (unsigned user_gpio, + unsigned baud, + unsigned data_bits, + unsigned stop_bits, + unsigned offset, + unsigned numBytes, + char *str); +/*D +This function adds a waveform representing serial data to the +existing waveform (if any). The serial data starts offset +microseconds from the start of the waveform. + +. . +user_gpio: 0-31 + baud: 50-1000000 +data_bits: 1-32 +stop_bits: 2-8 + offset: >=0 + numBytes: >=1 + str: an array of chars (which may contain nulls) +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOPBITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +NOTES: + +The serial data is formatted as one start bit, data_bits data bits, and +stop_bits/2 stop bits. + +It is legal to add serial data streams with different baud rates to +the same waveform. + +numBytes is the number of bytes of data in str. + +The bytes required for each character depend upon data_bits. + +For data_bits 1-8 there will be one byte per character. +For data_bits 9-16 there will be two bytes per character. +For data_bits 17-32 there will be four bytes per character. + +... +#define MSG_LEN 8 + +int i; +char *str; +char data[MSG_LEN]; + +str = "Hello world!"; + +gpioWaveAddSerial(4, 9600, 8, 2, 0, strlen(str), str); + +for (i=0; i=0, as returned by [*gpioWaveCreate*] +. . + +Wave ids are allocated in order, 0, 1, 2, etc. + +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. +D*/ + + +/*F*/ +int gpioWaveTxSend(unsigned wave_id, unsigned wave_mode); +/*D +This function transmits the waveform with id wave_id. The mode +determines whether the waveform is sent once or cycles endlessly. +The SYNC variants wait for the current waveform to reach the +end of a cycle or finish before starting the new waveform. + +WARNING: bad things may happen if you delete the previous +waveform before it has been synced to the new waveform. + +NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled. + +. . + wave_id: >=0, as returned by [*gpioWaveCreate*] +wave_mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT, + PI_WAVE_MODE_ONE_SHOT_SYNC, PI_WAVE_MODE_REPEAT_SYNC +. . + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + + +/*F*/ +int gpioWaveChain(char *buf, unsigned bufSize); +/*D +This function transmits a chain of waveforms. + +NOTE: Any hardware PWM started by [*gpioHardwarePWM*] will be cancelled. + +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of [*wave_id*]s and optional command +codes and related data. + +. . + buf: pointer to the wave_ids and optional command codes +bufSize: the number of bytes in buf +. . + +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +Delays between waves may be added with the delay command. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +Loop Start @ 255 0 @ Identify start of a wave block +Loop Repeat @ 255 1 x y @ loop x + y*256 times +Delay @ 255 2 x y @ delay x + y*256 microseconds +Loop Forever @ 255 3 @ loop forever + +If present Loop Forever must be the last entry in the chain. + +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +... +#include +#include + +#define WAVES 5 +#define GPIO 4 + +int main(int argc, char *argv[]) +{ + int i, wid[WAVES]; + + if (gpioInitialise()<0) return -1; + + gpioSetMode(GPIO, PI_OUTPUT); + + printf("start piscope, press return"); getchar(); + + for (i=0; i=0 +. . + +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +The bytes returned for each character depend upon the number of +data bits [*data_bits*] specified in the [*gpioSerialReadOpen*] command. + +For [*data_bits*] 1-8 there will be one byte per character. +For [*data_bits*] 9-16 there will be two bytes per character. +For [*data_bits*] 17-32 there will be four bytes per character. +D*/ + + +/*F*/ +int gpioSerialReadClose(unsigned user_gpio); +/*D +This function closes a GPIO for bit bang reading of serial data. + +. . +user_gpio: 0-31, previously opened with [*gpioSerialReadOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. +D*/ + +/*F*/ +int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags); +/*D +This returns a handle for the device at the address on the I2C bus. + +. . + i2cBus: >=0 + i2cAddr: 0-0x7F +i2cFlags: 0 +. . + +No flags are currently defined. This parameter should be set to zero. + +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +The GPIO used are given in the following table. + + @ SDA @ SCL +I2C 0 @ 0 @ 1 +I2C 1 @ 2 @ 3 + +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +. . +S (1 bit) : Start bit +P (1 bit) : Stop bit +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +A, NA (1 bit) : Accept and not accept bit. +Addr (7 bits): I2C 7 bit address. +i2cReg (8 bits): Command byte, a byte which often selects a register. +Data (8 bits): A data byte. +Count (8 bits): A byte defining the length of a block operation. + +[..]: Data sent by the device. +. . +D*/ + + +/*F*/ +int i2cClose(unsigned handle); +/*D +This closes the I2C device associated with the handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + + +/*F*/ +int i2cWriteQuick(unsigned handle, unsigned bit); +/*D +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + bit: 0-1, the value to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Quick command. SMBus 2.0 5.5.1 +. . +S Addr bit [A] P +. . +D*/ + + +/*F*/ +int i2cWriteByte(unsigned handle, unsigned bVal); +/*D +This sends a single byte to the device associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + bVal: 0-0xFF, the value to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Send byte. SMBus 2.0 5.5.2 +. . +S Addr Wr [A] bVal [A] P +. . +D*/ + + +/*F*/ +int i2cReadByte(unsigned handle); +/*D +This reads a single byte from the device associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +Receive byte. SMBus 2.0 5.5.3 +. . +S Addr Rd [A] [Data] NA P +. . +D*/ + + +/*F*/ +int i2cWriteByteData(unsigned handle, unsigned i2cReg, unsigned bVal); +/*D +This writes a single byte to the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write + bVal: 0-0xFF, the value to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write byte. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] i2cReg [A] bVal [A] P +. . +D*/ + + +/*F*/ +int i2cWriteWordData(unsigned handle, unsigned i2cReg, unsigned wVal); +/*D +This writes a single 16 bit word to the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write + wVal: 0-0xFFFF, the value to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write word. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] P +. . +D*/ + + +/*F*/ +int i2cReadByteData(unsigned handle, unsigned i2cReg); +/*D +This reads a single byte from the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to read +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read byte. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] i2cReg [A] S Addr Rd [A] [Data] NA P +. . +D*/ + + +/*F*/ +int i2cReadWordData(unsigned handle, unsigned i2cReg); +/*D +This reads a single 16 bit word from the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to read +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read word. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] i2cReg [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + + +/*F*/ +int i2cProcessCall(unsigned handle, unsigned i2cReg, unsigned wVal); +/*D +This writes 16 bits of data to the specified register of the device +associated with handle and reads 16 bits of data in return. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write/read + wVal: 0-0xFFFF, the value to write +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Process call. SMBus 2.0 5.5.6 +. . +S Addr Wr [A] i2cReg [A] wValLow [A] wValHigh [A] + S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + + +/*F*/ +int i2cWriteBlockData( +unsigned handle, unsigned i2cReg, char *buf, unsigned count); +/*D +This writes up to 32 bytes to the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write + buf: an array with the data to send + count: 1-32, the number of bytes to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Block write. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] i2cReg [A] count [A] + buf0 [A] buf1 [A] ... [A] bufn [A] P +. . +D*/ + + +/*F*/ +int i2cReadBlockData(unsigned handle, unsigned i2cReg, char *buf); +/*D +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to read + buf: an array to receive the read data +. . + +The amount of returned data is set by the device. + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Block read. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] i2cReg [A] + S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + + +/*F*/ +int i2cBlockProcessCall( +unsigned handle, unsigned i2cReg, char *buf, unsigned count); +/*D +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write/read + buf: an array with the data to send and to receive the read data + count: 1-32, the number of bytes to write +. . + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +The SMBus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +Block write-block read. SMBus 2.0 5.5.8 +. . +S Addr Wr [A] i2cReg [A] count [A] buf0 [A] ... bufn [A] + S Addr Rd [A] [Count] A [buf0] A ... [bufn] A P +. . +D*/ + + +/*F*/ +int i2cReadI2CBlockData( +unsigned handle, unsigned i2cReg, char *buf, unsigned count); +/*D +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to read + buf: an array to receive the read data + count: 1-32, the number of bytes to read +. . + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +. . +S Addr Wr [A] i2cReg [A] + S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + + +/*F*/ +int i2cWriteI2CBlockData( +unsigned handle, unsigned i2cReg, char *buf, unsigned count); +/*D +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] +i2cReg: 0-255, the register to write + buf: the data to write + count: 1-32, the number of bytes to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +. . +S Addr Wr [A] i2cReg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +. . +D*/ + +/*F*/ +int i2cReadDevice(unsigned handle, char *buf, unsigned count); +/*D +This reads count bytes from the raw device into buf. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + buf: an array to receive the read data bytes + count: >0, the number of bytes to read +. . + +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. + +. . +S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + + +/*F*/ +int i2cWriteDevice(unsigned handle, char *buf, unsigned count); +/*D +This writes count bytes from buf to the raw device. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + buf: an array containing the data bytes to write + count: >0, the number of bytes to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +. . +S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +. . +D*/ + +/*F*/ +void i2cSwitchCombined(int setting); +/*D +This sets the I2C (i2c-bcm2708) module "use combined transactions" +parameter on or off. + +. . +setting: 0 to set the parameter off, non-zero to set it on +. . + + +NOTE: when the flag is on a write followed by a read to the same +slave address will use a repeated start (rather than a stop/start). +D*/ + +/*F*/ +int i2cSegments(unsigned handle, pi_i2c_msg_t *segs, unsigned numSegs); +/*D +This function executes multiple I2C segments in one transaction by +calling the I2C_RDWR ioctl. + +. . + handle: >=0, as returned by a call to [*i2cOpen*] + segs: an array of I2C segments +numSegs: >0, the number of I2C segments +. . + +Returns the number of segments if OK, otherwise PI_BAD_I2C_SEG. +D*/ + +/*F*/ +int i2cZip( + unsigned handle, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +On @ 2 @ Switch combined flag on +Off @ 3 @ Switch combined flag off +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53, write 0x32, read 6 bytes +Set address 0x1E, write 0x03, read 6 bytes +Set address 0x68, write 0x1B, read 8 bytes +End + +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +0x00 +... +D*/ + +/*F*/ +int bbI2COpen(unsigned SDA, unsigned SCL, unsigned baud); +/*D +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +o baud rates as low as 50 +o repeated starts +o clock stretching +o I2C on any pair of spare GPIO + +. . + SDA: 0-31 + SCL: 0-31 +baud: 50-500000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +NOTE: + +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. +D*/ + +/*F*/ +int bbI2CClose(unsigned SDA); +/*D +This function stops bit banging I2C on a pair of GPIO previously +opened with [*bbI2COpen*]. + +. . +SDA: 0-31, the SDA GPIO used in a prior call to [*bbI2COpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. +D*/ + +/*F*/ +int bbI2CZip( + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . + SDA: 0-31 (as used in a prior call to [*bbI2COpen*]) + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +Start @ 2 @ Start condition +Stop @ 3 @ Stop condition +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +No flags are currently defined. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53 +start, write 0x32, (re)start, read 6 bytes, stop +Set address 0x1E +start, write 0x03, (re)start, read 6 bytes, stop +Set address 0x68 +start, write 0x1B, (re)start, read 8 bytes, stop +End + +0x04 0x53 +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 + +0x04 0x1E +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 + +0x04 0x68 +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 + +0x00 +... +D*/ + +/*F*/ +int bscXfer(bsc_xfer_t *bsc_xfer); +/*D +This function provides a low-level interface to the +SPI/I2C Slave peripheral. This peripheral allows the +Pi to act as a slave device on an I2C or SPI bus. + +I can't get SPI to work properly. I tried with a +control word of 0x303 and swapped MISO and MOSI. + +The function sets the BSC mode, writes any data in +the transmit buffer to the BSC transmit FIFO, and +copies any data in the BSC receive FIFO to the +receive buffer. + +. . +bsc_xfer:= a structure defining the transfer + +typedef struct +{ + uint32_t control; // Write + int rxCnt; // Read only + char rxBuf[BSC_FIFO_SIZE]; // Read only + int txCnt; // Write + char txBuf[BSC_FIFO_SIZE]; // Write +} bsc_xfer_t; +. . + +To start a transfer set control (see below) and copy the bytes to +be sent (if any) to txBuf and set the byte count in txCnt. + +Upon return rxCnt will be set to the number of received bytes placed +in rxBuf. + +Note that the control word sets the BSC mode. The BSC will stay in +that mode until a different control word is sent. + +The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode +and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You +need to swap MISO/MOSI between master and slave. + +When a zero control word is received GPIO 18-21 will be reset +to INPUT mode. + +The returned function value is the status of the transfer (see below). + +If there was an error the status will be less than zero +(and will contain the error code). + +The most significant word of the returned status contains the number +of bytes actually copied from txBuf to the BSC transmit FIFO (may be +less than requested if the FIFO already contained untransmitted data). + +control consists of the following bits. + +. . +22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN +. . + +Bits 0-13 are copied unchanged to the BSC CR register. See +pages 163-165 of the Broadcom peripherals document for full +details. + +aaaaaaa @ defines the I2C slave address (only relevant in I2C mode) +IT @ invert transmit status flags +HC @ enable host control +TF @ enable test FIFO +IR @ invert receive status flags +RE @ enable receive +TE @ enable transmit +BK @ abort operation and clear FIFOs +EC @ send control register as first I2C byte +ES @ send status register as first I2C byte +PL @ set SPI polarity high +PH @ set SPI phase high +I2 @ enable I2C mode +SP @ enable SPI mode +EN @ enable BSC peripheral + +The returned status has the following format + +. . +20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + S S S S S R R R R R T T T T T RB TE RF TF RE TB +. . + +Bits 0-15 are copied unchanged from the BSC FR register. See +pages 165-166 of the Broadcom peripherals document for full +details. + +SSSSS @ number of bytes successfully copied to transmit FIFO +RRRRR @ number of bytes in receieve FIFO +TTTTT @ number of bytes in transmit FIFO +RB @ receive busy +TE @ transmit FIFO empty +RF @ receive FIFO full +TF @ transmit FIFO full +RE @ receive FIFO empty +TB @ transmit busy + +The following example shows how to configure the BSC peripheral as +an I2C slave with address 0x13 and send four bytes. + +... +bsc_xfer_t xfer; + +xfer.control = (0x13<<16) | 0x305; + +memcpy(xfer.txBuf, "ABCD", 4); +xfer.txCnt = 4; + +status = bscXfer(&xfer); + +if (status >= 0) +{ + // process transfer +} +... +D*/ + +/*F*/ +int bbSPIOpen( + unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, + unsigned baud, unsigned spiFlags); +/*D +This function selects a set of GPIO for bit banging SPI with +a specified baud rate and mode. + +. . + CS: 0-31 + MISO: 0-31 + MOSI: 0-31 + SCLK: 0-31 + baud: 50-250000 +spiFlags: see below +. . + +spiFlags consists of the least significant 22 bits. + +. . +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m +. . + +mm defines the SPI mode, defaults to 0 + +. . +Mode CPOL CPHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +p is 0 if CS is active low (default) and 1 for active high. + +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. + +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. + +The other bits in flags should be set to zero. + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or +PI_GPIO_IN_USE. + +If more than one device is connected to the SPI bus (defined by +SCLK, MOSI, and MISO) each must have its own CS. + +... +bbSPIOpen(10, MISO, MOSI, SCLK, 10000, 0); // device 1 +bbSPIOpen(11, MISO, MOSI, SCLK, 20000, 3); // device 2 +... +D*/ + +/*F*/ +int bbSPIClose(unsigned CS); +/*D +This function stops bit banging SPI on a set of GPIO +opened with [*bbSPIOpen*]. + +. . +CS: 0-31, the CS GPIO used in a prior call to [*bbSPIOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO. +D*/ + +/*F*/ +int bbSPIXfer( + unsigned CS, + char *inBuf, + char *outBuf, + unsigned count); +/*D +This function executes a bit banged SPI transfer. + +. . + CS: 0-31 (as used in a prior call to [*bbSPIOpen*]) + inBuf: pointer to buffer to hold data to be sent +outBuf: pointer to buffer to hold returned data + count: size of data transfer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER. + +... +// gcc -Wall -pthread -o bbSPIx_test bbSPIx_test.c -lpigpio +// sudo ./bbSPIx_test + + +#include + +#include "pigpio.h" + +#define CE0 5 +#define CE1 6 +#define MISO 13 +#define MOSI 19 +#define SCLK 12 + +int main(int argc, char *argv[]) +{ + int i, count, set_val, read_val; + unsigned char inBuf[3]; + char cmd1[] = {0, 0}; + char cmd2[] = {12, 0}; + char cmd3[] = {1, 128, 0}; + + if (gpioInitialise() < 0) + { + fprintf(stderr, "pigpio initialisation failed.\n"); + return 1; + } + + bbSPIOpen(CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC + bbSPIOpen(CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC + + for (i=0; i<256; i++) + { + cmd1[1] = i; + + count = bbSPIXfer(CE0, cmd1, (char *)inBuf, 2); // > DAC + + if (count == 2) + { + count = bbSPIXfer(CE0, cmd2, (char *)inBuf, 2); // < DAC + + if (count == 2) + { + set_val = inBuf[1]; + + count = bbSPIXfer(CE1, cmd3, (char *)inBuf, 3); // < ADC + + if (count == 3) + { + read_val = ((inBuf[1]&3)<<8) | inBuf[2]; + printf("%d %d\n", set_val, read_val); + } + } + } + } + + bbSPIClose(CE0); + bbSPIClose(CE1); + + gpioTerminate(); + + return 0; +} +... +D*/ + +/*F*/ +int spiOpen(unsigned spiChan, unsigned baud, unsigned spiFlags); +/*D +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +The Pi has two SPI peripherals: main and auxiliary. + +The main SPI has two chip selects (channels), the auxiliary has +three. + +The auxiliary SPI is available on all models but the A and B. + +The GPIO used are given in the following table. + + @ MISO @ MOSI @ SCLK @ CE0 @ CE1 @ CE2 +Main SPI @ 9 @ 10 @ 11 @ 8 @ 7 @ - +Aux SPI @ 19 @ 20 @ 21 @ 18 @ 17 @ 16 + +. . + spiChan: 0-1 (0-2 for the auxiliary SPI) + baud: 32K-125M (values above 30M are unlikely to work) +spiFlags: see below +. . + +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +spiFlags consists of the least significant 22 bits. + +. . +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +. . + +mm defines the SPI mode. + +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +. . +Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +px is 0 if CEx is active low (default) and 1 for active high. + +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +A is 0 for the main SPI, 1 for the auxiliary SPI. + +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +The [*spiRead*], [*spiWrite*], and [*spiXfer*] functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +For bits 1-8 there will be one byte per word. +For bits 9-16 there will be two bytes per word. +For bits 17-32 there will be four bytes per word. + +Multi-byte transfers are made in least significant byte first order. + +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +The other bits in flags should be set to zero. +D*/ + +/*F*/ +int spiClose(unsigned handle); +/*D +This functions closes the SPI device identified by the handle. + +. . +handle: >=0, as returned by a call to [*spiOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + + +/*F*/ +int spiRead(unsigned handle, char *buf, unsigned count); +/*D +This function reads count bytes of data from the SPI +device associated with the handle. + +. . +handle: >=0, as returned by a call to [*spiOpen*] + buf: an array to receive the read data bytes + count: the number of bytes to read +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + + +/*F*/ +int spiWrite(unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +. . +handle: >=0, as returned by a call to [*spiOpen*] + buf: the data bytes to write + count: the number of bytes to write +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count); +/*D +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +. . +handle: >=0, as returned by a call to [*spiOpen*] + txBuf: the data bytes to write + rxBuf: the received data bytes + count: the number of bytes to transfer +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + + +/*F*/ +int serOpen(char *sertty, unsigned baud, unsigned serFlags); +/*D +This function opens a serial device at a specified baud rate +and with specified flags. The device name must start with +/dev/tty or /dev/serial. + +. . + sertty: the serial device to open + baud: the baud rate in bits per second, see below +serFlags: 0 +. . + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +No flags are currently defined. This parameter should be set to zero. +D*/ + + +/*F*/ +int serClose(unsigned handle); +/*D +This function closes the serial device associated with handle. + +. . +handle: >=0, as returned by a call to [*serOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int serWriteByte(unsigned handle, unsigned bVal); +/*D +This function writes bVal to the serial port associated with handle. + +. . +handle: >=0, as returned by a call to [*serOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + +/*F*/ +int serReadByte(unsigned handle); +/*D +This function reads a byte from the serial port associated with handle. + +. . +handle: >=0, as returned by a call to [*serOpen*] +. . + +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +If no data is ready PI_SER_READ_NO_DATA is returned. +D*/ + +/*F*/ +int serWrite(unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes from buf to the the serial port +associated with handle. + +. . +handle: >=0, as returned by a call to [*serOpen*] + buf: the array of bytes to write + count: the number of bytes to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + + +/*F*/ +int serRead(unsigned handle, char *buf, unsigned count); +/*D +This function reads up count bytes from the the serial port +associated with handle and writes them to buf. + +. . +handle: >=0, as returned by a call to [*serOpen*] + buf: an array to receive the read data + count: the maximum number of bytes to read +. . + +Returns the number of bytes read (>0=) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_SER_READ_NO_DATA. + +If no data is ready zero is returned. +D*/ + + +/*F*/ +int serDataAvailable(unsigned handle); +/*D +This function returns the number of bytes available +to be read from the device associated with handle. + +. . +handle: >=0, as returned by a call to [*serOpen*] +. . + +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. +D*/ + + +/*F*/ +int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level); +/*D +This function sends a trigger pulse to a GPIO. The GPIO is set to +level for pulseLen microseconds and then reset to not level. + +. . +user_gpio: 0-31 + pulseLen: 1-100 + level: 0,1 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, +or PI_BAD_PULSELEN. +D*/ + + +/*F*/ +int gpioSetWatchdog(unsigned user_gpio, unsigned timeout); +/*D +Sets a watchdog for a GPIO. + +. . +user_gpio: 0-31 + timeout: 0-60000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT. + +The watchdog is nominally in milliseconds. + +One watchdog may be registered per GPIO. + +The watchdog may be cancelled by setting timeout to 0. + +Until cancelled a timeout will be reported every timeout milliseconds +after the last GPIO activity. + +In particular: + +1) any registered alert function for the GPIO will be called with + the level set to PI_TIMEOUT. + +2) any notification for the GPIO will have a report written to the + fifo with the flags set to indicate a watchdog timeout. + +... +void aFunction(int gpio, int level, uint32_t tick) +{ + printf("GPIO %d became %d at %d", gpio, level, tick); +} + +// call aFunction whenever GPIO 4 changes state +gpioSetAlertFunc(4, aFunction); + +// or approximately every 5 millis +gpioSetWatchdog(4, 5); +... +D*/ + + +/*F*/ +int gpioNoiseFilter(unsigned user_gpio, unsigned steady, unsigned active); +/*D +Sets a noise filter on a GPIO. + +Level changes on the GPIO are ignored until a level which has +been stable for [*steady*] microseconds is detected. Level changes +on the GPIO are then reported for [*active*] microseconds after +which the process repeats. + +. . +user_gpio: 0-31 + steady: 0-300000 + active: 0-1000000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +This filter affects the GPIO samples returned to callbacks set up +with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*], +and [*gpioSetGetSamplesFuncEx*]. + +It does not affect interrupts set up with [*gpioSetISRFunc*], +[*gpioSetISRFuncEx*], or levels read by [*gpioRead*], +[*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*]. + +Level changes before and after the active period may +be reported. Your software must be designed to cope with +such reports. +D*/ + + +/*F*/ +int gpioGlitchFilter(unsigned user_gpio, unsigned steady); +/*D +Sets a glitch filter on a GPIO. + +Level changes on the GPIO are not reported unless the level +has been stable for at least [*steady*] microseconds. The +level is then reported. Level changes of less than [*steady*] +microseconds are ignored. + +. . +user_gpio: 0-31 + steady: 0-300000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +This filter affects the GPIO samples returned to callbacks set up +with [*gpioSetAlertFunc*], [*gpioSetAlertFuncEx*], [*gpioSetGetSamplesFunc*], +and [*gpioSetGetSamplesFuncEx*]. + +It does not affect interrupts set up with [*gpioSetISRFunc*], +[*gpioSetISRFuncEx*], or levels read by [*gpioRead*], +[*gpioRead_Bits_0_31*], or [*gpioRead_Bits_32_53*]. + +Each (stable) edge will be timestamped [*steady*] microseconds +after it was first detected. +D*/ + + +/*F*/ +int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits); +/*D +Registers a function to be called (a callback) every millisecond +with the latest GPIO samples. + +. . + f: the function to call +bits: the GPIO of interest +. . + +Returns 0 if OK. + +The function is passed a pointer to the samples (an array of +[*gpioSample_t*]), and the number of samples. + +Only one function can be registered. + +The callback may be cancelled by passing NULL as the function. + +The samples returned will be the union of bits, plus any active alerts, +plus any active notifications. + +e.g. if there are alerts for GPIO 7, 8, and 9, notifications for GPIO +8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for GPIO +7, 8, 9, 10, 17, 23, and 24 will be reported. +D*/ + + +/*F*/ +int gpioSetGetSamplesFuncEx( + gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata); +/*D +Registers a function to be called (a callback) every millisecond +with the latest GPIO samples. + +. . + f: the function to call + bits: the GPIO of interest +userdata: a pointer to arbitrary user data +. . + +Returns 0 if OK. + +The function is passed a pointer to the samples (an array of +[*gpioSample_t*]), the number of samples, and the userdata pointer. + +Only one of [*gpioGetSamplesFunc*] or [*gpioGetSamplesFuncEx*] can be +registered. + +See [*gpioSetGetSamplesFunc*] for further details. +D*/ + + +/*F*/ +int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f); +/*D +Registers a function to be called (a callback) every millis milliseconds. + +. . + timer: 0-9 +millis: 10-60000 + f: the function to call +. . + +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. + +10 timers are supported numbered 0 to 9. + +One function may be registered per timer. + +The timer may be cancelled by passing NULL as the function. + +... +void bFunction(void) +{ + printf("two seconds have elapsed"); +} + +// call bFunction every 2000 milliseconds +gpioSetTimerFunc(0, 2000, bFunction); +... +D*/ + + +/*F*/ +int gpioSetTimerFuncEx( + unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata); +/*D +Registers a function to be called (a callback) every millis milliseconds. + +. . + timer: 0-9. + millis: 10-60000 + f: the function to call +userdata: a pointer to arbitrary user data +. . + +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. + +The function is passed the userdata pointer. + +Only one of [*gpioSetTimerFunc*] or [*gpioSetTimerFuncEx*] can be +registered per timer. + +See [*gpioSetTimerFunc*] for further details. +D*/ + + +/*F*/ +pthread_t *gpioStartThread(gpioThreadFunc_t f, void *userdata); +/*D +Starts a new thread of execution with f as the main routine. + +. . + f: the main function for the new thread +userdata: a pointer to arbitrary user data +. . + +Returns a pointer to pthread_t if OK, otherwise NULL. + +The function is passed the single argument arg. + +The thread can be cancelled by passing the pointer to pthread_t to +[*gpioStopThread*]. + +... +#include +#include + +void *myfunc(void *arg) +{ + while (1) + { + printf("%s", arg); + sleep(1); + } +} + +int main(int argc, char *argv[]) +{ + pthread_t *p1, *p2, *p3; + + if (gpioInitialise() < 0) return 1; + + p1 = gpioStartThread(myfunc, "thread 1"); sleep(3); + + p2 = gpioStartThread(myfunc, "thread 2"); sleep(3); + + p3 = gpioStartThread(myfunc, "thread 3"); sleep(3); + + gpioStopThread(p3); sleep(3); + + gpioStopThread(p2); sleep(3); + + gpioStopThread(p1); sleep(3); + + gpioTerminate(); +} +... +D*/ + + +/*F*/ +void gpioStopThread(pthread_t *pth); +/*D +Cancels the thread pointed at by pth. + +. . +pth: a thread pointer returned by [*gpioStartThread*] +. . + +No value is returned. + +The thread to be stopped should have been started with [*gpioStartThread*]. +D*/ + + +/*F*/ +int gpioStoreScript(char *script); +/*D +This function stores a null terminated script for later execution. + +See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details. + +. . +script: the text of the script +. . + +The function returns a script id if the script is valid, +otherwise PI_BAD_SCRIPT. +D*/ + + +/*F*/ +int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param); +/*D +This function runs a stored script. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] + numPar: 0-10, the number of parameters + param: an array of parameters +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + +/*F*/ +int gpioRunScript(unsigned script_id, unsigned numPar, uint32_t *param); +/*D +This function runs a stored script. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] + numPar: 0-10, the number of parameters + param: an array of parameters +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + + + +/*F*/ +int gpioUpdateScript(unsigned script_id, unsigned numPar, uint32_t *param); +/*D +This function sets the parameters of a script. The script may or +may not be running. The first numPar parameters of the script are +overwritten with the new values. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] + numPar: 0-10, the number of parameters + param: an array of parameters +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + + +/*F*/ +int gpioScriptStatus(unsigned script_id, uint32_t *param); +/*D +This function returns the run status of a stored script as well as +the current values of parameters 0 to 9. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] + param: an array to hold the returned 10 parameters +. . + +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +The run status may be + +. . +PI_SCRIPT_INITING +PI_SCRIPT_HALTED +PI_SCRIPT_RUNNING +PI_SCRIPT_WAITING +PI_SCRIPT_FAILED +. . + +The current value of script parameters 0 to 9 are returned in param. +D*/ + + +/*F*/ +int gpioStopScript(unsigned script_id); +/*D +This function stops a running script. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + + +/*F*/ +int gpioDeleteScript(unsigned script_id); +/*D +This function deletes a stored script. + +. . +script_id: >=0, as returned by [*gpioStoreScript*] +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + + +/*F*/ +int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f); +/*D +Registers a function to be called (a callback) when a signal occurs. + +. . +signum: 0-63 + f: the callback function +. . + +Returns 0 if OK, otherwise PI_BAD_SIGNUM. + +The function is passed the signal number. + +One function may be registered per signal. + +The callback may be cancelled by passing NULL. + +By default all signals are treated as fatal and cause the library +to call gpioTerminate and then exit. +D*/ + + +/*F*/ +int gpioSetSignalFuncEx( + unsigned signum, gpioSignalFuncEx_t f, void *userdata); +/*D +Registers a function to be called (a callback) when a signal occurs. + +. . + signum: 0-63 + f: the callback function +userdata: a pointer to arbitrary user data +. . + +Returns 0 if OK, otherwise PI_BAD_SIGNUM. + +The function is passed the signal number and the userdata pointer. + +Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be +registered per signal. + +See gpioSetSignalFunc for further details. +D*/ + + +/*F*/ +uint32_t gpioRead_Bits_0_31(void); +/*D +Returns the current level of GPIO 0-31. +D*/ + + +/*F*/ +uint32_t gpioRead_Bits_32_53(void); +/*D +Returns the current level of GPIO 32-53. +D*/ + + +/*F*/ +int gpioWrite_Bits_0_31_Clear(uint32_t bits); +/*D +Clears GPIO 0-31 if the corresponding bit in bits is set. + +. . +bits: a bit mask of GPIO to clear +. . + +Returns 0 if OK. + +... +// To clear (set to 0) GPIO 4, 7, and 15 +gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) ); +... +D*/ + + +/*F*/ +int gpioWrite_Bits_32_53_Clear(uint32_t bits); +/*D +Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +. . +bits: a bit mask of GPIO to clear +. . + +Returns 0 if OK. +D*/ + + +/*F*/ +int gpioWrite_Bits_0_31_Set(uint32_t bits); +/*D +Sets GPIO 0-31 if the corresponding bit in bits is set. + +. . +bits: a bit mask of GPIO to set +. . + +Returns 0 if OK. +D*/ + + +/*F*/ +int gpioWrite_Bits_32_53_Set(uint32_t bits); +/*D +Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +. . +bits: a bit mask of GPIO to set +. . + +Returns 0 if OK. + +... +// To set (set to 1) GPIO 32, 40, and 53 +gpioWrite_Bits_32_53_Set((1<<(32-32)) | (1<<(40-32)) | (1<<(53-32))); +... +D*/ + +/*F*/ +int gpioHardwareClock(unsigned gpio, unsigned clkfreq); +/*D +Starts a hardware clock on a GPIO at the specified frequency. +Frequencies above 30MHz are unlikely to work. + +. . + gpio: see description +clkfreq: 0 (off) or 4689-250000000 (250M) +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HCLK_GPIO, +PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS. + +The same clock is available on multiple GPIO. The latest +frequency setting will be used by all GPIO which share a clock. + +The GPIO must be one of the following. + +. . +4 clock 0 All models +5 clock 1 All models but A and B (reserved for system use) +6 clock 2 All models but A and B +20 clock 0 All models but A and B +21 clock 1 All models but A and Rev.2 B (reserved for system use) + +32 clock 0 Compute module only +34 clock 0 Compute module only +42 clock 1 Compute module only (reserved for system use) +43 clock 2 Compute module only +44 clock 1 Compute module only (reserved for system use) +. . + +Access to clock 1 is protected by a password as its use will likely +crash the Pi. The password is given by or'ing 0x5A000000 with the +GPIO number. +D*/ + +/*F*/ +int gpioHardwarePWM(unsigned gpio, unsigned PWMfreq, unsigned PWMduty); +/*D +Starts hardware PWM on a GPIO at the specified frequency and dutycycle. +Frequencies above 30MHz are unlikely to work. + +NOTE: Any waveform started by [*gpioWaveTxSend*], or +[*gpioWaveChain*] will be cancelled. + +This function is only valid if the pigpio main clock is PCM. The +main clock defaults to PCM but may be overridden by a call to +[*gpioCfgClock*]. + +. . + gpio: see description +PWMfreq: 0 (off) or 1-125000000 (125M) +PWMduty: 0 (off) to 1000000 (1M)(fully on) +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_NOT_HPWM_GPIO, +PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, or PI_HPWM_ILLEGAL. + +The same PWM channel is available on multiple GPIO. The latest +frequency and dutycycle setting will be used by all GPIO which +share a PWM channel. + +The GPIO must be one of the following. + +. . +12 PWM channel 0 All models but A and B +13 PWM channel 1 All models but A and B +18 PWM channel 0 All models +19 PWM channel 1 All models but A and B + +40 PWM channel 0 Compute module only +41 PWM channel 1 Compute module only +45 PWM channel 1 Compute module only +52 PWM channel 0 Compute module only +53 PWM channel 1 Compute module only +. . + +The actual number of steps beween off and fully on is the +integral part of 250 million divided by PWMfreq. + +The actual frequency set is 250 million / steps. + +There will only be a million steps for a PWMfreq of 250. +Lower frequencies will have more steps and higher +frequencies will have fewer steps. PWMduty is +automatically scaled to take this into account. +D*/ + +/*F*/ +int gpioTime(unsigned timetype, int *seconds, int *micros); +/*D +Updates the seconds and micros variables with the current time. + +. . +timetype: 0 (relative), 1 (absolute) + seconds: a pointer to an int to hold seconds + micros: a pointer to an int to hold microseconds +. . + +Returns 0 if OK, otherwise PI_BAD_TIMETYPE. + +If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the +number of seconds and microseconds since the epoch (1st January 1970). + +If timetype is PI_TIME_RELATIVE updates seconds and micros with the +number of seconds and microseconds since the library was initialised. + +... +int secs, mics; + +// print the number of seconds since the library was started +gpioTime(PI_TIME_RELATIVE, &secs, &mics); +printf("library started %d.%03d seconds ago", secs, mics/1000); +... +D*/ + + +/*F*/ +int gpioSleep(unsigned timetype, int seconds, int micros); +/*D +Sleeps for the number of seconds and microseconds specified by seconds +and micros. + +. . +timetype: 0 (relative), 1 (absolute) + seconds: seconds to sleep + micros: microseconds to sleep +. . + +Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS, +or PI_BAD_MICROS. + +If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds +and microseconds since the epoch (1st January 1970) has elapsed. System +clock changes are taken into account. + +If timetype is PI_TIME_RELATIVE the sleep is for the specified number +of seconds and microseconds. System clock changes do not effect the +sleep length. + +For short delays (say, 50 microseonds or less) use [*gpioDelay*]. + +... +gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds + +gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 0.1 seconds + +gpioSleep(PI_TIME_RELATIVE, 60, 0); // sleep for one minute +... +D*/ + + +/*F*/ +uint32_t gpioDelay(uint32_t micros); +/*D +Delays for at least the number of microseconds specified by micros. + +. . +micros: the number of microseconds to sleep +. . + +Returns the actual length of the delay in microseconds. + +Delays of 100 microseconds or less use busy waits. +D*/ + + +/*F*/ +uint32_t gpioTick(void); +/*D +Returns the current system tick. + +Tick is the number of microseconds since system boot. + +As tick is an unsigned 32 bit quantity it wraps around after +2^32 microseconds, which is approximately 1 hour 12 minutes. + +You don't need to worry about the wrap around as long as you +take a tick (uint32_t) from another tick, i.e. the following +code will always provide the correct difference. + +... +uint32_t startTick, endTick; +int diffTick; + +startTick = gpioTick(); + +// do some processing + +endTick = gpioTick(); + +diffTick = endTick - startTick; + +printf("some processing took %d microseconds", diffTick); +... +D*/ + + +/*F*/ +unsigned gpioHardwareRevision(void); +/*D +Returns the hardware revision. + +If the hardware revision can not be found or is not a valid hexadecimal +number the function returns 0. + +The hardware revision is the last few characters on the Revision line of +/proc/cpuinfo. + +The revision number can be used to determine the assignment of GPIO +to pins (see [*gpio*]). + +There are at least three types of board. + +Type 1 boards have hardware revision numbers of 2 and 3. + +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. + +Type 3 boards have hardware revision numbers of 16 or greater. + +for "Revision : 0002" the function returns 2. +for "Revision : 000f" the function returns 15. +for "Revision : 000g" the function returns 0. +D*/ + + +/*F*/ +unsigned gpioVersion(void); +/*D +Returns the pigpio version. +D*/ + + +/*F*/ +int gpioGetPad(unsigned pad); +/*D +This function returns the pad drive strength in mA. + +. . +pad: 0-2, the pad to get +. . + +Returns the pad drive strength if OK, otherwise PI_BAD_PAD. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +... +strength = gpioGetPad(1); // get pad 1 strength +... +D*/ + + +/*F*/ +int gpioSetPad(unsigned pad, unsigned padStrength); +/*D +This function sets the pad drive strength in mA. + +. . + pad: 0-2, the pad to set +padStrength: 1-16 mA +. . + +Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +... +gpioSetPad(0, 16); // set pad 0 strength to 16 mA +... +D*/ + +/*F*/ +int eventMonitor(unsigned handle, uint32_t bits); +/*D +This function selects the events to be reported on a previously +opened handle. + +. . +handle: >=0, as returned by [*gpioNotifyOpen*] + bits: a bit mask indicating the events of interest +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +A report is sent each time an event is triggered providing the +corresponding bit in bits is set. + +See [*gpioNotifyBegin*] for the notification format. + +... +// Start reporting events 3, 6, and 7. + +// bit 76543210 +// (0xC8 = 0b11001000) + +eventMonitor(h, 0xC8); +... + +D*/ + +/*F*/ +int eventSetFunc(unsigned event, eventFunc_t f); +/*D +Registers a function to be called (a callback) when the specified +event occurs. + +. . +event: 0-31 + f: the callback function +. . + +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +One function may be registered per event. + +The function is passed the event, and the tick. + +The callback may be cancelled by passing NULL as the function. +D*/ + +/*F*/ +int eventSetFuncEx(unsigned event, eventFuncEx_t f, void *userdata); +/*D +Registers a function to be called (a callback) when the specified +event occurs. + +. . + event: 0-31 + f: the callback function +userdata: pointer to arbitrary user data +. . + +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +One function may be registered per event. + +The function is passed the event, the tick, and the ueserdata pointer. + +The callback may be cancelled by passing NULL as the function. + +Only one of [*eventSetFunc*] or [*eventSetFuncEx*] can be +registered per event. +D*/ + +/*F*/ +int eventTrigger(unsigned event); +/*D +This function signals the occurrence of an event. + +. . +event: 0-31, the event +. . + +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +An event is a signal used to inform one or more consumers +to start an action. Each consumer which has registered an interest +in the event (e.g. by calling [*eventSetFunc*]) will be informed by +a callback. + +One event, PI_EVENT_BSC (31) is predefined. This event is +auto generated on BSC slave activity. + +The meaning of other events is arbitrary. + +Note that other than its id and its tick there is no data associated +with an event. +D*/ + + +/*F*/ +int shell(char *scriptName, char *scriptString); +/*D +This function uses the system call to execute a shell script +with the given string as its parameter. + +. . + scriptName: the name of the script, only alphanumeric characters, + '-' and '_' are allowed in the name +scriptString: the string to pass to the script +. . + +The exit status of the system call is returned if OK, otherwise +PI_BAD_SHELL_STATUS. + +scriptName must exist in /opt/pigpio/cgi and must be executable. + +The returned exit status is normally 256 times that set by the +shell script exit function. If the script can't be found 32512 will +be returned. + +The following table gives some example returned statuses. + +Script exit status @ Returned system call status +1 @ 256 +5 @ 1280 +10 @ 2560 +200 @ 51200 +script not found @ 32512 + +... +// pass two parameters, hello and world +status = shell("scr1", "hello world"); + +// pass three parameters, hello, string with spaces, and world +status = shell("scr1", "hello 'string with spaces' world"); + +// pass one parameter, hello string with spaces world +status = shell("scr1", "\"hello string with spaces world\""); +... +D*/ + +#pragma GCC diagnostic push + +#pragma GCC diagnostic ignored "-Wcomment" + +/*F*/ +int fileOpen(char *file, unsigned mode); +/*D +This function returns a handle to a file opened in a specified mode. + +. . +file: the file to open +mode: the file open mode +. . + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS, +PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR. + +File + +A file may only be opened if permission is granted by an entry in +/opt/pigpio/access. This is intended to allow remote access to files +in a more or less controlled manner. + +Each entry in /opt/pigpio/access takes the form of a file path +which may contain wildcards followed by a single letter permission. +The permission may be R for read, W for write, U for read/write, +and N for no access. + +Where more than one entry matches a file the most specific rule +applies. If no entry matches a file then access is denied. + +Suppose /opt/pigpio/access contains the following entries + +. . +/home/* n +/home/pi/shared/dir_1/* w +/home/pi/shared/dir_2/* r +/home/pi/shared/dir_3/* u +/home/pi/shared/dir_1/file.txt n +. . + +Files may be written in directory dir_1 with the exception +of file.txt. + +Files may be read in directory dir_2. + +Files may be read and written in directory dir_3. + +If a directory allows read, write, or read/write access then files may +be created in that directory. + +In an attempt to prevent risky permissions the following paths are +ignored in /opt/pigpio/access. + +. . +a path containing .. +a path containing only wildcards (*?) +a path containing less than two non-wildcard parts +. . + +Mode + +The mode may have the following values. + +Macro @ Value @ Meaning +PI_FILE_READ @ 1 @ open file for reading +PI_FILE_WRITE @ 2 @ open file for writing +PI_FILE_RW @ 3 @ open file for reading and writing + +The following values may be or'd into the mode. + +Macro @ Value @ Meaning +PI_FILE_APPEND @ 4 @ Writes append data to the end of the file +PI_FILE_CREATE @ 8 @ The file is created if it doesn't exist +PI_FILE_TRUNC @ 16 @ The file is truncated + +Newly created files are owned by root with permissions owner read and write. + +... +#include +#include + +int main(int argc, char *argv[]) +{ + int handle, c; + char buf[60000]; + + if (gpioInitialise() < 0) return 1; + + // assumes /opt/pigpio/access contains the following line + // /ram/*.c r + + handle = fileOpen("/ram/pigpio.c", PI_FILE_READ); + + if (handle >= 0) + { + while ((c=fileRead(handle, buf, sizeof(buf)-1))) + { + buf[c] = 0; + printf("%s", buf); + } + + fileClose(handle); + } + + gpioTerminate(); +} +... +D*/ + +#pragma GCC diagnostic pop + +/*F*/ +int fileClose(unsigned handle); +/*D +This function closes the file associated with handle. + +. . +handle: >=0, as returned by a call to [*fileOpen*] +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +... +fileClose(h); +... +D*/ + + +/*F*/ +int fileWrite(unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes from buf to the the file +associated with handle. + +. . +handle: >=0, as returned by a call to [*fileOpen*] + buf: the array of bytes to write + count: the number of bytes to write +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, +PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE. + +... +status = fileWrite(h, buf, count); +if (status == 0) +{ + // okay +} +else +{ + // error +} +... +D*/ + + +/*F*/ +int fileRead(unsigned handle, char *buf, unsigned count); +/*D +This function reads up to count bytes from the the file +associated with handle and writes them to buf. + +. . +handle: >=0, as returned by a call to [*fileOpen*] + buf: an array to receive the read data + count: the maximum number of bytes to read +. . + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE. + +... +if (fileRead(h, buf, sizeof(buf)) > 0) +{ + // process read data +} +... +D*/ + + +/*F*/ +int fileSeek(unsigned handle, int32_t seekOffset, int seekFrom); +/*D +This function seeks to a position within the file associated +with handle. + +. . + handle: >=0, as returned by a call to [*fileOpen*] +seekOffset: the number of bytes to move. Positive offsets + move forward, negative offsets backwards. + seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1), + or PI_FROM_END (2) +. . + +Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK. + +... +fileSeek(0, 20, PI_FROM_START); // Seek to start plus 20 + +size = fileSeek(0, 0, PI_FROM_END); // Seek to end, return size + +pos = fileSeek(0, 0, PI_FROM_CURRENT); // Return current position +... +D*/ + +#pragma GCC diagnostic push + +#pragma GCC diagnostic ignored "-Wcomment" + +/*F*/ +int fileList(char *fpat, char *buf, unsigned count); +/*D +This function returns a list of files which match a pattern. The +pattern may contain wildcards. + +. . + fpat: file pattern to match + buf: an array to receive the matching file names +count: the maximum number of bytes to read +. . + +Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS, +or PI_NO_FILE_MATCH. + +The pattern must match an entry in /opt/pigpio/access. The pattern +may contain wildcards. See [*fileOpen*]. + +NOTE + +The returned value is not the number of files, it is the number +of bytes in the buffer. The file names are separated by newline +characters. + +... +#include +#include + +int main(int argc, char *argv[]) +{ + int c; + char buf[1000]; + + if (gpioInitialise() < 0) return 1; + + // assumes /opt/pigpio/access contains the following line + // /ram/*.c r + + c = fileList("/ram/p*.c", buf, sizeof(buf)); + + if (c >= 0) + { + // terminate string + buf[c] = 0; + printf("%s", buf); + } + + gpioTerminate(); +} +... +D*/ + +#pragma GCC diagnostic pop + + +/*F*/ +int gpioCfgBufferSize(unsigned cfgMillis); +/*D +Configures pigpio to buffer cfgMillis milliseconds of GPIO samples. + +This function is only effective if called before [*gpioInitialise*]. + +. . +cfgMillis: 100-10000 +. . + +The default setting is 120 milliseconds. + +The intention is to allow for bursts of data and protection against +other processes hogging cpu time. + +I haven't seen a process locked out for more than 100 milliseconds. + +Making the buffer bigger uses a LOT of memory at the more frequent +sampling rates as shown in the following table in MBs. + +. . + buffer milliseconds + 120 250 500 1sec 2sec 4sec 8sec + + 1 16 31 55 107 --- --- --- + 2 10 18 31 55 107 --- --- +sample 4 8 12 18 31 55 107 --- + rate 5 8 10 14 24 45 87 --- + (us) 8 6 8 12 18 31 55 107 + 10 6 8 10 14 24 45 87 +. . +D*/ + + +/*F*/ +int gpioCfgClock( + unsigned cfgMicros, unsigned cfgPeripheral, unsigned cfgSource); +/*D +Configures pigpio to use a particular sample rate timed by a specified +peripheral. + +This function is only effective if called before [*gpioInitialise*]. + +. . + cfgMicros: 1, 2, 4, 5, 8, 10 +cfgPeripheral: 0 (PWM), 1 (PCM) + cfgSource: deprecated, value is ignored +. . + +The timings are provided by the specified peripheral (PWM or PCM). + +The default setting is 5 microseconds using the PCM peripheral. + +The approximate CPU percentage used for each sample rate is: + +. . +sample cpu + rate % + + 1 25 + 2 16 + 4 11 + 5 10 + 8 15 + 10 14 +. . + +A sample rate of 5 microseconds seeems to be the sweet spot. +D*/ + + +/*F*/ +int gpioCfgDMAchannel(unsigned DMAchannel); /* DEPRECATED */ +/*D +Configures pigpio to use the specified DMA channel. + +This function is only effective if called before [*gpioInitialise*]. + +. . +DMAchannel: 0-14 +. . + +The default setting is to use channel 14. +D*/ + + +/*F*/ +int gpioCfgDMAchannels( + unsigned primaryChannel, unsigned secondaryChannel); +/*D +Configures pigpio to use the specified DMA channels. + +This function is only effective if called before [*gpioInitialise*]. + +. . + primaryChannel: 0-14 +secondaryChannel: 0-14 +. . + +The default setting is to use channel 14 for the primary channel and +channel 6 for the secondary channel. + +The secondary channel is only used for the transmission of waves. + +If possible use one of channels 0 to 6 for the secondary channel +(a full channel). + +A full channel only requires one DMA control block regardless of the +length of a pulse delay. Channels 7 to 14 (lite channels) require +one DMA control block for each 16383 microseconds of delay. I.e. +a 10 second pulse delay requires one control block on a full channel +and 611 control blocks on a lite channel. +D*/ + + +/*F*/ +int gpioCfgPermissions(uint64_t updateMask); +/*D +Configures pigpio to restrict GPIO updates via the socket or pipe +interfaces to the GPIO specified by the mask. Programs directly +calling the pigpio library (i.e. linked with -lpigpio are not +affected). A GPIO update is a write to a GPIO or a GPIO mode +change or any function which would force such an action. + +This function is only effective if called before [*gpioInitialise*]. + +. . +updateMask: bit (1<=0 +arg2: >=0 +argx: extra (byte) arguments +argc: number of extra arguments +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. +D*/ + + +/*F*/ +int gpioCustom2(unsigned arg1, char *argx, unsigned argc, + char *retBuf, unsigned retMax); +/*D +This function is available for user customisation. + +It differs from gpioCustom1 in that it returns an array of bytes +rather than just an integer. + +The returned value is an integer indicating the number of returned bytes. +. . + arg1: >=0 + argx: extra (byte) arguments + argc: number of extra arguments +retBuf: buffer for returned bytes +retMax: maximum number of bytes to return +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. + +The number of returned bytes must be retMax or less. +D*/ + + +/*F*/ +int rawWaveAddSPI( + rawSPI_t *spi, + unsigned offset, + unsigned spiSS, + char *buf, + unsigned spiTxBits, + unsigned spiBitFirst, + unsigned spiBitLast, + unsigned spiBits); +/*D +This function adds a waveform representing SPI data to the +existing waveform (if any). + +. . + spi: a pointer to a spi object + offset: microseconds from the start of the waveform + spiSS: the slave select GPIO + buf: the bits to transmit, most significant bit first + spiTxBits: the number of bits to write +spiBitFirst: the first bit to read + spiBitLast: the last bit to read + spiBits: the number of bits to transfer +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. + +Not intended for general use. +D*/ + +/*F*/ +int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses); +/*D +This function adds a number of pulses to the current waveform. + +. . +numPulses: the number of pulses + pulses: the array containing the pulses +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +The advantage of this function over gpioWaveAddGeneric is that it +allows the setting of the flags field. + +The pulses are interleaved in time order within the existing waveform +(if any). + +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. + +Not intended for general use. +D*/ + +/*F*/ +unsigned rawWaveCB(void); +/*D +Returns the number of the cb being currently output. + +Not intended for general use. +D*/ + +/*F*/ +rawCbs_t *rawWaveCBAdr(int cbNum); +/*D +Return the (Linux) address of contol block cbNum. + +. . +cbNum: the cb of interest +. . + +Not intended for general use. +D*/ + +/*F*/ +uint32_t rawWaveGetOOL(int pos); +/*D +Gets the OOL parameter stored at pos. + +. . +pos: the position of interest. +. . + +Not intended for general use. +D*/ + + +/*F*/ +void rawWaveSetOOL(int pos, uint32_t lVal); +/*D +Sets the OOL parameter stored at pos to value. + +. . + pos: the position of interest +lVal: the value to write +. . + +Not intended for general use. +D*/ + +/*F*/ +uint32_t rawWaveGetOut(int pos); +/*D +Gets the wave output parameter stored at pos. + +DEPRECATED: use rawWaveGetOOL instead. + +. . +pos: the position of interest. +. . + +Not intended for general use. +D*/ + + +/*F*/ +void rawWaveSetOut(int pos, uint32_t lVal); +/*D +Sets the wave output parameter stored at pos to value. + +DEPRECATED: use rawWaveSetOOL instead. + +. . + pos: the position of interest +lVal: the value to write +. . + +Not intended for general use. +D*/ + +/*F*/ +uint32_t rawWaveGetIn(int pos); +/*D +Gets the wave input value parameter stored at pos. + +DEPRECATED: use rawWaveGetOOL instead. + +. . +pos: the position of interest +. . + +Not intended for general use. +D*/ + + +/*F*/ +void rawWaveSetIn(int pos, uint32_t lVal); +/*D +Sets the wave input value stored at pos to value. + +DEPRECATED: use rawWaveSetOOL instead. + +. . + pos: the position of interest +lVal: the value to write +. . + +Not intended for general use. +D*/ + +/*F*/ +rawWaveInfo_t rawWaveInfo(int wave_id); +/*D +Gets details about the wave with id wave_id. + +. . +wave_id: the wave of interest +. . + +Not intended for general use. +D*/ + +/*F*/ +int getBitInBytes(int bitPos, char *buf, int numBits); +/*D +Returns the value of the bit bitPos bits from the start of buf. Returns +0 if bitPos is greater than or equal to numBits. + +. . + bitPos: bit index from the start of buf + buf: array of bits +numBits: number of valid bits in buf +. . + +D*/ + +/*F*/ +void putBitInBytes(int bitPos, char *buf, int bit); +/*D +Sets the bit bitPos bits from the start of buf to bit. + +. . +bitPos: bit index from the start of buf + buf: array of bits + bit: 0-1, value to set +. . + +D*/ + +/*F*/ +double time_time(void); +/*D +Return the current time in seconds since the Epoch. +D*/ + + +/*F*/ +void time_sleep(double seconds); +/*D +Delay execution for a given number of seconds + +. . +seconds: the number of seconds to sleep +. . +D*/ + + +/*F*/ +void rawDumpWave(void); +/*D +Used to print a readable version of the current waveform to stderr. + +Not intended for general use. +D*/ + + +/*F*/ +void rawDumpScript(unsigned script_id); +/*D +Used to print a readable version of a script to stderr. + +. . +script_id: >=0, a script_id returned by [*gpioStoreScript*] +. . + +Not intended for general use. +D*/ + + +#ifdef __cplusplus +} +#endif + +/*PARAMS + +active :: 0-1000000 + +The number of microseconds level changes are reported for once +a noise filter has been triggered (by [*steady*] microseconds of +a stable level). + +arg1:: + +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +arg2:: + +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +argc:: +The count of bytes passed to a user customised function. + +*argx:: +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +baud:: +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +bit:: +A value of 0 or 1. + +bitPos:: +A bit position within a byte or word. The least significant bit is +position 0. + +bits:: +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +A convenient way to set bit n is to or in (1<=0 + +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + +gpio:: + +A Broadcom numbered GPIO, in the range 0-53. + +There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through +GPIO53. + +They are split into two banks. Bank 1 consists of GPIO0 through +GPIO31. Bank 2 consists of GPIO32 through GPIO53. + +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +See [*gpioHardwareRevision*]. + +The user GPIO are marked with an X in the following table. + +. . + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +Type 1 X X - - X - - X X X X X - - X X +Type 2 - - X X X - - X X X X X - - X X +Type 3 X X X X X X X X X X X X X X + + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +Type 1 - X X - - X X X X X - - - - - - +Type 2 - X X - - - X X X X - X X X X X +Type 3 X X X X X X X X X X X X - - - - +. . + +gpioAlertFunc_t:: +. . +typedef void (*gpioAlertFunc_t) (int gpio, int level, uint32_t tick); +. . + +gpioAlertFuncEx_t:: +. . +typedef void (*eventFuncEx_t) + (int event, int level, uint32_t tick, void *userdata); +. . + +gpioCfg*:: + +These functions are only effective if called before [*gpioInitialise*]. + +[*gpioCfgBufferSize*] +[*gpioCfgClock*] +[*gpioCfgDMAchannel*] +[*gpioCfgDMAchannels*] +[*gpioCfgPermissions*] +[*gpioCfgInterfaces*] +[*gpioCfgSocketPort*] +[*gpioCfgMemAlloc*] + +gpioGetSamplesFunc_t:: +. . +typedef void (*gpioGetSamplesFunc_t) + (const gpioSample_t *samples, int numSamples); +. . + +gpioGetSamplesFuncEx_t:: +. . +typedef void (*gpioGetSamplesFuncEx_t) + (const gpioSample_t *samples, int numSamples, void *userdata); +. . + +gpioISRFunc_t:: +. . +typedef void (*gpioISRFunc_t) + (int gpio, int level, uint32_t tick); +. . + +gpioISRFuncEx_t:: +. . +typedef void (*gpioISRFuncEx_t) + (int gpio, int level, uint32_t tick, void *userdata); +. . + +gpioPulse_t:: +. . +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; +. . + +gpioSample_t:: +. . +typedef struct +{ + uint32_t tick; + uint32_t level; +} gpioSample_t; +. . + +gpioSignalFunc_t:: +. . +typedef void (*gpioSignalFunc_t) (int signum); +. . + +gpioSignalFuncEx_t:: +. . +typedef void (*gpioSignalFuncEx_t) (int signum, void *userdata); +. . + +gpioThreadFunc_t:: +. . +typedef void *(gpioThreadFunc_t) (void *); +. . + +gpioTimerFunc_t:: +. . +typedef void (*gpioTimerFunc_t) (void); +. . + +gpioTimerFuncEx_t:: +. . +typedef void (*gpioTimerFuncEx_t) (void *userdata); +. . + +gpioWaveAdd*:: + +One of + +[*gpioWaveAddNew*] +[*gpioWaveAddGeneric*] +[*gpioWaveAddSerial*] + +handle::>=0 + +A number referencing an object opened by one of + +[*fileOpen*] +[*gpioNotifyOpen*] +[*i2cOpen*] +[*serOpen*] +[*spiOpen*] + +i2cAddr:: 0-0x7F +The address of a device on the I2C bus. + +i2cBus::>=0 + +An I2C bus number. + +i2cFlags::0 + +Flags which modify an I2C open command. None are currently defined. + +i2cReg:: 0-255 + +A register of an I2C device. + +ifFlags::0-3 +. . +PI_DISABLE_FIFO_IF 1 +PI_DISABLE_SOCK_IF 2 +. . + +*inBuf:: +A buffer used to pass data to a function. + +inLen:: +The number of bytes of data in a buffer. + +int:: +A whole number, negative or positive. + +int32_t:: +A 32-bit signed value. + +invert:: +A flag used to set normal or inverted bit bang serial data level logic. + +level:: +The level of a GPIO. Low or High. + +. . +PI_OFF 0 +PI_ON 1 + +PI_CLEAR 0 +PI_SET 1 + +PI_LOW 0 +PI_HIGH 1 +. . + +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See [*gpioSetWatchdog*]. + +. . +PI_TIMEOUT 2 +. . + + +lVal::0-4294967295 (Hex 0x0-0xFFFFFFFF, Octal 0-37777777777) + +A 32-bit word value. + +memAllocMode:: 0-2 + +The DMA memory allocation mode. + +. . +PI_MEM_ALLOC_AUTO 0 +PI_MEM_ALLOC_PAGEMAP 1 +PI_MEM_ALLOC_MAILBOX 2 +. . + +*micros:: + +A value representing microseconds. + +micros:: + +A value representing microseconds. + +millis:: + +A value representing milliseconds. + +MISO:: +The GPIO used for the MISO signal when bit banging SPI. + +mode:: + +1. The operational mode of a GPIO, normally INPUT or OUTPUT. + +. . +PI_INPUT 0 +PI_OUTPUT 1 +PI_ALT0 4 +PI_ALT1 5 +PI_ALT2 6 +PI_ALT3 7 +PI_ALT4 3 +PI_ALT5 2 +. . + +2. A file open mode. + +. . +PI_FILE_READ 1 +PI_FILE_WRITE 2 +PI_FILE_RW 3 +. . + +The following values can be or'd into the mode. + +. . +PI_FILE_APPEND 4 +PI_FILE_CREATE 8 +PI_FILE_TRUNC 16 +. . + +MOSI:: +The GPIO used for the MOSI signal when bit banging SPI. + +numBits:: + +The number of bits stored in a buffer. + +numBytes:: +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +numPar:: 0-10 +The number of parameters passed to a script. + +numPulses:: +The number of pulses to be added to a waveform. + +numSegs:: +The number of segments in a combined I2C transaction. + +numSockAddr:: +The number of network addresses allowed to use the socket interface. + +0 means all addresses allowed. + +offset:: +The associated data starts this number of microseconds from the start of +the waveform. + +*outBuf:: +A buffer used to return data from a function. + +outLen:: +The size in bytes of an output buffer. + +pad:: 0-2 +A set of GPIO which share common drivers. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +padStrength:: 1-16 +The mA which may be drawn from each GPIO whilst still guaranteeing the +high and low levels. + +*param:: +An array of script parameters. + +pi_i2c_msg_t:: +. . +typedef struct +{ + uint16_t addr; // slave address + uint16_t flags; + uint16_t len; // msg length + uint8_t *buf; // pointer to msg data +} pi_i2c_msg_t; +. . + +port:: 1024-32000 +The port used to bind to the pigpio socket. Defaults to 8888. + +pos:: +The position of an item. + +primaryChannel:: 0-14 +The DMA channel used to time the sampling of GPIO and to time servo and +PWM pulses. + +*pth:: + +A thread identifier, returned by [*gpioStartThread*]. + +pthread_t:: + +A thread identifier. + +pud::0-2 + +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. + +. . +PI_PUD_OFF 0 +PI_PUD_DOWN 1 +PI_PUD_UP 2 +. . + +pulseLen:: + +1-100, the length of a trigger pulse in microseconds. + +*pulses:: + +An array of pulses to be added to a waveform. + +pulsewidth::0, 500-2500 +. . +PI_SERVO_OFF 0 +PI_MIN_SERVO_PULSEWIDTH 500 +PI_MAX_SERVO_PULSEWIDTH 2500 +. . + +PWMduty::0-1000000 (1M) +The hardware PWM dutycycle. + +. . +PI_HW_PWM_RANGE 1000000 +. . + +PWMfreq::5-250K +The hardware PWM frequency. + +. . +PI_HW_PWM_MIN_FREQ 1 +PI_HW_PWM_MAX_FREQ 125000000 +. . + +range::25-40000 +. . +PI_MIN_DUTYCYCLE_RANGE 25 +PI_MAX_DUTYCYCLE_RANGE 40000 +. . + +rawCbs_t:: +. . +typedef struct // linux/arch/arm/mach-bcm2708/include/mach/dma.h +{ + unsigned long info; + unsigned long src; + unsigned long dst; + unsigned long length; + unsigned long stride; + unsigned long next; + unsigned long pad[2]; +} rawCbs_t; +. . + +rawSPI_t:: +. . +typedef struct +{ + int clk; // GPIO for clock + int mosi; // GPIO for MOSI + int miso; // GPIO for MISO + int ss_pol; // slave select off state + int ss_us; // delay after slave select + int clk_pol; // clock off state + int clk_pha; // clock phase + int clk_us; // clock micros +} rawSPI_t; +. . + +rawWave_t:: +. . +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; + uint32_t flags; +} rawWave_t; +. . + +rawWaveInfo_t:: +. . +typedef struct +{ + uint16_t botCB; // first CB used by wave + uint16_t topCB; // last CB used by wave + uint16_t botOOL; // last OOL used by wave + uint16_t topOOL; // first OOL used by wave + uint16_t deleted; + uint16_t numCB; + uint16_t numBOOL; + uint16_t numTOOL; +} rawWaveInfo_t; +. . + +*retBuf:: + +A buffer to hold a number of bytes returned to a used customised function, + +retMax:: + +The maximum number of bytes a user customised function should return. + +*rxBuf:: + +A pointer to a buffer to receive data. + +SCL:: +The user GPIO to use for the clock when bit banging I2C. + +SCLK:: +The GPIO used for the SCLK signal when bit banging SPI. + +*script:: +A pointer to the text of a script. + +script_id:: +An id of a stored script as returned by [*gpioStoreScript*]. + +*scriptName:: +The name of a [*shell*] script to be executed. The script must be present in +/opt/pigpio/cgi and must have execute permission. + +*scriptString:: +The string to be passed to a [*shell*] script to be executed. + +SDA:: +The user GPIO to use for data when bit banging I2C. + +secondaryChannel:: 0-6 + +The DMA channel used to time output waveforms. + +*seconds:: + +A pointer to a uint32_t to store the second component of +a returned time. + +seconds:: +The number of seconds. + +seekFrom:: + +. . +PI_FROM_START 0 +PI_FROM_CURRENT 1 +PI_FROM_END 2 +. . + +seekOffset:: +The number of bytes to move forward (positive) or backwards (negative) +from the seek position (start, current, or end of file). + +*segs:: +An array of segments which make up a combined I2C transaction. + +serFlags:: +Flags which modify a serial open command. None are currently defined. + +*sertty:: +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +setting:: +A value used to set a flag, 0 for false, non-zero for true. + +signum::0-63 +. . +PI_MIN_SIGNUM 0 +PI_MAX_SIGNUM 63 +. . + +size_t:: + +A standard type used to indicate the size of an object in bytes. + +*sockAddr:: +An array of network addresses allowed to use the socket interface encoded +as 32 bit numbers. + +E.g. address 192.168.1.66 would be encoded as 0x4201a8c0. + +*spi:: +A pointer to a [*rawSPI_t*] structure. + +spiBitFirst:: +GPIO reads are made from spiBitFirst to spiBitLast. + +spiBitLast:: + +GPIO reads are made from spiBitFirst to spiBitLast. + +spiBits:: +The number of bits to transfer in a raw SPI transaction. + +spiChan:: +A SPI channel, 0-2. + +spiFlags:: +See [*spiOpen*] and [*bbSPIOpen*]. + +spiSS:: +The SPI slave select GPIO in a raw SPI transaction. + +spiTxBits:: +The number of bits to transfer dring a raw SPI transaction + +steady :: 0-300000 + +The number of microseconds level changes must be stable for +before reporting the level changed ([*gpioGlitchFilter*]) or triggering +the active part of a noise filter ([*gpioNoiseFilter*]). + +stop_bits::2-8 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +. . +PI_MIN_WAVE_HALFSTOPBITS 2 +PI_MAX_WAVE_HALFSTOPBITS 8 +. . + +*str:: +An array of characters. + +timeout:: +A GPIO level change timeout in milliseconds. + +[*gpioSetWatchdog*] +. . +PI_MIN_WDOG_TIMEOUT 0 +PI_MAX_WDOG_TIMEOUT 60000 +. . + +[*gpioSetISRFunc*] and [*gpioSetISRFuncEx*] +. . +<=0 cancel timeout +>0 timeout after specified milliseconds +. . + +timer:: +. . +PI_MIN_TIMER 0 +PI_MAX_TIMER 9 +. . + +timetype:: +. . +PI_TIME_RELATIVE 0 +PI_TIME_ABSOLUTE 1 +. . + +*txBuf:: + +An array of bytes to transmit. + +uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF) + +A 32-bit unsigned value. + +uint64_t::0-(2^64)-1 + +A 64-bit unsigned value. + +unsigned:: + +A whole number >= 0. + +updateMask:: + +A 64 bit mask indicating which GPIO may be written to by the user. + +If GPIO#n may be written then bit (1< 4 +#define PI_BAD_CHANNEL -27 // DMA channel not 0-14 +#define PI_BAD_PRIM_CHANNEL -27 // DMA primary channel not 0-14 +#define PI_BAD_SOCKET_PORT -28 // socket port not 1024-32000 +#define PI_BAD_FIFO_COMMAND -29 // unrecognized fifo command +#define PI_BAD_SECO_CHANNEL -30 // DMA secondary channel not 0-6 +#define PI_NOT_INITIALISED -31 // function called before gpioInitialise +#define PI_INITIALISED -32 // function called after gpioInitialise +#define PI_BAD_WAVE_MODE -33 // waveform mode not 0-3 +#define PI_BAD_CFG_INTERNAL -34 // bad parameter in gpioCfgInternals call +#define PI_BAD_WAVE_BAUD -35 // baud rate not 50-250K(RX)/50-1M(TX) +#define PI_TOO_MANY_PULSES -36 // waveform has too many pulses +#define PI_TOO_MANY_CHARS -37 // waveform has too many chars +#define PI_NOT_SERIAL_GPIO -38 // no bit bang serial read on GPIO +#define PI_BAD_SERIAL_STRUC -39 // bad (null) serial structure parameter +#define PI_BAD_SERIAL_BUF -40 // bad (null) serial buf parameter +#define PI_NOT_PERMITTED -41 // GPIO operation not permitted +#define PI_SOME_PERMITTED -42 // one or more GPIO not permitted +#define PI_BAD_WVSC_COMMND -43 // bad WVSC subcommand +#define PI_BAD_WVSM_COMMND -44 // bad WVSM subcommand +#define PI_BAD_WVSP_COMMND -45 // bad WVSP subcommand +#define PI_BAD_PULSELEN -46 // trigger pulse length not 1-100 +#define PI_BAD_SCRIPT -47 // invalid script +#define PI_BAD_SCRIPT_ID -48 // unknown script id +#define PI_BAD_SER_OFFSET -49 // add serial data offset > 30 minutes +#define PI_GPIO_IN_USE -50 // GPIO already in use +#define PI_BAD_SERIAL_COUNT -51 // must read at least a byte at a time +#define PI_BAD_PARAM_NUM -52 // script parameter id not 0-9 +#define PI_DUP_TAG -53 // script has duplicate tag +#define PI_TOO_MANY_TAGS -54 // script has too many tags +#define PI_BAD_SCRIPT_CMD -55 // illegal script command +#define PI_BAD_VAR_NUM -56 // script variable id not 0-149 +#define PI_NO_SCRIPT_ROOM -57 // no more room for scripts +#define PI_NO_MEMORY -58 // can't allocate temporary memory +#define PI_SOCK_READ_FAILED -59 // socket read failed +#define PI_SOCK_WRIT_FAILED -60 // socket write failed +#define PI_TOO_MANY_PARAM -61 // too many script parameters (> 10) +#define PI_NOT_HALTED -62 // DEPRECATED +#define PI_SCRIPT_NOT_READY -62 // script initialising +#define PI_BAD_TAG -63 // script has unresolved tag +#define PI_BAD_MICS_DELAY -64 // bad MICS delay (too large) +#define PI_BAD_MILS_DELAY -65 // bad MILS delay (too large) +#define PI_BAD_WAVE_ID -66 // non existent wave id +#define PI_TOO_MANY_CBS -67 // No more CBs for waveform +#define PI_TOO_MANY_OOL -68 // No more OOL for waveform +#define PI_EMPTY_WAVEFORM -69 // attempt to create an empty waveform +#define PI_NO_WAVEFORM_ID -70 // no more waveforms +#define PI_I2C_OPEN_FAILED -71 // can't open I2C device +#define PI_SER_OPEN_FAILED -72 // can't open serial device +#define PI_SPI_OPEN_FAILED -73 // can't open SPI device +#define PI_BAD_I2C_BUS -74 // bad I2C bus +#define PI_BAD_I2C_ADDR -75 // bad I2C address +#define PI_BAD_SPI_CHANNEL -76 // bad SPI channel +#define PI_BAD_FLAGS -77 // bad i2c/spi/ser open flags +#define PI_BAD_SPI_SPEED -78 // bad SPI speed +#define PI_BAD_SER_DEVICE -79 // bad serial device name +#define PI_BAD_SER_SPEED -80 // bad serial baud rate +#define PI_BAD_PARAM -81 // bad i2c/spi/ser parameter +#define PI_I2C_WRITE_FAILED -82 // i2c write failed +#define PI_I2C_READ_FAILED -83 // i2c read failed +#define PI_BAD_SPI_COUNT -84 // bad SPI count +#define PI_SER_WRITE_FAILED -85 // ser write failed +#define PI_SER_READ_FAILED -86 // ser read failed +#define PI_SER_READ_NO_DATA -87 // ser read no data available +#define PI_UNKNOWN_COMMAND -88 // unknown command +#define PI_SPI_XFER_FAILED -89 // spi xfer/read/write failed +#define PI_BAD_POINTER -90 // bad (NULL) pointer +#define PI_NO_AUX_SPI -91 // no auxiliary SPI on Pi A or B +#define PI_NOT_PWM_GPIO -92 // GPIO is not in use for PWM +#define PI_NOT_SERVO_GPIO -93 // GPIO is not in use for servo pulses +#define PI_NOT_HCLK_GPIO -94 // GPIO has no hardware clock +#define PI_NOT_HPWM_GPIO -95 // GPIO has no hardware PWM +#define PI_BAD_HPWM_FREQ -96 // hardware PWM frequency not 1-125M +#define PI_BAD_HPWM_DUTY -97 // hardware PWM dutycycle not 0-1M +#define PI_BAD_HCLK_FREQ -98 // hardware clock frequency not 4689-250M +#define PI_BAD_HCLK_PASS -99 // need password to use hardware clock 1 +#define PI_HPWM_ILLEGAL -100 // illegal, PWM in use for main clock +#define PI_BAD_DATABITS -101 // serial data bits not 1-32 +#define PI_BAD_STOPBITS -102 // serial (half) stop bits not 2-8 +#define PI_MSG_TOOBIG -103 // socket/pipe message too big +#define PI_BAD_MALLOC_MODE -104 // bad memory allocation mode +#define PI_TOO_MANY_SEGS -105 // too many I2C transaction segments +#define PI_BAD_I2C_SEG -106 // an I2C transaction segment failed +#define PI_BAD_SMBUS_CMD -107 // SMBus command not supported by driver +#define PI_NOT_I2C_GPIO -108 // no bit bang I2C in progress on GPIO +#define PI_BAD_I2C_WLEN -109 // bad I2C write length +#define PI_BAD_I2C_RLEN -110 // bad I2C read length +#define PI_BAD_I2C_CMD -111 // bad I2C command +#define PI_BAD_I2C_BAUD -112 // bad I2C baud rate, not 50-500k +#define PI_CHAIN_LOOP_CNT -113 // bad chain loop count +#define PI_BAD_CHAIN_LOOP -114 // empty chain loop +#define PI_CHAIN_COUNTER -115 // too many chain counters +#define PI_BAD_CHAIN_CMD -116 // bad chain command +#define PI_BAD_CHAIN_DELAY -117 // bad chain delay micros +#define PI_CHAIN_NESTING -118 // chain counters nested too deeply +#define PI_CHAIN_TOO_BIG -119 // chain is too long +#define PI_DEPRECATED -120 // deprecated function removed +#define PI_BAD_SER_INVERT -121 // bit bang serial invert not 0 or 1 +#define PI_BAD_EDGE -122 // bad ISR edge value, not 0-2 +#define PI_BAD_ISR_INIT -123 // bad ISR initialisation +#define PI_BAD_FOREVER -124 // loop forever must be last command +#define PI_BAD_FILTER -125 // bad filter parameter +#define PI_BAD_PAD -126 // bad pad number +#define PI_BAD_STRENGTH -127 // bad pad drive strength +#define PI_FIL_OPEN_FAILED -128 // file open failed +#define PI_BAD_FILE_MODE -129 // bad file mode +#define PI_BAD_FILE_FLAG -130 // bad file flag +#define PI_BAD_FILE_READ -131 // bad file read +#define PI_BAD_FILE_WRITE -132 // bad file write +#define PI_FILE_NOT_ROPEN -133 // file not open for read +#define PI_FILE_NOT_WOPEN -134 // file not open for write +#define PI_BAD_FILE_SEEK -135 // bad file seek +#define PI_NO_FILE_MATCH -136 // no files match pattern +#define PI_NO_FILE_ACCESS -137 // no permission to access file +#define PI_FILE_IS_A_DIR -138 // file is a directory +#define PI_BAD_SHELL_STATUS -139 // bad shell return status +#define PI_BAD_SCRIPT_NAME -140 // bad script name +#define PI_BAD_SPI_BAUD -141 // bad SPI baud rate, not 50-500k +#define PI_NOT_SPI_GPIO -142 // no bit bang SPI in progress on GPIO +#define PI_BAD_EVENT_ID -143 // bad event id +#define PI_CMD_INTERRUPTED -144 // Used by Python + +#define PI_PIGIF_ERR_0 -2000 +#define PI_PIGIF_ERR_99 -2099 + +#define PI_CUSTOM_ERR_0 -3000 +#define PI_CUSTOM_ERR_999 -3999 + +/*DEF_E*/ + +/*DEF_S Defaults*/ + +#define PI_DEFAULT_BUFFER_MILLIS 120 +#define PI_DEFAULT_CLK_MICROS 5 +#define PI_DEFAULT_CLK_PERIPHERAL PI_CLOCK_PCM +#define PI_DEFAULT_IF_FLAGS 0 +#define PI_DEFAULT_FOREGROUND 0 +#define PI_DEFAULT_DMA_CHANNEL 14 +#define PI_DEFAULT_DMA_PRIMARY_CHANNEL 14 +#define PI_DEFAULT_DMA_SECONDARY_CHANNEL 6 +#define PI_DEFAULT_SOCKET_PORT 8888 +#define PI_DEFAULT_SOCKET_PORT_STR "8888" +#define PI_DEFAULT_SOCKET_ADDR_STR "127.0.0.1" +#define PI_DEFAULT_UPDATE_MASK_UNKNOWN 0x0000000FFFFFFCLL +#define PI_DEFAULT_UPDATE_MASK_B1 0x03E7CF93 +#define PI_DEFAULT_UPDATE_MASK_A_B2 0xFBC7CF9C +#define PI_DEFAULT_UPDATE_MASK_APLUS_BPLUS 0x0080480FFFFFFCLL +#define PI_DEFAULT_UPDATE_MASK_ZERO 0x0080000FFFFFFCLL +#define PI_DEFAULT_UPDATE_MASK_PI2B 0x0080480FFFFFFCLL +#define PI_DEFAULT_UPDATE_MASK_PI3B 0x0000000FFFFFFCLL +#define PI_DEFAULT_UPDATE_MASK_COMPUTE 0x00FFFFFFFFFFFFLL +#define PI_DEFAULT_MEM_ALLOC_MODE PI_MEM_ALLOC_AUTO + +#define PI_DEFAULT_CFG_INTERNALS 0 + +/*DEF_E*/ + +#endif + diff --git a/thirdparty/PIGPIO/pigpio.py b/thirdparty/PIGPIO/pigpio.py new file mode 100644 index 0000000000..ae7be89b80 --- /dev/null +++ b/thirdparty/PIGPIO/pigpio.py @@ -0,0 +1,5647 @@ +""" +pigpio is a Python module for the Raspberry which talks to +the pigpio daemon to allow control of the general purpose +input outputs (GPIO). + +[http://abyz.me.uk/rpi/pigpio/python.html] + +*Features* + +o the pigpio Python module can run on Windows, Macs, or Linux + +o controls one or more Pi's + +o hardware timed PWM on any of GPIO 0-31 + +o hardware timed servo pulses on any of GPIO 0-31 + +o callbacks when any of GPIO 0-31 change state + +o creating and transmitting precisely timed waveforms + +o reading/writing GPIO and setting their modes + +o wrappers for I2C, SPI, and serial links + +o creating and running scripts on the pigpio daemon + +*GPIO* + +ALL GPIO are identified by their Broadcom number. + +*Notes* + +Transmitted waveforms are accurate to a microsecond. + +Callback level changes are time-stamped and will be +accurate to within a few microseconds. + +*Settings* + +A number of settings are determined when the pigpio daemon is started. + +o the sample rate (1, 2, 4, 5, 8, or 10 us, default 5 us). + +o the set of GPIO which may be updated (generally written to). The + default set is those available on the Pi board revision. + +o the available PWM frequencies (see [*set_PWM_frequency*]). + +*Exceptions* + +By default a fatal exception is raised if you pass an invalid +argument to a pigpio function. + +If you wish to handle the returned status yourself you should set +pigpio.exceptions to False. + +You may prefer to check the returned status in only a few parts +of your code. In that case do the following: + +... +pigpio.exceptions = False + +# Code where you want to test the error status. + +pigpio.exceptions = True +... + +*Usage* + +This module uses the services of the C pigpio library. pigpio +must be running on the Pi(s) whose GPIO are to be manipulated. + +The normal way to start pigpio is as a daemon (during system +start). + +sudo pigpiod + +Your Python program must import pigpio and create one or more +instances of the pigpio.pi class. This class gives access to +a specified Pi's GPIO. + +... +pi1 = pigpio.pi() # pi1 accesses the local Pi's GPIO +pi2 = pigpio.pi('tom') # pi2 accesses tom's GPIO +pi3 = pigpio.pi('dick') # pi3 accesses dick's GPIO + +pi1.write(4, 0) # set local Pi's GPIO 4 low +pi2.write(4, 1) # set tom's GPIO 4 to high +pi3.read(4) # get level of dick's GPIO 4 +... + +The later example code snippets assume that pi is an instance of +the pigpio.pi class. + +OVERVIEW + +Essential + +pigpio.pi Initialise Pi connection +stop Stop a Pi connection + +Beginner + +set_mode Set a GPIO mode +get_mode Get a GPIO mode +set_pull_up_down Set/clear GPIO pull up/down resistor + +read Read a GPIO +write Write a GPIO + +set_PWM_dutycycle Start/stop PWM pulses on a GPIO +get_PWM_dutycycle Get PWM dutycycle set on a GPIO + +set_servo_pulsewidth Start/Stop servo pulses on a GPIO +get_servo_pulsewidth Get servo pulsewidth set on a GPIO + +callback Create GPIO level change callback +wait_for_edge Wait for GPIO level change + +Intermediate + +gpio_trigger Send a trigger pulse to a GPIO + +set_watchdog Set a watchdog on a GPIO + +set_PWM_range Configure PWM range of a GPIO +get_PWM_range Get configured PWM range of a GPIO + +set_PWM_frequency Set PWM frequency of a GPIO +get_PWM_frequency Get PWM frequency of a GPIO + +read_bank_1 Read all bank 1 GPIO +read_bank_2 Read all bank 2 GPIO + +clear_bank_1 Clear selected GPIO in bank 1 +clear_bank_2 Clear selected GPIO in bank 2 + +set_bank_1 Set selected GPIO in bank 1 +set_bank_2 Set selected GPIO in bank 2 + +Advanced + +get_PWM_real_range Get underlying PWM range for a GPIO + +notify_open Request a notification handle +notify_begin Start notifications for selected GPIO +notify_pause Pause notifications +notify_close Close a notification + +bb_serial_read_open Open a GPIO for bit bang serial reads +bb_serial_read Read bit bang serial data from a GPIO +bb_serial_read_close Close a GPIO for bit bang serial reads +bb_serial_invert Invert serial logic (1 invert, 0 normal) + +hardware_clock Start hardware clock on supported GPIO +hardware_PWM Start hardware PWM on supported GPIO + +set_glitch_filter Set a glitch filter on a GPIO +set_noise_filter Set a noise filter on a GPIO + +get_pad_strength Gets a pads drive strength +set_pad_strength Sets a pads drive strength + +shell Executes a shell command + +Scripts + +store_script Store a script +run_script Run a stored script +update_script Set a scripts parameters +script_status Get script status and parameters +stop_script Stop a running script +delete_script Delete a stored script + +Waves + +wave_clear Deletes all waveforms + +wave_add_new Starts a new waveform +wave_add_generic Adds a series of pulses to the waveform +wave_add_serial Adds serial data to the waveform + +wave_create Creates a waveform from added data +wave_delete Deletes a waveform + +wave_send_once Transmits a waveform once +wave_send_repeat Transmits a waveform repeatedly +wave_send_using_mode Transmits a waveform in the chosen mode + +wave_chain Transmits a chain of waveforms + +wave_tx_at Returns the current transmitting waveform +wave_tx_busy Checks to see if a waveform has ended +wave_tx_stop Aborts the current waveform + +wave_get_micros Length in microseconds of the current waveform +wave_get_max_micros Absolute maximum allowed micros +wave_get_pulses Length in pulses of the current waveform +wave_get_max_pulses Absolute maximum allowed pulses +wave_get_cbs Length in cbs of the current waveform +wave_get_max_cbs Absolute maximum allowed cbs + +I2C + +i2c_open Opens an I2C device +i2c_close Closes an I2C device + +i2c_write_quick SMBus write quick +i2c_write_byte SMBus write byte +i2c_read_byte SMBus read byte +i2c_write_byte_data SMBus write byte data +i2c_write_word_data SMBus write word data +i2c_read_byte_data SMBus read byte data +i2c_read_word_data SMBus read word data +i2c_process_call SMBus process call +i2c_write_block_data SMBus write block data +i2c_read_block_data SMBus read block data +i2c_block_process_call SMBus block process call + +i2c_read_i2c_block_data SMBus read I2C block data +i2c_write_i2c_block_data SMBus write I2C block data + +i2c_read_device Reads the raw I2C device +i2c_write_device Writes the raw I2C device + +i2c_zip Performs multiple I2C transactions + +bb_i2c_open Opens GPIO for bit banging I2C +bb_i2c_close Closes GPIO for bit banging I2C +bb_i2c_zip Performs multiple bit banged I2C transactions + +SPI + +spi_open Opens a SPI device +spi_close Closes a SPI device + +spi_read Reads bytes from a SPI device +spi_write Writes bytes to a SPI device +spi_xfer Transfers bytes with a SPI device + +bb_spi_open Opens GPIO for bit banging SPI +bb_spi_close Closes GPIO for bit banging SPI +bb_spi_xfer Transfers bytes with bit banging SPI + +I2C/SPI_Slave + +bsc_xfer I2C/SPI as slave transfer +bsc_i2c I2C as slave transfer + +Serial + +serial_open Opens a serial device +serial_close Closes a serial device + +serial_read Reads bytes from a serial device +serial_read_byte Reads a byte from a serial device + +serial_write Writes bytes to a serial device +serial_write_byte Writes a byte to a serial device + +serial_data_available Returns number of bytes ready to be read + +Files + +file_open Opens a file +file_close Closes a file +file_read Reads bytes from a file +file_write Writes bytes to a file +file_seek Seeks to a position within a file +file_list List files which match a pattern + +Events + +event_callback Sets a callback for an event +event_trigger Triggers an event +wait_for_event Wait for an event + +Custom + +custom_1 User custom function 1 +custom_2 User custom function 2 + +Utility + +get_current_tick Get current tick (microseconds) + +get_hardware_revision Get hardware revision +get_pigpio_version Get the pigpio version + +pigpio.error_text Gets error text from error number +pigpio.tickDiff Returns difference between two ticks +""" + +import sys +import socket +import struct +import time +import threading +import os +import atexit + +VERSION = "1.42" + +exceptions = True + +# GPIO levels + +OFF = 0 +LOW = 0 +CLEAR = 0 + +ON = 1 +HIGH = 1 +SET = 1 + +TIMEOUT = 2 + +# GPIO edges + +RISING_EDGE = 0 +FALLING_EDGE = 1 +EITHER_EDGE = 2 + +# GPIO modes + +INPUT = 0 +OUTPUT = 1 +ALT0 = 4 +ALT1 = 5 +ALT2 = 6 +ALT3 = 7 +ALT4 = 3 +ALT5 = 2 + +# GPIO Pull Up Down + +PUD_OFF = 0 +PUD_DOWN = 1 +PUD_UP = 2 + +# script run status + +PI_SCRIPT_INITING=0 +PI_SCRIPT_HALTED =1 +PI_SCRIPT_RUNNING=2 +PI_SCRIPT_WAITING=3 +PI_SCRIPT_FAILED =4 + +# notification flags + +NTFY_FLAGS_EVENT = (1 << 7) +NTFY_FLAGS_ALIVE = (1 << 6) +NTFY_FLAGS_WDOG = (1 << 5) +NTFY_FLAGS_GPIO = 31 + +# wave modes + +WAVE_MODE_ONE_SHOT =0 +WAVE_MODE_REPEAT =1 +WAVE_MODE_ONE_SHOT_SYNC=2 +WAVE_MODE_REPEAT_SYNC =3 + +WAVE_NOT_FOUND = 9998 # Transmitted wave not found. +NO_TX_WAVE = 9999 # No wave being transmitted. + +FILE_READ=1 +FILE_WRITE=2 +FILE_RW=3 + +FILE_APPEND=4 +FILE_CREATE=8 +FILE_TRUNC=16 + +FROM_START=0 +FROM_CURRENT=1 +FROM_END=2 + +SPI_MODE_0 = 0 +SPI_MODE_1 = 1 +SPI_MODE_2 = 2 +SPI_MODE_3 = 3 + +SPI_CPHA = 1 << 0 +SPI_CPOL = 1 << 1 + +SPI_CS_HIGH_ACTIVE = 1 << 2 + +SPI_TX_LSBFIRST = 1 << 14 +SPI_RX_LSBFIRST = 1 << 15 + +EVENT_BSC = 31 + +_SOCK_CMD_LEN = 16 + +# pigpio command numbers + +_PI_CMD_MODES= 0 +_PI_CMD_MODEG= 1 +_PI_CMD_PUD= 2 +_PI_CMD_READ= 3 +_PI_CMD_WRITE= 4 +_PI_CMD_PWM= 5 +_PI_CMD_PRS= 6 +_PI_CMD_PFS= 7 +_PI_CMD_SERVO= 8 +_PI_CMD_WDOG= 9 +_PI_CMD_BR1= 10 +_PI_CMD_BR2= 11 +_PI_CMD_BC1= 12 +_PI_CMD_BC2= 13 +_PI_CMD_BS1= 14 +_PI_CMD_BS2= 15 +_PI_CMD_TICK= 16 +_PI_CMD_HWVER=17 + +_PI_CMD_NO= 18 +_PI_CMD_NB= 19 +_PI_CMD_NP= 20 +_PI_CMD_NC= 21 + +_PI_CMD_PRG= 22 +_PI_CMD_PFG= 23 +_PI_CMD_PRRG= 24 +_PI_CMD_HELP= 25 +_PI_CMD_PIGPV=26 + +_PI_CMD_WVCLR=27 +_PI_CMD_WVAG= 28 +_PI_CMD_WVAS= 29 +_PI_CMD_WVGO= 30 +_PI_CMD_WVGOR=31 +_PI_CMD_WVBSY=32 +_PI_CMD_WVHLT=33 +_PI_CMD_WVSM= 34 +_PI_CMD_WVSP= 35 +_PI_CMD_WVSC= 36 + +_PI_CMD_TRIG= 37 + +_PI_CMD_PROC= 38 +_PI_CMD_PROCD=39 +_PI_CMD_PROCR=40 +_PI_CMD_PROCS=41 + +_PI_CMD_SLRO= 42 +_PI_CMD_SLR= 43 +_PI_CMD_SLRC= 44 + +_PI_CMD_PROCP=45 +_PI_CMD_MICRO=46 +_PI_CMD_MILLI=47 +_PI_CMD_PARSE=48 + +_PI_CMD_WVCRE=49 +_PI_CMD_WVDEL=50 +_PI_CMD_WVTX =51 +_PI_CMD_WVTXR=52 +_PI_CMD_WVNEW=53 + +_PI_CMD_I2CO =54 +_PI_CMD_I2CC =55 +_PI_CMD_I2CRD=56 +_PI_CMD_I2CWD=57 +_PI_CMD_I2CWQ=58 +_PI_CMD_I2CRS=59 +_PI_CMD_I2CWS=60 +_PI_CMD_I2CRB=61 +_PI_CMD_I2CWB=62 +_PI_CMD_I2CRW=63 +_PI_CMD_I2CWW=64 +_PI_CMD_I2CRK=65 +_PI_CMD_I2CWK=66 +_PI_CMD_I2CRI=67 +_PI_CMD_I2CWI=68 +_PI_CMD_I2CPC=69 +_PI_CMD_I2CPK=70 + +_PI_CMD_SPIO =71 +_PI_CMD_SPIC =72 +_PI_CMD_SPIR =73 +_PI_CMD_SPIW =74 +_PI_CMD_SPIX =75 + +_PI_CMD_SERO =76 +_PI_CMD_SERC =77 +_PI_CMD_SERRB=78 +_PI_CMD_SERWB=79 +_PI_CMD_SERR =80 +_PI_CMD_SERW =81 +_PI_CMD_SERDA=82 + +_PI_CMD_GDC =83 +_PI_CMD_GPW =84 + +_PI_CMD_HC =85 +_PI_CMD_HP =86 + +_PI_CMD_CF1 =87 +_PI_CMD_CF2 =88 + +_PI_CMD_NOIB =99 + +_PI_CMD_BI2CC=89 +_PI_CMD_BI2CO=90 +_PI_CMD_BI2CZ=91 + +_PI_CMD_I2CZ =92 + +_PI_CMD_WVCHA=93 + +_PI_CMD_SLRI =94 + +_PI_CMD_CGI =95 +_PI_CMD_CSI =96 + +_PI_CMD_FG =97 +_PI_CMD_FN =98 + +_PI_CMD_WVTXM=100 +_PI_CMD_WVTAT=101 + +_PI_CMD_PADS =102 +_PI_CMD_PADG =103 + +_PI_CMD_FO =104 +_PI_CMD_FC =105 +_PI_CMD_FR =106 +_PI_CMD_FW =107 +_PI_CMD_FS =108 +_PI_CMD_FL =109 +_PI_CMD_SHELL=110 + +_PI_CMD_BSPIC=111 +_PI_CMD_BSPIO=112 +_PI_CMD_BSPIX=113 + +_PI_CMD_BSCX =114 + +_PI_CMD_EVM =115 +_PI_CMD_EVT =116 + +_PI_CMD_PROCU=117 + +# pigpio error numbers + +_PI_INIT_FAILED =-1 +PI_BAD_USER_GPIO =-2 +PI_BAD_GPIO =-3 +PI_BAD_MODE =-4 +PI_BAD_LEVEL =-5 +PI_BAD_PUD =-6 +PI_BAD_PULSEWIDTH =-7 +PI_BAD_DUTYCYCLE =-8 +_PI_BAD_TIMER =-9 +_PI_BAD_MS =-10 +_PI_BAD_TIMETYPE =-11 +_PI_BAD_SECONDS =-12 +_PI_BAD_MICROS =-13 +_PI_TIMER_FAILED =-14 +PI_BAD_WDOG_TIMEOUT =-15 +_PI_NO_ALERT_FUNC =-16 +_PI_BAD_CLK_PERIPH =-17 +_PI_BAD_CLK_SOURCE =-18 +_PI_BAD_CLK_MICROS =-19 +_PI_BAD_BUF_MILLIS =-20 +PI_BAD_DUTYRANGE =-21 +_PI_BAD_SIGNUM =-22 +_PI_BAD_PATHNAME =-23 +PI_NO_HANDLE =-24 +PI_BAD_HANDLE =-25 +_PI_BAD_IF_FLAGS =-26 +_PI_BAD_CHANNEL =-27 +_PI_BAD_PRIM_CHANNEL=-27 +_PI_BAD_SOCKET_PORT =-28 +_PI_BAD_FIFO_COMMAND=-29 +_PI_BAD_SECO_CHANNEL=-30 +_PI_NOT_INITIALISED =-31 +_PI_INITIALISED =-32 +_PI_BAD_WAVE_MODE =-33 +_PI_BAD_CFG_INTERNAL=-34 +PI_BAD_WAVE_BAUD =-35 +PI_TOO_MANY_PULSES =-36 +PI_TOO_MANY_CHARS =-37 +PI_NOT_SERIAL_GPIO =-38 +_PI_BAD_SERIAL_STRUC=-39 +_PI_BAD_SERIAL_BUF =-40 +PI_NOT_PERMITTED =-41 +PI_SOME_PERMITTED =-42 +PI_BAD_WVSC_COMMND =-43 +PI_BAD_WVSM_COMMND =-44 +PI_BAD_WVSP_COMMND =-45 +PI_BAD_PULSELEN =-46 +PI_BAD_SCRIPT =-47 +PI_BAD_SCRIPT_ID =-48 +PI_BAD_SER_OFFSET =-49 +PI_GPIO_IN_USE =-50 +PI_BAD_SERIAL_COUNT =-51 +PI_BAD_PARAM_NUM =-52 +PI_DUP_TAG =-53 +PI_TOO_MANY_TAGS =-54 +PI_BAD_SCRIPT_CMD =-55 +PI_BAD_VAR_NUM =-56 +PI_NO_SCRIPT_ROOM =-57 +PI_NO_MEMORY =-58 +PI_SOCK_READ_FAILED =-59 +PI_SOCK_WRIT_FAILED =-60 +PI_TOO_MANY_PARAM =-61 +PI_SCRIPT_NOT_READY =-62 +PI_BAD_TAG =-63 +PI_BAD_MICS_DELAY =-64 +PI_BAD_MILS_DELAY =-65 +PI_BAD_WAVE_ID =-66 +PI_TOO_MANY_CBS =-67 +PI_TOO_MANY_OOL =-68 +PI_EMPTY_WAVEFORM =-69 +PI_NO_WAVEFORM_ID =-70 +PI_I2C_OPEN_FAILED =-71 +PI_SER_OPEN_FAILED =-72 +PI_SPI_OPEN_FAILED =-73 +PI_BAD_I2C_BUS =-74 +PI_BAD_I2C_ADDR =-75 +PI_BAD_SPI_CHANNEL =-76 +PI_BAD_FLAGS =-77 +PI_BAD_SPI_SPEED =-78 +PI_BAD_SER_DEVICE =-79 +PI_BAD_SER_SPEED =-80 +PI_BAD_PARAM =-81 +PI_I2C_WRITE_FAILED =-82 +PI_I2C_READ_FAILED =-83 +PI_BAD_SPI_COUNT =-84 +PI_SER_WRITE_FAILED =-85 +PI_SER_READ_FAILED =-86 +PI_SER_READ_NO_DATA =-87 +PI_UNKNOWN_COMMAND =-88 +PI_SPI_XFER_FAILED =-89 +_PI_BAD_POINTER =-90 +PI_NO_AUX_SPI =-91 +PI_NOT_PWM_GPIO =-92 +PI_NOT_SERVO_GPIO =-93 +PI_NOT_HCLK_GPIO =-94 +PI_NOT_HPWM_GPIO =-95 +PI_BAD_HPWM_FREQ =-96 +PI_BAD_HPWM_DUTY =-97 +PI_BAD_HCLK_FREQ =-98 +PI_BAD_HCLK_PASS =-99 +PI_HPWM_ILLEGAL =-100 +PI_BAD_DATABITS =-101 +PI_BAD_STOPBITS =-102 +PI_MSG_TOOBIG =-103 +PI_BAD_MALLOC_MODE =-104 +_PI_TOO_MANY_SEGS =-105 +_PI_BAD_I2C_SEG =-106 +PI_BAD_SMBUS_CMD =-107 +PI_NOT_I2C_GPIO =-108 +PI_BAD_I2C_WLEN =-109 +PI_BAD_I2C_RLEN =-110 +PI_BAD_I2C_CMD =-111 +PI_BAD_I2C_BAUD =-112 +PI_CHAIN_LOOP_CNT =-113 +PI_BAD_CHAIN_LOOP =-114 +PI_CHAIN_COUNTER =-115 +PI_BAD_CHAIN_CMD =-116 +PI_BAD_CHAIN_DELAY =-117 +PI_CHAIN_NESTING =-118 +PI_CHAIN_TOO_BIG =-119 +PI_DEPRECATED =-120 +PI_BAD_SER_INVERT =-121 +_PI_BAD_EDGE =-122 +_PI_BAD_ISR_INIT =-123 +PI_BAD_FOREVER =-124 +PI_BAD_FILTER =-125 +PI_BAD_PAD =-126 +PI_BAD_STRENGTH =-127 +PI_FIL_OPEN_FAILED =-128 +PI_BAD_FILE_MODE =-129 +PI_BAD_FILE_FLAG =-130 +PI_BAD_FILE_READ =-131 +PI_BAD_FILE_WRITE =-132 +PI_FILE_NOT_ROPEN =-133 +PI_FILE_NOT_WOPEN =-134 +PI_BAD_FILE_SEEK =-135 +PI_NO_FILE_MATCH =-136 +PI_NO_FILE_ACCESS =-137 +PI_FILE_IS_A_DIR =-138 +PI_BAD_SHELL_STATUS =-139 +PI_BAD_SCRIPT_NAME =-140 +PI_BAD_SPI_BAUD =-141 +PI_NOT_SPI_GPIO =-142 +PI_BAD_EVENT_ID =-143 +PI_CMD_INTERRUPTED =-144 + +# pigpio error text + +_errors=[ + [_PI_INIT_FAILED , "pigpio initialisation failed"], + [PI_BAD_USER_GPIO , "GPIO not 0-31"], + [PI_BAD_GPIO , "GPIO not 0-53"], + [PI_BAD_MODE , "mode not 0-7"], + [PI_BAD_LEVEL , "level not 0-1"], + [PI_BAD_PUD , "pud not 0-2"], + [PI_BAD_PULSEWIDTH , "pulsewidth not 0 or 500-2500"], + [PI_BAD_DUTYCYCLE , "dutycycle not 0-range (default 255)"], + [_PI_BAD_TIMER , "timer not 0-9"], + [_PI_BAD_MS , "ms not 10-60000"], + [_PI_BAD_TIMETYPE , "timetype not 0-1"], + [_PI_BAD_SECONDS , "seconds < 0"], + [_PI_BAD_MICROS , "micros not 0-999999"], + [_PI_TIMER_FAILED , "gpioSetTimerFunc failed"], + [PI_BAD_WDOG_TIMEOUT , "timeout not 0-60000"], + [_PI_NO_ALERT_FUNC , "DEPRECATED"], + [_PI_BAD_CLK_PERIPH , "clock peripheral not 0-1"], + [_PI_BAD_CLK_SOURCE , "DEPRECATED"], + [_PI_BAD_CLK_MICROS , "clock micros not 1, 2, 4, 5, 8, or 10"], + [_PI_BAD_BUF_MILLIS , "buf millis not 100-10000"], + [PI_BAD_DUTYRANGE , "dutycycle range not 25-40000"], + [_PI_BAD_SIGNUM , "signum not 0-63"], + [_PI_BAD_PATHNAME , "can't open pathname"], + [PI_NO_HANDLE , "no handle available"], + [PI_BAD_HANDLE , "unknown handle"], + [_PI_BAD_IF_FLAGS , "ifFlags > 4"], + [_PI_BAD_CHANNEL , "DMA channel not 0-14"], + [_PI_BAD_SOCKET_PORT , "socket port not 1024-30000"], + [_PI_BAD_FIFO_COMMAND , "unknown fifo command"], + [_PI_BAD_SECO_CHANNEL , "DMA secondary channel not 0-14"], + [_PI_NOT_INITIALISED , "function called before gpioInitialise"], + [_PI_INITIALISED , "function called after gpioInitialise"], + [_PI_BAD_WAVE_MODE , "waveform mode not 0-1"], + [_PI_BAD_CFG_INTERNAL , "bad parameter in gpioCfgInternals call"], + [PI_BAD_WAVE_BAUD , "baud rate not 50-250000(RX)/1000000(TX)"], + [PI_TOO_MANY_PULSES , "waveform has too many pulses"], + [PI_TOO_MANY_CHARS , "waveform has too many chars"], + [PI_NOT_SERIAL_GPIO , "no bit bang serial read in progress on GPIO"], + [PI_NOT_PERMITTED , "no permission to update GPIO"], + [PI_SOME_PERMITTED , "no permission to update one or more GPIO"], + [PI_BAD_WVSC_COMMND , "bad WVSC subcommand"], + [PI_BAD_WVSM_COMMND , "bad WVSM subcommand"], + [PI_BAD_WVSP_COMMND , "bad WVSP subcommand"], + [PI_BAD_PULSELEN , "trigger pulse length not 1-100"], + [PI_BAD_SCRIPT , "invalid script"], + [PI_BAD_SCRIPT_ID , "unknown script id"], + [PI_BAD_SER_OFFSET , "add serial data offset > 30 minute"], + [PI_GPIO_IN_USE , "GPIO already in use"], + [PI_BAD_SERIAL_COUNT , "must read at least a byte at a time"], + [PI_BAD_PARAM_NUM , "script parameter id not 0-9"], + [PI_DUP_TAG , "script has duplicate tag"], + [PI_TOO_MANY_TAGS , "script has too many tags"], + [PI_BAD_SCRIPT_CMD , "illegal script command"], + [PI_BAD_VAR_NUM , "script variable id not 0-149"], + [PI_NO_SCRIPT_ROOM , "no more room for scripts"], + [PI_NO_MEMORY , "can't allocate temporary memory"], + [PI_SOCK_READ_FAILED , "socket read failed"], + [PI_SOCK_WRIT_FAILED , "socket write failed"], + [PI_TOO_MANY_PARAM , "too many script parameters (> 10)"], + [PI_SCRIPT_NOT_READY , "script initialising"], + [PI_BAD_TAG , "script has unresolved tag"], + [PI_BAD_MICS_DELAY , "bad MICS delay (too large)"], + [PI_BAD_MILS_DELAY , "bad MILS delay (too large)"], + [PI_BAD_WAVE_ID , "non existent wave id"], + [PI_TOO_MANY_CBS , "No more CBs for waveform"], + [PI_TOO_MANY_OOL , "No more OOL for waveform"], + [PI_EMPTY_WAVEFORM , "attempt to create an empty waveform"], + [PI_NO_WAVEFORM_ID , "No more waveform ids"], + [PI_I2C_OPEN_FAILED , "can't open I2C device"], + [PI_SER_OPEN_FAILED , "can't open serial device"], + [PI_SPI_OPEN_FAILED , "can't open SPI device"], + [PI_BAD_I2C_BUS , "bad I2C bus"], + [PI_BAD_I2C_ADDR , "bad I2C address"], + [PI_BAD_SPI_CHANNEL , "bad SPI channel"], + [PI_BAD_FLAGS , "bad i2c/spi/ser open flags"], + [PI_BAD_SPI_SPEED , "bad SPI speed"], + [PI_BAD_SER_DEVICE , "bad serial device name"], + [PI_BAD_SER_SPEED , "bad serial baud rate"], + [PI_BAD_PARAM , "bad i2c/spi/ser parameter"], + [PI_I2C_WRITE_FAILED , "I2C write failed"], + [PI_I2C_READ_FAILED , "I2C read failed"], + [PI_BAD_SPI_COUNT , "bad SPI count"], + [PI_SER_WRITE_FAILED , "ser write failed"], + [PI_SER_READ_FAILED , "ser read failed"], + [PI_SER_READ_NO_DATA , "ser read no data available"], + [PI_UNKNOWN_COMMAND , "unknown command"], + [PI_SPI_XFER_FAILED , "SPI xfer/read/write failed"], + [_PI_BAD_POINTER , "bad (NULL) pointer"], + [PI_NO_AUX_SPI , "no auxiliary SPI on Pi A or B"], + [PI_NOT_PWM_GPIO , "GPIO is not in use for PWM"], + [PI_NOT_SERVO_GPIO , "GPIO is not in use for servo pulses"], + [PI_NOT_HCLK_GPIO , "GPIO has no hardware clock"], + [PI_NOT_HPWM_GPIO , "GPIO has no hardware PWM"], + [PI_BAD_HPWM_FREQ , "hardware PWM frequency not 1-125M"], + [PI_BAD_HPWM_DUTY , "hardware PWM dutycycle not 0-1M"], + [PI_BAD_HCLK_FREQ , "hardware clock frequency not 4689-250M"], + [PI_BAD_HCLK_PASS , "need password to use hardware clock 1"], + [PI_HPWM_ILLEGAL , "illegal, PWM in use for main clock"], + [PI_BAD_DATABITS , "serial data bits not 1-32"], + [PI_BAD_STOPBITS , "serial (half) stop bits not 2-8"], + [PI_MSG_TOOBIG , "socket/pipe message too big"], + [PI_BAD_MALLOC_MODE , "bad memory allocation mode"], + [_PI_TOO_MANY_SEGS , "too many I2C transaction segments"], + [_PI_BAD_I2C_SEG , "an I2C transaction segment failed"], + [PI_BAD_SMBUS_CMD , "SMBus command not supported"], + [PI_NOT_I2C_GPIO , "no bit bang I2C in progress on GPIO"], + [PI_BAD_I2C_WLEN , "bad I2C write length"], + [PI_BAD_I2C_RLEN , "bad I2C read length"], + [PI_BAD_I2C_CMD , "bad I2C command"], + [PI_BAD_I2C_BAUD , "bad I2C baud rate, not 50-500k"], + [PI_CHAIN_LOOP_CNT , "bad chain loop count"], + [PI_BAD_CHAIN_LOOP , "empty chain loop"], + [PI_CHAIN_COUNTER , "too many chain counters"], + [PI_BAD_CHAIN_CMD , "bad chain command"], + [PI_BAD_CHAIN_DELAY , "bad chain delay micros"], + [PI_CHAIN_NESTING , "chain counters nested too deeply"], + [PI_CHAIN_TOO_BIG , "chain is too long"], + [PI_DEPRECATED , "deprecated function removed"], + [PI_BAD_SER_INVERT , "bit bang serial invert not 0 or 1"], + [_PI_BAD_EDGE , "bad ISR edge value, not 0-2"], + [_PI_BAD_ISR_INIT , "bad ISR initialisation"], + [PI_BAD_FOREVER , "loop forever must be last chain command"], + [PI_BAD_FILTER , "bad filter parameter"], + [PI_BAD_PAD , "bad pad number"], + [PI_BAD_STRENGTH , "bad pad drive strength"], + [PI_FIL_OPEN_FAILED , "file open failed"], + [PI_BAD_FILE_MODE , "bad file mode"], + [PI_BAD_FILE_FLAG , "bad file flag"], + [PI_BAD_FILE_READ , "bad file read"], + [PI_BAD_FILE_WRITE , "bad file write"], + [PI_FILE_NOT_ROPEN , "file not open for read"], + [PI_FILE_NOT_WOPEN , "file not open for write"], + [PI_BAD_FILE_SEEK , "bad file seek"], + [PI_NO_FILE_MATCH , "no files match pattern"], + [PI_NO_FILE_ACCESS , "no permission to access file"], + [PI_FILE_IS_A_DIR , "file is a directory"], + [PI_BAD_SHELL_STATUS , "bad shell return status"], + [PI_BAD_SCRIPT_NAME , "bad script name"], + [PI_BAD_SPI_BAUD , "bad SPI baud rate, not 50-500k"], + [PI_NOT_SPI_GPIO , "no bit bang SPI in progress on GPIO"], + [PI_BAD_EVENT_ID , "bad event id"], + [PI_CMD_INTERRUPTED , "pigpio command interrupted"], +] + +_except_a = "%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%\n{}" + +_except_z = "%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%" + +_except_1 = """ +Did you start the pigpio daemon? E.g. sudo pigpiod + +Did you specify the correct Pi host/port in the environment +variables PIGPIO_ADDR/PIGPIO_PORT? +E.g. export PIGPIO_ADDR=soft, export PIGPIO_PORT=8888 + +Did you specify the correct Pi host/port in the +pigpio.pi() function? E.g. pigpio.pi('soft', 8888)""" + +_except_2 = """ +Do you have permission to access the pigpio daemon? +Perhaps it was started with sudo pigpiod -nlocalhost""" + +_except_3 = """ +Can't create callback thread. +Perhaps too many simultaneous pigpio connections.""" + +class _socklock: + """ + A class to store socket and lock. + """ + def __init__(self): + self.s = None + self.l = threading.Lock() + +class error(Exception): + """pigpio module exception""" + def __init__(self, value): + self.value = value + def __str__(self): + return repr(self.value) + +class pulse: + """ + A class to store pulse information. + """ + + def __init__(self, gpio_on, gpio_off, delay): + """ + Initialises a pulse. + + gpio_on:= the GPIO to switch on at the start of the pulse. + gpio_off:= the GPIO to switch off at the start of the pulse. + delay:= the delay in microseconds before the next pulse. + + """ + self.gpio_on = gpio_on + self.gpio_off = gpio_off + self.delay = delay + +def error_text(errnum): + """ + Returns a text description of a pigpio error. + + errnum:= <0, the error number + + ... + print(pigpio.error_text(-5)) + level not 0-1 + ... + """ + for e in _errors: + if e[0] == errnum: + return e[1] + return "unknown error ({})".format(errnum) + +def tickDiff(t1, t2): + """ + Returns the microsecond difference between two ticks. + + t1:= the earlier tick + t2:= the later tick + + ... + print(pigpio.tickDiff(4294967272, 12)) + 36 + ... + """ + tDiff = t2 - t1 + if tDiff < 0: + tDiff += (1 << 32) + return tDiff + +# A couple of hacks to cope with different string handling +# between various Python versions +# 3 != 2.7.8 != 2.7.3 + +if sys.hexversion < 0x03000000: + def _b(x): + return x +else: + def _b(x): + return x.encode('latin-1') + +if sys.hexversion < 0x02070800: + def _str(x): + return buffer(x) +else: + def _str(x): + return x + +def u2i(uint32): + """ + Converts a 32 bit unsigned number to signed. + + uint32:= an unsigned 32 bit number + + ... + print(u2i(4294967272)) + -24 + print(u2i(37)) + 37 + ... + """ + mask = (2 ** 32) - 1 + if uint32 & (1 << 31): + v = uint32 | ~mask + else: + v = uint32 & mask + return v + +def _u2i(uint32): + """ + Converts a 32 bit unsigned number to signed. If the number + is negative it indicates an error. On error a pigpio + exception will be raised if exceptions is True. + """ + v = u2i(uint32) + if v < 0: + if exceptions: + raise error(error_text(v)) + return v + +def _pigpio_command(sl, cmd, p1, p2): + """ + Runs a pigpio socket command. + + sl:= command socket and lock. + cmd:= the command to be executed. + p1:= command parameter 1 (if applicable). + p2:= command parameter 2 (if applicable). + """ + res = PI_CMD_INTERRUPTED + with sl.l: + sl.s.send(struct.pack('IIII', cmd, p1, p2, 0)) + dummy, res = struct.unpack('12sI', sl.s.recv(_SOCK_CMD_LEN)) + return res + +def _pigpio_command_nolock(sl, cmd, p1, p2): + """ + Runs a pigpio socket command. + + sl:= command socket and lock. + cmd:= the command to be executed. + p1:= command parameter 1 (if applicable). + p2:= command parameter 2 (if applicable). + """ + res = PI_CMD_INTERRUPTED + sl.s.send(struct.pack('IIII', cmd, p1, p2, 0)) + dummy, res = struct.unpack('12sI', sl.s.recv(_SOCK_CMD_LEN)) + return res + +def _pigpio_command_ext(sl, cmd, p1, p2, p3, extents): + """ + Runs an extended pigpio socket command. + + sl:= command socket and lock. + cmd:= the command to be executed. + p1:= command parameter 1 (if applicable). + p2:= command parameter 2 (if applicable). + p3:= total size in bytes of following extents + extents:= additional data blocks + """ + ext = bytearray(struct.pack('IIII', cmd, p1, p2, p3)) + for x in extents: + if type(x) == type(""): + ext.extend(_b(x)) + else: + ext.extend(x) + res = PI_CMD_INTERRUPTED + with sl.l: + sl.s.sendall(ext) + dummy, res = struct.unpack('12sI', sl.s.recv(_SOCK_CMD_LEN)) + return res + +def _pigpio_command_ext_nolock(sl, cmd, p1, p2, p3, extents): + """ + Runs an extended pigpio socket command. + + sl:= command socket and lock. + cmd:= the command to be executed. + p1:= command parameter 1 (if applicable). + p2:= command parameter 2 (if applicable). + p3:= total size in bytes of following extents + extents:= additional data blocks + """ + res = PI_CMD_INTERRUPTED + ext = bytearray(struct.pack('IIII', cmd, p1, p2, p3)) + for x in extents: + if type(x) == type(""): + ext.extend(_b(x)) + else: + ext.extend(x) + sl.s.sendall(ext) + dummy, res = struct.unpack('12sI', sl.s.recv(_SOCK_CMD_LEN)) + return res + +class _event_ADT: + """ + An ADT class to hold event callback information. + """ + + def __init__(self, event, func): + """ + Initialises an event callback ADT. + + event:= the event id. + func:= a user function taking one argument, the event id. + """ + self.event = event + self.func = func + self.bit = 1<= MSG_SIZ: + msgbuf = buf[offset:offset + MSG_SIZ] + offset += MSG_SIZ + seq, flags, tick, level = (struct.unpack('HHII', msgbuf)) + + if flags == 0: + changed = level ^ lastLevel + lastLevel = level + for cb in self.callbacks: + if cb.bit & changed: + newLevel = 0 + if cb.bit & level: + newLevel = 1 + if (cb.edge ^ newLevel): + cb.func(cb.gpio, newLevel, tick) + else: + if flags & NTFY_FLAGS_WDOG: + gpio = flags & NTFY_FLAGS_GPIO + for cb in self.callbacks: + if cb.gpio == gpio: + cb.func(gpio, TIMEOUT, tick) + elif flags & NTFY_FLAGS_EVENT: + event = flags & NTFY_FLAGS_GPIO + for cb in self.events: + if cb.event == event: + cb.func(event, tick) + buf = buf[offset:] + + self.sl.s.close() + +class _callback: + """A class to provide GPIO level change callbacks.""" + + def __init__(self, notify, user_gpio, edge=RISING_EDGE, func=None): + """ + Initialise a callback and adds it to the notification thread. + """ + self._notify = notify + self.count=0 + self._reset = False + if func is None: + func=self._tally + self.callb = _callback_ADT(user_gpio, edge, func) + self._notify.append(self.callb) + + def cancel(self): + """Cancels a callback by removing it from the notification thread.""" + self._notify.remove(self.callb) + + def _tally(self, user_gpio, level, tick): + """Increment the callback called count.""" + if self._reset: + self._reset = False + self.count = 0 + self.count += 1 + + def tally(self): + """ + Provides a count of how many times the default tally + callback has triggered. + + The count will be zero if the user has supplied their own + callback function. + """ + return self.count + + def reset_tally(self): + """ + Resets the tally count to zero. + """ + self._reset = True + self.count = 0 + +class _event: + """A class to provide event callbacks.""" + + def __init__(self, notify, event, func=None): + """ + Initialise an event and adds it to the notification thread. + """ + self._notify = notify + self.count=0 + self._reset = False + if func is None: + func=self._tally + self.callb = _event_ADT(event, func) + self._notify.append_event(self.callb) + + def cancel(self): + """ + Cancels a event callback by removing it from the + notification thread. + """ + self._notify.remove_event(self.callb) + + def _tally(self, event, tick): + """Increment the event callback called count.""" + if self._reset: + self._reset = False + self.count = 0 + self.count += 1 + + def tally(self): + """ + Provides a count of how many times the default tally + callback has triggered. + + The count will be zero if the user has supplied their own + callback function. + """ + return self.count + + def reset_tally(self): + """ + Resets the tally count to zero. + """ + self._reset = True + self.count = 0 + +class _wait_for_edge: + """Encapsulates waiting for GPIO edges.""" + + def __init__(self, notify, gpio, edge, timeout): + """Initialises a wait_for_edge.""" + self._notify = notify + self.callb = _callback_ADT(gpio, edge, self.func) + self.trigger = False + self._notify.append(self.callb) + self.start = time.time() + while (self.trigger == False) and ((time.time()-self.start) < timeout): + time.sleep(0.05) + self._notify.remove(self.callb) + + def func(self, gpio, level, tick): + """Sets wait_for_edge triggered.""" + self.trigger = True + +class _wait_for_event: + """Encapsulates waiting for an event.""" + + def __init__(self, notify, event, timeout): + """Initialises wait_for_event.""" + self._notify = notify + self.callb = _event_ADT(event, self.func) + self.trigger = False + self._notify.append_event(self.callb) + self.start = time.time() + while (self.trigger == False) and ((time.time()-self.start) < timeout): + time.sleep(0.05) + self._notify.remove_event(self.callb) + + def func(self, event, tick): + """Sets wait_for_event triggered.""" + self.trigger = True + +class pi(): + + def _rxbuf(self, count): + """Returns count bytes from the command socket.""" + ext = bytearray(self.sl.s.recv(count)) + while len(ext) < count: + ext.extend(self.sl.s.recv(count - len(ext))) + return ext + + def set_mode(self, gpio, mode): + """ + Sets the GPIO mode. + + gpio:= 0-53. + mode:= INPUT, OUTPUT, ALT0, ALT1, ALT2, ALT3, ALT4, ALT5. + + ... + pi.set_mode( 4, pigpio.INPUT) # GPIO 4 as input + pi.set_mode(17, pigpio.OUTPUT) # GPIO 17 as output + pi.set_mode(24, pigpio.ALT2) # GPIO 24 as ALT2 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_MODES, gpio, mode)) + + def get_mode(self, gpio): + """ + Returns the GPIO mode. + + gpio:= 0-53. + + Returns a value as follows + + . . + 0 = INPUT + 1 = OUTPUT + 2 = ALT5 + 3 = ALT4 + 4 = ALT0 + 5 = ALT1 + 6 = ALT2 + 7 = ALT3 + . . + + ... + print(pi.get_mode(0)) + 4 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_MODEG, gpio, 0)) + + def set_pull_up_down(self, gpio, pud): + """ + Sets or clears the internal GPIO pull-up/down resistor. + + gpio:= 0-53. + pud:= PUD_UP, PUD_DOWN, PUD_OFF. + + ... + pi.set_pull_up_down(17, pigpio.PUD_OFF) + pi.set_pull_up_down(23, pigpio.PUD_UP) + pi.set_pull_up_down(24, pigpio.PUD_DOWN) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PUD, gpio, pud)) + + def read(self, gpio): + """ + Returns the GPIO level. + + gpio:= 0-53. + + ... + pi.set_mode(23, pigpio.INPUT) + + pi.set_pull_up_down(23, pigpio.PUD_DOWN) + print(pi.read(23)) + 0 + + pi.set_pull_up_down(23, pigpio.PUD_UP) + print(pi.read(23)) + 1 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_READ, gpio, 0)) + + def write(self, gpio, level): + """ + Sets the GPIO level. + + GPIO:= 0-53. + level:= 0, 1. + + If PWM or servo pulses are active on the GPIO they are + switched off. + + ... + pi.set_mode(17, pigpio.OUTPUT) + + pi.write(17,0) + print(pi.read(17)) + 0 + + pi.write(17,1) + print(pi.read(17)) + 1 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WRITE, gpio, level)) + + def set_PWM_dutycycle(self, user_gpio, dutycycle): + """ + Starts (non-zero dutycycle) or stops (0) PWM pulses on the GPIO. + + user_gpio:= 0-31. + dutycycle:= 0-range (range defaults to 255). + + The [*set_PWM_range*] function can change the default range of 255. + + ... + pi.set_PWM_dutycycle(4, 0) # PWM off + pi.set_PWM_dutycycle(4, 64) # PWM 1/4 on + pi.set_PWM_dutycycle(4, 128) # PWM 1/2 on + pi.set_PWM_dutycycle(4, 192) # PWM 3/4 on + pi.set_PWM_dutycycle(4, 255) # PWM full on + ... + """ + return _u2i(_pigpio_command( + self.sl, _PI_CMD_PWM, user_gpio, int(dutycycle))) + + def get_PWM_dutycycle(self, user_gpio): + """ + Returns the PWM dutycycle being used on the GPIO. + + user_gpio:= 0-31. + + Returns the PWM dutycycle. + + + For normal PWM the dutycycle will be out of the defined range + for the GPIO (see [*get_PWM_range*]). + + If a hardware clock is active on the GPIO the reported + dutycycle will be 500000 (500k) out of 1000000 (1M). + + If hardware PWM is active on the GPIO the reported dutycycle + will be out of a 1000000 (1M). + + ... + pi.set_PWM_dutycycle(4, 25) + print(pi.get_PWM_dutycycle(4)) + 25 + + pi.set_PWM_dutycycle(4, 203) + print(pi.get_PWM_dutycycle(4)) + 203 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_GDC, user_gpio, 0)) + + def set_PWM_range(self, user_gpio, range_): + """ + Sets the range of PWM values to be used on the GPIO. + + user_gpio:= 0-31. + range_:= 25-40000. + + ... + pi.set_PWM_range(9, 100) # now 25 1/4, 50 1/2, 75 3/4 on + pi.set_PWM_range(9, 500) # now 125 1/4, 250 1/2, 375 3/4 on + pi.set_PWM_range(9, 3000) # now 750 1/4, 1500 1/2, 2250 3/4 on + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PRS, user_gpio, range_)) + + def get_PWM_range(self, user_gpio): + """ + Returns the range of PWM values being used on the GPIO. + + user_gpio:= 0-31. + + If a hardware clock or hardware PWM is active on the GPIO + the reported range will be 1000000 (1M). + + ... + pi.set_PWM_range(9, 500) + print(pi.get_PWM_range(9)) + 500 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PRG, user_gpio, 0)) + + def get_PWM_real_range(self, user_gpio): + """ + Returns the real (underlying) range of PWM values being + used on the GPIO. + + user_gpio:= 0-31. + + If a hardware clock is active on the GPIO the reported + real range will be 1000000 (1M). + + If hardware PWM is active on the GPIO the reported real range + will be approximately 250M divided by the set PWM frequency. + + ... + pi.set_PWM_frequency(4, 800) + print(pi.get_PWM_real_range(4)) + 250 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PRRG, user_gpio, 0)) + + def set_PWM_frequency(self, user_gpio, frequency): + """ + Sets the frequency (in Hz) of the PWM to be used on the GPIO. + + user_gpio:= 0-31. + frequency:= >=0 Hz + + Returns the numerically closest frequency if OK, otherwise + PI_BAD_USER_GPIO or PI_NOT_PERMITTED. + + If PWM is currently active on the GPIO it will be switched + off and then back on at the new frequency. + + Each GPIO can be independently set to one of 18 different + PWM frequencies. + + The selectable frequencies depend upon the sample rate which + may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The + sample rate is set when the pigpio daemon is started. + + The frequencies for each sample rate are: + + . . + Hertz + + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 + 1250 1000 800 500 400 250 200 100 50 + + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 + 625 500 400 250 200 125 100 50 25 + + 4: 10000 5000 2500 2000 1250 1000 625 500 400 + 313 250 200 125 100 63 50 25 13 + sample + rate + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 + 250 200 160 100 80 50 40 20 10 + + 8: 5000 2500 1250 1000 625 500 313 250 200 + 156 125 100 63 50 31 25 13 6 + + 10: 4000 2000 1000 800 500 400 250 200 160 + 125 100 80 50 40 25 20 10 5 + . . + + ... + pi.set_PWM_frequency(4,0) + print(pi.get_PWM_frequency(4)) + 10 + + pi.set_PWM_frequency(4,100000) + print(pi.get_PWM_frequency(4)) + 8000 + ... + """ + return _u2i( + _pigpio_command(self.sl, _PI_CMD_PFS, user_gpio, frequency)) + + def get_PWM_frequency(self, user_gpio): + """ + Returns the frequency of PWM being used on the GPIO. + + user_gpio:= 0-31. + + Returns the frequency (in Hz) used for the GPIO. + + For normal PWM the frequency will be that defined for the GPIO + by [*set_PWM_frequency*]. + + If a hardware clock is active on the GPIO the reported frequency + will be that set by [*hardware_clock*]. + + If hardware PWM is active on the GPIO the reported frequency + will be that set by [*hardware_PWM*]. + + ... + pi.set_PWM_frequency(4,0) + print(pi.get_PWM_frequency(4)) + 10 + + pi.set_PWM_frequency(4, 800) + print(pi.get_PWM_frequency(4)) + 800 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PFG, user_gpio, 0)) + + def set_servo_pulsewidth(self, user_gpio, pulsewidth): + """ + Starts (500-2500) or stops (0) servo pulses on the GPIO. + + user_gpio:= 0-31. + pulsewidth:= 0 (off), + 500 (most anti-clockwise) - 2500 (most clockwise). + + The selected pulsewidth will continue to be transmitted until + changed by a subsequent call to set_servo_pulsewidth. + + The pulsewidths supported by servos varies and should probably + be determined by experiment. A value of 1500 should always be + safe and represents the mid-point of rotation. + + You can DAMAGE a servo if you command it to move beyond its + limits. + + ... + pi.set_servo_pulsewidth(17, 0) # off + pi.set_servo_pulsewidth(17, 1000) # safe anti-clockwise + pi.set_servo_pulsewidth(17, 1500) # centre + pi.set_servo_pulsewidth(17, 2000) # safe clockwise + ... + """ + return _u2i(_pigpio_command( + self.sl, _PI_CMD_SERVO, user_gpio, int(pulsewidth))) + + def get_servo_pulsewidth(self, user_gpio): + """ + Returns the servo pulsewidth being used on the GPIO. + + user_gpio:= 0-31. + + Returns the servo pulsewidth. + + ... + pi.set_servo_pulsewidth(4, 525) + print(pi.get_servo_pulsewidth(4)) + 525 + + pi.set_servo_pulsewidth(4, 2130) + print(pi.get_servo_pulsewidth(4)) + 2130 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_GPW, user_gpio, 0)) + + def notify_open(self): + """ + Returns a notification handle (>=0). + + A notification is a method for being notified of GPIO state + changes via a pipe. + + Pipes are only accessible from the local machine so this + function serves no purpose if you are using Python from a + remote machine. The in-built (socket) notifications + provided by [*callback*] should be used instead. + + Notifications for handle x will be available at the pipe + named /dev/pigpiox (where x is the handle number). + + E.g. if the function returns 15 then the notifications must be + read from /dev/pigpio15. + + Notifications have the following structure: + + . . + H seqno + H flags + I tick + I level + . . + + seqno: starts at 0 each time the handle is opened and then + increments by one for each report. + + flags: three flags are defined, PI_NTFY_FLAGS_WDOG, + PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT. + + If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the + flags indicate a GPIO which has had a watchdog timeout. + + If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep + alive signal on the pipe/socket and is sent once a minute + in the absence of other notification activity. + + If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the + flags indicate an event which has been triggered. + + + tick: the number of microseconds since system boot. It wraps + around after 1h12m. + + level: indicates the level of each GPIO. If bit 1<= 0: + pi.notify_begin(h, 1234) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_NO, 0, 0)) + + def notify_begin(self, handle, bits): + """ + Starts notifications on a handle. + + handle:= >=0 (as returned by a prior call to [*notify_open*]) + bits:= a 32 bit mask indicating the GPIO to be notified. + + The notification sends state changes for each GPIO whose + corresponding bit in bits is set. + + The following code starts notifications for GPIO 1, 4, + 6, 7, and 10 (1234 = 0x04D2 = 0b0000010011010010). + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_NB, handle, bits)) + + def notify_pause(self, handle): + """ + Pauses notifications on a handle. + + handle:= >=0 (as returned by a prior call to [*notify_open*]) + + Notifications for the handle are suspended until + [*notify_begin*] is called again. + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + pi.notify_pause(h) + ... + pi.notify_begin(h, 1234) + ... + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_NB, handle, 0)) + + def notify_close(self, handle): + """ + Stops notifications on a handle and releases the handle for reuse. + + handle:= >=0 (as returned by a prior call to [*notify_open*]) + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + pi.notify_close(h) + ... + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_NC, handle, 0)) + + def set_watchdog(self, user_gpio, wdog_timeout): + """ + Sets a watchdog timeout for a GPIO. + + user_gpio:= 0-31. + wdog_timeout:= 0-60000. + + The watchdog is nominally in milliseconds. + + Only one watchdog may be registered per GPIO. + + The watchdog may be cancelled by setting timeout to 0. + + Once a watchdog has been started callbacks for the GPIO + will be triggered every timeout interval after the last + GPIO activity. + + The callback will receive the special level TIMEOUT. + + ... + pi.set_watchdog(23, 1000) # 1000 ms watchdog on GPIO 23 + pi.set_watchdog(23, 0) # cancel watchdog on GPIO 23 + ... + """ + return _u2i(_pigpio_command( + self.sl, _PI_CMD_WDOG, user_gpio, int(wdog_timeout))) + + def read_bank_1(self): + """ + Returns the levels of the bank 1 GPIO (GPIO 0-31). + + The returned 32 bit integer has a bit set if the corresponding + GPIO is high. GPIO n has bit value (1<=0) if OK, otherwise PI_EMPTY_WAVEFORM, + PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID. + + The data provided by the [*wave_add_**] functions is consumed by + this function. + + As many waveforms may be created as there is space available. + The wave id is passed to [*wave_send_**] to specify the waveform + to transmit. + + Normal usage would be + + Step 1. [*wave_clear*] to clear all waveforms and added data. + + Step 2. [*wave_add_**] calls to supply the waveform data. + + Step 3. [*wave_create*] to create the waveform and get a unique id + + Repeat steps 2 and 3 as needed. + + Step 4. [*wave_send_**] with the id of the waveform to transmit. + + A waveform comprises one or more pulses. + + A pulse specifies + + 1) the GPIO to be switched on at the start of the pulse. + 2) the GPIO to be switched off at the start of the pulse. + 3) the delay in microseconds before the next pulse. + + Any or all the fields can be zero. It doesn't make any sense + to set all the fields to zero (the pulse will be ignored). + + When a waveform is started each pulse is executed in order with + the specified delay between the pulse and the next. + + ... + wid = pi.wave_create() + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVCRE, 0, 0)) + + def wave_delete(self, wave_id): + """ + This function deletes the waveform with id wave_id. + + wave_id:= >=0 (as returned by a prior call to [*wave_create*]). + + Wave ids are allocated in order, 0, 1, 2, etc. + + The wave is flagged for deletion. The resources used by the wave + will only be reused when either of the following apply. + + - all waves with higher numbered wave ids have been deleted or have + been flagged for deletion. + + - a new wave is created which uses exactly the same resources as + the current wave (see the C source for gpioWaveCreate for details). + + ... + pi.wave_delete(6) # delete waveform with id 6 + + pi.wave_delete(0) # delete waveform with id 0 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVDEL, wave_id, 0)) + + def wave_tx_start(self): # DEPRECATED + """ + This function is deprecated and has been removed. + + Use [*wave_create*]/[*wave_send_**] instead. + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVGO, 0, 0)) + + def wave_tx_repeat(self): # DEPRECATED + """ + This function is deprecated and has beeen removed. + + Use [*wave_create*]/[*wave_send_**] instead. + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVGOR, 0, 0)) + + def wave_send_once(self, wave_id): + """ + Transmits the waveform with id wave_id. The waveform is sent + once. + + NOTE: Any hardware PWM started by [*hardware_PWM*] will + be cancelled. + + wave_id:= >=0 (as returned by a prior call to [*wave_create*]). + + Returns the number of DMA control blocks used in the waveform. + + ... + cbs = pi.wave_send_once(wid) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVTX, wave_id, 0)) + + def wave_send_repeat(self, wave_id): + """ + Transmits the waveform with id wave_id. The waveform repeats + until wave_tx_stop is called or another call to [*wave_send_**] + is made. + + NOTE: Any hardware PWM started by [*hardware_PWM*] will + be cancelled. + + wave_id:= >=0 (as returned by a prior call to [*wave_create*]). + + Returns the number of DMA control blocks used in the waveform. + + ... + cbs = pi.wave_send_repeat(wid) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVTXR, wave_id, 0)) + + def wave_send_using_mode(self, wave_id, mode): + """ + Transmits the waveform with id wave_id using mode mode. + + wave_id:= >=0 (as returned by a prior call to [*wave_create*]). + mode:= WAVE_MODE_ONE_SHOT, WAVE_MODE_REPEAT, + WAVE_MODE_ONE_SHOT_SYNC, or WAVE_MODE_REPEAT_SYNC. + + WAVE_MODE_ONE_SHOT: same as [*wave_send_once*]. + + WAVE_MODE_REPEAT same as [*wave_send_repeat*]. + + WAVE_MODE_ONE_SHOT_SYNC same as [*wave_send_once*] but tries + to sync with the previous waveform. + + WAVE_MODE_REPEAT_SYNC same as [*wave_send_repeat*] but tries + to sync with the previous waveform. + + WARNING: bad things may happen if you delete the previous + waveform before it has been synced to the new waveform. + + NOTE: Any hardware PWM started by [*hardware_PWM*] will + be cancelled. + + wave_id:= >=0 (as returned by a prior call to [*wave_create*]). + + Returns the number of DMA control blocks used in the waveform. + + ... + cbs = pi.wave_send_using_mode(wid, WAVE_MODE_REPEAT_SYNC) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVTXM, wave_id, mode)) + + def wave_tx_at(self): + """ + Returns the id of the waveform currently being + transmitted. + + Returns the waveform id or one of the following special + values: + + WAVE_NOT_FOUND (9998) - transmitted wave not found. + NO_TX_WAVE (9999) - no wave being transmitted. + + ... + wid = pi.wave_tx_at() + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVTAT, 0, 0)) + + def wave_tx_busy(self): + """ + Returns 1 if a waveform is currently being transmitted, + otherwise 0. + + ... + pi.wave_send_once(0) # send first waveform + + while pi.wave_tx_busy(): # wait for waveform to be sent + time.sleep(0.1) + + pi.wave_send_once(1) # send next waveform + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVBSY, 0, 0)) + + def wave_tx_stop(self): + """ + Stops the transmission of the current waveform. + + This function is intended to stop a waveform started with + wave_send_repeat. + + ... + pi.wave_send_repeat(3) + + time.sleep(5) + + pi.wave_tx_stop() + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_WVHLT, 0, 0)) + + def wave_chain(self, data): + """ + This function transmits a chain of waveforms. + + NOTE: Any hardware PWM started by [*hardware_PWM*] + will be cancelled. + + The waves to be transmitted are specified by the contents + of data which contains an ordered list of [*wave_id*]s + and optional command codes and related data. + + Returns 0 if OK, otherwise PI_CHAIN_NESTING, + PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, + PI_CHAIN_COUNTER, PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, + or PI_BAD_WAVE_ID. + + Each wave is transmitted in the order specified. A wave + may occur multiple times per chain. + + A blocks of waves may be transmitted multiple times by + using the loop commands. The block is bracketed by loop + start and end commands. Loops may be nested. + + Delays between waves may be added with the delay command. + + The following command codes are supported: + + Name @ Cmd & Data @ Meaning + Loop Start @ 255 0 @ Identify start of a wave block + Loop Repeat @ 255 1 x y @ loop x + y*256 times + Delay @ 255 2 x y @ delay x + y*256 microseconds + Loop Forever @ 255 3 @ loop forever + + If present Loop Forever must be the last entry in the chain. + + The code is currently dimensioned to support a chain with + roughly 600 entries and 20 loop counters. + + ... + #!/usr/bin/env python + + import time + import pigpio + + WAVES=5 + GPIO=4 + + wid=[0]*WAVES + + pi = pigpio.pi() # Connect to local Pi. + + pi.set_mode(GPIO, pigpio.OUTPUT); + + for i in range(WAVES): + pi.wave_add_generic([ + pigpio.pulse(1<=0) for the device at the I2C bus address. + + i2c_bus:= >=0. + i2c_address:= 0-0x7F. + i2c_flags:= 0, no flags are currently defined. + + Physically buses 0 and 1 are available on the Pi. Higher + numbered buses will be available if a kernel supported bus + multiplexor is being used. + + The GPIO used are given in the following table. + + @ SDA @ SCL + I2C 0 @ 0 @ 1 + I2C 1 @ 2 @ 3 + + For the SMBus commands the low level transactions are shown + at the end of the function description. The following + abbreviations are used: + + . . + S (1 bit) : Start bit + P (1 bit) : Stop bit + Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. + A, NA (1 bit) : Accept and not accept bit. + Addr (7 bits): I2C 7 bit address. + reg (8 bits): Command byte, which often selects a register. + Data (8 bits): A data byte. + Count (8 bits): A byte defining the length of a block operation. + + [..]: Data sent by the device. + . . + + ... + h = pi.i2c_open(1, 0x53) # open device at address 0x53 on bus 1 + ... + """ + # I p1 i2c_bus + # I p2 i2c_addr + # I p3 4 + ## extension ## + # I i2c_flags + extents = [struct.pack("I", i2c_flags)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CO, i2c_bus, i2c_address, 4, extents)) + + def i2c_close(self, handle): + """ + Closes the I2C device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + + ... + pi.i2c_close(h) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_I2CC, handle, 0)) + + def i2c_write_quick(self, handle, bit): + """ + Sends a single bit to the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + bit:= 0 or 1, the value to write. + + SMBus 2.0 5.5.1 - Quick command. + . . + S Addr bit [A] P + . . + + ... + pi.i2c_write_quick(0, 1) # send 1 to device 0 + pi.i2c_write_quick(3, 0) # send 0 to device 3 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_I2CWQ, handle, bit)) + + def i2c_write_byte(self, handle, byte_val): + """ + Sends a single byte to the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + byte_val:= 0-255, the value to write. + + SMBus 2.0 5.5.2 - Send byte. + . . + S Addr Wr [A] byte_val [A] P + . . + + ... + pi.i2c_write_byte(1, 17) # send byte 17 to device 1 + pi.i2c_write_byte(2, 0x23) # send byte 0x23 to device 2 + ... + """ + return _u2i( + _pigpio_command(self.sl, _PI_CMD_I2CWS, handle, byte_val)) + + def i2c_read_byte(self, handle): + """ + Reads a single byte from the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + + SMBus 2.0 5.5.3 - Receive byte. + . . + S Addr Rd [A] [Data] NA P + . . + + ... + b = pi.i2c_read_byte(2) # read a byte from device 2 + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_I2CRS, handle, 0)) + + def i2c_write_byte_data(self, handle, reg, byte_val): + """ + Writes a single byte to the specified register of the device + associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + byte_val:= 0-255, the value to write. + + SMBus 2.0 5.5.4 - Write byte. + . . + S Addr Wr [A] reg [A] byte_val [A] P + . . + + ... + # send byte 0xC5 to reg 2 of device 1 + pi.i2c_write_byte_data(1, 2, 0xC5) + + # send byte 9 to reg 4 of device 2 + pi.i2c_write_byte_data(2, 4, 9) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I byte_val + extents = [struct.pack("I", byte_val)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CWB, handle, reg, 4, extents)) + + def i2c_write_word_data(self, handle, reg, word_val): + """ + Writes a single 16 bit word to the specified register of the + device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + word_val:= 0-65535, the value to write. + + SMBus 2.0 5.5.4 - Write word. + . . + S Addr Wr [A] reg [A] word_val_Low [A] word_val_High [A] P + . . + + ... + # send word 0xA0C5 to reg 5 of device 4 + pi.i2c_write_word_data(4, 5, 0xA0C5) + + # send word 2 to reg 2 of device 5 + pi.i2c_write_word_data(5, 2, 23) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I word_val + extents = [struct.pack("I", word_val)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CWW, handle, reg, 4, extents)) + + def i2c_read_byte_data(self, handle, reg): + """ + Reads a single byte from the specified register of the device + associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + + SMBus 2.0 5.5.5 - Read byte. + . . + S Addr Wr [A] reg [A] S Addr Rd [A] [Data] NA P + . . + + ... + # read byte from reg 17 of device 2 + b = pi.i2c_read_byte_data(2, 17) + + # read byte from reg 1 of device 0 + b = pi.i2c_read_byte_data(0, 1) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_I2CRB, handle, reg)) + + def i2c_read_word_data(self, handle, reg): + """ + Reads a single 16 bit word from the specified register of the + device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + + SMBus 2.0 5.5.5 - Read word. + . . + S Addr Wr [A] reg [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P + . . + + ... + # read word from reg 2 of device 3 + w = pi.i2c_read_word_data(3, 2) + + # read word from reg 7 of device 2 + w = pi.i2c_read_word_data(2, 7) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_I2CRW, handle, reg)) + + def i2c_process_call(self, handle, reg, word_val): + """ + Writes 16 bits of data to the specified register of the device + associated with handle and reads 16 bits of data in return. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + word_val:= 0-65535, the value to write. + + SMBus 2.0 5.5.6 - Process call. + . . + S Addr Wr [A] reg [A] word_val_Low [A] word_val_High [A] + S Addr Rd [A] [DataLow] A [DataHigh] NA P + . . + + ... + r = pi.i2c_process_call(h, 4, 0x1231) + r = pi.i2c_process_call(h, 6, 0) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I word_val + extents = [struct.pack("I", word_val)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CPC, handle, reg, 4, extents)) + + def i2c_write_block_data(self, handle, reg, data): + """ + Writes up to 32 bytes to the specified register of the device + associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + data:= the bytes to write. + + SMBus 2.0 5.5.7 - Block write. + . . + S Addr Wr [A] reg [A] len(data) [A] data0 [A] data1 [A] ... [A] + datan [A] P + . . + + ... + pi.i2c_write_block_data(4, 5, b'hello') + + pi.i2c_write_block_data(4, 5, "data bytes") + + pi.i2c_write_block_data(5, 0, b'\\x00\\x01\\x22') + + pi.i2c_write_block_data(6, 2, [0, 1, 0x22]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CWK, handle, reg, len(data), [data])) + else: + return 0 + + def i2c_read_block_data(self, handle, reg): + """ + Reads a block of up to 32 bytes from the specified register of + the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + + SMBus 2.0 5.5.7 - Block read. + . . + S Addr Wr [A] reg [A] + S Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P + . . + + The amount of returned data is set by the device. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_read_block_data(h, 10) + if b >= 0: + # process data + else: + # process read failure + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_nolock( + self.sl, _PI_CMD_I2CRK, handle, reg)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def i2c_block_process_call(self, handle, reg, data): + """ + Writes data bytes to the specified register of the device + associated with handle and reads a device specified number + of bytes of data in return. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + data:= the bytes to write. + + The SMBus 2.0 documentation states that a minimum of 1 byte may + be sent and a minimum of 1 byte may be received. The total + number of bytes sent/received must be 32 or less. + + SMBus 2.0 5.5.8 - Block write-block read. + . . + S Addr Wr [A] reg [A] len(data) [A] data0 [A] ... datan [A] + S Addr Rd [A] [Count] A [Data] ... A P + . . + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_block_process_call(h, 10, b'\\x02\\x05\\x00') + + (b, d) = pi.i2c_block_process_call(h, 10, b'abcdr') + + (b, d) = pi.i2c_block_process_call(h, 10, "abracad") + + (b, d) = pi.i2c_block_process_call(h, 10, [2, 5, 16]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_I2CPK, handle, reg, len(data), [data])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def i2c_write_i2c_block_data(self, handle, reg, data): + """ + Writes data bytes to the specified register of the device + associated with handle . 1-32 bytes may be written. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + data:= the bytes to write. + + . . + S Addr Wr [A] reg [A] data0 [A] data1 [A] ... [A] datan [NA] P + . . + + ... + pi.i2c_write_i2c_block_data(4, 5, 'hello') + + pi.i2c_write_i2c_block_data(4, 5, b'hello') + + pi.i2c_write_i2c_block_data(5, 0, b'\\x00\\x01\\x22') + + pi.i2c_write_i2c_block_data(6, 2, [0, 1, 0x22]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CWI, handle, reg, len(data), [data])) + else: + return 0 + + def i2c_read_i2c_block_data(self, handle, reg, count): + """ + Reads count bytes from the specified register of the device + associated with handle . The count may be 1-32. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + reg:= >=0, the device register. + count:= >0, the number of bytes to read. + + . . + S Addr Wr [A] reg [A] + S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P + . . + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_read_i2c_block_data(h, 4, 32) + if b >= 0: + # process data + else: + # process read failure + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I count + extents = [struct.pack("I", count)] + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_I2CRI, handle, reg, 4, extents)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def i2c_read_device(self, handle, count): + """ + Returns count bytes read from the raw device associated + with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + count:= >0, the number of bytes to read. + + . . + S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P + . . + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, data) = pi.i2c_read_device(h, 12) + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i( + _pigpio_command_nolock(self.sl, _PI_CMD_I2CRD, handle, count)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def i2c_write_device(self, handle, data): + """ + Writes the data bytes to the raw device associated with handle. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + data:= the bytes to write. + + . . + S Addr Wr [A] data0 [A] data1 [A] ... [A] datan [A] P + . . + + ... + pi.i2c_write_device(h, b"\\x12\\x34\\xA8") + + pi.i2c_write_device(h, b"help") + + pi.i2c_write_device(h, 'help') + + pi.i2c_write_device(h, [23, 56, 231]) + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_I2CWD, handle, 0, len(data), [data])) + else: + return 0 + + + def i2c_zip(self, handle, data): + """ + This function executes a sequence of I2C operations. The + operations to be performed are specified by the contents of data + which contains the concatenated command codes and associated data. + + handle:= >=0 (as returned by a prior call to [*i2c_open*]). + data:= the concatenated I2C commands, see below + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, data) = pi.i2c_zip(h, [4, 0x53, 7, 1, 0x32, 6, 6, 0]) + ... + + The following command codes are supported: + + Name @ Cmd & Data @ Meaning + End @ 0 @ No more commands + Escape @ 1 @ Next P is two bytes + On @ 2 @ Switch combined flag on + Off @ 3 @ Switch combined flag off + Address @ 4 P @ Set I2C address to P + Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) + Read @ 6 P @ Read P bytes of data + Write @ 7 P ... @ Write P bytes of data + + The address, read, and write commands take a parameter P. + Normally P is one byte (0-255). If the command is preceded by + the Escape command then P is two bytes (0-65535, least significant + byte first). + + The address defaults to that associated with the handle. + The flags default to 0. The address and flags maintain their + previous value until updated. + + Any read I2C data is concatenated in the returned bytearray. + + ... + Set address 0x53, write 0x32, read 6 bytes + Set address 0x1E, write 0x03, read 6 bytes + Set address 0x68, write 0x1B, read 8 bytes + End + + 0x04 0x53 0x07 0x01 0x32 0x06 0x06 + 0x04 0x1E 0x07 0x01 0x03 0x06 0x06 + 0x04 0x68 0x07 0x01 0x1B 0x06 0x08 + 0x00 + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_I2CZ, handle, 0, len(data), [data])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + + def bb_spi_open(self, CS, MISO, MOSI, SCLK, baud=100000, spi_flags=0): + """ + This function selects a set of GPIO for bit banging SPI at a + specified baud rate. + + CS := 0-31 + MISO := 0-31 + MOSI := 0-31 + SCLK := 0-31 + baud := 50-250000 + spiFlags := see below + + spiFlags consists of the least significant 22 bits. + + . . + 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m + . . + + mm defines the SPI mode, defaults to 0 + + . . + Mode CPOL CPHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 + . . + + The following constants may be used to set the mode: + + . . + pigpio.SPI_MODE_0 + pigpio.SPI_MODE_1 + pigpio.SPI_MODE_2 + pigpio.SPI_MODE_3 + . . + + Alternatively pigpio.SPI_CPOL and/or pigpio.SPI_CPHA + may be used. + + p is 0 if CS is active low (default) and 1 for active high. + pigpio.SPI_CS_HIGH_ACTIVE may be used to set this flag. + + T is 1 if the least significant bit is transmitted on MOSI first, + the default (0) shifts the most significant bit out first. + pigpio.SPI_TX_LSBFIRST may be used to set this flag. + + R is 1 if the least significant bit is received on MISO first, + the default (0) receives the most significant bit first. + pigpio.SPI_RX_LSBFIRST may be used to set this flag. + + The other bits in spiFlags should be set to zero. + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or + PI_GPIO_IN_USE. + + If more than one device is connected to the SPI bus (defined by + SCLK, MOSI, and MISO) each must have its own CS. + + ... + bb_spi_open(10, MISO, MOSI, SCLK, 10000, 0); // device 1 + bb_spi_open(11, MISO, MOSI, SCLK, 20000, 3); // device 2 + ... + """ + # I p1 CS + # I p2 0 + # I p3 20 + ## extension ## + # I MISO + # I MOSI + # I SCLK + # I baud + # I spi_flags + + extents = [struct.pack("IIIII", MISO, MOSI, SCLK, baud, spi_flags)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_BSPIO, CS, 0, 20, extents)) + + + def bb_spi_close(self, CS): + """ + This function stops bit banging SPI on a set of GPIO + opened with [*bb_spi_open*]. + + CS:= 0-31, the CS GPIO used in a prior call to [*bb_spi_open*] + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO. + + ... + pi.bb_spi_close(CS) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_BSPIC, CS, 0)) + + + def bb_spi_xfer(self, CS, data): + """ + This function executes a bit banged SPI transfer. + + CS:= 0-31 (as used in a prior call to [*bb_spi_open*]) + data:= data to be sent + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + #!/usr/bin/env python + + import pigpio + + CE0=5 + CE1=6 + MISO=13 + MOSI=19 + SCLK=12 + + pi = pigpio.pi() + if not pi.connected: + exit() + + pi.bb_spi_open(CE0, MISO, MOSI, SCLK, 10000, 0) # MCP4251 DAC + pi.bb_spi_open(CE1, MISO, MOSI, SCLK, 20000, 3) # MCP3008 ADC + + for i in range(256): + + count, data = pi.bb_spi_xfer(CE0, [0, i]) # Set DAC value + + if count == 2: + + count, data = pi.bb_spi_xfer(CE0, [12, 0]) # Read back DAC + + if count == 2: + + set_val = data[1] + + count, data = pi.bb_spi_xfer(CE1, [1, 128, 0]) # Read ADC + + if count == 3: + + read_val = ((data[1]&3)<<8) | data[2] + + print("{} {}".format(set_val, read_val)) + + pi.bb_spi_close(CE0) + pi.bb_spi_close(CE1) + + pi.stop() + ... + """ + # I p1 CS + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_BSPIX, CS, 0, len(data), [data])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + + def bb_i2c_open(self, SDA, SCL, baud=100000): + """ + This function selects a pair of GPIO for bit banging I2C at a + specified baud rate. + + Bit banging I2C allows for certain operations which are not possible + with the standard I2C driver. + + o baud rates as low as 50 + o repeated starts + o clock stretching + o I2C on any pair of spare GPIO + + SDA:= 0-31 + SCL:= 0-31 + baud:= 50-500000 + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or + PI_GPIO_IN_USE. + + NOTE: + + The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. + As a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. + + ... + h = pi.bb_i2c_open(4, 5, 50000) # bit bang on GPIO 4/5 at 50kbps + ... + """ + # I p1 SDA + # I p2 SCL + # I p3 4 + ## extension ## + # I baud + extents = [struct.pack("I", baud)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_BI2CO, SDA, SCL, 4, extents)) + + + def bb_i2c_close(self, SDA): + """ + This function stops bit banging I2C on a pair of GPIO + previously opened with [*bb_i2c_open*]. + + SDA:= 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*] + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. + + ... + pi.bb_i2c_close(SDA) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_BI2CC, SDA, 0)) + + + def bb_i2c_zip(self, SDA, data): + """ + This function executes a sequence of bit banged I2C operations. + The operations to be performed are specified by the contents + of data which contains the concatenated command codes and + associated data. + + SDA:= 0-31 (as used in a prior call to [*bb_i2c_open*]) + data:= the concatenated I2C commands, see below + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, data) = pi.bb_i2c_zip( + SDA, [4, 0x53, 2, 7, 1, 0x32, 2, 6, 6, 3, 0]) + ... + + The following command codes are supported: + + Name @ Cmd & Data @ Meaning + End @ 0 @ No more commands + Escape @ 1 @ Next P is two bytes + Start @ 2 @ Start condition + Stop @ 3 @ Stop condition + Address @ 4 P @ Set I2C address to P + Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) + Read @ 6 P @ Read P bytes of data + Write @ 7 P ... @ Write P bytes of data + + The address, read, and write commands take a parameter P. + Normally P is one byte (0-255). If the command is preceded by + the Escape command then P is two bytes (0-65535, least significant + byte first). + + The address and flags default to 0. The address and flags maintain + their previous value until updated. + + No flags are currently defined. + + Any read I2C data is concatenated in the returned bytearray. + + ... + Set address 0x53 + start, write 0x32, (re)start, read 6 bytes, stop + Set address 0x1E + start, write 0x03, (re)start, read 6 bytes, stop + Set address 0x68 + start, write 0x1B, (re)start, read 8 bytes, stop + End + + 0x04 0x53 + 0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 + + 0x04 0x1E + 0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 + + 0x04 0x68 + 0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 + + 0x00 + ... + """ + # I p1 SDA + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_BI2CZ, SDA, 0, len(data), [data])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def event_trigger(self, event): + """ + This function signals the occurrence of an event. + + event:= 0-31, the event + + Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + + An event is a signal used to inform one or more consumers + to start an action. Each consumer which has registered an + interest in the event (e.g. by calling [*event_callback*]) will + be informed by a callback. + + One event, EVENT_BSC (31) is predefined. This event is + auto generated on BSC slave activity. + + The meaning of other events is arbitrary. + + Note that other than its id and its tick there is no data associated + with an event. + + ... + pi.event_trigger(23) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_EVT, event, 0)) + + + def bsc_xfer(self, bsc_control, data): + """ + This function provides a low-level interface to the + SPI/I2C Slave peripheral. This peripheral allows the + Pi to act as a slave device on an I2C or SPI bus. + + I can't get SPI to work properly. I tried with a + control word of 0x303 and swapped MISO and MOSI. + + + The function sets the BSC mode, writes any data in + the transmit buffer to the BSC transmit FIFO, and + copies any data in the BSC receive FIFO to the + receive buffer. + + bsc_control:= see below + data:= the data bytes to place in the transmit FIFO. + + The returned value is a tuple of the status (see below), + the number of bytes read, and a bytearray containing the + read bytes. If there was an error the status will be less + than zero (and will contain the error code). + + Note that the control word sets the BSC mode. The BSC will + stay in that mode until a different control word is sent. + + The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) + in I2C mode and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), + and 21 (CE) in SPI mode. You need to swap MISO/MOSI + between master and slave. + + When a zero control word is received GPIO 18-21 will be reset + to INPUT mode. + + bsc_control consists of the following bits: + + . . + 22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN + . . + + Bits 0-13 are copied unchanged to the BSC CR register. See + pages 163-165 of the Broadcom peripherals document for full + details. + + aaaaaaa @ defines the I2C slave address (only relevant in I2C mode) + IT @ invert transmit status flags + HC @ enable host control + TF @ enable test FIFO + IR @ invert receive status flags + RE @ enable receive + TE @ enable transmit + BK @ abort operation and clear FIFOs + EC @ send control register as first I2C byte + ES @ send status register as first I2C byte + PL @ set SPI polarity high + PH @ set SPI phase high + I2 @ enable I2C mode + SP @ enable SPI mode + EN @ enable BSC peripheral + + The status has the following format: + + . . + 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + S S S S S R R R R R T T T T T RB TE RF TF RE TB + . . + + Bits 0-15 are copied unchanged from the BSC FR register. See + pages 165-166 of the Broadcom peripherals document for full + details. + + SSSSS @ number of bytes successfully copied to transmit FIFO + RRRRR @ number of bytes in receieve FIFO + TTTTT @ number of bytes in transmit FIFO + RB @ receive busy + TE @ transmit FIFO empty + RF @ receive FIFO full + TF @ transmit FIFO full + RE @ receive FIFO empty + TB @ transmit busy + + ... + (status, count, data) = pi.bsc_xfer(0x330305, "Hello!") + ... + """ + # I p1 control + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + status = PI_CMD_INTERRUPTED + bytes = 0 + rdata = bytearray(b'') + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_BSCX, bsc_control, 0, len(data), [data])) + if bytes > 0: + rx = self._rxbuf(bytes) + status = struct.unpack('I', rx[0:4])[0] + bytes -= 4 + rdata = rx[4:] + else: + status = bytes + bytes = 0 + return status, bytes, rdata + + def bsc_i2c(self, i2c_address, data=[]): + """ + This function allows the Pi to act as a slave I2C device. + + The data bytes (if any) are written to the BSC transmit + FIFO and the bytes in the BSC receive FIFO are returned. + + i2c_address:= the I2C slave address. + data:= the data bytes to transmit. + + The returned value is a tuple of the status, the number + of bytes read, and a bytearray containing the read bytes. + + See [*bsc_xfer*] for details of the status value. + + If there was an error the status will be less than zero + (and will contain the error code). + + Note that an i2c_address of 0 may be used to close + the BSC device and reassign the used GPIO (18/19) + as inputs. + + This example assumes GPIO 2/3 are connected to GPIO 18/19. + + ... + #!/usr/bin/env python + import time + import pigpio + + I2C_ADDR=0x13 + + def i2c(id, tick): + global pi + + s, b, d = pi.bsc_i2c(I2C_ADDR) + if b: + if d[0] == ord('t'): # 116 send 'HH:MM:SS*' + + print("sent={} FR={} received={} [{}]". + format(s>>16, s&0xfff,b,d)) + + s, b, d = pi.bsc_i2c(I2C_ADDR, + "{}*".format(time.asctime()[11:19])) + + elif d[0] == ord('d'): # 100 send 'Sun Oct 30*' + + print("sent={} FR={} received={} [{}]". + format(s>>16, s&0xfff,b,d)) + + s, b, d = pi.bsc_i2c(I2C_ADDR, + "{}*".format(time.asctime()[:10])) + + pi = pigpio.pi() + + if not pi.connected: + exit() + + # Respond to BSC slave activity + + e = pi.event_callback(pigpio.EVENT_BSC, i2c) + + pi.bsc_i2c(I2C_ADDR) # Configure BSC as I2C slave + + time.sleep(600) + + e.cancel() + + pi.bsc_i2c(0) # Disable BSC peripheral + + pi.stop() + ... + + While running the above. + + . . + $ i2cdetect -y 1 + 0 1 2 3 4 5 6 7 8 9 a b c d e f + 00: -- -- -- -- -- -- -- -- -- -- -- -- -- + 10: -- -- -- 13 -- -- -- -- -- -- -- -- -- -- -- -- + 20: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- + 30: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- + 40: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- + 50: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- + 60: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- + 70: -- -- -- -- -- -- -- -- + + $ pigs i2co 1 0x13 0 + 0 + + $ pigs i2cwd 0 116 + $ pigs i2crd 0 9 -a + 9 10:13:58* + + $ pigs i2cwd 0 116 + $ pigs i2crd 0 9 -a + 9 10:14:29* + + $ pigs i2cwd 0 100 + $ pigs i2crd 0 11 -a + 11 Sun Oct 30* + + $ pigs i2cwd 0 100 + $ pigs i2crd 0 11 -a + 11 Sun Oct 30* + + $ pigs i2cwd 0 116 + $ pigs i2crd 0 9 -a + 9 10:23:16* + + $ pigs i2cwd 0 100 + $ pigs i2crd 0 11 -a + 11 Sun Oct 30* + . . + """ + if i2c_address: + control = (i2c_address<<16)|0x305 + else: + control = 0 + return self.bsc_xfer(control, data) + + def spi_open(self, spi_channel, baud, spi_flags=0): + """ + Returns a handle for the SPI device on the channel. Data + will be transferred at baud bits per second. The flags + may be used to modify the default behaviour of 4-wire + operation, mode 0, active low chip select. + + The Pi has two SPI peripherals: main and auxiliary. + + The main SPI has two chip selects (channels), the auxiliary + has three. + + The auxiliary SPI is available on all models but the A and B. + + The GPIO used are given in the following table. + + @ MISO @ MOSI @ SCLK @ CE0 @ CE1 @ CE2 + Main SPI @ 9 @ 10 @ 11 @ 8 @ 7 @ - + Aux SPI @ 19 @ 20 @ 21 @ 18 @ 17 @ 16 + + spi_channel:= 0-1 (0-2 for the auxiliary SPI). + baud:= 32K-125M (values above 30M are unlikely to work). + spi_flags:= see below. + + spi_flags consists of the least significant 22 bits. + + . . + 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m + . . + + mm defines the SPI mode. + + WARNING: modes 1 and 3 do not appear to work on + the auxiliary SPI. + + . . + Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 + . . + + px is 0 if CEx is active low (default) and 1 for active high. + + ux is 0 if the CEx GPIO is reserved for SPI (default) + and 1 otherwise. + + A is 0 for the main SPI, 1 for the auxiliary SPI. + + W is 0 if the device is not 3-wire, 1 if the device is 3-wire. + Main SPI only. + + nnnn defines the number of bytes (0-15) to write before + switching the MOSI line to MISO to read data. This field + is ignored if W is not set. Main SPI only. + + T is 1 if the least significant bit is transmitted on MOSI + first, the default (0) shifts the most significant bit out + first. Auxiliary SPI only. + + R is 1 if the least significant bit is received on MISO + first, the default (0) receives the most significant bit + first. Auxiliary SPI only. + + bbbbbb defines the word size in bits (0-32). The default (0) + sets 8 bits per word. Auxiliary SPI only. + + The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions + transfer data packed into 1, 2, or 4 bytes according to + the word size in bits. + + For bits 1-8 there will be one byte per character. + For bits 9-16 there will be two bytes per character. + For bits 17-32 there will be four bytes per character. + + Multi-byte transfers are made in least significant byte + first order. + + E.g. to transfer 32 11-bit words data should + contain 64 bytes. + + E.g. to transfer the 14 bit value 0x1ABC send the + bytes 0xBC followed by 0x1A. + + The other bits in flags should be set to zero. + + ... + # open SPI device on channel 1 in mode 3 at 50000 bits per second + + h = pi.spi_open(1, 50000, 3) + ... + """ + # I p1 spi_channel + # I p2 baud + # I p3 4 + ## extension ## + # I spi_flags + extents = [struct.pack("I", spi_flags)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SPIO, spi_channel, baud, 4, extents)) + + def spi_close(self, handle): + """ + Closes the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to [*spi_open*]). + + ... + pi.spi_close(h) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SPIC, handle, 0)) + + def spi_read(self, handle, count): + """ + Reads count bytes from the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to [*spi_open*]). + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.spi_read(h, 60) # read 60 bytes from device h + if b == 60: + # process read data + else: + # error path + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_nolock( + self.sl, _PI_CMD_SPIR, handle, count)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def spi_write(self, handle, data): + """ + Writes the data bytes to the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to [*spi_open*]). + data:= the bytes to write. + + ... + pi.spi_write(0, b'\\x02\\xc0\\x80') # write 3 bytes to device 0 + + pi.spi_write(0, b'defgh') # write 5 bytes to device 0 + + pi.spi_write(0, "def") # write 3 bytes to device 0 + + pi.spi_write(1, [2, 192, 128]) # write 3 bytes to device 1 + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SPIW, handle, 0, len(data), [data])) + + def spi_xfer(self, handle, data): + """ + Writes the data bytes to the SPI device associated with handle, + returning the data bytes read from the device. + + handle:= >=0 (as returned by a prior call to [*spi_open*]). + data:= the bytes to write. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, rx_data) = pi.spi_xfer(h, b'\\x01\\x80\\x00') + + (count, rx_data) = pi.spi_xfer(h, [1, 128, 0]) + + (count, rx_data) = pi.spi_xfer(h, b"hello") + + (count, rx_data) = pi.spi_xfer(h, "hello") + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_SPIX, handle, 0, len(data), [data])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def serial_open(self, tty, baud, ser_flags=0): + """ + Returns a handle for the serial tty device opened + at baud bits per second. The device name must start + with /dev/tty or /dev/serial. + + tty:= the serial device to open. + baud:= baud rate in bits per second, see below. + ser_flags:= 0, no flags are currently defined. + + Normally you would only use the [*serial_**] functions if + you are or will be connecting to the Pi over a network. If + you will always run on the local Pi use the standard serial + module instead. + + The baud rate must be one of 50, 75, 110, 134, 150, + 200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, + 38400, 57600, 115200, or 230400. + + ... + h1 = pi.serial_open("/dev/ttyAMA0", 300) + + h2 = pi.serial_open("/dev/ttyUSB1", 19200, 0) + + h3 = pi.serial_open("/dev/serial0", 9600) + ... + """ + # I p1 baud + # I p2 ser_flags + # I p3 len + ## extension ## + # s len data bytes + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SERO, baud, ser_flags, len(tty), [tty])) + + def serial_close(self, handle): + """ + Closes the serial device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + + ... + pi.serial_close(h1) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SERC, handle, 0)) + + def serial_read_byte(self, handle): + """ + Returns a single byte from the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + + If no data is ready a negative error code will be returned. + + ... + b = pi.serial_read_byte(h1) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SERRB, handle, 0)) + + def serial_write_byte(self, handle, byte_val): + """ + Writes a single byte to the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + byte_val:= 0-255, the value to write. + + ... + pi.serial_write_byte(h1, 23) + + pi.serial_write_byte(h1, ord('Z')) + ... + """ + return _u2i( + _pigpio_command(self.sl, _PI_CMD_SERWB, handle, byte_val)) + + def serial_read(self, handle, count=1000): + """ + Reads up to count bytes from the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + count:= >0, the number of bytes to read (defaults to 1000). + + The returned value is a tuple of the number of bytes read and + a bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + If no data is ready a bytes read of zero is returned. + ... + (b, d) = pi.serial_read(h2, 100) + if b > 0: + # process read data + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i( + _pigpio_command_nolock(self.sl, _PI_CMD_SERR, handle, count)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def serial_write(self, handle, data): + """ + Writes the data bytes to the device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + data:= the bytes to write. + + ... + pi.serial_write(h1, b'\\x02\\x03\\x04') + + pi.serial_write(h2, b'help') + + pi.serial_write(h2, "hello") + + pi.serial_write(h1, [2, 3, 4]) + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SERW, handle, 0, len(data), [data])) + + def serial_data_available(self, handle): + """ + Returns the number of bytes available to be read from the + device associated with handle. + + handle:= >=0 (as returned by a prior call to [*serial_open*]). + + ... + rdy = pi.serial_data_available(h1) + + if rdy > 0: + (b, d) = pi.serial_read(h1, rdy) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SERDA, handle, 0)) + + def gpio_trigger(self, user_gpio, pulse_len=10, level=1): + """ + Send a trigger pulse to a GPIO. The GPIO is set to + level for pulse_len microseconds and then reset to not level. + + user_gpio:= 0-31 + pulse_len:= 1-100 + level:= 0-1 + + ... + pi.gpio_trigger(23, 10, 1) + ... + """ + # pigpio message format + + # I p1 user_gpio + # I p2 pulse_len + # I p3 4 + ## extension ## + # I level + extents = [struct.pack("I", level)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_TRIG, user_gpio, pulse_len, 4, extents)) + + def set_glitch_filter(self, user_gpio, steady): + """ + Sets a glitch filter on a GPIO. + + Level changes on the GPIO are not reported unless the level + has been stable for at least [*steady*] microseconds. The + level is then reported. Level changes of less than [*steady*] + microseconds are ignored. + + user_gpio:= 0-31 + steady:= 0-300000 + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + + This filter affects the GPIO samples returned to callbacks set up + with [*callback*] and [*wait_for_edge*]. + + It does not affect levels read by [*read*], + [*read_bank_1*], or [*read_bank_2*]. + + Each (stable) edge will be timestamped [*steady*] + microseconds after it was first detected. + + ... + pi.set_glitch_filter(23, 100) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_FG, user_gpio, steady)) + + def set_noise_filter(self, user_gpio, steady, active): + """ + Sets a noise filter on a GPIO. + + Level changes on the GPIO are ignored until a level which has + been stable for [*steady*] microseconds is detected. Level + changes on the GPIO are then reported for [*active*] + microseconds after which the process repeats. + + user_gpio:= 0-31 + steady:= 0-300000 + active:= 0-1000000 + + Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + + This filter affects the GPIO samples returned to callbacks set up + with [*callback*] and [*wait_for_edge*]. + + It does not affect levels read by [*read*], + [*read_bank_1*], or [*read_bank_2*]. + + Level changes before and after the active period may + be reported. Your software must be designed to cope with + such reports. + + ... + pi.set_noise_filter(23, 1000, 5000) + ... + """ + # pigpio message format + + # I p1 user_gpio + # I p2 steady + # I p3 4 + ## extension ## + # I active + extents = [struct.pack("I", active)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_FN, user_gpio, steady, 4, extents)) + + def store_script(self, script): + """ + Store a script for later execution. + + See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for + details. + + script:= the script text as a series of bytes. + + Returns a >=0 script id if OK. + + ... + sid = pi.store_script( + b'tag 0 w 22 1 mils 100 w 22 0 mils 100 dcr p0 jp 0') + ... + """ + # I p1 0 + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + if len(script): + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_PROC, 0, 0, len(script), [script])) + else: + return 0 + + def run_script(self, script_id, params=None): + """ + Runs a stored script. + + script_id:= id of stored script. + params:= up to 10 parameters required by the script. + + ... + s = pi.run_script(sid, [par1, par2]) + + s = pi.run_script(sid) + + s = pi.run_script(sid, [1, 2, 3, 4, 5, 6, 7, 8, 9, 10]) + ... + """ + # I p1 script id + # I p2 0 + # I p3 params * 4 (0-10 params) + ## (optional) extension ## + # I[] params + if params is not None: + ext = bytearray() + for p in params: + ext.extend(struct.pack("I", p)) + nump = len(params) + extents = [ext] + else: + nump = 0 + extents = [] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_PROCR, script_id, 0, nump*4, extents)) + + def update_script(self, script_id, params=None): + """ + Sets the parameters of a script. The script may or + may not be running. The first parameters of the script are + overwritten with the new values. + + script_id:= id of stored script. + params:= up to 10 parameters required by the script. + + ... + s = pi.update_script(sid, [par1, par2]) + + s = pi.update_script(sid, [1, 2, 3, 4, 5, 6, 7, 8, 9, 10]) + ... + """ + # I p1 script id + # I p2 0 + # I p3 params * 4 (0-10 params) + ## (optional) extension ## + # I[] params + if params is not None: + ext = bytearray() + for p in params: + ext.extend(struct.pack("I", p)) + nump = len(params) + extents = [ext] + else: + nump = 0 + extents = [] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_PROCU, script_id, 0, nump*4, extents)) + + def script_status(self, script_id): + """ + Returns the run status of a stored script as well as the + current values of parameters 0 to 9. + + script_id:= id of stored script. + + The run status may be + + . . + PI_SCRIPT_INITING + PI_SCRIPT_HALTED + PI_SCRIPT_RUNNING + PI_SCRIPT_WAITING + PI_SCRIPT_FAILED + . . + + The return value is a tuple of run status and a list of + the 10 parameters. On error the run status will be negative + and the parameter list will be empty. + + ... + (s, pars) = pi.script_status(sid) + ... + """ + status = PI_CMD_INTERRUPTED + params = () + with self.sl.l: + bytes = u2i( + _pigpio_command_nolock(self.sl, _PI_CMD_PROCP, script_id, 0)) + if bytes > 0: + data = self._rxbuf(bytes) + pars = struct.unpack('11i', _str(data)) + status = pars[0] + params = pars[1:] + else: + status = bytes + return status, params + + def stop_script(self, script_id): + """ + Stops a running script. + + script_id:= id of stored script. + + ... + status = pi.stop_script(sid) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PROCS, script_id, 0)) + + def delete_script(self, script_id): + """ + Deletes a stored script. + + script_id:= id of stored script. + + ... + status = pi.delete_script(sid) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PROCD, script_id, 0)) + + def bb_serial_read_open(self, user_gpio, baud, bb_bits=8): + """ + Opens a GPIO for bit bang reading of serial data. + + user_gpio:= 0-31, the GPIO to use. + baud:= 50-250000, the baud rate. + bb_bits:= 1-32, the number of bits per word, default 8. + + The serial data is held in a cyclic buffer and is read using + [*bb_serial_read*]. + + It is the caller's responsibility to read data from the cyclic + buffer in a timely fashion. + + ... + status = pi.bb_serial_read_open(4, 19200) + status = pi.bb_serial_read_open(17, 9600) + ... + """ + # pigpio message format + + # I p1 user_gpio + # I p2 baud + # I p3 4 + ## extension ## + # I bb_bits + extents = [struct.pack("I", bb_bits)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SLRO, user_gpio, baud, 4, extents)) + + def bb_serial_read(self, user_gpio): + """ + Returns data from the bit bang serial cyclic buffer. + + user_gpio:= 0-31 (opened in a prior call to [*bb_serial_read_open*]) + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + The bytes returned for each character depend upon the number of + data bits [*bb_bits*] specified in the [*bb_serial_read_open*] + command. + + For [*bb_bits*] 1-8 there will be one byte per character. + For [*bb_bits*] 9-16 there will be two bytes per character. + For [*bb_bits*] 17-32 there will be four bytes per character. + + ... + (count, data) = pi.bb_serial_read(4) + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i( + _pigpio_command_nolock(self.sl, _PI_CMD_SLR, user_gpio, 10000)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + + def bb_serial_read_close(self, user_gpio): + """ + Closes a GPIO for bit bang reading of serial data. + + user_gpio:= 0-31 (opened in a prior call to [*bb_serial_read_open*]) + + ... + status = pi.bb_serial_read_close(17) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SLRC, user_gpio, 0)) + + def bb_serial_invert(self, user_gpio, invert): + """ + Invert serial logic. + + user_gpio:= 0-31 (opened in a prior call to [*bb_serial_read_open*]) + invert:= 0-1 (1 invert, 0 normal) + + ... + status = pi.bb_serial_invert(17, 1) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_SLRI, user_gpio, invert)) + + + def custom_1(self, arg1=0, arg2=0, argx=[]): + """ + Calls a pigpio function customised by the user. + + arg1:= >=0, default 0. + arg2:= >=0, default 0. + argx:= extra arguments (each 0-255), default empty. + + The returned value is an integer which by convention + should be >=0 for OK and <0 for error. + + ... + value = pi.custom_1() + + value = pi.custom_1(23) + + value = pi.custom_1(0, 55) + + value = pi.custom_1(23, 56, [1, 5, 7]) + + value = pi.custom_1(23, 56, b"hello") + + value = pi.custom_1(23, 56, "hello") + ... + """ + # I p1 arg1 + # I p2 arg2 + # I p3 len + ## extension ## + # s len argx bytes + + return u2i(_pigpio_command_ext( + self.sl, _PI_CMD_CF1, arg1, arg2, len(argx), [argx])) + + def custom_2(self, arg1=0, argx=[], retMax=8192): + """ + Calls a pigpio function customised by the user. + + arg1:= >=0, default 0. + argx:= extra arguments (each 0-255), default empty. + retMax:= >=0, maximum number of bytes to return, default 8192. + + The returned value is a tuple of the number of bytes + returned and a bytearray containing the bytes. If + there was an error the number of bytes read will be + less than zero (and will contain the error code). + + ... + (count, data) = pi.custom_2() + + (count, data) = pi.custom_2(23) + + (count, data) = pi.custom_2(23, [1, 5, 7]) + + (count, data) = pi.custom_2(23, b"hello") + + (count, data) = pi.custom_2(23, "hello", 128) + ... + """ + # I p1 arg1 + # I p2 retMax + # I p3 len + ## extension ## + # s len argx bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_CF2, arg1, retMax, len(argx), [argx])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def get_pad_strength(self, pad): + """ + This function returns the pad drive strength in mA. + + pad:= 0-2, the pad to get. + + Returns the pad drive strength if OK, otherwise PI_BAD_PAD. + + Pad @ GPIO + 0 @ 0-27 + 1 @ 28-45 + 2 @ 46-53 + + ... + strength = pi.get_pad_strength(0) # Get pad 0 strength. + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PADG, pad, 0)) + + def set_pad_strength(self, pad, pad_strength): + """ + This function sets the pad drive strength in mA. + + + pad:= 0-2, the pad to set. + pad_strength:= 1-16 mA. + + Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH. + + Pad @ GPIO + 0 @ 0-27 + 1 @ 28-45 + 2 @ 46-53 + + ... + pi.set_pad_strength(2, 14) # Set pad 2 to 14 mA. + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_PADS, pad, pad_strength)) + + + def file_open(self, file_name, file_mode): + """ + This function returns a handle to a file opened in a specified mode. + + file_name:= the file to open. + file_mode:= the file open mode. + + Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, + PI_NO_FILE_ACCESS, PI_BAD_FILE_MODE, + PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR. + + ... + h = pi.file_open("/home/pi/shared/dir_3/file.txt", + pigpio.FILE_WRITE | pigpio.FILE_CREATE) + + pi.file_write(h, "Hello world") + + pi.file_close(h) + ... + + File + + A file may only be opened if permission is granted by an entry + in /opt/pigpio/access. This is intended to allow remote access + to files in a more or less controlled manner. + + Each entry in /opt/pigpio/access takes the form of a file path + which may contain wildcards followed by a single letter permission. + The permission may be R for read, W for write, U for read/write, + and N for no access. + + Where more than one entry matches a file the most specific rule + applies. If no entry matches a file then access is denied. + + Suppose /opt/pigpio/access contains the following entries: + + . . + /home/* n + /home/pi/shared/dir_1/* w + /home/pi/shared/dir_2/* r + /home/pi/shared/dir_3/* u + /home/pi/shared/dir_1/file.txt n + . . + + Files may be written in directory dir_1 with the exception + of file.txt. + + Files may be read in directory dir_2. + + Files may be read and written in directory dir_3. + + If a directory allows read, write, or read/write access then files + may be created in that directory. + + In an attempt to prevent risky permissions the following paths are + ignored in /opt/pigpio/access: + + . . + a path containing .. + a path containing only wildcards (*?) + a path containing less than two non-wildcard parts + . . + + Mode + + The mode may have the following values: + + Constant @ Value @ Meaning + FILE_READ @ 1 @ open file for reading + FILE_WRITE @ 2 @ open file for writing + FILE_RW @ 3 @ open file for reading and writing + + The following values may be or'd into the mode: + + Name @ Value @ Meaning + FILE_APPEND @ 4 @ All writes append data to the end of the file + FILE_CREATE @ 8 @ The file is created if it doesn't exist + FILE_TRUNC @ 16 @ The file is truncated + + Newly created files are owned by root with permissions owner + read and write. + + ... + #!/usr/bin/env python + + import pigpio + + pi = pigpio.pi() + + if not pi.connected: + exit() + + # Assumes /opt/pigpio/access contains the following line: + # /ram/*.c r + + handle = pi.file_open("/ram/pigpio.c", pigpio.FILE_READ) + + done = False + + while not done: + c, d = pi.file_read(handle, 60000) + if c > 0: + print(d) + else: + done = True + + pi.file_close(handle) + + pi.stop() + ... + """ + # I p1 file_mode + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_FO, file_mode, 0, len(file_name), [file_name])) + + def file_close(self, handle): + """ + Closes the file associated with handle. + + handle:= >=0 (as returned by a prior call to [*file_open*]). + + ... + pi.file_close(handle) + ... + """ + return _u2i(_pigpio_command(self.sl, _PI_CMD_FC, handle, 0)) + + def file_read(self, handle, count): + """ + Reads up to count bytes from the file associated with handle. + + handle:= >=0 (as returned by a prior call to [*file_open*]). + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.file_read(h2, 100) + if b > 0: + # process read data + ... + """ + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i( + _pigpio_command_nolock(self.sl, _PI_CMD_FR, handle, count)) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def file_write(self, handle, data): + """ + Writes the data bytes to the file associated with handle. + + handle:= >=0 (as returned by a prior call to [*file_open*]). + data:= the bytes to write. + + ... + pi.file_write(h1, b'\\x02\\x03\\x04') + + pi.file_write(h2, b'help') + + pi.file_write(h2, "hello") + + pi.file_write(h1, [2, 3, 4]) + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_FW, handle, 0, len(data), [data])) + + def file_seek(self, handle, seek_offset, seek_from): + """ + Seeks to a position relative to the start, current position, + or end of the file. Returns the new position. + + handle:= >=0 (as returned by a prior call to [*file_open*]). + seek_offset:= byte offset. + seek_from:= FROM_START, FROM_CURRENT, or FROM_END. + + ... + new_pos = pi.file_seek(h, 100, pigpio.FROM_START) + + cur_pos = pi.file_seek(h, 0, pigpio.FROM_CURRENT) + + file_size = pi.file_seek(h, 0, pigpio.FROM_END) + ... + """ + # I p1 handle + # I p2 seek_offset + # I p3 4 + ## extension ## + # I seek_from + extents = [struct.pack("I", seek_from)] + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_FS, handle, seek_offset, 4, extents)) + + def file_list(self, fpattern): + """ + Returns a list of files which match a pattern. + + fpattern:= file pattern to match. + + Returns the number of returned bytes if OK, otherwise + PI_NO_FILE_ACCESS, or PI_NO_FILE_MATCH. + + The pattern must match an entry in /opt/pigpio/access. The + pattern may contain wildcards. See [*file_open*]. + + NOTE + + The returned value is not the number of files, it is the number + of bytes in the buffer. The file names are separated by newline + characters. + + ... + #!/usr/bin/env python + + import pigpio + + pi = pigpio.pi() + + if not pi.connected: + exit() + + # Assumes /opt/pigpio/access contains the following line: + # /ram/*.c r + + c, d = pi.file_list("/ram/p*.c") + if c > 0: + print(d) + + pi.stop() + ... + """ + # I p1 60000 + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + bytes = PI_CMD_INTERRUPTED + rdata = "" + with self.sl.l: + bytes = u2i(_pigpio_command_ext_nolock( + self.sl, _PI_CMD_FL, 60000, 0, len(fpattern), [fpattern])) + if bytes > 0: + rdata = self._rxbuf(bytes) + return bytes, rdata + + def shell(self, shellscr, pstring=""): + """ + This function uses the system call to execute a shell script + with the given string as its parameter. + + shellscr:= the name of the script, only alphanumerics, + '-' and '_' are allowed in the name + pstring := the parameter string to pass to the script + + The exit status of the system call is returned if OK, + otherwise PI_BAD_SHELL_STATUS. + + [*shellscr*] must exist in /opt/pigpio/cgi and must be executable. + + The returned exit status is normally 256 times that set by + the shell script exit function. If the script can't be + found 32512 will be returned. + + The following table gives some example returned statuses: + + Script exit status @ Returned system call status + 1 @ 256 + 5 @ 1280 + 10 @ 2560 + 200 @ 51200 + script not found @ 32512 + + ... + // pass two parameters, hello and world + status = pi.shell("scr1", "hello world"); + + // pass three parameters, hello, string with spaces, and world + status = pi.shell("scr1", "hello 'string with spaces' world"); + + // pass one parameter, hello string with spaces world + status = pi.shell("scr1", "\\"hello string with spaces world\\""); + ... + """ + # I p1 len(shellscr) + # I p2 0 + # I p3 len(shellscr)+len(pstring)+1 + ## extension ## + # s len data bytes + + ls = len(shellscr) + lp = len(pstring) + return _u2i(_pigpio_command_ext( + self.sl, _PI_CMD_SHELL, ls, 0, ls+lp+1, [shellscr+'\x00'+pstring])) + + + def callback(self, user_gpio, edge=RISING_EDGE, func=None): + """ + Calls a user supplied function (a callback) whenever the + specified GPIO edge is detected. + + user_gpio:= 0-31. + edge:= EITHER_EDGE, RISING_EDGE (default), or FALLING_EDGE. + func:= user supplied callback function. + + The user supplied callback receives three parameters, the GPIO, + the level, and the tick. + + . . + Parameter Value Meaning + + GPIO 0-31 The GPIO which has changed state + + level 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + + tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes + . . + + If a user callback is not specified a default tally callback is + provided which simply counts edges. The count may be retrieved + by calling the tally function. The count may be reset to zero + by calling the reset_tally function. + + The callback may be cancelled by calling the cancel function. + + A GPIO may have multiple callbacks (although I can't think of + a reason to do so). + + ... + def cbf(gpio, level, tick): + print(gpio, level, tick) + + cb1 = pi.callback(22, pigpio.EITHER_EDGE, cbf) + + cb2 = pi.callback(4, pigpio.EITHER_EDGE) + + cb3 = pi.callback(17) + + print(cb3.tally()) + + cb3.reset_tally() + + cb1.cancel() # To cancel callback cb1. + ... + """ + return _callback(self._notify, user_gpio, edge, func) + + def event_callback(self, event, func=None): + """ + Calls a user supplied function (a callback) whenever the + specified event is signalled. + + event:= 0-31. + func:= user supplied callback function. + + The user supplied callback receives two parameters, the event id, + and the tick. + + If a user callback is not specified a default tally callback is + provided which simply counts events. The count may be retrieved + by calling the tally function. The count may be reset to zero + by calling the reset_tally function. + + The callback may be cancelled by calling the event_cancel function. + + An event may have multiple callbacks (although I can't think of + a reason to do so). + + ... + def cbf(event, tick): + print(event, tick) + + cb1 = pi.event_callback(22, cbf) + + cb2 = pi.event_callback(4) + + print(cb2.tally()) + + cb2.reset_tally() + + cb1.event_cancel() # To cancel callback cb1. + ... + """ + + return _event(self._notify, event, func) + + def wait_for_edge(self, user_gpio, edge=RISING_EDGE, wait_timeout=60.0): + """ + Wait for an edge event on a GPIO. + + user_gpio:= 0-31. + edge:= EITHER_EDGE, RISING_EDGE (default), or + FALLING_EDGE. + wait_timeout:= >=0.0 (default 60.0). + + The function returns when the edge is detected or after + the number of seconds specified by timeout has expired. + + Do not use this function for precise timing purposes, + the edge is only checked 20 times a second. Whenever + you need to know the accurate time of GPIO events use + a [*callback*] function. + + The function returns True if the edge is detected, + otherwise False. + + ... + if pi.wait_for_edge(23): + print("Rising edge detected") + else: + print("wait for edge timed out") + + if pi.wait_for_edge(23, pigpio.FALLING_EDGE, 5.0): + print("Falling edge detected") + else: + print("wait for falling edge timed out") + ... + """ + a = _wait_for_edge(self._notify, user_gpio, edge, wait_timeout) + return a.trigger + + def wait_for_event(self, event, wait_timeout=60.0): + """ + Wait for an event. + + event:= 0-31. + wait_timeout:= >=0.0 (default 60.0). + + The function returns when the event is signalled or after + the number of seconds specified by timeout has expired. + + The function returns True if the event is detected, + otherwise False. + + ... + if pi.wait_for_event(23): + print("event detected") + else: + print("wait for event timed out") + ... + """ + a = _wait_for_event(self._notify, event, wait_timeout) + return a.trigger + + def __init__(self, + host = os.getenv("PIGPIO_ADDR", 'localhost'), + port = os.getenv("PIGPIO_PORT", 8888), + show_errors = True): + """ + Grants access to a Pi's GPIO. + + host:= the host name of the Pi on which the pigpio daemon is + running. The default is localhost unless overridden by + the PIGPIO_ADDR environment variable. + + port:= the port number on which the pigpio daemon is listening. + The default is 8888 unless overridden by the PIGPIO_PORT + environment variable. The pigpio daemon must have been + started with the same port number. + + This connects to the pigpio daemon and reserves resources + to be used for sending commands and receiving notifications. + + An instance attribute [*connected*] may be used to check the + success of the connection. If the connection is established + successfully [*connected*] will be True, otherwise False. + + ... + pi = pigio.pi() # use defaults + pi = pigpio.pi('mypi') # specify host, default port + pi = pigpio.pi('mypi', 7777) # specify host and port + + pi = pigpio.pi() # exit script if no connection + if not pi.connected: + exit() + ... + """ + self.connected = True + + self.sl = _socklock() + self._notify = None + + port = int(port) + + if host == '': + host = "localhost" + + self._host = host + self._port = port + + try: + self.sl.s = socket.create_connection((host, port), None) + + # Disable the Nagle algorithm. + self.sl.s.setsockopt(socket.IPPROTO_TCP, socket.TCP_NODELAY, 1) + + self._notify = _callback_thread(self.sl, host, port) + + except socket.error: + exception = 1 + + except struct.error: + exception = 2 + + except error: + # assumed to be no handle available + exception = 3 + + else: + exception = 0 + atexit.register(self.stop) + + if exception != 0: + + self.connected = False + + if self.sl.s is not None: + self.sl.s = None + + if show_errors: + + s = "Can't connect to pigpio at {}({})".format(host, str(port)) + + + print(_except_a.format(s)) + if exception == 1: + print(_except_1) + elif exception == 2: + print(_except_2) + else: + print(_except_3) + print(_except_z) + + def __repr__(self): + return "".format(self._host, self._port) + + def stop(self): + """Release pigpio resources. + + ... + pi.stop() + ... + """ + + self.connected = False + + if self._notify is not None: + self._notify.stop() + self._notify = None + + if self.sl.s is not None: + self.sl.s.close() + self.sl.s = None + +def xref(): + """ + active: 0-1000000 + The number of microseconds level changes are reported for once + a noise filter has been triggered (by [*steady*] microseconds of + a stable level). + + + arg1: + An unsigned argument passed to a user customised function. Its + meaning is defined by the customiser. + + arg2: + An unsigned argument passed to a user customised function. Its + meaning is defined by the customiser. + + argx: + An array of bytes passed to a user customised function. + Its meaning and content is defined by the customiser. + + baud: + The speed of serial communication (I2C, SPI, serial link, waves) + in bits per second. + + bb_bits: 1-32 + The number of data bits to be used when adding serial data to a + waveform. + + bb_stop: 2-8 + The number of (half) stop bits to be used when adding serial data + to a waveform. + + bit: 0-1 + A value of 0 or 1. + + bits: 32 bit number + A mask used to select GPIO to be operated on. If bit n is set + then GPIO n is selected. A convenient way of setting bit n is to + bit or in the value (1<=1 + The length of a pulse in microseconds. + + dutycycle: 0-range_ + A number between 0 and range_. + + The dutycycle sets the proportion of time on versus time off during each + PWM cycle. + + Dutycycle @ On time + 0 @ Off + range_ * 0.25 @ 25% On + range_ * 0.50 @ 50% On + range_ * 0.75 @ 75% On + range_ @ Fully On + + edge: 0-2 + + . . + EITHER_EDGE = 2 + FALLING_EDGE = 1 + RISING_EDGE = 0 + . . + + errnum: <0 + + . . + PI_BAD_USER_GPIO = -2 + PI_BAD_GPIO = -3 + PI_BAD_MODE = -4 + PI_BAD_LEVEL = -5 + PI_BAD_PUD = -6 + PI_BAD_PULSEWIDTH = -7 + PI_BAD_DUTYCYCLE = -8 + PI_BAD_WDOG_TIMEOUT = -15 + PI_BAD_DUTYRANGE = -21 + PI_NO_HANDLE = -24 + PI_BAD_HANDLE = -25 + PI_BAD_WAVE_BAUD = -35 + PI_TOO_MANY_PULSES = -36 + PI_TOO_MANY_CHARS = -37 + PI_NOT_SERIAL_GPIO = -38 + PI_NOT_PERMITTED = -41 + PI_SOME_PERMITTED = -42 + PI_BAD_WVSC_COMMND = -43 + PI_BAD_WVSM_COMMND = -44 + PI_BAD_WVSP_COMMND = -45 + PI_BAD_PULSELEN = -46 + PI_BAD_SCRIPT = -47 + PI_BAD_SCRIPT_ID = -48 + PI_BAD_SER_OFFSET = -49 + PI_GPIO_IN_USE = -50 + PI_BAD_SERIAL_COUNT = -51 + PI_BAD_PARAM_NUM = -52 + PI_DUP_TAG = -53 + PI_TOO_MANY_TAGS = -54 + PI_BAD_SCRIPT_CMD = -55 + PI_BAD_VAR_NUM = -56 + PI_NO_SCRIPT_ROOM = -57 + PI_NO_MEMORY = -58 + PI_SOCK_READ_FAILED = -59 + PI_SOCK_WRIT_FAILED = -60 + PI_TOO_MANY_PARAM = -61 + PI_SCRIPT_NOT_READY = -62 + PI_BAD_TAG = -63 + PI_BAD_MICS_DELAY = -64 + PI_BAD_MILS_DELAY = -65 + PI_BAD_WAVE_ID = -66 + PI_TOO_MANY_CBS = -67 + PI_TOO_MANY_OOL = -68 + PI_EMPTY_WAVEFORM = -69 + PI_NO_WAVEFORM_ID = -70 + PI_I2C_OPEN_FAILED = -71 + PI_SER_OPEN_FAILED = -72 + PI_SPI_OPEN_FAILED = -73 + PI_BAD_I2C_BUS = -74 + PI_BAD_I2C_ADDR = -75 + PI_BAD_SPI_CHANNEL = -76 + PI_BAD_FLAGS = -77 + PI_BAD_SPI_SPEED = -78 + PI_BAD_SER_DEVICE = -79 + PI_BAD_SER_SPEED = -80 + PI_BAD_PARAM = -81 + PI_I2C_WRITE_FAILED = -82 + PI_I2C_READ_FAILED = -83 + PI_BAD_SPI_COUNT = -84 + PI_SER_WRITE_FAILED = -85 + PI_SER_READ_FAILED = -86 + PI_SER_READ_NO_DATA = -87 + PI_UNKNOWN_COMMAND = -88 + PI_SPI_XFER_FAILED = -89 + PI_NO_AUX_SPI = -91 + PI_NOT_PWM_GPIO = -92 + PI_NOT_SERVO_GPIO = -93 + PI_NOT_HCLK_GPIO = -94 + PI_NOT_HPWM_GPIO = -95 + PI_BAD_HPWM_FREQ = -96 + PI_BAD_HPWM_DUTY = -97 + PI_BAD_HCLK_FREQ = -98 + PI_BAD_HCLK_PASS = -99 + PI_HPWM_ILLEGAL = -100 + PI_BAD_DATABITS = -101 + PI_BAD_STOPBITS = -102 + PI_MSG_TOOBIG = -103 + PI_BAD_MALLOC_MODE = -104 + PI_BAD_SMBUS_CMD = -107 + PI_NOT_I2C_GPIO = -108 + PI_BAD_I2C_WLEN = -109 + PI_BAD_I2C_RLEN = -110 + PI_BAD_I2C_CMD = -111 + PI_BAD_I2C_BAUD = -112 + PI_CHAIN_LOOP_CNT = -113 + PI_BAD_CHAIN_LOOP = -114 + PI_CHAIN_COUNTER = -115 + PI_BAD_CHAIN_CMD = -116 + PI_BAD_CHAIN_DELAY = -117 + PI_CHAIN_NESTING = -118 + PI_CHAIN_TOO_BIG = -119 + PI_DEPRECATED = -120 + PI_BAD_SER_INVERT = -121 + PI_BAD_FOREVER = -124 + PI_BAD_FILTER = -125 + PI_BAD_PAD = -126 + PI_BAD_STRENGTH = -127 + PI_FIL_OPEN_FAILED = -128 + PI_BAD_FILE_MODE = -129 + PI_BAD_FILE_FLAG = -130 + PI_BAD_FILE_READ = -131 + PI_BAD_FILE_WRITE = -132 + PI_FILE_NOT_ROPEN = -133 + PI_FILE_NOT_WOPEN = -134 + PI_BAD_FILE_SEEK = -135 + PI_NO_FILE_MATCH = -136 + PI_NO_FILE_ACCESS = -137 + PI_FILE_IS_A_DIR = -138 + PI_BAD_SHELL_STATUS = -139 + PI_BAD_SCRIPT_NAME = -140 + PI_BAD_SPI_BAUD = -141 + PI_NOT_SPI_GPIO = -142 + PI_BAD_EVENT_ID = -143 + PI_CMD_INTERRUPTED = -144 + . . + + event:0-31 + An event is a signal used to inform one or more consumers + to start an action. + + file_mode: + The mode may have the following values + + . . + FILE_READ 1 + FILE_WRITE 2 + FILE_RW 3 + . . + + The following values can be or'd into the file open mode + + . . + FILE_APPEND 4 + FILE_CREATE 8 + FILE_TRUNC 16 + . . + + file_name: + A full file path. To be accessible the path must match + an entry in /opt/pigpio/access. + + fpattern: + A file path which may contain wildcards. To be accessible the path + must match an entry in /opt/pigpio/access. + + frequency: 0-40000 + Defines the frequency to be used for PWM on a GPIO. + The closest permitted frequency will be used. + + func: + A user supplied callback function. + + gpio: 0-53 + A Broadcom numbered GPIO. All the user GPIO are in the range 0-31. + + There are 54 General Purpose Input Outputs (GPIO) named GPIO0 + through GPIO53. + + They are split into two banks. Bank 1 consists of GPIO0 + through GPIO31. Bank 2 consists of GPIO32 through GPIO53. + + All the GPIO which are safe for the user to read and write are in + bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards + have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + + See [*get_hardware_revision*]. + + The user GPIO are marked with an X in the following table + + . . + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 + Type 1 X X - - X - - X X X X X - - X X + Type 2 - - X X X - - X X X X X - - X X + Type 3 X X X X X X X X X X X X X X + + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 + Type 1 - X X - - X X X X X - - - - - - + Type 2 - X X - - - X X X X - X X X X X + Type 3 X X X X X X X X X X X X - - - - + . . + + gpio_off: + A mask used to select GPIO to be operated on. See [*bits*]. + + This mask selects the GPIO to be switched off at the start + of a pulse. + + gpio_on: + A mask used to select GPIO to be operated on. See [*bits*]. + + This mask selects the GPIO to be switched on at the start + of a pulse. + + handle: >=0 + A number referencing an object opened by one of the following + + [*file_open*] + [*i2c_open*] + [*notify_open*] + [*serial_open*] + [*spi_open*] + + host: + The name or IP address of the Pi running the pigpio daemon. + + i2c_address: 0-0x7F + The address of a device on the I2C bus. + + i2c_bus: >=0 + An I2C bus number. + + i2c_flags: 0 + No I2C flags are currently defined. + + invert: 0-1 + A flag used to set normal or inverted bit bang serial data + level logic. + + level: 0-1 (2) + + . . + CLEAR = 0 + HIGH = 1 + LOW = 0 + OFF = 0 + ON = 1 + SET = 1 + TIMEOUT = 2 # only returned for a watchdog timeout + . . + + MISO: + The GPIO used for the MISO signal when bit banging SPI. + + mode: + + 1.The operational mode of a GPIO, normally INPUT or OUTPUT. + + . . + ALT0 = 4 + ALT1 = 5 + ALT2 = 6 + ALT3 = 7 + ALT4 = 3 + ALT5 = 2 + INPUT = 0 + OUTPUT = 1 + . . + + 2. The mode of waveform transmission. + + . . + WAVE_MODE_ONE_SHOT = 0 + WAVE_MODE_REPEAT = 1 + WAVE_MODE_ONE_SHOT_SYNC = 2 + WAVE_MODE_REPEAT_SYNC = 3 + . . + + MOSI: + The GPIO used for the MOSI signal when bit banging SPI. + + offset: >=0 + The offset wave data starts from the beginning of the waveform + being currently defined. + + pad: 0-2 + A set of GPIO which share common drivers. + + Pad @ GPIO + 0 @ 0-27 + 1 @ 28-45 + 2 @ 46-53 + + pad_strength: 1-16 + The mA which may be drawn from each GPIO whilst still guaranteeing the + high and low levels. + + params: 32 bit number + When scripts are started they can receive up to 10 parameters + to define their operation. + + port: + The port used by the pigpio daemon, defaults to 8888. + + pstring: + The string to be passed to a [*shell*] script to be executed. + + pud: 0-2 + . . + PUD_DOWN = 1 + PUD_OFF = 0 + PUD_UP = 2 + . . + + pulse_len: 1-100 + The length of the trigger pulse in microseconds. + + pulses: + A list of class pulse objects defining the characteristics of a + waveform. + + pulsewidth: + The servo pulsewidth in microseconds. 0 switches pulses off. + + PWMduty: 0-1000000 (1M) + The hardware PWM dutycycle. + + PWMfreq: 1-125000000 (125M) + The hardware PWM frequency. + + range_: 25-40000 + Defines the limits for the [*dutycycle*] parameter. + + range_ defaults to 255. + + reg: 0-255 + An I2C device register. The usable registers depend on the + actual device. + + retMax: >=0 + The maximum number of bytes a user customised function + should return, default 8192. + + SCL: + The user GPIO to use for the clock when bit banging I2C. + + SCLK:: + The GPIO used for the SCLK signal when bit banging SPI. + + script: + The text of a script to store on the pigpio daemon. + + script_id: >=0 + A number referencing a script created by [*store_script*]. + + SDA: + The user GPIO to use for data when bit banging I2C. + + seek_from: 0-2 + Direction to seek for [*file_seek*]. + + . . + FROM_START=0 + FROM_CURRENT=1 + FROM_END=2 + . . + + seek_offset: + The number of bytes to move forward (positive) or backwards + (negative) from the seek position (start, current, or end of file). + + ser_flags: 32 bit + No serial flags are currently defined. + + serial_*: + One of the serial_ functions. + + shellscr: + The name of a shell script. The script must exist + in /opt/pigpio/cgi and must be executable. + + show_errors: + Controls the display of pigpio daemon connection failures. + The default of True prints the probable failure reasons to + standard output. + + spi_channel: 0-2 + A SPI channel. + + spi_flags: 32 bit + See [*spi_open*]. + + steady: 0-300000 + + The number of microseconds level changes must be stable for + before reporting the level changed ([*set_glitch_filter*]) + or triggering the active part of a noise filter + ([*set_noise_filter*]). + + t1: + A tick (earlier). + + t2: + A tick (later). + + tty: + A Pi serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0 + + uint32: + An unsigned 32 bit number. + + user_gpio: 0-31 + A Broadcom numbered GPIO. + + All the user GPIO are in the range 0-31. + + Not all the GPIO within this range are usable, some are reserved + for system use. + + See [*gpio*]. + + wait_timeout: 0.0 - + The number of seconds to wait in [*wait_for_edge*] before timing out. + + wave_add_*: + One of the following + + [*wave_add_new*] + [*wave_add_generic*] + [*wave_add_serial*] + + wave_id: >=0 + A number referencing a wave created by [*wave_create*]. + + wave_send_*: + One of the following + + [*wave_send_once*] + [*wave_send_repeat*] + + wdog_timeout: 0-60000 + Defines a GPIO watchdog timeout in milliseconds. If no level + change is detected on the GPIO for timeout millisecond a watchdog + timeout report is issued (with level TIMEOUT). + + word_val: 0-65535 + A whole number. + """ + pass + diff --git a/thirdparty/PIGPIO/pigpio.service b/thirdparty/PIGPIO/pigpio.service new file mode 100644 index 0000000000..342a1673d5 --- /dev/null +++ b/thirdparty/PIGPIO/pigpio.service @@ -0,0 +1,16 @@ +[Unit] +Description=PIGPIO daemon +After=network.target auditd.service + +[Service] +ExecStart=/usr/local/bin/pigpiod -g +#KillMode=process +Restart=on-failure +#RestartPreventExitStatus=255 +Type=exec +CPUSchedulingPolicy=fifo +CPUSchedulingPriority=20 + +[Install] +WantedBy=multi-user.target +Alias=PIGPIO.service diff --git a/thirdparty/PIGPIO/pigpiod.1 b/thirdparty/PIGPIO/pigpiod.1 new file mode 100644 index 0000000000..1f7d3d1d3f --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod.1 @@ -0,0 +1,273 @@ + +." Process this file with +." groff -man -Tascii pigpiod.1 +." +.TH pigpiod 1 2012-2018 Linux "pigpio archive" +.SH NAME +pigpiod - A utility to start the pigpio library as a daemon. + +.SH SYNOPSIS + +sudo pigpiod [OPTION]... +.SH DESCRIPTION + + +.ad l + +.nh +pigpiod is a utility which launches the pigpio library as a daemon. +.br + +.br +Once launched the pigpio library runs in the background accepting commands from the pipe and socket interfaces. +.br + +.br +The pigpiod utility requires sudo privileges to launch the library but thereafter the pipe and socket commands may be issued by normal users. +.br + +.br +pigpiod accepts the following configuration options +.br + +.br +.SH OPTIONS + +.IP "\fB-a value\fP" +DMA memory allocation mode. +0=AUTO, 1=PMAP, 2=MBOX. +Default AUTO +. +.IP "\fB-b value\fP" +GPIO sample buffer size in milliseconds. +100-10000. +Default 120 +. +.IP "\fB-c value\fP" +Library internal settings. +. +Default 0 +. +.IP "\fB-d value\fP" +Primary DMA channel. +0-14. +Default 14 +. +.IP "\fB-e value\fP" +Secondary DMA channel. +0-14. +Default 6. Preferably use one of DMA channels 0 to 6 for the secondary channel +. +.IP "\fB-f\fP" +Disable fifo interface. +. +Default enabled +. +.IP "\fB-g\fP" +Run in foreground (do not fork). +. +Default disabled +. +.IP "\fB-k\fP" +Disable local and remote socket interface. +. +Default enabled +. +.IP "\fB-l\fP" +Disable remote socket interface. +. +Default enabled +. +.IP "\fB-m\fP" +Disable alerts (sampling). +. +Default enabled +. +.IP "\fB-n IP address\fP" +Allow IP address to use the socket interface. +Name (e.g. paul) or dotted quad (e.g. 192.168.1.66). +If the -n option is not used all addresses are allowed (unless overridden by the -k or -l options). Multiple -n options are allowed. If -k has been used -n has no effect. If -l has been used only -n localhost has any effect +. +.IP "\fB-p value\fP" +Socket port. +1024-32000. +Default 8888 +. +.IP "\fB-s value\fP" +Sample rate. +1, 2, 4, 5, 8, or 10 microseconds. +Default 5 +. +.IP "\fB-t value\fP" +Clock peripheral. +0=PWM 1=PCM. +Default PCM. pigpio uses one or both of PCM and PWM. If PCM is used then PWM is available for audio. If PWM is used then PCM is available for audio. If waves or hardware PWM are used neither PWM nor PCM will be available for audio. +. +.IP "\fB-v -V\fP" +Display pigpio version and exit. +. + +. +.IP "\fB-x mask\fP" +GPIO which may be updated. +A 54 bit mask with (1< +*/ + +/* +This version is for pigpio version 65+ +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "pigpio.h" + +/* +This program starts the pigpio library as a daemon. +*/ + +static unsigned bufferSizeMilliseconds = PI_DEFAULT_BUFFER_MILLIS; +static unsigned clockMicros = PI_DEFAULT_CLK_MICROS; +static unsigned clockPeripheral = PI_DEFAULT_CLK_PERIPHERAL; +static unsigned ifFlags = PI_DEFAULT_IF_FLAGS; +static int foreground = PI_DEFAULT_FOREGROUND; +static unsigned DMAprimaryChannel = PI_DEFAULT_DMA_PRIMARY_CHANNEL; +static unsigned DMAsecondaryChannel = PI_DEFAULT_DMA_SECONDARY_CHANNEL; +static unsigned socketPort = PI_DEFAULT_SOCKET_PORT; +static unsigned memAllocMode = PI_DEFAULT_MEM_ALLOC_MODE; +static uint64_t updateMask = -1; + +static uint32_t cfgInternals = PI_DEFAULT_CFG_INTERNALS; + +static int updateMaskSet = 0; + +static FILE * errFifo; + +static uint32_t sockNetAddr[MAX_CONNECT_ADDRESSES]; + +static int numSockNetAddr = 0; + +void fatal(char *fmt, ...) +{ + char buf[128]; + va_list ap; + + va_start(ap, fmt); + vsnprintf(buf, sizeof(buf), fmt, ap); + va_end(ap); + + fprintf(stderr, "%s\n", buf); + + fflush(stderr); + + exit(EXIT_FAILURE); +} + +void usage() +{ + fprintf(stderr, "\n" \ + "pigpio V%d\n" \ + "Usage: sudo pigpiod [OPTION] ...\n" \ + " -a value, DMA mode, 0=AUTO, 1=PMAP, 2=MBOX, default AUTO\n" \ + " -b value, sample buffer size in ms, default 120\n" \ + " -c value, library internal settings, default 0\n" \ + " -d value, primary DMA channel, 0-14, default 14\n" \ + " -e value, secondary DMA channel, 0-14, default 6\n" \ + " -f, disable fifo interface, default enabled\n" \ + " -g, run in foreground (do not fork), default disabled\n" \ + " -k, disable socket interface, default enabled\n" \ + " -l, localhost socket only default local+remote\n" \ + " -m, disable alerts default enabled\n" \ + " -n IP addr, allow address, name or dotted, default allow all\n" \ + " -p value, socket port, 1024-32000, default 8888\n" \ + " -s value, sample rate, 1, 2, 4, 5, 8, or 10, default 5\n" \ + " -t value, clock peripheral, 0=PWM 1=PCM, default PCM\n" \ + " -v, -V, display pigpio version and exit\n" \ + " -x mask, GPIO which may be updated, default board GPIO\n" \ + "EXAMPLE\n" \ + "sudo pigpiod -s 2 -b 200 -f\n" \ + " Set a sample rate of 2 microseconds with a 200 millisecond\n" \ + " buffer. Disable the fifo interface.\n" \ + "\n", PIGPIO_VERSION); +} + +static uint64_t getNum(char *str, int *err) +{ + uint64_t val; + char *endptr; + + *err = 0; + val = strtoll(str, &endptr, 0); + if (*endptr) {*err = 1; val = -1;} + return val; +} + +static uint32_t checkAddr(char *addrStr) +{ + int err; + struct addrinfo hints, *res; + struct sockaddr_in *sin; + const char *portStr; + uint32_t addr; + + portStr = getenv(PI_ENVPORT); + + if (!portStr) portStr = PI_DEFAULT_SOCKET_PORT_STR; + + memset (&hints, 0, sizeof (hints)); + + hints.ai_family = AF_INET; + hints.ai_socktype = SOCK_STREAM; + hints.ai_flags |= AI_CANONNAME; + + err = getaddrinfo(addrStr, portStr, &hints, &res); + + if (err) return 0; + + sin = (struct sockaddr_in *)res->ai_addr; + addr = sin->sin_addr.s_addr; + + freeaddrinfo(res); + + return addr; +} + +static void initOpts(int argc, char *argv[]) +{ + int opt, err, i; + uint32_t addr; + int64_t mask; + + while ((opt = getopt(argc, argv, "a:b:c:d:e:fgkln:mp:s:t:x:vV")) != -1) + { + switch (opt) + { + case 'a': + i = getNum(optarg, &err); + if ((i >= PI_MEM_ALLOC_AUTO) && (i <= PI_MEM_ALLOC_MAILBOX)) + memAllocMode = i; + else fatal("invalid -a option (%d)", i); + break; + + case 'b': + i = getNum(optarg, &err); + if ((i >= PI_BUF_MILLIS_MIN) && (i <= PI_BUF_MILLIS_MAX)) + bufferSizeMilliseconds = i; + else fatal("invalid -b option (%d)", i); + break; + + case 'c': + i = getNum(optarg, &err); + if ((i >= 0) && (i < PI_CFG_ILLEGAL_VAL)) + cfgInternals = i; + else fatal("invalid -c option (%x)", i); + break; + + case 'd': + i = getNum(optarg, &err); + if ((i >= PI_MIN_DMA_CHANNEL) && (i <= PI_MAX_DMA_CHANNEL)) + DMAprimaryChannel = i; + else fatal("invalid -d option (%d)", i); + break; + + case 'e': + i = getNum(optarg, &err); + if ((i >= PI_MIN_DMA_CHANNEL) && (i <= PI_MAX_DMA_CHANNEL)) + DMAsecondaryChannel = i; + else fatal("invalid -e option (%d)", i); + break; + + case 'f': + ifFlags |= PI_DISABLE_FIFO_IF; + break; + + case 'g': + foreground = 1; + break; + + case 'k': + ifFlags |= PI_DISABLE_SOCK_IF; + break; + + case 'l': + ifFlags |= PI_LOCALHOST_SOCK_IF; + break; + + case 'm': + ifFlags |= PI_DISABLE_ALERT; + break; + + case 'n': + addr = checkAddr(optarg); + if (addr && (numSockNetAddr= PI_MIN_SOCKET_PORT) && (i <= PI_MAX_SOCKET_PORT)) + socketPort = i; + else fatal("invalid -p option (%d)", i); + break; + + case 's': + i = getNum(optarg, &err); + + switch(i) + { + case 1: + case 2: + case 4: + case 5: + case 8: + case 10: + clockMicros = i; + break; + + default: + fatal("invalid -s option (%d)", i); + break; + } + break; + + case 't': + i = getNum(optarg, &err); + if ((i >= PI_CLOCK_PWM) && (i <= PI_CLOCK_PCM)) + clockPeripheral = i; + else fatal("invalid -t option (%d)", i); + break; + + case 'v': + case 'V': + printf("%d\n", PIGPIO_VERSION); + exit(EXIT_SUCCESS); + break; + + case 'x': + mask = getNum(optarg, &err); + if (!err) + { + updateMask = mask; + updateMaskSet = 1; + } + else fatal("invalid -x option (%s)", optarg); + break; + + default: /* '?' */ + usage(); + exit(EXIT_FAILURE); + } + } +} + +void terminate(int signum) +{ + /* only registered for SIGHUP/SIGTERM */ + + gpioTerminate(); + + fprintf(errFifo, "SIGHUP/SIGTERM received\n"); + + fflush(NULL); + + fclose(errFifo); + + unlink(PI_ERRFIFO); + + exit(0); +} + + +int main(int argc, char **argv) +{ + pid_t pid; + int flags; + + /* check command line parameters */ + + initOpts(argc, argv); + + if (!foreground) { + /* Fork off the parent process */ + + pid = fork(); + + if (pid < 0) { exit(EXIT_FAILURE); } + + /* If we got a good PID, then we can exit the parent process. */ + + if (pid > 0) { exit(EXIT_SUCCESS); } + + /* Change the file mode mask */ + + umask(0); + + /* Open any logs here */ + + /* NONE */ + + /* Create a new SID for the child process */ + + if (setsid() < 0) fatal("setsid failed (%m)"); + + /* Change the current working directory */ + + if ((chdir("/")) < 0) fatal("chdir failed (%m)"); + + /* Close out the standard file descriptors */ + + fclose(stdin); + fclose(stdout); + } + + /* configure library */ + + gpioCfgBufferSize(bufferSizeMilliseconds); + + gpioCfgClock(clockMicros, clockPeripheral, 0); + + gpioCfgInterfaces(ifFlags); + + gpioCfgDMAchannels(DMAprimaryChannel, DMAsecondaryChannel); + + gpioCfgSocketPort(socketPort); + + gpioCfgMemAlloc(memAllocMode); + + if (updateMaskSet) gpioCfgPermissions(updateMask); + + gpioCfgNetAddr(numSockNetAddr, sockNetAddr); + + gpioCfgSetInternals(cfgInternals); + + /* start library */ + + if (gpioInitialise()< 0) fatal("Can't initialise pigpio library"); + + /* create pipe for error reporting */ + + unlink(PI_ERRFIFO); + + mkfifo(PI_ERRFIFO, 0664); + + if (chmod(PI_ERRFIFO, 0664) < 0) + fatal("chmod %s failed (%m)", PI_ERRFIFO); + + errFifo = freopen(PI_ERRFIFO, "w+", stderr); + + if (errFifo) + { + /* set stderr non-blocking */ + + flags = fcntl(fileno(errFifo), F_GETFL, 0); + fcntl(fileno(errFifo), F_SETFL, flags | O_NONBLOCK); + + /* request SIGHUP/SIGTERM from libarary for termination */ + + gpioSetSignalFunc(SIGHUP, terminate); + gpioSetSignalFunc(SIGTERM, terminate); + + /* sleep forever */ + + while (1) + { + /* cat /dev/pigerr to view daemon errors */ + + sleep(5); + + fflush(errFifo); + } + } + else + { + fprintf(stderr, "freopen failed (%m)"); + + gpioTerminate(); + } + + return 0; +} + + diff --git a/thirdparty/PIGPIO/pigpiod_if.3 b/thirdparty/PIGPIO/pigpiod_if.3 new file mode 100644 index 0000000000..c079c789ae --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if.3 @@ -0,0 +1,5003 @@ + +." Process this file with +." groff -man -Tascii pigpiod_if.3 +." +.TH pigpiod_if 3 2012-2018 Linux "pigpio archive" +.SH NAME +pigpiod_if - A C library to interface to the pigpio daemon. + +.SH SYNOPSIS + +#include + + +gcc -Wall -pthread -o prog prog.c -lpigpiod_if -lrt + + ./prog +.SH DESCRIPTION + + +.ad l + +.nh + +.br + +.br +THIS LIBRARY IS DEPRECATED. NEW CODE SHOULD BE WRITTEN TO +USE THE MORE VERSATILE pigpiod_if2 LIBRARY. + +.br + +.br +pigpiod_if is a C library for the Raspberry which allows control +of the GPIO via the socket interface to the pigpio daemon. +.br + +.br + +.br +.SS Features +.br + +.br +o hardware timed PWM on any of GPIO 0-31 + +.br + +.br +o hardware timed servo pulses on any of GPIO 0-31 + +.br + +.br +o callbacks when any of GPIO 0-31 change state + +.br + +.br +o callbacks at timed intervals + +.br + +.br +o reading/writing all of the GPIO in a bank as one operation + +.br + +.br +o individually setting GPIO modes, reading and writing + +.br + +.br +o notifications when any of GPIO 0-31 change state + +.br + +.br +o the construction of output waveforms with microsecond timing + +.br + +.br +o rudimentary permission control over GPIO + +.br + +.br +o a simple interface to start and stop new threads + +.br + +.br +o I2C, SPI, and serial link wrappers + +.br + +.br +o creating and running scripts on the pigpio daemon + +.br + +.br +.SS GPIO +.br + +.br +ALL GPIO are identified by their Broadcom number. + +.br + +.br +.SS Notes +.br + +.br +The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals. + +.br + +.br +.SS Usage +.br + +.br +Include in your source files. + +.br + +.br +Assuming your source is in prog.c use the following command to build + +.br + +.br + +.EX +gcc -Wall -pthread -o prog prog.c -lpigpiod_if -lrt +.br + +.EE + +.br + +.br +to run make sure the pigpio daemon is running + +.br + +.br + +.EX +sudo pigpiod +.br + +.br + ./prog # sudo is not required to run programs linked to pigpiod_if +.br + +.EE + +.br + +.br +For examples see x_pigpiod_if.c within the pigpio archive file. + +.br + +.br +.SS Notes +.br + +.br +All the functions which return an int return < 0 on error + +.br + +.br +.SH FUNCTIONS + +.IP "\fBdouble time_time(void)\fP" +.IP "" 4 +Return the current time in seconds since the Epoch. + +.IP "\fBvoid time_sleep(double seconds)\fP" +.IP "" 4 +Delay execution for a given number of seconds. + +.br + +.br + +.EX +seconds: the number of seconds to delay. +.br + +.EE + +.IP "\fBchar *pigpio_error(int errnum)\fP" +.IP "" 4 +Return a text description for an error code. + +.br + +.br + +.EX +errnum: the error code. +.br + +.EE + +.IP "\fBunsigned pigpiod_if_version(void)\fP" +.IP "" 4 +Return the pigpiod_if version. + +.IP "\fBpthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata)\fP" +.IP "" 4 +Starts a new thread of execution with thread_func as the main routine. + +.br + +.br + +.EX +thread_func: the main function for the new thread. +.br + userdata: a pointer to an arbitrary argument. +.br + +.EE + +.br + +.br +Returns a pointer to pthread_t if OK, otherwise NULL. + +.br + +.br +The function is passed the single argument userdata. + +.br + +.br +The thread can be cancelled by passing the pointer to pthread_t to +\fBstop_thread\fP. + +.IP "\fBvoid stop_thread(pthread_t *pth)\fP" +.IP "" 4 +Cancels the thread pointed at by pth. + +.br + +.br + +.EX +pth: the thread to be stopped. +.br + +.EE + +.br + +.br +No value is returned. + +.br + +.br +The thread to be stopped should have been started with \fBstart_thread\fP. + +.IP "\fBint pigpio_start(char *addrStr, char *portStr)\fP" +.IP "" 4 +Connect to the pigpio daemon. Reserving command and +notification streams. + +.br + +.br + +.EX +addrStr: specifies the host or IP address of the Pi running the +.br + pigpio daemon. It may be NULL in which case localhost +.br + is used unless overridden by the PIGPIO_ADDR environment +.br + variable. +.br + +.br +portStr: specifies the port address used by the Pi running the +.br + pigpio daemon. It may be NULL in which case "8888" +.br + is used unless overridden by the PIGPIO_PORT environment +.br + variable. +.br + +.EE + +.IP "\fBvoid pigpio_stop(void)\fP" +.IP "" 4 +Terminates the connection to the pigpio daemon and releases +resources used by the library. + +.IP "\fBint set_mode(unsigned gpio, unsigned mode)\fP" +.IP "" 4 +Set the GPIO mode. + +.br + +.br + +.EX +gpio: 0-53. +.br +mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1, +.br + PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE, +or PI_NOT_PERMITTED. + +.IP "\fBint get_mode(unsigned gpio)\fP" +.IP "" 4 +Get the GPIO mode. + +.br + +.br + +.EX +gpio: 0-53. +.br + +.EE + +.br + +.br +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. + +.IP "\fBint set_pull_up_down(unsigned gpio, unsigned pud)\fP" +.IP "" 4 +Set or clear the GPIO pull-up/down resistor. + +.br + +.br + +.EX +gpio: 0-53. +.br + pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD, +or PI_NOT_PERMITTED. + +.IP "\fBint gpio_read(unsigned gpio)\fP" +.IP "" 4 +Read the GPIO level. + +.br + +.br + +.EX +gpio:0-53. +.br + +.EE + +.br + +.br +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. + +.IP "\fBint gpio_write(unsigned gpio, unsigned level)\fP" +.IP "" 4 +Write the GPIO level. + +.br + +.br + +.EX + gpio: 0-53. +.br +level: 0, 1. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL, +or PI_NOT_PERMITTED. + +.br + +.br +Notes + +.br + +.br +If PWM or servo pulses are active on the GPIO they are switched off. + +.IP "\fBint set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle)\fP" +.IP "" 4 +Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br +dutycycle: 0-range (range defaults to 255). +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE, +or PI_NOT_PERMITTED. +Notes + +.br + +.br +The \fBset_PWM_range\fP function may be used to change the +default range of 255. + +.IP "\fBint get_PWM_dutycycle(unsigned user_gpio)\fP" +.IP "" 4 +Return the PWM dutycycle in use on a GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +.br + +.br +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see \fBget_PWM_range\fP). + +.br + +.br +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). + +.IP "\fBint set_PWM_range(unsigned user_gpio, unsigned range)\fP" +.IP "" 4 +Set the range of PWM values to be used on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + range: 25-40000. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE, +or PI_NOT_PERMITTED. + +.br + +.br +Notes + +.br + +.br +If PWM is currently active on the GPIO its dutycycle will be +scaled to reflect the new range. + +.br + +.br +The real range, the number of steps between fully off and fully on +for each of the 18 available GPIO frequencies is + +.br + +.br + +.EX + 25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6), +.br + 400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12), +.br +2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18) +.br + +.EE + +.br + +.br +The real value set by set_PWM_range is (dutycycle * real range) / range. + +.IP "\fBint get_PWM_range(unsigned user_gpio)\fP" +.IP "" 4 +Get the range of PWM values being used on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns the dutycycle range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.br + +.br +If a hardware clock or hardware PWM is active on the GPIO the +reported range will be 1000000 (1M). + +.IP "\fBint get_PWM_real_range(unsigned user_gpio)\fP" +.IP "" 4 +Get the real underlying range of PWM values being used on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns the real range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.br + +.br +If a hardware clock is active on the GPIO the reported +real range will be 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +.br + +.br + +.IP "\fBint set_PWM_frequency(unsigned user_gpio, unsigned frequency)\fP" +.IP "" 4 +Set the frequency (in Hz) of the PWM to be used on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br +frequency: >=0 (Hz). +.br + +.EE + +.br + +.br +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PERMITTED. + +.br + +.br +If PWM is currently active on the GPIO it will be switched +off and then back on at the new frequency. + +.br + +.br +Each GPIO can be independently set to one of 18 different +PWM frequencies. + +.br + +.br +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The +sample rate is set when the pigpio daemon is started. + +.br + +.br +The frequencies for each sample rate are: + +.br + +.br + +.EX + Hertz +.br + +.br + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 +.br + 1250 1000 800 500 400 250 200 100 50 +.br + +.br + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 +.br + 625 500 400 250 200 125 100 50 25 +.br + +.br + 4: 10000 5000 2500 2000 1250 1000 625 500 400 +.br + 313 250 200 125 100 63 50 25 13 +.br +sample +.br + rate +.br + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 +.br + 250 200 160 100 80 50 40 20 10 +.br + +.br + 8: 5000 2500 1250 1000 625 500 313 250 200 +.br + 156 125 100 63 50 31 25 13 6 +.br + +.br + 10: 4000 2000 1000 800 500 400 250 200 160 +.br + 125 100 80 50 40 25 20 10 5 +.br + +.EE + +.IP "\fBint get_PWM_frequency(unsigned user_gpio)\fP" +.IP "" 4 +Get the frequency of PWM being used on the GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + +.EE + +.br + +.br +For normal PWM the frequency will be that defined for the GPIO by +\fBset_PWM_frequency\fP. + +.br + +.br +If a hardware clock is active on the GPIO the reported frequency +will be that set by \fBhardware_clock\fP. + +.br + +.br +If hardware PWM is active on the GPIO the reported frequency +will be that set by \fBhardware_PWM\fP. + +.br + +.br +Returns the frequency (in hertz) used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.IP "\fBint set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth)\fP" +.IP "" 4 +Start (500-2500) or stop (0) servo pulses on the GPIO. + +.br + +.br + +.EX + user_gpio: 0-31. +.br +pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise). +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or +PI_NOT_PERMITTED. + +.br + +.br +The selected pulsewidth will continue to be transmitted until +changed by a subsequent call to set_servo_pulsewidth. + +.br + +.br +The pulsewidths supported by servos varies and should probably be +determined by experiment. A value of 1500 should always be safe and +represents the mid-point of rotation. + +.br + +.br +You can DAMAGE a servo if you command it to move beyond its limits. + +.br + +.br +OTHER UPDATE RATES: + +.br + +.br +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +.br + +.br + +.EX +Update Rate (Hz) 50 100 200 400 500 +.br +1E6/Hz 20000 10000 5000 2500 2000 +.br + +.EE + +.br + +.br +Firstly set the desired PWM frequency using \fBset_PWM_frequency\fP. + +.br + +.br +Then set the PWM range using \fBset_PWM_range\fP to 1E6/Hz. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +.br + +.br +E.g. If you want to update a servo connected to GPIO 25 at 400Hz + +.br + +.br + +.EX +set_PWM_frequency(25, 400); +.br +set_PWM_range(25, 2500); +.br + +.EE + +.br + +.br +Thereafter use the \fBset_PWM_dutycycle\fP function to move the servo, +e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. +.br + +.IP "\fBint get_servo_pulsewidth(unsigned user_gpio)\fP" +.IP "" 4 +Return the servo pulsewidth in use on a GPIO. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. + +.IP "\fBint notify_open(void)\fP" +.IP "" 4 +Get a free notification handle. + +.br + +.br +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +.br + +.br +A notification is a method for being notified of GPIO state +changes via a pipe. + +.br + +.br +Pipes are only accessible from the local machine so this function +serves no purpose if you are using the library from a remote machine. +The in-built (socket) notifications provided by \fBcallback\fP +should be used instead. + +.br + +.br +Notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). +E.g. if the function returns 15 then the notifications must be +read from /dev/pigpio15. + +.IP "\fBint notify_begin(unsigned handle, uint32_t bits)\fP" +.IP "" 4 +Start notifications on a previously opened handle. + +.br + +.br + +.EX +handle: 0-31 (as returned by \fBnotify_open\fP) +.br + bits: a mask indicating the GPIO to be notified. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +The notification sends state changes for each GPIO whose +corresponding bit in bits is set. + +.br + +.br +Each notification occupies 12 bytes in the fifo as follows: + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint16_t seqno; +.br + uint16_t flags; +.br + uint32_t tick; +.br + uint32_t level; +.br +} gpioReport_t; +.br + +.EE + +.br + +.br +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +.br + +.br +flags: two flags are defined, PI_NTFY_FLAGS_WDOG and PI_NTFY_FLAGS_ALIVE. + +.br + +.br +PI_NTFY_FLAGS_WDOG, if bit 5 is set then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +.br + +.br +PI_NTFY_FLAGS_ALIVE, if bit 6 is set this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +.br + +.br +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +.br + +.br +level: indicates the level of each GPIO. If bit 1<=0 +.br + numBytes: >=1 +.br + str: an array of chars. +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +.br + +.br +NOTES: + +.br + +.br +The serial data is formatted as one start bit, \fBdata_bits\fP data bits, +and \fBstop_bits\fP/2 stop bits. + +.br + +.br +It is legal to add serial data streams with different baud rates to +the same waveform. + +.br + +.br +\fBnumBytes\fP is the number of bytes of data in str. + +.br + +.br +The bytes required for each character depend upon \fBdata_bits\fP. + +.br + +.br +For \fBdata_bits\fP 1-8 there will be one byte per character. +.br +For \fBdata_bits\fP 9-16 there will be two bytes per character. +.br +For \fBdata_bits\fP 17-32 there will be four bytes per character. + +.IP "\fBint wave_create(void)\fP" +.IP "" 4 +This function creates a waveform from the data provided by the prior +calls to the \fBwave_add_*\fP functions. Upon success a wave id +greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM, +PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID. + +.br + +.br +The data provided by the \fBwave_add_*\fP functions is consumed by this +function. + +.br + +.br +As many waveforms may be created as there is space available. The +wave id is passed to \fBwave_send_*\fP to specify the waveform to transmit. + +.br + +.br +Normal usage would be + +.br + +.br +Step 1. \fBwave_clear\fP to clear all waveforms and added data. + +.br + +.br +Step 2. \fBwave_add_*\fP calls to supply the waveform data. + +.br + +.br +Step 3. \fBwave_create\fP to create the waveform and get a unique id + +.br + +.br +Repeat steps 2 and 3 as needed. + +.br + +.br +Step 4. \fBwave_send_*\fP with the id of the waveform to transmit. + +.br + +.br +A waveform comprises one or more pulses. Each pulse consists of a +\fBgpioPulse_t\fP structure. + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint32_t gpioOn; +.br + uint32_t gpioOff; +.br + uint32_t usDelay; +.br +} gpioPulse_t; +.br + +.EE + +.br + +.br +The fields specify + +.br + +.br +1) the GPIO to be switched on at the start of the pulse. +.br +2) the GPIO to be switched off at the start of the pulse. +.br +3) the delay in microseconds before the next pulse. +.br + +.br + +.br +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). + +.br + +.br +When a waveform is started each pulse is executed in order with the +specified delay between the pulse and the next. + +.br + +.br +Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, +PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. + +.IP "\fBint wave_delete(unsigned wave_id)\fP" +.IP "" 4 +This function deletes the waveform with id wave_id. + +.br + +.br + +.EX +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Wave ids are allocated in order, 0, 1, 2, etc. + +.br + +.br +The wave is flagged for deletion. The resources used by the wave +will only be reused when either of the following apply. + +.br + +.br +- all waves with higher numbered wave ids have been deleted or have +been flagged for deletion. + +.br + +.br +- a new wave is created which uses exactly the same resources as +the current wave (see the C source for gpioWaveCreate for details). + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. + +.IP "\fBint wave_send_once(unsigned wave_id)\fP" +.IP "" 4 +This function transmits the waveform with id wave_id. The waveform +is sent once. + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br + +.EX +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint wave_send_repeat(unsigned wave_id)\fP" +.IP "" 4 +This function transmits the waveform with id wave_id. The waveform +cycles until cancelled (either by the sending of a new waveform or +by \fBwave_tx_stop\fP). + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br + +.EX +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint wave_chain(char *buf, unsigned bufSize)\fP" +.IP "" 4 +This function transmits a chain of waveforms. + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of \fBwave_id\fPs and optional command +codes and related data. + +.br + +.br + +.EX + buf: pointer to the wave_ids and optional command codes +.br +bufSize: the number of bytes in buf +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +.br + +.br +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +.br + +.br +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +.br + +.br +Delays between waves may be added with the delay command. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +Loop Start 255 0 Identify start of a wave block +.br +Loop Repeat 255 1 x y loop x + y*256 times +.br +Delay 255 2 x y delay x + y*256 microseconds +.br +Loop Forever 255 3 loop forever +.br + +.br + +.br +If present Loop Forever must be the last entry in the chain. + +.br + +.br +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +#define WAVES 5 +.br +#define GPIO 4 +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int i, wid[WAVES]; +.br + +.br + if (pigpio_start(0, 0)<0) return -1; +.br + +.br + set_mode(GPIO, PI_OUTPUT); +.br + +.br + for (i=0; i=0, as returned by \fBstore_script\fP. +.br + numPar: 0-10, the number of parameters. +.br + param: an array of parameters. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint script_status(unsigned script_id, uint32_t *param)\fP" +.IP "" 4 +This function returns the run status of a stored script as well +as the current values of parameters 0 to 9. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBstore_script\fP. +.br + param: an array to hold the returned 10 parameters. +.br + +.EE + +.br + +.br +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +.br + +.br +The run status may be + +.br + +.br + +.EX +PI_SCRIPT_INITING +.br +PI_SCRIPT_HALTED +.br +PI_SCRIPT_RUNNING +.br +PI_SCRIPT_WAITING +.br +PI_SCRIPT_FAILED +.br + +.EE + +.br + +.br +The current value of script parameters 0 to 9 are returned in param. + +.IP "\fBint stop_script(unsigned script_id)\fP" +.IP "" 4 +This function stops a running script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBstore_script\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint delete_script(unsigned script_id)\fP" +.IP "" 4 +This function deletes a stored script. + +.br + +.br + +.EX +script_id: >=0, as returned by \fBstore_script\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint bb_serial_read_open(unsigned user_gpio, unsigned baud, unsigned data_bits)\fP" +.IP "" 4 +This function opens a GPIO for bit bang reading of serial data. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + baud: 50-250000 +.br +data_bits: 1-32 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, +or PI_GPIO_IN_USE. + +.br + +.br +The serial data is returned in a cyclic buffer and is read using +bb_serial_read. + +.br + +.br +It is the caller's responsibility to read data from the cyclic buffer +in a timely fashion. + +.IP "\fBint bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize)\fP" +.IP "" 4 +This function copies up to bufSize bytes of data read from the +bit bang serial cyclic buffer to the buffer starting at buf. + +.br + +.br + +.EX +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + buf: an array to receive the read bytes. +.br + bufSize: >=0 +.br + +.EE + +.br + +.br +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +.br + +.br +The bytes returned for each character depend upon the number of +data bits \fBdata_bits\fP specified in the \fBbb_serial_read_open\fP command. + +.br + +.br +For \fBdata_bits\fP 1-8 there will be one byte per character. +.br +For \fBdata_bits\fP 9-16 there will be two bytes per character. +.br +For \fBdata_bits\fP 17-32 there will be four bytes per character. + +.IP "\fBint bb_serial_read_close(unsigned user_gpio)\fP" +.IP "" 4 +This function closes a GPIO for bit bang reading of serial data. + +.br + +.br + +.EX +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. + +.IP "\fBint bb_serial_invert(unsigned user_gpio, unsigned invert)\fP" +.IP "" 4 +This function inverts serial logic for big bang serial reads. + +.br + +.br + +.EX +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + invert: 0-1, 1 invert, 0 normal. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT. + +.IP "\fBint i2c_open(unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags)\fP" +.IP "" 4 +This returns a handle for the device at address i2c_addr on bus i2c_bus. + +.br + +.br + +.EX + i2c_bus: >=0. +.br + i2c_addr: 0-0x7F. +.br +i2c_flags: 0. +.br + +.EE + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.br + +.br +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + SDA SCL +.br +I2C 0 0 1 +.br +I2C 1 2 3 +.br + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +.br + +.br +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +.br + +.br + +.EX +S (1 bit) : Start bit +.br +P (1 bit) : Stop bit +.br +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +.br +A, NA (1 bit) : Accept and not accept bit. +.br +.br +.br +Addr (7 bits): I2C 7 bit address. +.br +Comm (8 bits): Command byte, a data byte which often selects a register. +.br +Data (8 bits): A data byte. +.br +Count (8 bits): A data byte containing the length of a block operation. +.br + +.br +[..]: Data sent by the device. +.br + +.EE + +.IP "\fBint i2c_close(unsigned handle)\fP" +.IP "" 4 +This closes the I2C device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint i2c_write_quick(unsigned handle, unsigned bit)\fP" +.IP "" 4 +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + bit: 0-1, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Quick command. SMBus 2.0 5.5.1 + +.EX +S Addr Rd/Wr [A] P +.br + +.EE + +.IP "\fBint i2c_write_byte(unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This sends a single byte to the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + bVal: 0-0xFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Send byte. SMBus 2.0 5.5.2 + +.EX +S Addr Wr [A] Data [A] P +.br + +.EE + +.IP "\fBint i2c_read_byte(unsigned handle)\fP" +.IP "" 4 +This reads a single byte from the device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +.br + +.br +Receive byte. SMBus 2.0 5.5.3 + +.EX +S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2c_write_byte_data(unsigned handle, unsigned i2c_reg, unsigned bVal)\fP" +.IP "" 4 +This writes a single byte to the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + bVal: 0-0xFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write byte. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] Comm [A] Data [A] P +.br + +.EE + +.IP "\fBint i2c_write_word_data(unsigned handle, unsigned i2c_reg, unsigned wVal)\fP" +.IP "" 4 +This writes a single 16 bit word to the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + wVal: 0-0xFFFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write word. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] P +.br + +.EE + +.IP "\fBint i2c_read_byte_data(unsigned handle, unsigned i2c_reg)\fP" +.IP "" 4 +This reads a single byte from the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read byte. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] Comm [A] S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2c_read_word_data(unsigned handle, unsigned i2c_reg)\fP" +.IP "" 4 +This reads a single 16 bit word from the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read word. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] Comm [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2c_process_call(unsigned handle, unsigned i2c_reg, unsigned wVal)\fP" +.IP "" 4 +This writes 16 bits of data to the specified register of the device +associated with handle and and reads 16 bits of data in return. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write/read. +.br + wVal: 0-0xFFFF, the value to write. +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Process call. SMBus 2.0 5.5.6 + +.EX +S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] +.br + S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2c_write_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes up to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + buf: an array with the data to send. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Block write. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] Comm [A] Count [A] Data [A] Data [A] ... [A] Data [A] P +.br + +.EE + +.IP "\fBint i2c_read_block_data(unsigned handle, unsigned i2c_reg, char *buf)\fP" +.IP "" 4 +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + buf: an array to receive the read data. +.br + +.EE + +.br + +.br +The amount of returned data is set by the device. + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Block read. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] Comm [A] +.br + S Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P +.br + +.EE + +.IP "\fBint i2c_block_process_call(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write/read. +.br + buf: an array with the data to send and to receive the read data. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +The smbus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +.br + +.br +Block write-block read. SMBus 2.0 5.5.8 + +.EX +S Addr Wr [A] Comm [A] Count [A] Data [A] ... +.br + S Addr Rd [A] [Count] A [Data] ... A P +.br + +.EE + +.IP "\fBint i2c_read_i2c_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + buf: an array to receive the read data. +.br + count: 1-32, the number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] Comm [A] +.br + S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P +.br + +.EE + +.IP "\fBint i2c_write_i2c_block_data(unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + buf: the data to write. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] Comm [A] Data [A] Data [A] ... [A] Data [A] P +.br + +.EE + +.IP "\fBint i2c_read_device(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the raw device into buf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + buf: an array to receive the read data bytes. +.br + count: >0, the number of bytes to read. +.br + +.EE + +.br + +.br +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. + +.IP "\fBint i2c_write_device(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This writes count bytes from buf to the raw device. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + buf: an array containing the data bytes to write. +.br + count: >0, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.IP "\fBint i2c_zip(unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +On 2 Switch combined flag on +.br +Off 3 Switch combined flag off +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53, write 0x32, read 6 bytes +.br +Set address 0x1E, write 0x03, read 6 bytes +.br +Set address 0x68, write 0x1B, read 8 bytes +.br +End +.br + +.br +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +.br +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +.br +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +.br +0x00 +.br + +.EE + +.br + +.br + +.IP "\fBint bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud)\fP" +.IP "" 4 +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +.br + +.br +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +.br + +.br +o baud rates as low as 50 +.br +o repeated starts +.br +o clock stretching +.br +o I2C on any pair of spare GPIO + +.br + +.br + +.EX + SDA: 0-31 +.br + SCL: 0-31 +.br +baud: 50-500000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +.br + +.br +NOTE: + +.br + +.br +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. + +.IP "\fBint bb_i2c_close(unsigned SDA)\fP" +.IP "" 4 +This function stops bit banging I2C on a pair of GPIO previously +opened with \fBbb_i2c_open\fP. + +.br + +.br + +.EX +SDA: 0-31, the SDA GPIO used in a prior call to \fBbb_i2c_open\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. + +.IP "\fBint bb_i2c_zip(unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX + SDA: 0-31 (as used in a prior call to \fBbb_i2c_open\fP) +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +Start 2 Start condition +.br +Stop 3 Stop condition +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +.br + +.br +No flags are currently defined. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53 +.br +start, write 0x32, (re)start, read 6 bytes, stop +.br +Set address 0x1E +.br +start, write 0x03, (re)start, read 6 bytes, stop +.br +Set address 0x68 +.br +start, write 0x1B, (re)start, read 8 bytes, stop +.br +End +.br + +.br +0x04 0x53 +.br +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x1E +.br +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x68 +.br +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 +.br + +.br +0x00 +.br + +.EE + +.IP "\fBint spi_open(unsigned spi_channel, unsigned baud, unsigned spi_flags)\fP" +.IP "" 4 +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +.br + +.br +The Pi has two SPI peripherals: main and auxiliary. + +.br + +.br +The main SPI has two chip selects (channels), the auxiliary has +three. + +.br + +.br +The auxiliary SPI is available on all models but the A and B. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + MISO MOSI SCLK CE0 CE1 CE2 +.br +Main SPI 9 10 11 8 7 - +.br +Aux SPI 19 20 21 18 17 16 +.br + +.br + +.br + +.EX +spi_channel: 0-1 (0-2 for the auxiliary SPI). +.br + baud: 32K-125M (values above 30M are unlikely to work). +.br + spi_flags: see below. +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +.br + +.br +spi_flags consists of the least significant 22 bits. + +.br + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +.br + +.EE + +.br + +.br +mm defines the SPI mode. + +.br + +.br +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +.br + +.br + +.EX +Mode POL PHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br + +.br +px is 0 if CEx is active low (default) and 1 for active high. + +.br + +.br +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +.br + +.br +A is 0 for the main SPI, 1 for the auxiliary SPI. + +.br + +.br +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +.br + +.br +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +.br + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +.br + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +.br + +.br +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +.br + +.br +The \fBspi_read\fP, \fBspi_write\fP, and \fBspi_xfer\fP functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +.br + +.br +For bits 1-8 there will be one byte per word. +.br +For bits 9-16 there will be two bytes per word. +.br +For bits 17-32 there will be four bytes per word. + +.br + +.br +Multi-byte transfers are made in least significant byte first order. + +.br + +.br +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +.br + +.br +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +.br + +.br +The other bits in flags should be set to zero. + +.IP "\fBint spi_close(unsigned handle)\fP" +.IP "" 4 +This functions closes the SPI device identified by the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint spi_read(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads count bytes of data from the SPI +device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + buf: an array to receive the read data bytes. +.br + count: the number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spi_write(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + buf: the data bytes to write. +.br + count: the number of bytes to write. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count)\fP" +.IP "" 4 +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + txBuf: the data bytes to write. +.br + rxBuf: the received data bytes. +.br + count: the number of bytes to transfer. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint serial_open(char *ser_tty, unsigned baud, unsigned ser_flags)\fP" +.IP "" 4 +This function opens a serial device at a specified baud rate +with specified flags. The device name must start with +/dev/tty or /dev/serial. + +.br + +.br + +.EX + ser_tty: the serial device to open. +.br + baud: the baud rate in bits per second, see below. +.br +ser_flags: 0. +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +.br + +.br +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.IP "\fBint serial_close(unsigned handle)\fP" +.IP "" 4 +This function closes the serial device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint serial_write_byte(unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This function writes bVal to the serial port associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serial_read_byte(unsigned handle)\fP" +.IP "" 4 +This function reads a byte from the serial port associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +.br + +.br +If no data is ready PI_SER_READ_NO_DATA is returned. + +.IP "\fBint serial_write(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes from buf to the the serial port +associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + buf: the array of bytes to write. +.br + count: the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serial_read(unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads up to count bytes from the the serial port +associated with handle and writes them to buf. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + buf: an array to receive the read data. +.br + count: the maximum number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED. + +.br + +.br +If no data is ready zero is returned. + +.IP "\fBint serial_data_available(unsigned handle)\fP" +.IP "" 4 +Returns the number of bytes available to be read from the +device associated with handle. + +.br + +.br + +.EX +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. + +.IP "\fBint custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned argc)\fP" +.IP "" 4 +This function is available for user customisation. + +.br + +.br +It returns a single integer value. + +.br + +.br + +.EX +arg1: >=0 +.br +arg2: >=0 +.br +argx: extra (byte) arguments +.br +argc: number of extra arguments +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.IP "\fBint custom_2(unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)\fP" +.IP "" 4 +This function is available for user customisation. + +.br + +.br +It differs from custom_1 in that it returns an array of bytes +rather than just an integer. + +.br + +.br +The return value is an integer indicating the number of returned bytes. + +.EX + arg1: >=0 +.br + argc: extra (byte) arguments +.br + count: number of extra arguments +.br +retBuf: buffer for returned data +.br +retMax: maximum number of bytes to return +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.br + +.br +Note, the number of returned bytes will be retMax or less. + +.IP "\fBint callback(unsigned user_gpio, unsigned edge, CBFunc_t f)\fP" +.IP "" 4 +This function initialises a new callback. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + f: the callback function. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the GPIO, edge, and tick, whenever the +GPIO has the identified edge. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +edge 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.EE + +.IP "\fBint callback_ex(unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata)\fP" +.IP "" 4 +This function initialises a new callback. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + f: the callback function. +.br + userdata: a pointer to arbitrary user data. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the GPIO, edge, tick, and user, whenever +the GPIO has the identified edge. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +edge 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.br +userdata pointer Pointer to an arbitrary object +.br + +.EE + +.IP "\fBint callback_cancel(unsigned callback_id)\fP" +.IP "" 4 +This function cancels a callback identified by its id. + +.br + +.br + +.EX +callback_id: >=0, as returned by a call to \fBcallback\fP or \fBcallback_ex\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise pigif_callback_not_found. + +.IP "\fBint wait_for_edge(unsigned user_gpio, unsigned edge, double timeout)\fP" +.IP "" 4 +This function waits for edge on the GPIO for up to timeout +seconds. + +.br + +.br + +.EX +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + timeout: >=0. +.br + +.EE + +.br + +.br +The function returns 1 if the edge occurred, otherwise 0. + +.br + +.br +The function returns when the edge occurs or after the timeout. +.SH PARAMETERS + +.br + +.br + +.IP "\fBactive\fP: 0-1000000" 0 + +.br + +.br +The number of microseconds level changes are reported for once +a noise filter has been triggered (by \fBsteady\fP microseconds of +a stable level). + +.br + +.br + +.IP "\fB*addrStr\fP" 0 +A string specifying the host or IP address of the Pi running +the pigpio daemon. It may be NULL in which case localhost +is used unless overridden by the PIGPIO_ADDR environment +variable. + +.br + +.br + +.IP "\fBarg1\fP" 0 +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBarg2\fP" 0 +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBargc\fP" 0 +The count of bytes passed to a user customised function. + +.br + +.br + +.IP "\fB*argx\fP" 0 +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +.br + +.br + +.IP "\fBbaud\fP" 0 +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +.br + +.br + +.IP "\fBbit\fP" 0 +A value of 0 or 1. + +.br + +.br + +.IP "\fBbits\fP" 0 +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +.br + +.br +A convenient way to set bit n is to or in (1<=0, as returned by a call to \fBcallback\fP or \fBcallback_ex\fP. This is +passed to \fBcallback_cancel\fP to cancel the callback. + +.br + +.br + +.IP "\fBCBFunc_t\fP" 0 + +.EX +typedef void (*CBFunc_t) +.br + (unsigned user_gpio, unsigned level, uint32_t tick); +.br + +.EE + +.br + +.br + +.IP "\fBCBFuncEx_t\fP" 0 + +.EX +typedef void (*CBFuncEx_t) +.br + (unsigned user_gpio, unsigned level, uint32_t tick, void * user); +.br + +.EE + +.br + +.br + +.IP "\fBchar\fP" 0 +A single character, an 8 bit quantity able to store 0-255. + +.br + +.br + +.IP "\fBclkfreq\fP: 4689-250000000 (250M)" 0 +The hardware clock frequency. + +.br + +.br + +.IP "\fBcount\fP" 0 +The number of bytes to be transferred in an I2C, SPI, or Serial +command. + +.br + +.br + +.IP "\fBdata_bits\fP: 1-32" 0 +The number of data bits in each character of serial data. + +.br + +.br + +.EX +#define PI_MIN_WAVE_DATABITS 1 +.br +#define PI_MAX_WAVE_DATABITS 32 +.br + +.EE + +.br + +.br + +.IP "\fBdouble\fP" 0 +A floating point number. + +.br + +.br + +.IP "\fBdutycycle\fP: 0-range" 0 +A number representing the ratio of on time to off time for PWM. + +.br + +.br +The number may vary between 0 and range (default 255) where +0 is off and range is fully on. + +.br + +.br + +.IP "\fBedge\fP" 0 +Used to identify a GPIO level transition of interest. A rising edge is +a level change from 0 to 1. A falling edge is a level change from 1 to 0. + +.br + +.br + +.EX +RISING_EDGE 0 +.br +FALLING_EDGE 1 +.br +EITHER_EDGE. 2 +.br + +.EE + +.br + +.br + +.IP "\fBerrnum\fP" 0 +A negative number indicating a function call failed and the nature +of the error. + +.br + +.br + +.IP "\fBf\fP" 0 +A function. + +.br + +.br + +.IP "\fBfrequency\fP: >=0" 0 +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + +.br + +.br + +.br + +.br + +.IP "\fBgpio\fP" 0 +A Broadcom numbered GPIO, in the range 0-53. + +.br + +.br +There are 54 General Purpose Input Outputs (GPIO) named gpio0 through +gpio53. + +.br + +.br +They are split into two banks. Bank 1 consists of gpio0 through +gpio31. Bank 2 consists of gpio32 through gpio53. + +.br + +.br +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +.br + +.br +See \fBget_hardware_revision\fP. + +.br + +.br +The user GPIO are marked with an X in the following table. + +.br + +.br + +.EX + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +.br +Type 1 X X - - X - - X X X X X - - X X +.br +Type 2 - - X X X - - X X X X X - - X X +.br +Type 3 X X X X X X X X X X X X X X +.br + +.br + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +.br +Type 1 - X X - - X X X X X - - - - - - +.br +Type 2 - X X - - - X X X X - X X X X X +.br +Type 3 X X X X X X X X X X X X - - - - +.br + +.EE + +.br + +.br + +.IP "\fBgpioPulse_t\fP" 0 + +.EX +typedef struct +.br +{ +.br +uint32_t gpioOn; +.br +uint32_t gpioOff; +.br +uint32_t usDelay; +.br +} gpioPulse_t; +.br + +.EE + +.br + +.br + +.IP "\fBgpioThreadFunc_t\fP" 0 + +.EX +typedef void *(gpioThreadFunc_t) (void *); +.br + +.EE + +.br + +.br + +.IP "\fBhandle\fP: >=0" 0 +A number referencing an object opened by one of \fBi2c_open\fP, \fBnotify_open\fP, +\fBserial_open\fP, and \fBspi_open\fP. + +.br + +.br + +.IP "\fBi2c_addr\fP: 0-0x7F" 0 +The address of a device on the I2C bus. + +.br + +.br + +.IP "\fBi2c_bus\fP: >=0" 0 +An I2C bus number. + +.br + +.br + +.IP "\fBi2c_flags\fP: 0" 0 +Flags which modify an I2C open command. None are currently defined. + +.br + +.br + +.IP "\fBi2c_reg\fP: 0-255" 0 +A register of an I2C device. + +.br + +.br + +.IP "\fB*inBuf\fP" 0 +A buffer used to pass data to a function. + +.br + +.br + +.IP "\fBinLen\fP" 0 +The number of bytes of data in a buffer. + +.br + +.br + +.IP "\fBint\fP" 0 +A whole number, negative or positive. + +.br + +.br + +.IP "\fBinvert\fP" 0 +A flag used to set normal or inverted bit bang serial data level logic. + +.br + +.br + +.IP "\fBlevel\fP" 0 +The level of a GPIO. Low or High. + +.br + +.br + +.EX +PI_OFF 0 +.br +PI_ON 1 +.br + +.br +PI_CLEAR 0 +.br +PI_SET 1 +.br + +.br +PI_LOW 0 +.br +PI_HIGH 1 +.br + +.EE + +.br + +.br +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See \fBset_watchdog\fP. + +.br + +.br + +.EX +PI_TIMEOUT 2 +.br + +.EE + +.br + +.br + +.IP "\fBmode\fP: 0-7" 0 +The operational mode of a GPIO, normally INPUT or OUTPUT. + +.br + +.br + +.EX +PI_INPUT 0 +.br +PI_OUTPUT 1 +.br +PI_ALT0 4 +.br +PI_ALT1 5 +.br +PI_ALT2 6 +.br +PI_ALT3 7 +.br +PI_ALT4 3 +.br +PI_ALT5 2 +.br + +.EE + +.br + +.br + +.IP "\fBnumBytes\fP" 0 +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +.br + +.br + +.IP "\fBnumPar\fP: 0-10" 0 +The number of parameters passed to a script. + +.br + +.br + +.IP "\fBnumPulses\fP" 0 +The number of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBoffset\fP" 0 +The associated data starts this number of microseconds from the start of +the waveform. + +.br + +.br + +.IP "\fB*outBuf\fP" 0 +A buffer used to return data from a function. + +.br + +.br + +.IP "\fBoutLen\fP" 0 +The size in bytes of an output buffer. + +.br + +.br + +.IP "\fB*param\fP" 0 +An array of script parameters. + +.br + +.br + +.IP "\fB*portStr\fP" 0 +A string specifying the port address used by the Pi running +the pigpio daemon. It may be NULL in which case "8888" +is used unless overridden by the PIGPIO_PORT environment +variable. + +.br + +.br + +.IP "\fB*pth\fP" 0 +A thread identifier, returned by \fBstart_thread\fP. + +.br + +.br + +.br + +.br + +.IP "\fBpthread_t\fP" 0 +A thread identifier. + +.br + +.br + +.IP "\fBpud\fP: 0-2" 0 +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. + +.EX +PI_PUD_OFF 0 +.br +PI_PUD_DOWN 1 +.br +PI_PUD_UP 2 +.br + +.EE + +.br + +.br + +.IP "\fBpulseLen\fP" 0 +1-100, the length of a trigger pulse in microseconds. + +.br + +.br + +.IP "\fB*pulses\fP" 0 +An array of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBpulsewidth\fP: 0, 500-2500" 0 + +.EX +PI_SERVO_OFF 0 +.br +PI_MIN_SERVO_PULSEWIDTH 500 +.br +PI_MAX_SERVO_PULSEWIDTH 2500 +.br + +.EE + +.br + +.br + +.IP "\fBPWMduty\fP: 0-1000000 (1M)" 0 +The hardware PWM dutycycle. + +.br + +.br + +.EX +#define PI_HW_PWM_RANGE 1000000 +.br + +.EE + +.br + +.br + +.IP "\fBPWMfreq\fP: 1-125000000 (125M)" 0 +The hardware PWM frequency. + +.br + +.br + +.EX +#define PI_HW_PWM_MIN_FREQ 1 +.br +#define PI_HW_PWM_MAX_FREQ 125000000 +.br + +.EE + +.br + +.br + +.IP "\fBrange\fP: 25-40000" 0 +The permissible dutycycle values are 0-range. + +.EX +PI_MIN_DUTYCYCLE_RANGE 25 +.br +PI_MAX_DUTYCYCLE_RANGE 40000 +.br + +.EE + +.br + +.br + +.IP "\fB*retBuf\fP" 0 +A buffer to hold a number of bytes returned to a used customised function, + +.br + +.br + +.IP "\fBretMax\fP" 0 +The maximum number of bytes a user customised function should return. + +.br + +.br + +.br + +.br + +.IP "\fB*rxBuf\fP" 0 +A pointer to a buffer to receive data. + +.br + +.br + +.IP "\fBSCL\fP" 0 +The user GPIO to use for the clock when bit banging I2C. + +.br + +.br + +.IP "\fB*script\fP" 0 +A pointer to the text of a script. + +.br + +.br + +.IP "\fBscript_id\fP" 0 +An id of a stored script as returned by \fBstore_script\fP. + +.br + +.br + +.IP "\fBSDA\fP" 0 +The user GPIO to use for data when bit banging I2C. + +.br + +.br + +.IP "\fBseconds\fP" 0 +The number of seconds. + +.br + +.br + +.IP "\fBser_flags\fP" 0 +Flags which modify a serial open command. None are currently defined. + +.br + +.br + +.IP "\fB*ser_tty\fP" 0 +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +.br + +.br + +.IP "\fBsize_t\fP" 0 +A standard type used to indicate the size of an object in bytes. + +.br + +.br + +.IP "\fBspi_channel\fP" 0 +A SPI channel, 0-2. + +.br + +.br + +.IP "\fBspi_flags\fP" 0 +See \fBspi_open\fP. + +.br + +.br + +.IP "\fBsteady\fP: 0-300000" 0 + +.br + +.br +The number of microseconds level changes must be stable for +before reporting the level changed (\fBset_glitch_filter\fP) or triggering +the active part of a noise filter (\fBset_noise_filter\fP). + +.br + +.br + +.IP "\fBstop_bits\fP: 2-8" 0 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +.br + +.br + +.EX +#define PI_MIN_WAVE_HALFSTOPBITS 2 +.br +#define PI_MAX_WAVE_HALFSTOPBITS 8 +.br + +.EE + +.br + +.br + +.IP "\fB*str\fP" 0 + An array of characters. + +.br + +.br + +.IP "\fBthread_func\fP" 0 +A function of type gpioThreadFunc_t used as the main function of a +thread. + +.br + +.br + +.IP "\fBtimeout\fP" 0 +A GPIO watchdog timeout in milliseconds. + +.EX +PI_MIN_WDOG_TIMEOUT 0 +.br +PI_MAX_WDOG_TIMEOUT 60000 +.br + +.EE + +.br + +.br + +.IP "\fB*txBuf\fP" 0 +An array of bytes to transmit. + +.br + +.br + +.IP "\fBuint32_t\fP: 0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)" 0 +A 32-bit unsigned value. + +.br + +.br + +.IP "\fBunsigned\fP" 0 +A whole number >= 0. + +.br + +.br + +.IP "\fBuser_gpio\fP" 0 +0-31, a Broadcom numbered GPIO. + +.br + +.br +See \fBgpio\fP. + +.br + +.br + +.IP "\fB*userdata\fP" 0 +A pointer to arbitrary user data. This may be used to identify the instance. + +.br + +.br + +.IP "\fBvoid\fP" 0 +Denoting no parameter is required + +.br + +.br + +.IP "\fBwave_add_*\fP" 0 +One of \fBwave_add_new\fP, \fBwave_add_generic\fP, \fBwave_add_serial\fP. + +.br + +.br + +.IP "\fBwave_id\fP" 0 +A number representing a waveform created by \fBwave_create\fP. + +.br + +.br + +.IP "\fBwave_send_*\fP" 0 +One of \fBwave_send_once\fP, \fBwave_send_repeat\fP. + +.br + +.br + +.IP "\fBwVal\fP: 0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)" 0 +A 16-bit word value. + +.br + +.br +.SH pigpiod_if Error Codes + +.EX + +.br +typedef enum +.br +{ +.br + pigif_bad_send = -2000, +.br + pigif_bad_recv = -2001, +.br + pigif_bad_getaddrinfo = -2002, +.br + pigif_bad_connect = -2003, +.br + pigif_bad_socket = -2004, +.br + pigif_bad_noib = -2005, +.br + pigif_duplicate_callback = -2006, +.br + pigif_bad_malloc = -2007, +.br + pigif_bad_callback = -2008, +.br + pigif_notify_failed = -2009, +.br + pigif_callback_not_found = -2010, +.br +} pigifError_t; +.br + +.br + +.EE + +.SH SEE ALSO + +pigpiod(1), pig2vcd(1), pigs(1), pigpio(3), pigpiod_if2(3) +.SH AUTHOR + +joan@abyz.me.uk diff --git a/thirdparty/PIGPIO/pigpiod_if.c b/thirdparty/PIGPIO/pigpiod_if.c new file mode 100644 index 0000000000..7802e57962 --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if.c @@ -0,0 +1,1572 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* PIGPIOD_IF_VERSION 27 */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include "pigpio.h" +#include "command.h" + +#include "pigpiod_if.h" + +#define PISCOPE_MAX_REPORTS_PER_READ 4096 + +#define STACK_SIZE (256*1024) + +typedef void (*CBF_t) (); + +struct callback_s +{ + + int id; + int gpio; + int edge; + CBF_t f; + void * user; + int ex; + callback_t *prev; + callback_t *next; +}; + +/* GLOBALS ---------------------------------------------------------------- */ + +static gpioReport_t gReport[PISCOPE_MAX_REPORTS_PER_READ]; + +static int gPigCommand = -1; +static int gPigHandle = -1; +static int gPigNotify = -1; + +static uint32_t gNotifyBits; +static uint32_t gLastLevel; + +callback_t *gCallBackFirst = 0; +callback_t *gCallBackLast = 0; + +static int gPigStarted = 0; + +static pthread_t *pthNotify; + +static pthread_mutex_t command_mutex = PTHREAD_MUTEX_INITIALIZER; + +/* PRIVATE ---------------------------------------------------------------- */ + +static int pigpio_command(int fd, int command, int p1, int p2, int rl) +{ + cmdCmd_t cmd; + + cmd.cmd = command; + cmd.p1 = p1; + cmd.p2 = p2; + cmd.res = 0; + + pthread_mutex_lock(&command_mutex); + + if (send(fd, &cmd, sizeof(cmd), 0) != sizeof(cmd)) + { + pthread_mutex_unlock(&command_mutex); + return pigif_bad_send; + } + + if (recv(fd, &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd)) + { + pthread_mutex_unlock(&command_mutex); + return pigif_bad_recv; + } + + if (rl) pthread_mutex_unlock(&command_mutex); + + return cmd.res; +} + +static int pigpio_command_ext + (int fd, int command, int p1, int p2, int p3, + int extents, gpioExtent_t *ext, int rl) +{ + int i; + cmdCmd_t cmd; + + cmd.cmd = command; + cmd.p1 = p1; + cmd.p2 = p2; + cmd.p3 = p3; + + pthread_mutex_lock(&command_mutex); + + if (send(fd, &cmd, sizeof(cmd), 0) != sizeof(cmd)) + { + pthread_mutex_unlock(&command_mutex); + return pigif_bad_send; + } + + for (i=0; iai_next) + { + sock = socket(rp->ai_family, rp->ai_socktype, rp->ai_protocol); + + if (sock == -1) continue; + + /* Disable the Nagle algorithm. */ + opt = 1; + setsockopt(sock, IPPROTO_TCP, TCP_NODELAY, (char*)&opt, sizeof(int)); + + if (connect(sock, rp->ai_addr, rp->ai_addrlen) != -1) break; + } + + freeaddrinfo(res); + + if (rp == NULL) return pigif_bad_connect; + + return sock; +} + +static void dispatch_notification(gpioReport_t *r) +{ + callback_t *p; + uint32_t changed; + int l, g; + + /* + printf("s=%d f=%d l=%8X, t=%10u\n", + r->seqno, r->flags, r->level, r->tick); + */ + + if (r->flags == 0) + { + changed = (r->level ^ gLastLevel) & gNotifyBits; + + gLastLevel = r->level; + + p = gCallBackFirst; + + while (p) + { + if (changed & (1<<(p->gpio))) + { + if ((r->level) & (1<<(p->gpio))) l = 1; else l = 0; + if ((p->edge) ^ l) + { + if (p->ex) (p->f)(p->gpio, l, r->tick, p->user); + else (p->f)(p->gpio, l, r->tick); + } + } + p = p->next; + } + } + else + { + g = (r->flags) & 31; + + p = gCallBackFirst; + + while (p) + { + if ((p->gpio) == g) + { + if (p->ex) (p->f)(g, PI_TIMEOUT, r->tick, p->user); + else (p->f)(g, PI_TIMEOUT, r->tick); + } + p = p->next; + } + } +} + +static void *pthNotifyThread(void *x) +{ + static int got = 0; + + int bytes, r; + + while (1) + { + bytes = read(gPigNotify, (char*)&gReport+got, sizeof(gReport)-got); + + if (bytes > 0) got += bytes; + else break; + + r = 0; + + while (got >= sizeof(gpioReport_t)) + { + dispatch_notification(&gReport[r]); + + r++; + + got -= sizeof(gpioReport_t); + } + + /* copy any partial report to start of array */ + + if (got && r) gReport[0] = gReport[r]; + } + return 0; +} + +static void findNotifyBits(void) +{ + callback_t *p; + uint32_t bits = 0; + + p = gCallBackFirst; + + while (p) + { + bits |= (1<<(p->gpio)); + p = p->next; + } + + if (bits != gNotifyBits) + { + gNotifyBits = bits; + pigpio_command(gPigCommand, PI_CMD_NB, gPigHandle, gNotifyBits, 1); + } +} + +static void _wfe(unsigned user_gpio, unsigned level, uint32_t tick, void *user) +{ + *(int *)user = 1; +} + +static int intCallback(unsigned user_gpio, unsigned edge, void *f, void *user, int ex) +{ + static int id = 0; + callback_t *p; + + if ((user_gpio >=0) && (user_gpio < 32) && (edge >=0) && (edge <= 2) && f) + { + /* prevent duplicates */ + + p = gCallBackFirst; + + while (p) + { + if ((p->gpio == user_gpio) && (p->edge == edge) && (p->f == f)) + { + return pigif_duplicate_callback; + } + p = p->next; + } + + p = malloc(sizeof(callback_t)); + + if (p) + { + if (!gCallBackFirst) gCallBackFirst = p; + + p->id = id++; + p->gpio = user_gpio; + p->edge = edge; + p->f = f; + p->user = user; + p->ex = ex; + p->next = 0; + p->prev = gCallBackLast; + + if (p->prev) (p->prev)->next = p; + gCallBackLast = p; + + findNotifyBits(); + + return p->id; + } + + return pigif_bad_malloc; + } + + return pigif_bad_callback; +} + +/* PUBLIC ----------------------------------------------------------------- */ + +double time_time(void) +{ + struct timeval tv; + double t; + + gettimeofday(&tv, 0); + + t = (double)tv.tv_sec + ((double)tv.tv_usec / 1E6); + + return t; +} + +void time_sleep(double seconds) +{ + struct timespec ts, rem; + + if (seconds > 0.0) + { + ts.tv_sec = seconds; + ts.tv_nsec = (seconds-(double)ts.tv_sec) * 1E9; + + while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem)) + { + /* copy remaining time to ts */ + ts.tv_sec = rem.tv_sec; + ts.tv_nsec = rem.tv_nsec; + } + } +} + +char *pigpio_error(int errnum) +{ + if (errnum > -1000) return cmdErrStr(errnum); + else + { + switch(errnum) + { + case pigif_bad_send: + return "failed to send to pigpiod"; + case pigif_bad_recv: + return "failed to receive from pigpiod"; + case pigif_bad_getaddrinfo: + return "failed to find address of pigpiod"; + case pigif_bad_connect: + return "failed to connect to pigpiod"; + case pigif_bad_socket: + return "failed to create socket"; + case pigif_bad_noib: + return "failed to open noib"; + case pigif_duplicate_callback: + return "identical callback exists"; + case pigif_bad_malloc: + return "failed to malloc"; + case pigif_bad_callback: + return "bad callback parameter"; + case pigif_notify_failed: + return "failed to create notification thread"; + case pigif_callback_not_found: + return "callback not found"; + default: + return "unknown error"; + } + } +} + +unsigned pigpiod_if_version(void) +{ + return PIGPIOD_IF_VERSION; +} + +pthread_t *start_thread(gpioThreadFunc_t thread_func, void *arg) +{ + pthread_t *pth; + pthread_attr_t pthAttr; + + pth = malloc(sizeof(pthread_t)); + + if (pth) + { + if (pthread_attr_init(&pthAttr)) + { + perror("pthread_attr_init failed"); + free(pth); + return NULL; + } + + if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE)) + { + perror("pthread_attr_setstacksize failed"); + free(pth); + return NULL; + } + + if (pthread_create(pth, &pthAttr, thread_func, arg)) + { + perror("pthread_create socket failed"); + free(pth); + return NULL; + } + } + return pth; +} + +void stop_thread(pthread_t *pth) +{ + if (pth) + { + pthread_cancel(*pth); + pthread_join(*pth, NULL); + free(pth); + } +} + +int pigpio_start(char *addrStr, char *portStr) +{ + if ((!addrStr) || (strlen(addrStr) == 0)) + { + addrStr = "localhost"; + } + + if (!gPigStarted) + { + gPigCommand = pigpioOpenSocket(addrStr, portStr); + + if (gPigCommand >= 0) + { + gPigNotify = pigpioOpenSocket(addrStr, portStr); + + if (gPigNotify >= 0) + { + gPigHandle = pigpio_command(gPigNotify, PI_CMD_NOIB, 0, 0, 1); + + if (gPigHandle < 0) return pigif_bad_noib; + else + { + gLastLevel = read_bank_1(); + + pthNotify = start_thread(pthNotifyThread, 0); + if (pthNotify) + { + gPigStarted = 1; + return 0; + } + else return pigif_notify_failed; + } + } + else return gPigNotify; + } + else return gPigCommand; + } + return 0; +} + +void pigpio_stop(void) +{ + gPigStarted = 0; + + if (pthNotify) + { + stop_thread(pthNotify); + pthNotify = 0; + } + + if (gPigNotify >= 0) + { + if (gPigHandle >= 0) + { + pigpio_command(gPigNotify, PI_CMD_NC, gPigHandle, 0, 1); + gPigHandle = -1; + } + + close(gPigNotify); + gPigNotify = -1; + } + + if (gPigCommand >= 0) + { + if (gPigHandle >= 0) + { + pigpio_command(gPigCommand, PI_CMD_NC, gPigHandle, 0, 1); + gPigHandle = -1; + } + + close(gPigCommand); + gPigCommand = -1; + } +} + +int set_mode(unsigned gpio, unsigned mode) + {return pigpio_command(gPigCommand, PI_CMD_MODES, gpio, mode, 1);} + +int get_mode(unsigned gpio) + {return pigpio_command(gPigCommand, PI_CMD_MODEG, gpio, 0, 1);} + +int set_pull_up_down(unsigned gpio, unsigned pud) + {return pigpio_command(gPigCommand, PI_CMD_PUD, gpio, pud, 1);} + +int gpio_read(unsigned gpio) + {return pigpio_command(gPigCommand, PI_CMD_READ, gpio, 0, 1);} + +int gpio_write(unsigned gpio, unsigned level) + {return pigpio_command(gPigCommand, PI_CMD_WRITE, gpio, level, 1);} + +int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle) + {return pigpio_command(gPigCommand, PI_CMD_PWM, user_gpio, dutycycle, 1);} + +int get_PWM_dutycycle(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_GDC, user_gpio, 0, 1);} + +int set_PWM_range(unsigned user_gpio, unsigned range) + {return pigpio_command(gPigCommand, PI_CMD_PRS, user_gpio, range, 1);} + +int get_PWM_range(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_PRG, user_gpio, 0, 1);} + +int get_PWM_real_range(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_PRRG, user_gpio, 0, 1);} + +int set_PWM_frequency(unsigned user_gpio, unsigned frequency) + {return pigpio_command(gPigCommand, PI_CMD_PFS, user_gpio, frequency, 1);} + +int get_PWM_frequency(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_PFG, user_gpio, 0, 1);} + +int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth) + {return pigpio_command(gPigCommand, PI_CMD_SERVO, user_gpio, pulsewidth, 1);} + +int get_servo_pulsewidth(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_GPW, user_gpio, 0, 1);} + +int notify_open(void) + {return pigpio_command(gPigCommand, PI_CMD_NO, 0, 0, 1);} + +int notify_begin(unsigned handle, uint32_t bits) + {return pigpio_command(gPigCommand, PI_CMD_NB, handle, bits, 1);} + +int notify_pause(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_NB, handle, 0, 1);} + +int notify_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_NC, handle, 0, 1);} + +int set_watchdog(unsigned user_gpio, unsigned timeout) + {return pigpio_command(gPigCommand, PI_CMD_WDOG, user_gpio, timeout, 1);} + +uint32_t read_bank_1(void) + {return pigpio_command(gPigCommand, PI_CMD_BR1, 0, 0, 1);} + +uint32_t read_bank_2(void) + {return pigpio_command(gPigCommand, PI_CMD_BR2, 0, 0, 1);} + +int clear_bank_1(uint32_t levels) + {return pigpio_command(gPigCommand, PI_CMD_BC1, levels, 0, 1);} + +int clear_bank_2(uint32_t levels) + {return pigpio_command(gPigCommand, PI_CMD_BC2, levels, 0, 1);} + +int set_bank_1(uint32_t levels) + {return pigpio_command(gPigCommand, PI_CMD_BS1, levels, 0, 1);} + +int set_bank_2(uint32_t levels) + {return pigpio_command(gPigCommand, PI_CMD_BS2, levels, 0, 1);} + +int hardware_clock(unsigned gpio, unsigned frequency) + {return pigpio_command(gPigCommand, PI_CMD_HC, gpio, frequency, 1);} + +int hardware_PWM(unsigned gpio, unsigned frequency, uint32_t dutycycle) +{ + gpioExtent_t ext[1]; + + /* + p1=gpio + p2=frequency + p3=4 + ## extension ## + uint32_t dutycycle + */ + + ext[0].size = sizeof(dutycycle); + ext[0].ptr = &dutycycle; + + return pigpio_command_ext( + gPigCommand, PI_CMD_HP, gpio, frequency, sizeof(dutycycle), 1, ext, 1); +} + +uint32_t get_current_tick(void) + {return pigpio_command(gPigCommand, PI_CMD_TICK, 0, 0, 1);} + +uint32_t get_hardware_revision(void) + {return pigpio_command(gPigCommand, PI_CMD_HWVER, 0, 0, 1);} + +uint32_t get_pigpio_version(void) + {return pigpio_command(gPigCommand, PI_CMD_PIGPV, 0, 0, 1);} + +int wave_clear(void) + {return pigpio_command(gPigCommand, PI_CMD_WVCLR, 0, 0, 1);} + +int wave_add_new(void) + {return pigpio_command(gPigCommand, PI_CMD_WVNEW, 0, 0, 1);} + +int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses) +{ + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=pulses*sizeof(gpioPulse_t) + ## extension ## + gpioPulse_t[] pulses + */ + + if (!numPulses) return 0; + + ext[0].size = numPulses * sizeof(gpioPulse_t); + ext[0].ptr = pulses; + + return pigpio_command_ext( + gPigCommand, PI_CMD_WVAG, 0, 0, ext[0].size, 1, ext, 1); +} + +int wave_add_serial( + unsigned user_gpio, unsigned baud, uint32_t databits, + uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str) +{ + uint8_t buf[12]; + gpioExtent_t ext[2]; + + /* + p1=user_gpio + p2=baud + p3=len+12 + ## extension ## + uint32_t databits + uint32_t stophalfbits + uint32_t offset + char[len] str + */ + + if (!numChar) return 0; + + memcpy(buf, &databits, 4); + memcpy(buf+4, &stophalfbits, 4); + memcpy(buf+8, &offset, 4); + + ext[0].size = sizeof(buf); + ext[0].ptr = buf; + + ext[1].size = numChar; + ext[1].ptr = str; + + return pigpio_command_ext(gPigCommand, PI_CMD_WVAS, + user_gpio, baud, numChar+sizeof(buf), 2, ext, 1); +} + +int wave_create(void) + {return pigpio_command(gPigCommand, PI_CMD_WVCRE, 0, 0, 1);} + +int wave_delete(unsigned wave_id) + {return pigpio_command(gPigCommand, PI_CMD_WVDEL, wave_id, 0, 1);} + +int wave_tx_start(void) /* DEPRECATED */ + {return pigpio_command(gPigCommand, PI_CMD_WVGO, 0, 0, 1);} + +int wave_tx_repeat(void) /* DEPRECATED */ + {return pigpio_command(gPigCommand, PI_CMD_WVGOR, 0, 0, 1);} + +int wave_send_once(unsigned wave_id) + {return pigpio_command(gPigCommand, PI_CMD_WVTX, wave_id, 0, 1);} + +int wave_send_repeat(unsigned wave_id) + {return pigpio_command(gPigCommand, PI_CMD_WVTXR, wave_id, 0, 1);} + +int wave_chain(char *buf, unsigned bufSize) +{ + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=bufSize + ## extension ## + char buf[bufSize] + */ + + ext[0].size = bufSize; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_WVCHA, 0, 0, bufSize, 1, ext, 1); +} + +int wave_tx_busy(void) + {return pigpio_command(gPigCommand, PI_CMD_WVBSY, 0, 0, 1);} + +int wave_tx_stop(void) + {return pigpio_command(gPigCommand, PI_CMD_WVHLT, 0, 0, 1);} + +int wave_get_micros(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSM, 0, 0, 1);} + +int wave_get_high_micros(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSM, 1, 0, 1);} + +int wave_get_max_micros(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSM, 2, 0, 1);} + +int wave_get_pulses(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSP, 0, 0, 1);} + +int wave_get_high_pulses(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSP, 1, 0, 1);} + +int wave_get_max_pulses(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSP, 2, 0, 1);} + +int wave_get_cbs(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSC, 0, 0, 1);} + +int wave_get_high_cbs(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSC, 1, 0, 1);} + +int wave_get_max_cbs(void) + {return pigpio_command(gPigCommand, PI_CMD_WVSC, 2, 0, 1);} + +int gpio_trigger(unsigned user_gpio, unsigned pulseLen, uint32_t level) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=pulseLen + p3=4 + ## extension ## + unsigned level + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &level; + + return pigpio_command_ext( + gPigCommand, PI_CMD_TRIG, user_gpio, pulseLen, 4, 1, ext, 1); +} + +int set_glitch_filter(unsigned user_gpio, unsigned steady) + {return pigpio_command(gPigCommand, PI_CMD_FG, user_gpio, steady, 1);} + +int set_noise_filter(unsigned user_gpio, unsigned steady, unsigned active) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=steady + p3=4 + ## extension ## + unsigned active + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &active; + + return pigpio_command_ext( + gPigCommand, PI_CMD_FN, user_gpio, steady, 4, 1, ext, 1); +} + +int store_script(char *script) +{ + unsigned len; + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=len + ## extension ## + char[len] script + */ + + len = strlen(script); + + if (!len) return 0; + + ext[0].size = len; + ext[0].ptr = script; + + return pigpio_command_ext(gPigCommand, PI_CMD_PROC, 0, 0, len, 1, ext, 1); +} + +int run_script(unsigned script_id, unsigned numPar, uint32_t *param) +{ + gpioExtent_t ext[1]; + + /* + p1=script id + p2=0 + p3=numPar * 4 + ## extension ## + uint32_t[numPar] pars + */ + + ext[0].size = 4 * numPar; + ext[0].ptr = param; + + return pigpio_command_ext + (gPigCommand, PI_CMD_PROCR, script_id, 0, numPar*4, 1, ext, 1); +} + +int recvMax(void *buf, int bufsize, int sent) +{ + uint8_t scratch[4096]; + int remaining, fetch, count; + + if (sent < bufsize) count = sent; else count = bufsize; + + if (count) recv(gPigCommand, buf, count, MSG_WAITALL); + + remaining = sent - count; + + while (remaining) + { + fetch = remaining; + if (fetch > sizeof(scratch)) fetch = sizeof(scratch); + recv(gPigCommand, scratch, fetch, MSG_WAITALL); + remaining -= fetch; + } + + return count; +} + +int script_status(unsigned script_id, uint32_t *param) +{ + int status; + uint32_t p[PI_MAX_SCRIPT_PARAMS+1]; /* space for script status */ + + status = pigpio_command(gPigCommand, PI_CMD_PROCP, script_id, 0, 0); + + if (status > 0) + { + recvMax(p, sizeof(p), status); + status = p[0]; + if (param) memcpy(param, p+1, sizeof(p)-4); + } + + pthread_mutex_unlock(&command_mutex); + + return status; +} + +int stop_script(unsigned script_id) + {return pigpio_command(gPigCommand, PI_CMD_PROCS, script_id, 0, 1);} + +int delete_script(unsigned script_id) + {return pigpio_command(gPigCommand, PI_CMD_PROCD, script_id, 0, 1);} + +int bb_serial_read_open(unsigned user_gpio, unsigned baud, uint32_t bbBits) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=baud + p3=4 + ## extension ## + unsigned bbBits + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &bbBits; + + return pigpio_command_ext( + gPigCommand, PI_CMD_SLRO, user_gpio, baud, 4, 1, ext, 1); +} + +int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize) +{ + int bytes; + + bytes = pigpio_command(gPigCommand, PI_CMD_SLR, user_gpio, bufSize, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, bufSize, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int bb_serial_read_close(unsigned user_gpio) + {return pigpio_command(gPigCommand, PI_CMD_SLRC, user_gpio, 0, 1);} + +int bb_serial_invert(unsigned user_gpio, unsigned invert) + {return pigpio_command(gPigCommand, PI_CMD_SLRI, user_gpio, invert, 1);} + +int i2c_open(unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags) +{ + gpioExtent_t ext[1]; + + /* + p1=i2c_bus + p2=i2c_addr + p3=4 + ## extension ## + uint32_t i2c_flags + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &i2c_flags; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CO, i2c_bus, i2c_addr, 4, 1, ext, 1); +} + +int i2c_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_I2CC, handle, 0, 1);} + +int i2c_write_quick(unsigned handle, unsigned bit) + {return pigpio_command(gPigCommand, PI_CMD_I2CWQ, handle, bit, 1);} + +int i2c_write_byte(unsigned handle, unsigned val) + {return pigpio_command(gPigCommand, PI_CMD_I2CWS, handle, val, 1);} + +int i2c_read_byte(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_I2CRS, handle, 0, 1);} + +int i2c_write_byte_data(unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWB, handle, reg, 4, 1, ext, 1); +} + +int i2c_write_word_data(unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWW, handle, reg, 4, 1, ext, 1); +} + +int i2c_read_byte_data(unsigned handle, unsigned reg) + {return pigpio_command(gPigCommand, PI_CMD_I2CRB, handle, reg, 1);} + +int i2c_read_word_data(unsigned handle, unsigned reg) + {return pigpio_command(gPigCommand, PI_CMD_I2CRW, handle, reg, 1);} + +int i2c_process_call(unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CPK, handle, reg, 4, 1, ext, 1); +} + +int i2c_write_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWK, handle, reg, count, 1, ext, 1); +} + +int i2c_read_block_data(unsigned handle, unsigned reg, char *buf) +{ + int bytes; + + bytes = pigpio_command(gPigCommand, PI_CMD_I2CRK, handle, reg, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, 32, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int i2c_block_process_call( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_I2CPK, handle, reg, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, 32, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int i2c_read_i2c_block_data( + unsigned handle, unsigned reg, char *buf, uint32_t count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t count + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &count; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_I2CRI, handle, reg, 4, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, count, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + + +int i2c_write_i2c_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWI, handle, reg, count, 1, ext, 1); +} + +int i2c_read_device(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command(gPigCommand, PI_CMD_I2CRD, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, count, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int i2c_write_device(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWD, handle, 0, count, 1, ext, 1); +} + +int i2c_zip( + unsigned handle, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=inLen + ## extension ## + char inBuf[inLen] + */ + + ext[0].size = inLen; + ext[0].ptr = inBuf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_I2CZ, handle, 0, inLen, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(outBuf, outLen, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud) +{ + gpioExtent_t ext[1]; + + /* + p1=SDA + p2=SCL + p3=4 + ## extension ## + uint32_t baud + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &baud; + + return pigpio_command_ext + (gPigCommand, PI_CMD_BI2CO, SDA, SCL, 4, 1, ext, 1); +} + +int bb_i2c_close(unsigned SDA) + {return pigpio_command(gPigCommand, PI_CMD_BI2CC, SDA, 0, 1);} + +int bb_i2c_zip( + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=SDA + p2=0 + p3=inLen + ## extension ## + char inBuf[inLen] + */ + + ext[0].size = inLen; + ext[0].ptr = inBuf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_BI2CZ, SDA, 0, inLen, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(outBuf, outLen, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int spi_open(unsigned channel, unsigned speed, uint32_t flags) +{ + gpioExtent_t ext[1]; + + /* + p1=channel + p2=speed + p3=4 + ## extension ## + uint32_t flags + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &flags; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SPIO, channel, speed, 4, 1, ext, 1); +} + +int spi_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SPIC, handle, 0, 1);} + +int spi_read(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (gPigCommand, PI_CMD_SPIR, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, count, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int spi_write(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SPIW, handle, 0, count, 1, ext, 1); +} + +int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = txBuf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_SPIX, handle, 0, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(rxBuf, count, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int serial_open(char *dev, unsigned baud, unsigned flags) +{ + int len; + gpioExtent_t ext[1]; + + len = strlen(dev); + + /* + p1=baud + p2=flags + p3=len + ## extension ## + char dev[len] + */ + + ext[0].size = len; + ext[0].ptr = dev; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SERO, baud, flags, len, 1, ext, 1); +} + +int serial_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERC, handle, 0, 1);} + +int serial_write_byte(unsigned handle, unsigned val) + {return pigpio_command(gPigCommand, PI_CMD_SERWB, handle, val, 1);} + +int serial_read_byte(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERRB, handle, 0, 1);} + +int serial_write(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SERW, handle, 0, count, 1, ext, 1); +} + +int serial_read(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (gPigCommand, PI_CMD_SERR, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(buf, count, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + +int serial_data_available(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERDA, handle, 0, 1);} + +int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=arg1 + p2=arg2 + p3=count + ## extension ## + char argx[count] + */ + + ext[0].size = count; + ext[0].ptr = argx; + + return pigpio_command_ext( + gPigCommand, PI_CMD_CF1, arg1, arg2, count, 1, ext, 1); +} + + +int custom_2(unsigned arg1, char *argx, unsigned count, + char *retBuf, uint32_t retMax) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=arg1 + p2=retMax + p3=count + ## extension ## + char argx[count] + */ + + ext[0].size = count; + ext[0].ptr = argx; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_CF2, arg1, retMax, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(retBuf, retMax, bytes); + } + + pthread_mutex_unlock(&command_mutex); + + return bytes; +} + + +int callback(unsigned user_gpio, unsigned edge, CBFunc_t f) + {return intCallback(user_gpio, edge, f, 0, 0);} + +int callback_ex(unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user) + {return intCallback(user_gpio, edge, f, user, 1);} + +int callback_cancel(unsigned id) +{ + callback_t *p; + + p = gCallBackFirst; + + while (p) + { + if (p->id == id) + { + if (p->prev) p->prev->next = p->next; + else gCallBackFirst = p->next; + + if (p->next) p->next->prev = p->prev; + else gCallBackLast = p->prev; + + free(p); + + findNotifyBits(); + + return 0; + } + p = p->next; + } + return pigif_callback_not_found; +} + +int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout) +{ + int triggered = 0; + int id; + double due; + + if (timeout <= 0.0) return 0; + + due = time_time() + timeout; + + id = callback_ex(user_gpio, edge, _wfe, &triggered); + + while (!triggered && (time_time() < due)) time_sleep(0.1); + + callback_cancel(id); + + return triggered; +} + + diff --git a/thirdparty/PIGPIO/pigpiod_if.h b/thirdparty/PIGPIO/pigpiod_if.h new file mode 100644 index 0000000000..e2b52b420c --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if.h @@ -0,0 +1,2996 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +#ifndef PIGPIOD_IF_H +#define PIGPIOD_IF_H + +#include "pigpio.h" + +#define PIGPIOD_IF_VERSION 28 + +/*TEXT + +THIS LIBRARY IS DEPRECATED. NEW CODE SHOULD BE WRITTEN TO +USE THE MORE VERSATILE pigpiod_if2 LIBRARY. + +pigpiod_if is a C library for the Raspberry which allows control +of the GPIO via the socket interface to the pigpio daemon. + +*Features* + +o hardware timed PWM on any of GPIO 0-31 + +o hardware timed servo pulses on any of GPIO 0-31 + +o callbacks when any of GPIO 0-31 change state + +o callbacks at timed intervals + +o reading/writing all of the GPIO in a bank as one operation + +o individually setting GPIO modes, reading and writing + +o notifications when any of GPIO 0-31 change state + +o the construction of output waveforms with microsecond timing + +o rudimentary permission control over GPIO + +o a simple interface to start and stop new threads + +o I2C, SPI, and serial link wrappers + +o creating and running scripts on the pigpio daemon + +*GPIO* + +ALL GPIO are identified by their Broadcom number. + +*Notes* + +The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals. + +*Usage* + +Include in your source files. + +Assuming your source is in prog.c use the following command to build + +. . +gcc -Wall -pthread -o prog prog.c -lpigpiod_if -lrt +. . + +to run make sure the pigpio daemon is running + +. . +sudo pigpiod + + ./prog # sudo is not required to run programs linked to pigpiod_if +. . + +For examples see x_pigpiod_if.c within the pigpio archive file. + +*Notes* + +All the functions which return an int return < 0 on error + +TEXT*/ + +/*OVERVIEW + +ESSENTIAL + +pigpio_start Connects to the pigpio daemon +pigpio_stop Disconnects from the pigpio daemon + +BEGINNER + +set_mode Set a GPIO mode +get_mode Get a GPIO mode + +set_pull_up_down Set/clear GPIO pull up/down resistor + +gpio_read Read a GPIO +gpio_write Write a GPIO + +set_PWM_dutycycle Start/stop PWM pulses on a GPIO +get_PWM_dutycycle Get the PWM dutycycle in use on a GPIO + +set_servo_pulsewidth Start/stop servo pulses on a GPIO +get_servo_pulsewidth Get the servo pulsewidth in use on a GPIO + +callback Create GPIO level change callback +callback_ex Create GPIO level change callback +callback_cancel Cancel a callback +wait_for_edge Wait for GPIO level change + +INTERMEDIATE + +gpio_trigger Send a trigger pulse to a GPIO. + +set_watchdog Set a watchdog on a GPIO. + +set_PWM_range Configure PWM range for a GPIO +get_PWM_range Get configured PWM range for a GPIO + +set_PWM_frequency Configure PWM frequency for a GPIO +get_PWM_frequency Get configured PWM frequency for a GPIO + +read_bank_1 Read all GPIO in bank 1 +read_bank_2 Read all GPIO in bank 2 + +clear_bank_1 Clear selected GPIO in bank 1 +clear_bank_2 Clear selected GPIO in bank 2 + +set_bank_1 Set selected GPIO in bank 1 +set_bank_2 Set selected GPIO in bank 2 + +start_thread Start a new thread +stop_thread Stop a previously started thread + +ADVANCED + +get_PWM_real_range Get underlying PWM range for a GPIO + +notify_open Request a notification handle +notify_begin Start notifications for selected GPIO +notify_pause Pause notifications +notify_close Close a notification + +bb_serial_read_open Opens a GPIO for bit bang serial reads +bb_serial_read Reads bit bang serial data from a GPIO +bb_serial_read_close Closes a GPIO for bit bang serial reads +bb_serial_invert Invert serial logic (1 invert, 0 normal) + +hardware_clock Start hardware clock on supported GPIO +hardware_PWM Start hardware PWM on supported GPIO + +set_glitch_filter Set a glitch filter on a GPIO +set_noise_filter Set a noise filter on a GPIO + +SCRIPTS + +store_script Store a script +run_script Run a stored script +script_status Get script status and parameters +stop_script Stop a running script +delete_script Delete a stored script + +WAVES + +wave_clear Deletes all waveforms + +wave_add_new Starts a new waveform +wave_add_generic Adds a series of pulses to the waveform +wave_add_serial Adds serial data to the waveform + +wave_create Creates a waveform from added data +wave_delete Deletes one or more waveforms + +wave_send_once Transmits a waveform once +wave_send_repeat Transmits a waveform repeatedly + +wave_chain Transmits a chain of waveforms + +wave_tx_busy Checks to see if the waveform has ended +wave_tx_stop Aborts the current waveform + +wave_get_micros Length in microseconds of the current waveform +wave_get_high_micros Length of longest waveform so far +wave_get_max_micros Absolute maximum allowed micros + +wave_get_pulses Length in pulses of the current waveform +wave_get_high_pulses Length of longest waveform so far +wave_get_max_pulses Absolute maximum allowed pulses + +wave_get_cbs Length in cbs of the current waveform +wave_get_high_cbs Length of longest waveform so far +wave_get_max_cbs Absolute maximum allowed cbs + +I2C + +i2c_open Opens an I2C device +i2c_close Closes an I2C device + +i2c_write_quick smbus write quick +i2c_write_byte smbus write byte +i2c_read_byte smbus read byte +i2c_write_byte_data smbus write byte data +i2c_write_word_data smbus write word data +i2c_read_byte_data smbus read byte data +i2c_read_word_data smbus read word data +i2c_process_call smbus process call +i2c_write_block_data smbus write block data +i2c_read_block_data smbus read block data +i2c_block_process_call smbus block process call + +i2c_write_i2c_block_data smbus write I2C block data +i2c_read_i2c_block_data smbus read I2C block data + +i2c_read_device Reads the raw I2C device +i2c_write_device Writes the raw I2C device + +i2c_zip Performs multiple I2C transactions + +bb_i2c_open Opens GPIO for bit banging I2C +bb_i2c_close Closes GPIO for bit banging I2C +bb_i2c_zip Performs multiple bit banged I2C transactions + +SPI + +spi_open Opens a SPI device +spi_close Closes a SPI device + +spi_read Reads bytes from a SPI device +spi_write Writes bytes to a SPI device +spi_xfer Transfers bytes with a SPI device + +SERIAL + +serial_open Opens a serial device +serial_close Closes a serial device + +serial_write_byte Writes a byte to a serial device +serial_read_byte Reads a byte from a serial device +serial_write Writes bytes to a serial device +serial_read Reads bytes from a serial device + +serial_data_available Returns number of bytes ready to be read + +CUSTOM + +custom_1 User custom function 1 +custom_2 User custom function 2 + +UTILITIES + +get_current_tick Get current tick (microseconds) + +get_hardware_revision Get hardware revision +get_pigpio_version Get the pigpio version +pigpiod_if_version Get the pigpiod_if version + +pigpio_error Get a text description of an error code. + +time_sleep Sleeps for a float number of seconds +time_time Float number of seconds since the epoch + +OVERVIEW*/ + +#ifdef __cplusplus +extern "C" { +#endif + +typedef void (*CBFunc_t) (unsigned user_gpio, unsigned level, uint32_t tick); + +typedef void (*CBFuncEx_t) + (unsigned user_gpio, unsigned level, uint32_t tick, void * user); + +typedef struct callback_s callback_t; + +/*F*/ +double time_time(void); +/*D +Return the current time in seconds since the Epoch. +D*/ + +/*F*/ +void time_sleep(double seconds); +/*D +Delay execution for a given number of seconds. + +. . +seconds: the number of seconds to delay. +. . +D*/ + +/*F*/ +char *pigpio_error(int errnum); +/*D +Return a text description for an error code. + +. . +errnum: the error code. +. . +D*/ + +/*F*/ +unsigned pigpiod_if_version(void); +/*D +Return the pigpiod_if version. +D*/ + +/*F*/ +pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata); +/*D +Starts a new thread of execution with thread_func as the main routine. + +. . +thread_func: the main function for the new thread. + userdata: a pointer to an arbitrary argument. +. . + +Returns a pointer to pthread_t if OK, otherwise NULL. + +The function is passed the single argument userdata. + +The thread can be cancelled by passing the pointer to pthread_t to +[*stop_thread*]. +D*/ + +/*F*/ +void stop_thread(pthread_t *pth); +/*D +Cancels the thread pointed at by pth. + +. . +pth: the thread to be stopped. +. . + +No value is returned. + +The thread to be stopped should have been started with [*start_thread*]. +D*/ + +/*F*/ +int pigpio_start(char *addrStr, char *portStr); +/*D +Connect to the pigpio daemon. Reserving command and +notification streams. + +. . +addrStr: specifies the host or IP address of the Pi running the + pigpio daemon. It may be NULL in which case localhost + is used unless overridden by the PIGPIO_ADDR environment + variable. + +portStr: specifies the port address used by the Pi running the + pigpio daemon. It may be NULL in which case "8888" + is used unless overridden by the PIGPIO_PORT environment + variable. +. . +D*/ + +/*F*/ +void pigpio_stop(void); +/*D +Terminates the connection to the pigpio daemon and releases +resources used by the library. +D*/ + +/*F*/ +int set_mode(unsigned gpio, unsigned mode); +/*D +Set the GPIO mode. + +. . +gpio: 0-53. +mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1, + PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE, +or PI_NOT_PERMITTED. +D*/ + +/*F*/ +int get_mode(unsigned gpio); +/*D +Get the GPIO mode. + +. . +gpio: 0-53. +. . + +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. +D*/ + +/*F*/ +int set_pull_up_down(unsigned gpio, unsigned pud); +/*D +Set or clear the GPIO pull-up/down resistor. + +. . +gpio: 0-53. + pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD, +or PI_NOT_PERMITTED. +D*/ + +/*F*/ +int gpio_read(unsigned gpio); +/*D +Read the GPIO level. + +. . +gpio:0-53. +. . + +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. +D*/ + +/*F*/ +int gpio_write(unsigned gpio, unsigned level); +/*D +Write the GPIO level. + +. . + gpio: 0-53. +level: 0, 1. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL, +or PI_NOT_PERMITTED. + +Notes + +If PWM or servo pulses are active on the GPIO they are switched off. +D*/ + +/*F*/ +int set_PWM_dutycycle(unsigned user_gpio, unsigned dutycycle); +/*D +Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO. + +. . +user_gpio: 0-31. +dutycycle: 0-range (range defaults to 255). +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE, +or PI_NOT_PERMITTED. +Notes + +The [*set_PWM_range*] function may be used to change the +default range of 255. +D*/ + +/*F*/ +int get_PWM_dutycycle(unsigned user_gpio); +/*D +Return the PWM dutycycle in use on a GPIO. + +. . +user_gpio: 0-31. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see [*get_PWM_range*]). + +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). +D*/ + +/*F*/ +int set_PWM_range(unsigned user_gpio, unsigned range); +/*D +Set the range of PWM values to be used on the GPIO. + +. . +user_gpio: 0-31. + range: 25-40000. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE, +or PI_NOT_PERMITTED. + +Notes + +If PWM is currently active on the GPIO its dutycycle will be +scaled to reflect the new range. + +The real range, the number of steps between fully off and fully on +for each of the 18 available GPIO frequencies is + +. . + 25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6), + 400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12), +2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18) +. . + +The real value set by set_PWM_range is (dutycycle * real range) / range. +D*/ + +/*F*/ +int get_PWM_range(unsigned user_gpio); +/*D +Get the range of PWM values being used on the GPIO. + +. . +user_gpio: 0-31. +. . + +Returns the dutycycle range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +If a hardware clock or hardware PWM is active on the GPIO the +reported range will be 1000000 (1M). +D*/ + +/*F*/ +int get_PWM_real_range(unsigned user_gpio); +/*D +Get the real underlying range of PWM values being used on the GPIO. + +. . +user_gpio: 0-31. +. . + +Returns the real range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +If a hardware clock is active on the GPIO the reported +real range will be 1000000 (1M). + +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +D*/ + +/*F*/ +int set_PWM_frequency(unsigned user_gpio, unsigned frequency); +/*D +Set the frequency (in Hz) of the PWM to be used on the GPIO. + +. . +user_gpio: 0-31. +frequency: >=0 (Hz). +. . + +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PERMITTED. + +If PWM is currently active on the GPIO it will be switched +off and then back on at the new frequency. + +Each GPIO can be independently set to one of 18 different +PWM frequencies. + +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The +sample rate is set when the pigpio daemon is started. + +The frequencies for each sample rate are: + +. . + Hertz + + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 + 1250 1000 800 500 400 250 200 100 50 + + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 + 625 500 400 250 200 125 100 50 25 + + 4: 10000 5000 2500 2000 1250 1000 625 500 400 + 313 250 200 125 100 63 50 25 13 +sample + rate + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 + 250 200 160 100 80 50 40 20 10 + + 8: 5000 2500 1250 1000 625 500 313 250 200 + 156 125 100 63 50 31 25 13 6 + + 10: 4000 2000 1000 800 500 400 250 200 160 + 125 100 80 50 40 25 20 10 5 +. . +D*/ + +/*F*/ +int get_PWM_frequency(unsigned user_gpio); +/*D +Get the frequency of PWM being used on the GPIO. + +. . +user_gpio: 0-31. +. . + +For normal PWM the frequency will be that defined for the GPIO by +[*set_PWM_frequency*]. + +If a hardware clock is active on the GPIO the reported frequency +will be that set by [*hardware_clock*]. + +If hardware PWM is active on the GPIO the reported frequency +will be that set by [*hardware_PWM*]. + +Returns the frequency (in hertz) used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. +D*/ + +/*F*/ +int set_servo_pulsewidth(unsigned user_gpio, unsigned pulsewidth); +/*D +Start (500-2500) or stop (0) servo pulses on the GPIO. + +. . + user_gpio: 0-31. +pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise). +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or +PI_NOT_PERMITTED. + +The selected pulsewidth will continue to be transmitted until +changed by a subsequent call to set_servo_pulsewidth. + +The pulsewidths supported by servos varies and should probably be +determined by experiment. A value of 1500 should always be safe and +represents the mid-point of rotation. + +You can DAMAGE a servo if you command it to move beyond its limits. + +OTHER UPDATE RATES: + +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +. . +Update Rate (Hz) 50 100 200 400 500 +1E6/Hz 20000 10000 5000 2500 2000 +. . + +Firstly set the desired PWM frequency using [*set_PWM_frequency*]. + +Then set the PWM range using [*set_PWM_range*] to 1E6/Hz. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +E.g. If you want to update a servo connected to GPIO 25 at 400Hz + +. . +set_PWM_frequency(25, 400); +set_PWM_range(25, 2500); +. . + +Thereafter use the [*set_PWM_dutycycle*] function to move the servo, +e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. +D*/ + +/*F*/ +int get_servo_pulsewidth(unsigned user_gpio); +/*D +Return the servo pulsewidth in use on a GPIO. + +. . +user_gpio: 0-31. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. +D*/ + +/*F*/ +int notify_open(void); +/*D +Get a free notification handle. + +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +A notification is a method for being notified of GPIO state +changes via a pipe. + +Pipes are only accessible from the local machine so this function +serves no purpose if you are using the library from a remote machine. +The in-built (socket) notifications provided by [*callback*] +should be used instead. + +Notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). +E.g. if the function returns 15 then the notifications must be +read from /dev/pigpio15. +D*/ + +/*F*/ +int notify_begin(unsigned handle, uint32_t bits); +/*D +Start notifications on a previously opened handle. + +. . +handle: 0-31 (as returned by [*notify_open*]) + bits: a mask indicating the GPIO to be notified. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +The notification sends state changes for each GPIO whose +corresponding bit in bits is set. + +Each notification occupies 12 bytes in the fifo as follows: + +. . +typedef struct +{ + uint16_t seqno; + uint16_t flags; + uint32_t tick; + uint32_t level; +} gpioReport_t; +. . + +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +flags: two flags are defined, PI_NTFY_FLAGS_WDOG and PI_NTFY_FLAGS_ALIVE. + +PI_NTFY_FLAGS_WDOG, if bit 5 is set then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +PI_NTFY_FLAGS_ALIVE, if bit 6 is set this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +level: indicates the level of each GPIO. If bit 1<=0 + numBytes: >=1 + str: an array of chars. +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +NOTES: + +The serial data is formatted as one start bit, [*data_bits*] data bits, +and [*stop_bits*]/2 stop bits. + +It is legal to add serial data streams with different baud rates to +the same waveform. + +[*numBytes*] is the number of bytes of data in str. + +The bytes required for each character depend upon [*data_bits*]. + +For [*data_bits*] 1-8 there will be one byte per character. +For [*data_bits*] 9-16 there will be two bytes per character. +For [*data_bits*] 17-32 there will be four bytes per character. +D*/ + +/*F*/ +int wave_create(void); +/*D +This function creates a waveform from the data provided by the prior +calls to the [*wave_add_**] functions. Upon success a wave id +greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM, +PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID. + +The data provided by the [*wave_add_**] functions is consumed by this +function. + +As many waveforms may be created as there is space available. The +wave id is passed to [*wave_send_**] to specify the waveform to transmit. + +Normal usage would be + +Step 1. [*wave_clear*] to clear all waveforms and added data. + +Step 2. [*wave_add_**] calls to supply the waveform data. + +Step 3. [*wave_create*] to create the waveform and get a unique id + +Repeat steps 2 and 3 as needed. + +Step 4. [*wave_send_**] with the id of the waveform to transmit. + +A waveform comprises one or more pulses. Each pulse consists of a +[*gpioPulse_t*] structure. + +. . +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; +. . + +The fields specify + +1) the GPIO to be switched on at the start of the pulse. +2) the GPIO to be switched off at the start of the pulse. +3) the delay in microseconds before the next pulse. + +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). + +When a waveform is started each pulse is executed in order with the +specified delay between the pulse and the next. + +Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, +PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. +D*/ + + +/*F*/ +int wave_delete(unsigned wave_id); +/*D +This function deletes the waveform with id wave_id. + +. . +wave_id: >=0, as returned by [*wave_create*]. +. . + +Wave ids are allocated in order, 0, 1, 2, etc. + +The wave is flagged for deletion. The resources used by the wave +will only be reused when either of the following apply. + +- all waves with higher numbered wave ids have been deleted or have +been flagged for deletion. + +- a new wave is created which uses exactly the same resources as +the current wave (see the C source for gpioWaveCreate for details). + +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. +D*/ + +/*F*/ +int wave_send_once(unsigned wave_id); +/*D +This function transmits the waveform with id wave_id. The waveform +is sent once. + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +. . +wave_id: >=0, as returned by [*wave_create*]. +. . + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + +/*F*/ +int wave_send_repeat(unsigned wave_id); +/*D +This function transmits the waveform with id wave_id. The waveform +cycles until cancelled (either by the sending of a new waveform or +by [*wave_tx_stop*]). + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +. . +wave_id: >=0, as returned by [*wave_create*]. +. . + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + +/*F*/ +int wave_chain(char *buf, unsigned bufSize); +/*D +This function transmits a chain of waveforms. + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of [*wave_id*]s and optional command +codes and related data. + +. . + buf: pointer to the wave_ids and optional command codes +bufSize: the number of bytes in buf +. . + +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +Delays between waves may be added with the delay command. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +Loop Start @ 255 0 @ Identify start of a wave block +Loop Repeat @ 255 1 x y @ loop x + y*256 times +Delay @ 255 2 x y @ delay x + y*256 microseconds +Loop Forever @ 255 3 @ loop forever + +If present Loop Forever must be the last entry in the chain. + +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +... +#include +#include + +#define WAVES 5 +#define GPIO 4 + +int main(int argc, char *argv[]) +{ + int i, wid[WAVES]; + + if (pigpio_start(0, 0)<0) return -1; + + set_mode(GPIO, PI_OUTPUT); + + for (i=0; i=0, as returned by [*store_script*]. + numPar: 0-10, the number of parameters. + param: an array of parameters. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + +/*F*/ +int script_status(unsigned script_id, uint32_t *param); +/*D +This function returns the run status of a stored script as well +as the current values of parameters 0 to 9. + +. . +script_id: >=0, as returned by [*store_script*]. + param: an array to hold the returned 10 parameters. +. . + +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +The run status may be + +. . +PI_SCRIPT_INITING +PI_SCRIPT_HALTED +PI_SCRIPT_RUNNING +PI_SCRIPT_WAITING +PI_SCRIPT_FAILED +. . + +The current value of script parameters 0 to 9 are returned in param. +D*/ + +/*F*/ +int stop_script(unsigned script_id); +/*D +This function stops a running script. + +. . +script_id: >=0, as returned by [*store_script*]. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + +/*F*/ +int delete_script(unsigned script_id); +/*D +This function deletes a stored script. + +. . +script_id: >=0, as returned by [*store_script*]. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + +/*F*/ +int bb_serial_read_open(unsigned user_gpio, unsigned baud, unsigned data_bits); +/*D +This function opens a GPIO for bit bang reading of serial data. + +. . +user_gpio: 0-31. + baud: 50-250000 +data_bits: 1-32 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, +or PI_GPIO_IN_USE. + +The serial data is returned in a cyclic buffer and is read using +bb_serial_read. + +It is the caller's responsibility to read data from the cyclic buffer +in a timely fashion. +D*/ + +/*F*/ +int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize); +/*D +This function copies up to bufSize bytes of data read from the +bit bang serial cyclic buffer to the buffer starting at buf. + +. . +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. + buf: an array to receive the read bytes. + bufSize: >=0 +. . + +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +The bytes returned for each character depend upon the number of +data bits [*data_bits*] specified in the [*bb_serial_read_open*] command. + +For [*data_bits*] 1-8 there will be one byte per character. +For [*data_bits*] 9-16 there will be two bytes per character. +For [*data_bits*] 17-32 there will be four bytes per character. +D*/ + +/*F*/ +int bb_serial_read_close(unsigned user_gpio); +/*D +This function closes a GPIO for bit bang reading of serial data. + +. . +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. +D*/ + +/*F*/ +int bb_serial_invert(unsigned user_gpio, unsigned invert); +/*D +This function inverts serial logic for big bang serial reads. + +. . +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. + invert: 0-1, 1 invert, 0 normal. +. . + +Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT. +D*/ + +/*F*/ +int i2c_open(unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags); +/*D +This returns a handle for the device at address i2c_addr on bus i2c_bus. + +. . + i2c_bus: >=0. + i2c_addr: 0-0x7F. +i2c_flags: 0. +. . + +No flags are currently defined. This parameter should be set to zero. + +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +The GPIO used are given in the following table. + + @ SDA @ SCL +I2C 0 @ 0 @ 1 +I2C 1 @ 2 @ 3 + +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +. . +S (1 bit) : Start bit +P (1 bit) : Stop bit +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +A, NA (1 bit) : Accept and not accept bit. +Addr (7 bits): I2C 7 bit address. +Comm (8 bits): Command byte, a data byte which often selects a register. +Data (8 bits): A data byte. +Count (8 bits): A data byte containing the length of a block operation. + +[..]: Data sent by the device. +. . +D*/ + +/*F*/ +int i2c_close(unsigned handle); +/*D +This closes the I2C device associated with the handle. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int i2c_write_quick(unsigned handle, unsigned bit); +/*D +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. + bit: 0-1, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Quick command. SMBus 2.0 5.5.1 +. . +S Addr Rd/Wr [A] P +. . +D*/ + +/*F*/ +int i2c_write_byte(unsigned handle, unsigned bVal); +/*D +This sends a single byte to the device associated with handle. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. + bVal: 0-0xFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Send byte. SMBus 2.0 5.5.2 +. . +S Addr Wr [A] Data [A] P +. . +D*/ + +/*F*/ +int i2c_read_byte(unsigned handle); +/*D +This reads a single byte from the device associated with handle. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +Receive byte. SMBus 2.0 5.5.3 +. . +S Addr Rd [A] [Data] NA P +. . +D*/ + +/*F*/ +int i2c_write_byte_data(unsigned handle, unsigned i2c_reg, unsigned bVal); +/*D +This writes a single byte to the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + bVal: 0-0xFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write byte. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] Comm [A] Data [A] P +. . +D*/ + +/*F*/ +int i2c_write_word_data(unsigned handle, unsigned i2c_reg, unsigned wVal); +/*D +This writes a single 16 bit word to the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + wVal: 0-0xFFFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write word. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] P +. . +D*/ + +/*F*/ +int i2c_read_byte_data(unsigned handle, unsigned i2c_reg); +/*D +This reads a single byte from the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read byte. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] Comm [A] S Addr Rd [A] [Data] NA P +. . +D*/ + +/*F*/ +int i2c_read_word_data(unsigned handle, unsigned i2c_reg); +/*D +This reads a single 16 bit word from the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read word. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] Comm [A] S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + +/*F*/ +int i2c_process_call(unsigned handle, unsigned i2c_reg, unsigned wVal); +/*D +This writes 16 bits of data to the specified register of the device +associated with handle and and reads 16 bits of data in return. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write/read. + wVal: 0-0xFFFF, the value to write. +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Process call. SMBus 2.0 5.5.6 +. . +S Addr Wr [A] Comm [A] DataLow [A] DataHigh [A] + S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + +/*F*/ +int i2c_write_block_data( +unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes up to 32 bytes to the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + buf: an array with the data to send. + count: 1-32, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Block write. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] Comm [A] Count [A] Data [A] Data [A] ... [A] Data [A] P +. . +D*/ + +/*F*/ +int i2c_read_block_data(unsigned handle, unsigned i2c_reg, char *buf); +/*D +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. + buf: an array to receive the read data. +. . + +The amount of returned data is set by the device. + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Block read. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] Comm [A] + S Addr Rd [A] [Count] A [Data] A [Data] A ... A [Data] NA P +. . +D*/ + +/*F*/ +int i2c_block_process_call( +unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write/read. + buf: an array with the data to send and to receive the read data. + count: 1-32, the number of bytes to write. +. . + + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +The smbus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +Block write-block read. SMBus 2.0 5.5.8 +. . +S Addr Wr [A] Comm [A] Count [A] Data [A] ... + S Addr Rd [A] [Count] A [Data] ... A P +. . +D*/ + +/*F*/ +int i2c_read_i2c_block_data( +unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. + buf: an array to receive the read data. + count: 1-32, the number of bytes to read. +. . + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +. . +S Addr Wr [A] Comm [A] + S Addr Rd [A] [Data] A [Data] A ... A [Data] NA P +. . +D*/ + + +/*F*/ +int i2c_write_i2c_block_data( +unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +. . + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + buf: the data to write. + count: 1-32, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +. . +S Addr Wr [A] Comm [A] Data [A] Data [A] ... [A] Data [A] P +. . +D*/ + +/*F*/ +int i2c_read_device(unsigned handle, char *buf, unsigned count); +/*D +This reads count bytes from the raw device into buf. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. + buf: an array to receive the read data bytes. + count: >0, the number of bytes to read. +. . + +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. +D*/ + +/*F*/ +int i2c_write_device(unsigned handle, char *buf, unsigned count); +/*D +This writes count bytes from buf to the raw device. + +. . +handle: >=0, as returned by a call to [*i2c_open*]. + buf: an array containing the data bytes to write. + count: >0, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +D*/ + +/*F*/ +int i2c_zip( + unsigned handle, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . +handle: >=0, as returned by a call to [*i2cOpen*] + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +On @ 2 @ Switch combined flag on +Off @ 3 @ Switch combined flag off +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53, write 0x32, read 6 bytes +Set address 0x1E, write 0x03, read 6 bytes +Set address 0x68, write 0x1B, read 8 bytes +End + +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +0x00 +... + +D*/ + +/*F*/ +int bb_i2c_open(unsigned SDA, unsigned SCL, unsigned baud); +/*D +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +o baud rates as low as 50 +o repeated starts +o clock stretching +o I2C on any pair of spare GPIO + +. . + SDA: 0-31 + SCL: 0-31 +baud: 50-500000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +NOTE: + +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. +D*/ + +/*F*/ +int bb_i2c_close(unsigned SDA); +/*D +This function stops bit banging I2C on a pair of GPIO previously +opened with [*bb_i2c_open*]. + +. . +SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. +D*/ + +/*F*/ +int bb_i2c_zip( + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . + SDA: 0-31 (as used in a prior call to [*bb_i2c_open*]) + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +Start @ 2 @ Start condition +Stop @ 3 @ Stop condition +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +No flags are currently defined. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53 +start, write 0x32, (re)start, read 6 bytes, stop +Set address 0x1E +start, write 0x03, (re)start, read 6 bytes, stop +Set address 0x68 +start, write 0x1B, (re)start, read 8 bytes, stop +End + +0x04 0x53 +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 + +0x04 0x1E +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 + +0x04 0x68 +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 + +0x00 +... +D*/ + +/*F*/ +int spi_open(unsigned spi_channel, unsigned baud, unsigned spi_flags); +/*D +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +The Pi has two SPI peripherals: main and auxiliary. + +The main SPI has two chip selects (channels), the auxiliary has +three. + +The auxiliary SPI is available on all models but the A and B. + +The GPIO used are given in the following table. + + @ MISO @ MOSI @ SCLK @ CE0 @ CE1 @ CE2 +Main SPI @ 9 @ 10 @ 11 @ 8 @ 7 @ - +Aux SPI @ 19 @ 20 @ 21 @ 18 @ 17 @ 16 + +. . +spi_channel: 0-1 (0-2 for the auxiliary SPI). + baud: 32K-125M (values above 30M are unlikely to work). + spi_flags: see below. +. . + +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +spi_flags consists of the least significant 22 bits. + +. . +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +. . + +mm defines the SPI mode. + +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +. . +Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +px is 0 if CEx is active low (default) and 1 for active high. + +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +A is 0 for the main SPI, 1 for the auxiliary SPI. + +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +For bits 1-8 there will be one byte per word. +For bits 9-16 there will be two bytes per word. +For bits 17-32 there will be four bytes per word. + +Multi-byte transfers are made in least significant byte first order. + +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +The other bits in flags should be set to zero. +D*/ + +/*F*/ +int spi_close(unsigned handle); +/*D +This functions closes the SPI device identified by the handle. + +. . +handle: >=0, as returned by a call to [*spi_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int spi_read(unsigned handle, char *buf, unsigned count); +/*D +This function reads count bytes of data from the SPI +device associated with the handle. + +. . +handle: >=0, as returned by a call to [*spi_open*]. + buf: an array to receive the read data bytes. + count: the number of bytes to read. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int spi_write(unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +. . +handle: >=0, as returned by a call to [*spi_open*]. + buf: the data bytes to write. + count: the number of bytes to write. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count); +/*D +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +. . +handle: >=0, as returned by a call to [*spi_open*]. + txBuf: the data bytes to write. + rxBuf: the received data bytes. + count: the number of bytes to transfer. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int serial_open(char *ser_tty, unsigned baud, unsigned ser_flags); +/*D +This function opens a serial device at a specified baud rate +with specified flags. The device name must start with +/dev/tty or /dev/serial. + +. . + ser_tty: the serial device to open. + baud: the baud rate in bits per second, see below. +ser_flags: 0. +. . + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +No flags are currently defined. This parameter should be set to zero. +D*/ + +/*F*/ +int serial_close(unsigned handle); +/*D +This function closes the serial device associated with handle. + +. . +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int serial_write_byte(unsigned handle, unsigned bVal); +/*D +This function writes bVal to the serial port associated with handle. + +. . +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + +/*F*/ +int serial_read_byte(unsigned handle); +/*D +This function reads a byte from the serial port associated with handle. + +. . +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +If no data is ready PI_SER_READ_NO_DATA is returned. +D*/ + +/*F*/ +int serial_write(unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes from buf to the the serial port +associated with handle. + +. . +handle: >=0, as returned by a call to [*serial_open*]. + buf: the array of bytes to write. + count: the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + +/*F*/ +int serial_read(unsigned handle, char *buf, unsigned count); +/*D +This function reads up to count bytes from the the serial port +associated with handle and writes them to buf. + +. . +handle: >=0, as returned by a call to [*serial_open*]. + buf: an array to receive the read data. + count: the maximum number of bytes to read. +. . + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED. + +If no data is ready zero is returned. +D*/ + +/*F*/ +int serial_data_available(unsigned handle); +/*D +Returns the number of bytes available to be read from the +device associated with handle. + +. . +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int custom_1(unsigned arg1, unsigned arg2, char *argx, unsigned argc); +/*D +This function is available for user customisation. + +It returns a single integer value. + +. . +arg1: >=0 +arg2: >=0 +argx: extra (byte) arguments +argc: number of extra arguments +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. +D*/ + + +/*F*/ +int custom_2(unsigned arg1, char *argx, unsigned argc, + char *retBuf, unsigned retMax); +/*D +This function is available for user customisation. + +It differs from custom_1 in that it returns an array of bytes +rather than just an integer. + +The return value is an integer indicating the number of returned bytes. +. . + arg1: >=0 + argc: extra (byte) arguments + count: number of extra arguments +retBuf: buffer for returned data +retMax: maximum number of bytes to return +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. + +Note, the number of returned bytes will be retMax or less. +D*/ + + +/*F*/ +int callback(unsigned user_gpio, unsigned edge, CBFunc_t f); +/*D +This function initialises a new callback. + +. . +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + f: the callback function. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the GPIO, edge, and tick, whenever the +GPIO has the identified edge. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +edge 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes +. . +D*/ + +/*F*/ +int callback_ex + (unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata); +/*D +This function initialises a new callback. + +. . +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + f: the callback function. + userdata: a pointer to arbitrary user data. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the GPIO, edge, tick, and user, whenever +the GPIO has the identified edge. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +edge 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes + +userdata pointer Pointer to an arbitrary object +. . +D*/ + +/*F*/ +int callback_cancel(unsigned callback_id); +/*D +This function cancels a callback identified by its id. + +. . +callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*]. +. . + +The function returns 0 if OK, otherwise pigif_callback_not_found. +D*/ + +/*F*/ +int wait_for_edge(unsigned user_gpio, unsigned edge, double timeout); +/*D +This function waits for edge on the GPIO for up to timeout +seconds. + +. . +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + timeout: >=0. +. . + +The function returns 1 if the edge occurred, otherwise 0. + +The function returns when the edge occurs or after the timeout. +D*/ + +/*PARAMS + +active :: 0-1000000 + +The number of microseconds level changes are reported for once +a noise filter has been triggered (by [*steady*] microseconds of +a stable level). + +*addrStr:: +A string specifying the host or IP address of the Pi running +the pigpio daemon. It may be NULL in which case localhost +is used unless overridden by the PIGPIO_ADDR environment +variable. + +arg1:: +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +arg2:: +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +argc:: +The count of bytes passed to a user customised function. + +*argx:: +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +baud:: +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +bit:: +A value of 0 or 1. + +bits:: +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +A convenient way to set bit n is to or in (1<=0, as returned by a call to [*callback*] or [*callback_ex*]. This is +passed to [*callback_cancel*] to cancel the callback. + +CBFunc_t:: +. . +typedef void (*CBFunc_t) + (unsigned user_gpio, unsigned level, uint32_t tick); +. . + +CBFuncEx_t:: +. . +typedef void (*CBFuncEx_t) + (unsigned user_gpio, unsigned level, uint32_t tick, void * user); +. . + +char:: +A single character, an 8 bit quantity able to store 0-255. + +clkfreq::4689-250000000 (250M) +The hardware clock frequency. + +count:: +The number of bytes to be transferred in an I2C, SPI, or Serial +command. + +data_bits::1-32 +The number of data bits in each character of serial data. + +. . +#define PI_MIN_WAVE_DATABITS 1 +#define PI_MAX_WAVE_DATABITS 32 +. . + +double:: +A floating point number. + +dutycycle::0-range +A number representing the ratio of on time to off time for PWM. + +The number may vary between 0 and range (default 255) where +0 is off and range is fully on. + +edge:: +Used to identify a GPIO level transition of interest. A rising edge is +a level change from 0 to 1. A falling edge is a level change from 1 to 0. + +. . +RISING_EDGE 0 +FALLING_EDGE 1 +EITHER_EDGE. 2 +. . + +errnum:: +A negative number indicating a function call failed and the nature +of the error. + +f:: +A function. + +frequency::>=0 +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + + +gpio:: +A Broadcom numbered GPIO, in the range 0-53. + +There are 54 General Purpose Input Outputs (GPIO) named gpio0 through +gpio53. + +They are split into two banks. Bank 1 consists of gpio0 through +gpio31. Bank 2 consists of gpio32 through gpio53. + +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +See [*get_hardware_revision*]. + +The user GPIO are marked with an X in the following table. + +. . + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +Type 1 X X - - X - - X X X X X - - X X +Type 2 - - X X X - - X X X X X - - X X +Type 3 X X X X X X X X X X X X X X + + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +Type 1 - X X - - X X X X X - - - - - - +Type 2 - X X - - - X X X X - X X X X X +Type 3 X X X X X X X X X X X X - - - - +. . + +gpioPulse_t:: +. . +typedef struct +{ +uint32_t gpioOn; +uint32_t gpioOff; +uint32_t usDelay; +} gpioPulse_t; +. . + +gpioThreadFunc_t:: +. . +typedef void *(gpioThreadFunc_t) (void *); +. . + +handle::>=0 +A number referencing an object opened by one of [*i2c_open*], [*notify_open*], +[*serial_open*], and [*spi_open*]. + +i2c_addr:: 0-0x7F +The address of a device on the I2C bus. + +i2c_bus::>=0 +An I2C bus number. + +i2c_flags::0 +Flags which modify an I2C open command. None are currently defined. + +i2c_reg:: 0-255 +A register of an I2C device. + +*inBuf:: +A buffer used to pass data to a function. + +inLen:: +The number of bytes of data in a buffer. + +int:: +A whole number, negative or positive. + +invert:: +A flag used to set normal or inverted bit bang serial data level logic. + +level:: +The level of a GPIO. Low or High. + +. . +PI_OFF 0 +PI_ON 1 + +PI_CLEAR 0 +PI_SET 1 + +PI_LOW 0 +PI_HIGH 1 +. . + +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See [*set_watchdog*]. + +. . +PI_TIMEOUT 2 +. . + +mode::0-7 +The operational mode of a GPIO, normally INPUT or OUTPUT. + +. . +PI_INPUT 0 +PI_OUTPUT 1 +PI_ALT0 4 +PI_ALT1 5 +PI_ALT2 6 +PI_ALT3 7 +PI_ALT4 3 +PI_ALT5 2 +. . + +numBytes:: +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +numPar:: 0-10 +The number of parameters passed to a script. + +numPulses:: +The number of pulses to be added to a waveform. + +offset:: +The associated data starts this number of microseconds from the start of +the waveform. + +*outBuf:: +A buffer used to return data from a function. + +outLen:: +The size in bytes of an output buffer. + +*param:: +An array of script parameters. + +*portStr:: +A string specifying the port address used by the Pi running +the pigpio daemon. It may be NULL in which case "8888" +is used unless overridden by the PIGPIO_PORT environment +variable. + +*pth:: +A thread identifier, returned by [*start_thread*]. + + +pthread_t:: +A thread identifier. + +pud::0-2 +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. +. . +PI_PUD_OFF 0 +PI_PUD_DOWN 1 +PI_PUD_UP 2 +. . + +pulseLen:: +1-100, the length of a trigger pulse in microseconds. + +*pulses:: +An array of pulses to be added to a waveform. + +pulsewidth::0, 500-2500 +. . +PI_SERVO_OFF 0 +PI_MIN_SERVO_PULSEWIDTH 500 +PI_MAX_SERVO_PULSEWIDTH 2500 +. . + +PWMduty::0-1000000 (1M) +The hardware PWM dutycycle. + +. . +#define PI_HW_PWM_RANGE 1000000 +. . + +PWMfreq::1-125000000 (125M) +The hardware PWM frequency. + +. . +#define PI_HW_PWM_MIN_FREQ 1 +#define PI_HW_PWM_MAX_FREQ 125000000 +. . + +range::25-40000 +The permissible dutycycle values are 0-range. +. . +PI_MIN_DUTYCYCLE_RANGE 25 +PI_MAX_DUTYCYCLE_RANGE 40000 +. . + +*retBuf:: +A buffer to hold a number of bytes returned to a used customised function, + +retMax:: +The maximum number of bytes a user customised function should return. + + +*rxBuf:: +A pointer to a buffer to receive data. + +SCL:: +The user GPIO to use for the clock when bit banging I2C. + +*script:: +A pointer to the text of a script. + +script_id:: +An id of a stored script as returned by [*store_script*]. + +SDA:: +The user GPIO to use for data when bit banging I2C. + +seconds:: +The number of seconds. + +ser_flags:: +Flags which modify a serial open command. None are currently defined. + +*ser_tty:: +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +size_t:: +A standard type used to indicate the size of an object in bytes. + +spi_channel:: +A SPI channel, 0-2. + +spi_flags:: +See [*spi_open*]. + +steady :: 0-300000 + +The number of microseconds level changes must be stable for +before reporting the level changed ([*set_glitch_filter*]) or triggering +the active part of a noise filter ([*set_noise_filter*]). + +stop_bits::2-8 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +. . +#define PI_MIN_WAVE_HALFSTOPBITS 2 +#define PI_MAX_WAVE_HALFSTOPBITS 8 +. . + +*str:: + An array of characters. + +thread_func:: +A function of type gpioThreadFunc_t used as the main function of a +thread. + +timeout:: +A GPIO watchdog timeout in milliseconds. +. . +PI_MIN_WDOG_TIMEOUT 0 +PI_MAX_WDOG_TIMEOUT 60000 +. . + +*txBuf:: +An array of bytes to transmit. + +uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF) +A 32-bit unsigned value. + +unsigned:: +A whole number >= 0. + +user_gpio:: +0-31, a Broadcom numbered GPIO. + +See [*gpio*]. + +*userdata:: +A pointer to arbitrary user data. This may be used to identify the instance. + +void:: +Denoting no parameter is required + +wave_add_*:: +One of [*wave_add_new*], [*wave_add_generic*], [*wave_add_serial*]. + +wave_id:: +A number representing a waveform created by [*wave_create*]. + +wave_send_*:: +One of [*wave_send_once*], [*wave_send_repeat*]. + +wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777) +A 16-bit word value. + +PARAMS*/ + +/*DEF_S pigpiod_if Error Codes*/ + +typedef enum +{ + pigif_bad_send = -2000, + pigif_bad_recv = -2001, + pigif_bad_getaddrinfo = -2002, + pigif_bad_connect = -2003, + pigif_bad_socket = -2004, + pigif_bad_noib = -2005, + pigif_duplicate_callback = -2006, + pigif_bad_malloc = -2007, + pigif_bad_callback = -2008, + pigif_notify_failed = -2009, + pigif_callback_not_found = -2010, +} pigifError_t; + +/*DEF_E*/ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/thirdparty/PIGPIO/pigpiod_if2.3 b/thirdparty/PIGPIO/pigpiod_if2.3 new file mode 100644 index 0000000000..d91c6867b6 --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if2.3 @@ -0,0 +1,7408 @@ + +." Process this file with +." groff -man -Tascii pigpiod_if2.3 +." +.TH pigpiod_if2 3 2012-2018 Linux "pigpio archive" +.SH NAME +pigpiod_if2 - A C library to interface to the pigpio daemon. + +.SH SYNOPSIS + +#include + + +gcc -Wall -pthread -o prog prog.c -lpigpiod_if2 -lrt + + ./prog +.SH DESCRIPTION + + +.ad l + +.nh + +.br + +.br +pigpiod_if2 is a C library for the Raspberry which allows control +of the GPIO via the socket interface to the pigpio daemon. +.br + +.br + +.br +.SS Features +.br + +.br +o hardware timed PWM on any of GPIO 0-31 + +.br + +.br +o hardware timed servo pulses on any of GPIO 0-31 + +.br + +.br +o callbacks when any of GPIO 0-31 change state + +.br + +.br +o callbacks at timed intervals + +.br + +.br +o reading/writing all of the GPIO in a bank as one operation + +.br + +.br +o individually setting GPIO modes, reading and writing + +.br + +.br +o notifications when any of GPIO 0-31 change state + +.br + +.br +o the construction of output waveforms with microsecond timing + +.br + +.br +o rudimentary permission control over GPIO + +.br + +.br +o a simple interface to start and stop new threads + +.br + +.br +o I2C, SPI, and serial link wrappers + +.br + +.br +o creating and running scripts on the pigpio daemon + +.br + +.br +.SS GPIO +.br + +.br +ALL GPIO are identified by their Broadcom number. + +.br + +.br +.SS Notes +.br + +.br +The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals. + +.br + +.br +.SS Usage +.br + +.br +Include in your source files. + +.br + +.br +Assuming your source is in prog.c use the following command to build + +.br + +.br + +.EX +gcc -Wall -pthread -o prog prog.c -lpigpiod_if2 -lrt +.br + +.EE + +.br + +.br +to run make sure the pigpio daemon is running + +.br + +.br + +.EX +sudo pigpiod +.br + +.br + ./prog # sudo is not required to run programs linked to pigpiod_if2 +.br + +.EE + +.br + +.br +For examples see x_pigpiod_if2.c within the pigpio archive file. + +.br + +.br +.SS Notes +.br + +.br +All the functions which return an int return < 0 on error + +.br + +.br +.SH FUNCTIONS + +.IP "\fBdouble time_time(void)\fP" +.IP "" 4 +Return the current time in seconds since the Epoch. + +.IP "\fBvoid time_sleep(double seconds)\fP" +.IP "" 4 +Delay execution for a given number of seconds. + +.br + +.br + +.EX +seconds: the number of seconds to delay. +.br + +.EE + +.IP "\fBchar *pigpio_error(int errnum)\fP" +.IP "" 4 +Return a text description for an error code. + +.br + +.br + +.EX +errnum: the error code. +.br + +.EE + +.IP "\fBunsigned pigpiod_if_version(void)\fP" +.IP "" 4 +Return the pigpiod_if2 version. + +.IP "\fBpthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata)\fP" +.IP "" 4 +Starts a new thread of execution with thread_func as the main routine. + +.br + +.br + +.EX +thread_func: the main function for the new thread. +.br + userdata: a pointer to an arbitrary argument. +.br + +.EE + +.br + +.br +Returns a pointer to pthread_t if OK, otherwise NULL. + +.br + +.br +The function is passed the single argument userdata. + +.br + +.br +The thread can be cancelled by passing the pointer to pthread_t to +\fBstop_thread\fP. + +.IP "\fBvoid stop_thread(pthread_t *pth)\fP" +.IP "" 4 +Cancels the thread pointed at by pth. + +.br + +.br + +.EX +pth: the thread to be stopped. +.br + +.EE + +.br + +.br +No value is returned. + +.br + +.br +The thread to be stopped should have been started with \fBstart_thread\fP. + +.IP "\fBint pigpio_start(char *addrStr, char *portStr)\fP" +.IP "" 4 +Connect to the pigpio daemon. Reserving command and +notification streams. + +.br + +.br + +.EX +addrStr: specifies the host or IP address of the Pi running the +.br + pigpio daemon. It may be NULL in which case localhost +.br + is used unless overridden by the PIGPIO_ADDR environment +.br + variable. +.br + +.br +portStr: specifies the port address used by the Pi running the +.br + pigpio daemon. It may be NULL in which case "8888" +.br + is used unless overridden by the PIGPIO_PORT environment +.br + variable. +.br + +.EE + +.br + +.br +Returns an integer value greater than or equal to zero if OK. + +.br + +.br +This value is passed to the GPIO routines to specify the Pi +to be operated on. + +.IP "\fBvoid pigpio_stop(int pi)\fP" +.IP "" 4 +Terminates the connection to a pigpio daemon and releases +resources used by the library. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint set_mode(int pi, unsigned gpio, unsigned mode)\fP" +.IP "" 4 +Set the GPIO mode. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +gpio: 0-53. +.br +mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1, +.br + PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE, +or PI_NOT_PERMITTED. + +.IP "\fBint get_mode(int pi, unsigned gpio)\fP" +.IP "" 4 +Get the GPIO mode. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +gpio: 0-53. +.br + +.EE + +.br + +.br +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. + +.IP "\fBint set_pull_up_down(int pi, unsigned gpio, unsigned pud)\fP" +.IP "" 4 +Set or clear the GPIO pull-up/down resistor. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +gpio: 0-53. +.br + pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD, +or PI_NOT_PERMITTED. + +.IP "\fBint gpio_read(int pi, unsigned gpio)\fP" +.IP "" 4 +Read the GPIO level. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +gpio:0-53. +.br + +.EE + +.br + +.br +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. + +.IP "\fBint gpio_write(int pi, unsigned gpio, unsigned level)\fP" +.IP "" 4 +Write the GPIO level. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + gpio: 0-53. +.br +level: 0, 1. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL, +or PI_NOT_PERMITTED. + +.br + +.br +Notes + +.br + +.br +If PWM or servo pulses are active on the GPIO they are switched off. + +.IP "\fBint set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle)\fP" +.IP "" 4 +Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br +dutycycle: 0-range (range defaults to 255). +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE, +or PI_NOT_PERMITTED. +Notes + +.br + +.br +The \fBset_PWM_range\fP function may be used to change the +default range of 255. + +.IP "\fBint get_PWM_dutycycle(int pi, unsigned user_gpio)\fP" +.IP "" 4 +Return the PWM dutycycle in use on a GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +.br + +.br +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see \fBget_PWM_range\fP). + +.br + +.br +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). + +.IP "\fBint set_PWM_range(int pi, unsigned user_gpio, unsigned range)\fP" +.IP "" 4 +Set the range of PWM values to be used on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + range: 25-40000. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE, +or PI_NOT_PERMITTED. + +.br + +.br +Notes + +.br + +.br +If PWM is currently active on the GPIO its dutycycle will be +scaled to reflect the new range. + +.br + +.br +The real range, the number of steps between fully off and fully on +for each of the 18 available GPIO frequencies is + +.br + +.br + +.EX + 25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6), +.br + 400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12), +.br +2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18) +.br + +.EE + +.br + +.br +The real value set by set_PWM_range is (dutycycle * real range) / range. + +.IP "\fBint get_PWM_range(int pi, unsigned user_gpio)\fP" +.IP "" 4 +Get the range of PWM values being used on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns the dutycycle range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.br + +.br +If a hardware clock or hardware PWM is active on the GPIO the +reported range will be 1000000 (1M). + +.IP "\fBint get_PWM_real_range(int pi, unsigned user_gpio)\fP" +.IP "" 4 +Get the real underlying range of PWM values being used on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns the real range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.br + +.br +If a hardware clock is active on the GPIO the reported +real range will be 1000000 (1M). + +.br + +.br +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +.br + +.br + +.IP "\fBint set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency)\fP" +.IP "" 4 +Set the frequency (in Hz) of the PWM to be used on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br +frequency: >=0 (Hz). +.br + +.EE + +.br + +.br +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PERMITTED. + +.br + +.br +If PWM is currently active on the GPIO it will be switched +off and then back on at the new frequency. + +.br + +.br +Each GPIO can be independently set to one of 18 different +PWM frequencies. + +.br + +.br +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The +sample rate is set when the pigpio daemon is started. + +.br + +.br +The frequencies for each sample rate are: + +.br + +.br + +.EX + Hertz +.br + +.br + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 +.br + 1250 1000 800 500 400 250 200 100 50 +.br + +.br + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 +.br + 625 500 400 250 200 125 100 50 25 +.br + +.br + 4: 10000 5000 2500 2000 1250 1000 625 500 400 +.br + 313 250 200 125 100 63 50 25 13 +.br +sample +.br + rate +.br + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 +.br + 250 200 160 100 80 50 40 20 10 +.br + +.br + 8: 5000 2500 1250 1000 625 500 313 250 200 +.br + 156 125 100 63 50 31 25 13 6 +.br + +.br + 10: 4000 2000 1000 800 500 400 250 200 160 +.br + 125 100 80 50 40 25 20 10 5 +.br + +.EE + +.IP "\fBint get_PWM_frequency(int pi, unsigned user_gpio)\fP" +.IP "" 4 +Get the frequency of PWM being used on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + +.EE + +.br + +.br +For normal PWM the frequency will be that defined for the GPIO by +\fBset_PWM_frequency\fP. + +.br + +.br +If a hardware clock is active on the GPIO the reported frequency +will be that set by \fBhardware_clock\fP. + +.br + +.br +If hardware PWM is active on the GPIO the reported frequency +will be that set by \fBhardware_PWM\fP. + +.br + +.br +Returns the frequency (in hertz) used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +.IP "\fBint set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth)\fP" +.IP "" 4 +Start (500-2500) or stop (0) servo pulses on the GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + user_gpio: 0-31. +.br +pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise). +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or +PI_NOT_PERMITTED. + +.br + +.br +The selected pulsewidth will continue to be transmitted until +changed by a subsequent call to set_servo_pulsewidth. + +.br + +.br +The pulsewidths supported by servos varies and should probably be +determined by experiment. A value of 1500 should always be safe and +represents the mid-point of rotation. + +.br + +.br +You can DAMAGE a servo if you command it to move beyond its limits. + +.br + +.br +OTHER UPDATE RATES: + +.br + +.br +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +.br + +.br + +.EX +Update Rate (Hz) 50 100 200 400 500 +.br +1E6/Hz 20000 10000 5000 2500 2000 +.br + +.EE + +.br + +.br +Firstly set the desired PWM frequency using \fBset_PWM_frequency\fP. + +.br + +.br +Then set the PWM range using \fBset_PWM_range\fP to 1E6/Hz. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +.br + +.br +E.g. If you want to update a servo connected to GPIO 25 at 400Hz + +.br + +.br + +.EX +set_PWM_frequency(25, 400); +.br +set_PWM_range(25, 2500); +.br + +.EE + +.br + +.br +Thereafter use the \fBset_PWM_dutycycle\fP function to move the servo, +e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. +.br + +.IP "\fBint get_servo_pulsewidth(int pi, unsigned user_gpio)\fP" +.IP "" 4 +Return the servo pulsewidth in use on a GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. + +.IP "\fBint notify_open(int pi)\fP" +.IP "" 4 +Get a free notification handle. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +.br + +.br +A notification is a method for being notified of GPIO state +changes via a pipe. + +.br + +.br +Pipes are only accessible from the local machine so this function +serves no purpose if you are using the library from a remote machine. +The in-built (socket) notifications provided by \fBcallback\fP +should be used instead. + +.br + +.br +Notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). +E.g. if the function returns 15 then the notifications must be +read from /dev/pigpio15. + +.IP "\fBint notify_begin(int pi, unsigned handle, uint32_t bits)\fP" +.IP "" 4 +Start notifications on a previously opened handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: 0-31 (as returned by \fBnotify_open\fP) +.br + bits: a mask indicating the GPIO to be notified. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +The notification sends state changes for each GPIO whose +corresponding bit in bits is set. + +.br + +.br +Each notification occupies 12 bytes in the fifo as follows: + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint16_t seqno; +.br + uint16_t flags; +.br + uint32_t tick; +.br + uint32_t level; +.br +} gpioReport_t; +.br + +.EE + +.br + +.br +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +.br + +.br +flags: three flags are defined, PI_NTFY_FLAGS_WDOG, +PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT. + +.br + +.br +If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +.br + +.br +If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +.br + +.br +If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags +indicate an event which has been triggered. + +.br + +.br +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +.br + +.br +level: indicates the level of each GPIO. If bit 1<=0 (as returned by \fBpigpio_start\fP). +.br +handle: 0-31 (as returned by \fBnotify_open\fP) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +Notifications for the handle are suspended until +\fBnotify_begin\fP is called again. + +.IP "\fBint notify_close(int pi, unsigned handle)\fP" +.IP "" 4 +Stop notifications on a previously opened handle and +release the handle for reuse. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: 0-31 (as returned by \fBnotify_open\fP) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint set_watchdog(int pi, unsigned user_gpio, unsigned timeout)\fP" +.IP "" 4 +Sets a watchdog for a GPIO. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + timeout: 0-60000. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO +or PI_BAD_WDOG_TIMEOUT. + +.br + +.br +The watchdog is nominally in milliseconds. + +.br + +.br +Only one watchdog may be registered per GPIO. + +.br + +.br +The watchdog may be cancelled by setting timeout to 0. + +.br + +.br +Once a watchdog has been started callbacks for the GPIO will be +triggered every timeout interval after the last GPIO activity. + +.br + +.br +The callback will receive the special level PI_TIMEOUT. + +.IP "\fBint set_glitch_filter(int pi, unsigned user_gpio, unsigned steady)\fP" +.IP "" 4 +Sets a glitch filter on a GPIO. + +.br + +.br +Level changes on the GPIO are not reported unless the level +has been stable for at least \fBsteady\fP microseconds. The +level is then reported. Level changes of less than +\fBsteady\fP microseconds are ignored. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31 +.br + steady: 0-300000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +.br + +.br +This filter affects the GPIO samples returned to callbacks set up +with \fBcallback\fP, \fBcallback_ex\fP and \fBwait_for_edge\fP. + +.br + +.br +It does not affect levels read by \fBgpio_read\fP, +\fBread_bank_1\fP, or \fBread_bank_2\fP. + +.br + +.br +Each (stable) edge will be timestamped \fBsteady\fP microseconds +after it was first detected. + +.IP "\fBint set_noise_filter(int pi, unsigned user_gpio, unsigned steady, unsigned active)\fP" +.IP "" 4 +Sets a noise filter on a GPIO. + +.br + +.br +Level changes on the GPIO are ignored until a level which has +been stable for \fBsteady\fP microseconds is detected. Level changes +on the GPIO are then reported for \fBactive\fP microseconds after +which the process repeats. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31 +.br + steady: 0-300000 +.br + active: 0-1000000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +.br + +.br +This filter affects the GPIO samples returned to callbacks set up +with \fBcallback\fP, \fBcallback_ex\fP and \fBwait_for_edge\fP. + +.br + +.br +It does not affect levels read by \fBgpio_read\fP, +\fBread_bank_1\fP, or \fBread_bank_2\fP. + +.br + +.br +Level changes before and after the active period may +be reported. Your software must be designed to cope with +such reports. + +.IP "\fBuint32_t read_bank_1(int pi)\fP" +.IP "" 4 +Read the levels of the bank 1 GPIO (GPIO 0-31). + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +The returned 32 bit integer has a bit set if the corresponding +GPIO is logic 1. GPIO n has bit value (1<=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +The returned 32 bit integer has a bit set if the corresponding +GPIO is logic 1. GPIO n has bit value (1<<(n-32)). + +.IP "\fBint clear_bank_1(int pi, uint32_t bits)\fP" +.IP "" 4 +Clears GPIO 0-31 if the corresponding bit in bits is set. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +bits: a bit mask with 1 set if the corresponding GPIO is +.br + to be cleared. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +.br + +.br +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. + +.IP "\fBint clear_bank_2(int pi, uint32_t bits)\fP" +.IP "" 4 +Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +bits: a bit mask with 1 set if the corresponding GPIO is +.br + to be cleared. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +.br + +.br +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. + +.IP "\fBint set_bank_1(int pi, uint32_t bits)\fP" +.IP "" 4 +Sets GPIO 0-31 if the corresponding bit in bits is set. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +bits: a bit mask with 1 set if the corresponding GPIO is +.br + to be set. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +.br + +.br +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. + +.IP "\fBint set_bank_2(int pi, uint32_t bits)\fP" +.IP "" 4 +Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +bits: a bit mask with 1 set if the corresponding GPIO is +.br + to be set. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +.br + +.br +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. + +.IP "\fBint hardware_clock(int pi, unsigned gpio, unsigned clkfreq)\fP" +.IP "" 4 +Starts a hardware clock on a GPIO at the specified frequency. +Frequencies above 30MHz are unlikely to work. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + gpio: see description +.br +frequency: 0 (off) or 4689-250000000 (250M) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO, +PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS. + +.br + +.br +The same clock is available on multiple GPIO. The latest +frequency setting will be used by all GPIO which share a clock. + +.br + +.br +The GPIO must be one of the following. + +.br + +.br + +.EX +4 clock 0 All models +.br +5 clock 1 All models but A and B (reserved for system use) +.br +6 clock 2 All models but A and B +.br +20 clock 0 All models but A and B +.br +21 clock 1 All models but A and Rev.2 B (reserved for system use) +.br + +.br +32 clock 0 Compute module only +.br +34 clock 0 Compute module only +.br +42 clock 1 Compute module only (reserved for system use) +.br +43 clock 2 Compute module only +.br +44 clock 1 Compute module only (reserved for system use) +.br + +.EE + +.br + +.br +Access to clock 1 is protected by a password as its use will likely +crash the Pi. The password is given by or'ing 0x5A000000 with the +GPIO number. + +.IP "\fBint hardware_PWM(int pi, unsigned gpio, unsigned PWMfreq, uint32_t PWMduty)\fP" +.IP "" 4 +Starts hardware PWM on a GPIO at the specified frequency and dutycycle. +Frequencies above 30MHz are unlikely to work. + +.br + +.br +NOTE: Any waveform started by \fBwave_send_*\fP or \fBwave_chain\fP +will be cancelled. + +.br + +.br +This function is only valid if the pigpio main clock is PCM. The +main clock defaults to PCM but may be overridden when the pigpio +daemon is started (option -t). + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + gpio: see descripton +.br +PWMfreq: 0 (off) or 1-125000000 (125M) +.br +PWMduty: 0 (off) to 1000000 (1M)(fully on) +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO, +PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, +or PI_HPWM_ILLEGAL. + +.br + +.br +The same PWM channel is available on multiple GPIO. The latest +frequency and dutycycle setting will be used by all GPIO which +share a PWM channel. + +.br + +.br +The GPIO must be one of the following. + +.br + +.br + +.EX +12 PWM channel 0 All models but A and B +.br +13 PWM channel 1 All models but A and B +.br +18 PWM channel 0 All models +.br +19 PWM channel 1 All models but A and B +.br + +.br +40 PWM channel 0 Compute module only +.br +41 PWM channel 1 Compute module only +.br +45 PWM channel 1 Compute module only +.br +52 PWM channel 0 Compute module only +.br +53 PWM channel 1 Compute module only +.br + +.EE + +.br + +.br +The actual number of steps beween off and fully on is the +integral part of 250 million divided by PWMfreq. + +.br + +.br +The actual frequency set is 250 million / steps. + +.br + +.br +There will only be a million steps for a PWMfreq of 250. +Lower frequencies will have more steps and higher +frequencies will have fewer steps. PWMduty is +automatically scaled to take this into account. + +.IP "\fBuint32_t get_current_tick(int pi)\fP" +.IP "" 4 +Gets the current system tick. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Tick is the number of microseconds since system boot. + +.br + +.br +As tick is an unsigned 32 bit quantity it wraps around after +2**32 microseconds, which is approximately 1 hour 12 minutes. + +.br + +.br + +.IP "\fBuint32_t get_hardware_revision(int pi)\fP" +.IP "" 4 +Get the Pi's hardware revision number. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +The hardware revision is the last few characters on the Revision line +of /proc/cpuinfo. + +.br + +.br +If the hardware revision can not be found or is not a valid +hexadecimal number the function returns 0. + +.br + +.br +The revision number can be used to determine the assignment of GPIO +to pins (see \fBgpio\fP). + +.br + +.br +There are at least three types of board. + +.br + +.br +Type 1 boards have hardware revision numbers of 2 and 3. + +.br + +.br +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. + +.br + +.br +Type 3 boards have hardware revision numbers of 16 or greater. + +.IP "\fBuint32_t get_pigpio_version(int pi)\fP" +.IP "" 4 +Returns the pigpio version. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_clear(int pi)\fP" +.IP "" 4 +This function clears all waveforms and any data added by calls to the +\fBwave_add_*\fP functions. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.IP "\fBint wave_add_new(int pi)\fP" +.IP "" 4 +This function starts a new empty waveform. You wouldn't normally need +to call this function as it is automatically called after a waveform is +created with the \fBwave_create\fP function. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.IP "\fBint wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses)\fP" +.IP "" 4 +This function adds a number of pulses to the current waveform. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +numPulses: the number of pulses. +.br + pulses: an array of pulses. +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +.br + +.br +The pulses are interleaved in time order within the existing waveform +(if any). + +.br + +.br +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +.br + +.br +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist solely of a delay. + +.IP "\fBint wave_add_serial(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits, unsigned stop_bits, unsigned offset, unsigned numBytes, char *str)\fP" +.IP "" 4 +This function adds a waveform representing serial data to the +existing waveform (if any). The serial data starts offset +microseconds from the start of the waveform. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + baud: 50-1000000 +.br +data_bits: number of data bits (1-32) +.br +stop_bits: number of stop half bits (2-8) +.br + offset: >=0 +.br + numBytes: >=1 +.br + str: an array of chars. +.br + +.EE + +.br + +.br +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +.br + +.br +NOTES: + +.br + +.br +The serial data is formatted as one start bit, \fBdata_bits\fP data bits, +and \fBstop_bits\fP/2 stop bits. + +.br + +.br +It is legal to add serial data streams with different baud rates to +the same waveform. + +.br + +.br +\fBnumBytes\fP is the number of bytes of data in str. + +.br + +.br +The bytes required for each character depend upon \fBdata_bits\fP. + +.br + +.br +For \fBdata_bits\fP 1-8 there will be one byte per character. +.br +For \fBdata_bits\fP 9-16 there will be two bytes per character. +.br +For \fBdata_bits\fP 17-32 there will be four bytes per character. + +.IP "\fBint wave_create(int pi)\fP" +.IP "" 4 +This function creates a waveform from the data provided by the prior +calls to the \fBwave_add_*\fP functions. Upon success a wave id +greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM, +PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +The data provided by the \fBwave_add_*\fP functions is consumed by this +function. + +.br + +.br +As many waveforms may be created as there is space available. The +wave id is passed to \fBwave_send_*\fP to specify the waveform to transmit. + +.br + +.br +Normal usage would be + +.br + +.br +Step 1. \fBwave_clear\fP to clear all waveforms and added data. + +.br + +.br +Step 2. \fBwave_add_*\fP calls to supply the waveform data. + +.br + +.br +Step 3. \fBwave_create\fP to create the waveform and get a unique id + +.br + +.br +Repeat steps 2 and 3 as needed. + +.br + +.br +Step 4. \fBwave_send_*\fP with the id of the waveform to transmit. + +.br + +.br +A waveform comprises one or more pulses. Each pulse consists of a +\fBgpioPulse_t\fP structure. + +.br + +.br + +.EX +typedef struct +.br +{ +.br + uint32_t gpioOn; +.br + uint32_t gpioOff; +.br + uint32_t usDelay; +.br +} gpioPulse_t; +.br + +.EE + +.br + +.br +The fields specify + +.br + +.br +1) the GPIO to be switched on at the start of the pulse. +.br +2) the GPIO to be switched off at the start of the pulse. +.br +3) the delay in microseconds before the next pulse. +.br + +.br + +.br +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). + +.br + +.br +When a waveform is started each pulse is executed in order with the +specified delay between the pulse and the next. + +.br + +.br +Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, +PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. + +.IP "\fBint wave_delete(int pi, unsigned wave_id)\fP" +.IP "" 4 +This function deletes the waveform with id wave_id. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Wave ids are allocated in order, 0, 1, 2, etc. + +.br + +.br +The wave is flagged for deletion. The resources used by the wave +will only be reused when either of the following apply. + +.br + +.br +- all waves with higher numbered wave ids have been deleted or have +been flagged for deletion. + +.br + +.br +- a new wave is created which uses exactly the same resources as +the current wave (see the C source for gpioWaveCreate for details). + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. + +.IP "\fBint wave_send_once(int pi, unsigned wave_id)\fP" +.IP "" 4 +This function transmits the waveform with id wave_id. The waveform +is sent once. + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint wave_send_repeat(int pi, unsigned wave_id)\fP" +.IP "" 4 +This function transmits the waveform with id wave_id. The waveform +cycles until cancelled (either by the sending of a new waveform or +by \fBwave_tx_stop\fP). + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +wave_id: >=0, as returned by \fBwave_create\fP. +.br + +.EE + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint wave_send_using_mode(int pi, unsigned wave_id, unsigned mode)\fP" +.IP "" 4 +Transmits the waveform with id wave_id using mode mode. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +wave_id: >=0, as returned by \fBwave_create\fP. +.br + mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT, +.br + PI_WAVE_MODE_ONE_SHOT_SYNC, or PI_WAVE_MODE_REPEAT_SYNC. +.br + +.EE + +.br + +.br +PI_WAVE_MODE_ONE_SHOT: same as \fBwave_send_once\fP. + +.br + +.br +PI_WAVE_MODE_REPEAT same as \fBwave_send_repeat\fP. + +.br + +.br +PI_WAVE_MODE_ONE_SHOT_SYNC same as \fBwave_send_once\fP but tries +to sync with the previous waveform. + +.br + +.br +PI_WAVE_MODE_REPEAT_SYNC same as \fBwave_send_repeat\fP but tries +to sync with the previous waveform. + +.br + +.br +WARNING: bad things may happen if you delete the previous +waveform before it has been synced to the new waveform. + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. + +.IP "\fBint wave_chain(int pi, char *buf, unsigned bufSize)\fP" +.IP "" 4 +This function transmits a chain of waveforms. + +.br + +.br +NOTE: Any hardware PWM started by \fBhardware_PWM\fP will be cancelled. + +.br + +.br +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of \fBwave_id\fPs and optional command +codes and related data. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + buf: pointer to the wave_ids and optional command codes +.br +bufSize: the number of bytes in buf +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +.br + +.br +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +.br + +.br +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +.br + +.br +Delays between waves may be added with the delay command. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +Loop Start 255 0 Identify start of a wave block +.br +Loop Repeat 255 1 x y loop x + y*256 times +.br +Delay 255 2 x y delay x + y*256 microseconds +.br +Loop Forever 255 3 loop forever +.br + +.br + +.br +If present Loop Forever must be the last entry in the chain. + +.br + +.br +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +#define WAVES 5 +.br +#define GPIO 4 +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int i, pi, wid[WAVES]; +.br + +.br + pi = pigpio_start(0, 0); +.br + if (pi<0) return -1; +.br + +.br + set_mode(pi, GPIO, PI_OUTPUT); +.br + +.br + for (i=0; i=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns the waveform id or one of the following special values: + +.br + +.br +PI_WAVE_NOT_FOUND (9998) - transmitted wave not found. +.br +PI_NO_TX_WAVE (9999) - no wave being transmitted. + +.IP "\fBint wave_tx_busy(int pi)\fP" +.IP "" 4 +This function checks to see if a waveform is currently being +transmitted. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns 1 if a waveform is currently being transmitted, otherwise 0. + +.IP "\fBint wave_tx_stop(int pi)\fP" +.IP "" 4 +This function stops the transmission of the current waveform. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.br + +.br +Returns 0 if OK. + +.br + +.br +This function is intended to stop a waveform started with the repeat mode. + +.IP "\fBint wave_get_micros(int pi)\fP" +.IP "" 4 +This function returns the length in microseconds of the current +waveform. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_high_micros(int pi)\fP" +.IP "" 4 +This function returns the length in microseconds of the longest waveform +created since the pigpio daemon was started. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_max_micros(int pi)\fP" +.IP "" 4 +This function returns the maximum possible size of a waveform in +.br +microseconds. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_pulses(int pi)\fP" +.IP "" 4 +This function returns the length in pulses of the current waveform. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_high_pulses(int pi)\fP" +.IP "" 4 +This function returns the length in pulses of the longest waveform +created since the pigpio daemon was started. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_max_pulses(int pi)\fP" +.IP "" 4 +This function returns the maximum possible size of a waveform in pulses. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_cbs(int pi)\fP" +.IP "" 4 +This function returns the length in DMA control blocks of the current +waveform. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_high_cbs(int pi)\fP" +.IP "" 4 +This function returns the length in DMA control blocks of the longest +waveform created since the pigpio daemon was started. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint wave_get_max_cbs(int pi)\fP" +.IP "" 4 +This function returns the maximum possible size of a waveform in DMA +control blocks. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br + +.EE + +.IP "\fBint gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, unsigned level)\fP" +.IP "" 4 +This function sends a trigger pulse to a GPIO. The GPIO is set to +level for pulseLen microseconds and then reset to not level. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + pulseLen: 1-100. +.br + level: 0,1. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, +PI_BAD_PULSELEN, or PI_NOT_PERMITTED. + +.IP "\fBint store_script(int pi, char *script)\fP" +.IP "" 4 +This function stores a script for later execution. + +.br + +.br +See \fBhttp://abyz.me.uk/rpi/pigpio/pigs.html#Scripts\fP for details. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script: the text of the script. +.br + +.EE + +.br + +.br +The function returns a script id if the script is valid, +otherwise PI_BAD_SCRIPT. + +.IP "\fBint run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)\fP" +.IP "" 4 +This function runs a stored script. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script_id: >=0, as returned by \fBstore_script\fP. +.br + numPar: 0-10, the number of parameters. +.br + param: an array of parameters. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param)\fP" +.IP "" 4 +This function sets the parameters of a script. The script may or +may not be running. The first numPar parameters of the script are +overwritten with the new values. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script_id: >=0, as returned by \fBstore_script\fP. +.br + numPar: 0-10, the number of parameters. +.br + param: an array of parameters. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +.br + +.br +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. + +.IP "\fBint script_status(int pi, unsigned script_id, uint32_t *param)\fP" +.IP "" 4 +This function returns the run status of a stored script as well +as the current values of parameters 0 to 9. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script_id: >=0, as returned by \fBstore_script\fP. +.br + param: an array to hold the returned 10 parameters. +.br + +.EE + +.br + +.br +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +.br + +.br +The run status may be + +.br + +.br + +.EX +PI_SCRIPT_INITING +.br +PI_SCRIPT_HALTED +.br +PI_SCRIPT_RUNNING +.br +PI_SCRIPT_WAITING +.br +PI_SCRIPT_FAILED +.br + +.EE + +.br + +.br +The current value of script parameters 0 to 9 are returned in param. + +.IP "\fBint stop_script(int pi, unsigned script_id)\fP" +.IP "" 4 +This function stops a running script. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script_id: >=0, as returned by \fBstore_script\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint delete_script(int pi, unsigned script_id)\fP" +.IP "" 4 +This function deletes a stored script. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +script_id: >=0, as returned by \fBstore_script\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. + +.IP "\fBint bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits)\fP" +.IP "" 4 +This function opens a GPIO for bit bang reading of serial data. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + baud: 50-250000 +.br +data_bits: 1-32 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, +or PI_GPIO_IN_USE. + +.br + +.br +The serial data is returned in a cyclic buffer and is read using +bb_serial_read. + +.br + +.br +It is the caller's responsibility to read data from the cyclic buffer +in a timely fashion. + +.IP "\fBint bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize)\fP" +.IP "" 4 +This function copies up to bufSize bytes of data read from the +bit bang serial cyclic buffer to the buffer starting at buf. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + buf: an array to receive the read bytes. +.br + bufSize: >=0 +.br + +.EE + +.br + +.br +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +.br + +.br +The bytes returned for each character depend upon the number of +data bits \fBdata_bits\fP specified in the \fBbb_serial_read_open\fP command. + +.br + +.br +For \fBdata_bits\fP 1-8 there will be one byte per character. +.br +For \fBdata_bits\fP 9-16 there will be two bytes per character. +.br +For \fBdata_bits\fP 17-32 there will be four bytes per character. + +.IP "\fBint bb_serial_read_close(int pi, unsigned user_gpio)\fP" +.IP "" 4 +This function closes a GPIO for bit bang reading of serial data. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. + +.IP "\fBint bb_serial_invert(int pi, unsigned user_gpio, unsigned invert)\fP" +.IP "" 4 +This function inverts serial logic for big bang serial reads. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31, previously opened with \fBbb_serial_read_open\fP. +.br + invert: 0-1, 1 invert, 0 normal. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT. + +.IP "\fBint i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags)\fP" +.IP "" 4 +This returns a handle for the device at address i2c_addr on bus i2c_bus. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + i2c_bus: >=0. +.br + i2c_addr: 0-0x7F. +.br +i2c_flags: 0. +.br + +.EE + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.br + +.br +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + SDA SCL +.br +I2C 0 0 1 +.br +I2C 1 2 3 +.br + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +.br + +.br +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +.br + +.br + +.EX +S (1 bit) : Start bit +.br +P (1 bit) : Stop bit +.br +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +.br +A, NA (1 bit) : Accept and not accept bit. +.br +.br +.br +Addr (7 bits): I2C 7 bit address. +.br +i2c_reg (8 bits): A byte which often selects a register. +.br +Data (8 bits): A data byte. +.br +Count (8 bits): A byte defining the length of a block operation. +.br + +.br +[..]: Data sent by the device. +.br + +.EE + +.IP "\fBint i2c_close(int pi, unsigned handle)\fP" +.IP "" 4 +This closes the I2C device associated with the handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint i2c_write_quick(int pi, unsigned handle, unsigned bit)\fP" +.IP "" 4 +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + bit: 0-1, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Quick command. SMBus 2.0 5.5.1 + +.EX +S Addr bit [A] P +.br + +.EE + +.IP "\fBint i2c_write_byte(int pi, unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This sends a single byte to the device associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + bVal: 0-0xFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Send byte. SMBus 2.0 5.5.2 + +.EX +S Addr Wr [A] bVal [A] P +.br + +.EE + +.IP "\fBint i2c_read_byte(int pi, unsigned handle)\fP" +.IP "" 4 +This reads a single byte from the device associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +.br + +.br +Receive byte. SMBus 2.0 5.5.3 + +.EX +S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2c_write_byte_data(int pi, unsigned handle, unsigned i2c_reg, unsigned bVal)\fP" +.IP "" 4 +This writes a single byte to the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + bVal: 0-0xFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write byte. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] i2c_reg [A] bVal [A] P +.br + +.EE + +.IP "\fBint i2c_write_word_data(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal)\fP" +.IP "" 4 +This writes a single 16 bit word to the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + wVal: 0-0xFFFF, the value to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Write word. SMBus 2.0 5.5.4 + +.EX +S Addr Wr [A] i2c_reg [A] wval_Low [A] wVal_High [A] P +.br + +.EE + +.IP "\fBint i2c_read_byte_data(int pi, unsigned handle, unsigned i2c_reg)\fP" +.IP "" 4 +This reads a single byte from the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + +.EE + +.br + +.br +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read byte. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] i2c_reg [A] S Addr Rd [A] [Data] NA P +.br + +.EE + +.IP "\fBint i2c_read_word_data(int pi, unsigned handle, unsigned i2c_reg)\fP" +.IP "" 4 +This reads a single 16 bit word from the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Read word. SMBus 2.0 5.5.5 + +.EX +S Addr Wr [A] i2c_reg [A] +.br + S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2c_process_call(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal)\fP" +.IP "" 4 +This writes 16 bits of data to the specified register of the device +associated with handle and and reads 16 bits of data in return. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write/read. +.br + wVal: 0-0xFFFF, the value to write. +.br + +.EE + +.br + +.br +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Process call. SMBus 2.0 5.5.6 + +.EX +S Addr Wr [A] i2c_reg [A] wVal_Low [A] wVal_High [A] +.br + S Addr Rd [A] [DataLow] A [DataHigh] NA P +.br + +.EE + +.IP "\fBint i2c_write_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes up to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + buf: an array with the data to send. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br +Block write. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] buf1 [A] ... +.br + [A] bufn [A] P +.br + +.EE + +.IP "\fBint i2c_read_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf)\fP" +.IP "" 4 +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + buf: an array to receive the read data. +.br + +.EE + +.br + +.br +The amount of returned data is set by the device. + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +Block read. SMBus 2.0 5.5.7 + +.EX +S Addr Wr [A] i2c_reg [A] +.br + S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2c_block_process_call(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write/read. +.br + buf: an array with the data to send and to receive the read data. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br +The smbus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +.br + +.br +Block write-block read. SMBus 2.0 5.5.8 + +.EX +S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] ... +.br + S Addr Rd [A] [Count] A [Data] ... A P +.br + +.EE + +.IP "\fBint i2c_read_i2c_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to read. +.br + buf: an array to receive the read data. +.br + count: 1-32, the number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] i2c_reg [A] +.br + S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2c_write_i2c_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count)\fP" +.IP "" 4 +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0, as returned by a call to \fBi2c_open\fP. +.br +i2c_reg: 0-255, the register to write. +.br + buf: the data to write. +.br + count: 1-32, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] i2c_reg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +.br + +.EE + +.IP "\fBint i2c_read_device(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This reads count bytes from the raw device into buf. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + buf: an array to receive the read data bytes. +.br + count: >0, the number of bytes to read. +.br + +.EE + +.br + +.br +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. + +.br + +.br + +.EX +S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +.br + +.EE + +.IP "\fBint i2c_write_device(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This writes count bytes from buf to the raw device. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2c_open\fP. +.br + buf: an array containing the data bytes to write. +.br + count: >0, the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +.br + +.br + +.EX +S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +.br + +.EE + +.IP "\fBint i2c_zip(int pi, unsigned handle, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBi2cOpen\fP +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +On 2 Switch combined flag on +.br +Off 3 Switch combined flag off +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53, write 0x32, read 6 bytes +.br +Set address 0x1E, write 0x03, read 6 bytes +.br +Set address 0x68, write 0x1B, read 8 bytes +.br +End +.br + +.br +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +.br +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +.br +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +.br +0x00 +.br + +.EE + +.br + +.br + +.IP "\fBint bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud)\fP" +.IP "" 4 +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +.br + +.br +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +.br + +.br +o baud rates as low as 50 +.br +o repeated starts +.br +o clock stretching +.br +o I2C on any pair of spare GPIO + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + SDA: 0-31 +.br + SCL: 0-31 +.br +baud: 50-500000 +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +.br + +.br +NOTE: + +.br + +.br +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. + +.IP "\fBint bb_i2c_close(int pi, unsigned SDA)\fP" +.IP "" 4 +This function stops bit banging I2C on a pair of GPIO previously +opened with \fBbb_i2c_open\fP. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +SDA: 0-31, the SDA GPIO used in a prior call to \fBbb_i2c_open\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. + +.IP "\fBint bb_i2c_zip(int pi, unsigned SDA, char *inBuf, unsigned inLen, char *outBuf, unsigned outLen)\fP" +.IP "" 4 +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + SDA: 0-31 (as used in a prior call to \fBbb_i2c_open\fP) +.br + inBuf: pointer to the concatenated I2C commands, see below +.br + inLen: size of command buffer +.br +outBuf: pointer to buffer to hold returned data +.br +outLen: size of output buffer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +.br + +.br +The following command codes are supported: + +.br + +.br +Name Cmd & Data Meaning +.br +End 0 No more commands +.br +Escape 1 Next P is two bytes +.br +Start 2 Start condition +.br +Stop 3 Stop condition +.br +Address 4 P Set I2C address to P +.br +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +.br +Read 6 P Read P bytes of data +.br +Write 7 P ... Write P bytes of data +.br + +.br + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br + +.br +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +.br + +.br +No flags are currently defined. + +.br + +.br +The returned I2C data is stored in consecutive locations of outBuf. + +.br + +.br +\fBExample\fP +.br + +.EX +Set address 0x53 +.br +start, write 0x32, (re)start, read 6 bytes, stop +.br +Set address 0x1E +.br +start, write 0x03, (re)start, read 6 bytes, stop +.br +Set address 0x68 +.br +start, write 0x1B, (re)start, read 8 bytes, stop +.br +End +.br + +.br +0x04 0x53 +.br +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x1E +.br +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x68 +.br +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 +.br + +.br +0x00 +.br + +.EE + +.IP "\fBint bb_spi_open(int pi, unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, unsigned baud, unsigned spi_flags)\fP" +.IP "" 4 +This function selects a set of GPIO for bit banging SPI at a +specified baud rate. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + CS: 0-31 +.br + MISO: 0-31 +.br + MOSI: 0-31 +.br + SCLK: 0-31 +.br + baud: 50-250000 +.br +spi_flags: see below +.br + +.EE + +.br + +.br +spi_flags consists of the least significant 22 bits. + +.br + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m +.br + +.EE + +.br + +.br +mm defines the SPI mode, defaults to 0 + +.br + +.br + +.EX +Mode CPOL CPHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br + +.br +p is 0 if CS is active low (default) and 1 for active high. + +.br + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. + +.br + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. + +.br + +.br +The other bits in flags should be set to zero. + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or +PI_GPIO_IN_USE. + +.br + +.br +If more than one device is connected to the SPI bus (defined by +SCLK, MOSI, and MISO) each must have its own CS. + +.br + +.br +\fBExample\fP +.br + +.EX +bb_spi_open(pi,10, MISO, MOSI, SCLK, 10000, 0); // device 1 +.br +bb_spi_open(pi,11, MISO, MOSI, SCLK, 20000, 3); // device 2 +.br + +.EE + +.IP "\fBint bb_spi_close(int pi, unsigned CS)\fP" +.IP "" 4 +This function stops bit banging SPI on a set of GPIO +opened with \fBbbSPIOpen\fP. + +.br + +.br + +.EX +pi: >=0 (as returned by \fBpigpio_start\fP). +.br +CS: 0-31, the CS GPIO used in a prior call to \fBbb_spi_open\fP +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO. + +.IP "\fBint bb_spi_xfer(int pi, unsigned CS, char *txBuf, char *rxBuf, unsigned count)\fP" +.IP "" 4 +This function executes a bit banged SPI transfer. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + CS: 0-31 (as used in a prior call to \fBbb_spi_open\fP) +.br +txBuf: pointer to buffer to hold data to be sent +.br +rxBuf: pointer to buffer to hold returned data +.br +count: size of data transfer +.br + +.EE + +.br + +.br +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER. + +.br + +.br +\fBExample\fP +.br + +.EX +// gcc -Wall -pthread -o bb_spi_x_test bb_spi_x_test.c -lpigpiod_if2 +.br +// ./bb_spi_x_test +.br + +.br +#include +.br + +.br +#include "pigpiod_if2.h" +.br + +.br +#define CE0 5 +.br +#define CE1 6 +.br +#define MISO 13 +.br +#define MOSI 19 +.br +#define SCLK 12 +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int i, pi, count, set_val, read_val; +.br + unsigned char inBuf[3]; +.br + char cmd1[] = {0, 0}; +.br + char cmd2[] = {12, 0}; +.br + char cmd3[] = {1, 128, 0}; +.br + +.br + if ((pi = pigpio_start(0, 0)) < 0) +.br + { +.br + fprintf(stderr, "pigpio initialisation failed (%d).\n", pi); +.br + return 1; +.br + } +.br + +.br + bb_spi_open(pi, CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC +.br + bb_spi_open(pi, CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC +.br + +.br + for (i=0; i<256; i++) +.br + { +.br + cmd1[1] = i; +.br + +.br + count = bb_spi_xfer(pi, CE0, cmd1, (char *)inBuf, 2); // > DAC +.br + +.br + if (count == 2) +.br + { +.br + count = bb_spi_xfer(pi, CE0, cmd2, (char *)inBuf, 2); // < DAC +.br + +.br + if (count == 2) +.br + { +.br + set_val = inBuf[1]; +.br + +.br + count = bb_spi_xfer(pi, CE1, cmd3, (char *)inBuf, 3); // < ADC +.br + +.br + if (count == 3) +.br + { +.br + read_val = ((inBuf[1]&3)<<8) | inBuf[2]; +.br + printf("%d %d\n", set_val, read_val); +.br + } +.br + } +.br + } +.br + } +.br + +.br + bb_spi_close(pi, CE0); +.br + bb_spi_close(pi, CE1); +.br + +.br + pigpio_stop(pi); +.br +} +.br + +.EE + +.IP "\fBint spi_open(int pi, unsigned spi_channel, unsigned baud, unsigned spi_flags)\fP" +.IP "" 4 +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +.br + +.br +The Pi has two SPI peripherals: main and auxiliary. + +.br + +.br +The main SPI has two chip selects (channels), the auxiliary has +three. + +.br + +.br +The auxiliary SPI is available on all models but the A and B. + +.br + +.br +The GPIO used are given in the following table. + +.br + +.br + MISO MOSI SCLK CE0 CE1 CE2 +.br +Main SPI 9 10 11 8 7 - +.br +Aux SPI 19 20 21 18 17 16 +.br + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +spi_channel: 0-1 (0-2 for the auxiliary SPI). +.br + baud: 32K-125M (values above 30M are unlikely to work). +.br + spi_flags: see below. +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +.br + +.br +spi_flags consists of the least significant 22 bits. + +.br + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +.br + +.EE + +.br + +.br +mm defines the SPI mode. + +.br + +.br +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +.br + +.br + +.EX +Mode POL PHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br + +.br +px is 0 if CEx is active low (default) and 1 for active high. + +.br + +.br +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +.br + +.br +A is 0 for the main SPI, 1 for the auxiliary SPI. + +.br + +.br +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +.br + +.br +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +.br + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +.br + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +.br + +.br +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +.br + +.br +The \fBspi_read\fP, \fBspi_write\fP, and \fBspi_xfer\fP functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +.br + +.br +For bits 1-8 there will be one byte per character. +.br +For bits 9-16 there will be two bytes per character. +.br +For bits 17-32 there will be four bytes per character. + +.br + +.br +Multi-byte transfers are made in least significant byte first order. + +.br + +.br +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +.br + +.br +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +.br + +.br +The other bits in flags should be set to zero. + +.IP "\fBint spi_close(int pi, unsigned handle)\fP" +.IP "" 4 +This functions closes the SPI device identified by the handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint spi_read(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads count bytes of data from the SPI +device associated with the handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + buf: an array to receive the read data bytes. +.br + count: the number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spi_write(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + buf: the data bytes to write. +.br + count: the number of bytes to write. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint spi_xfer(int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count)\fP" +.IP "" 4 +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBspi_open\fP. +.br + txBuf: the data bytes to write. +.br + rxBuf: the received data bytes. +.br + count: the number of bytes to transfer. +.br + +.EE + +.br + +.br +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. + +.IP "\fBint serial_open(int pi, char *ser_tty, unsigned baud, unsigned ser_flags)\fP" +.IP "" 4 +This function opens a serial device at a specified baud rate +with specified flags. The device name must start with +/dev/tty or /dev/serial. + +.br + +.br + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + ser_tty: the serial device to open. +.br + baud: the baud rate in bits per second, see below. +.br +ser_flags: 0. +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +.br + +.br +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +.br + +.br +No flags are currently defined. This parameter should be set to zero. + +.IP "\fBint serial_close(int pi, unsigned handle)\fP" +.IP "" 4 +This function closes the serial device associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.IP "\fBint serial_write_byte(int pi, unsigned handle, unsigned bVal)\fP" +.IP "" 4 +This function writes bVal to the serial port associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serial_read_byte(int pi, unsigned handle)\fP" +.IP "" 4 +This function reads a byte from the serial port associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +.br + +.br +If no data is ready PI_SER_READ_NO_DATA is returned. + +.IP "\fBint serial_write(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes from buf to the the serial port +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + buf: the array of bytes to write. +.br + count: the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. + +.IP "\fBint serial_read(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads up to count bytes from the the serial port +associated with handle and writes them to buf. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + buf: an array to receive the read data. +.br + count: the maximum number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED. + +.br + +.br +If no data is ready zero is returned. + +.IP "\fBint serial_data_available(int pi, unsigned handle)\fP" +.IP "" 4 +Returns the number of bytes available to be read from the +device associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0, as returned by a call to \fBserial_open\fP. +.br + +.EE + +.br + +.br +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. + +.IP "\fBint custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned argc)\fP" +.IP "" 4 +This function is available for user customisation. + +.br + +.br +It returns a single integer value. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +arg1: >=0 +.br +arg2: >=0 +.br +argx: extra (byte) arguments +.br +argc: number of extra arguments +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.IP "\fBint custom_2(int pi, unsigned arg1, char *argx, unsigned argc, char *retBuf, unsigned retMax)\fP" +.IP "" 4 +This function is available for user customisation. + +.br + +.br +It differs from custom_1 in that it returns an array of bytes +rather than just an integer. + +.br + +.br +The return value is an integer indicating the number of returned bytes. + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + arg1: >=0 +.br + argc: extra (byte) arguments +.br + count: number of extra arguments +.br +retBuf: buffer for returned data +.br +retMax: maximum number of bytes to return +.br + +.EE + +.br + +.br +Returns >= 0 if OK, less than 0 indicates a user defined error. + +.br + +.br +Note, the number of returned bytes will be retMax or less. + +.IP "\fBint get_pad_strength(int pi, unsigned pad)\fP" +.IP "" 4 +This function returns the pad drive strength in mA. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +pad: 0-2, the pad to get. +.br + +.EE + +.br + +.br +Returns the pad drive strength if OK, otherwise PI_BAD_PAD. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +strength = get_pad_strength(pi, 0); // get pad 0 strength +.br + +.EE + +.IP "\fBint set_pad_strength(int pi, unsigned pad, unsigned padStrength)\fP" +.IP "" 4 +This function sets the pad drive strength in mA. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + pad: 0-2, the pad to set. +.br +padStrength: 1-16 mA. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +set_pad_strength(pi, 0, 10); // set pad 0 strength to 10 mA +.br + +.EE + +.IP "\fBint shell_(int pi, char *scriptName, char *scriptString)\fP" +.IP "" 4 +This function uses the system call to execute a shell script +with the given string as its parameter. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + scriptName: the name of the script, only alphanumeric characters, +.br + '-' and '_' are allowed in the name. +.br +scriptString: the string to pass to the script. +.br + +.EE + +.br + +.br +The exit status of the system call is returned if OK, otherwise +PI_BAD_SHELL_STATUS. + +.br + +.br +scriptName must exist in /opt/pigpio/cgi and must be executable. + +.br + +.br +The returned exit status is normally 256 times that set by the +shell script exit function. If the script can't be found 32512 will +be returned. + +.br + +.br +The following table gives some example returned statuses. + +.br + +.br +Script exit status Returned system call status +.br +1 256 +.br +5 1280 +.br +10 2560 +.br +200 51200 +.br +script not found 32512 +.br + +.br + +.br +\fBExample\fP +.br + +.EX +// pass two parameters, hello and world +.br +status = shell_(pi, "scr1", "hello world"); +.br + +.br +// pass three parameters, hello, string with spaces, and world +.br +status = shell_(pi, "scr1", "hello 'string with spaces' world"); +.br + +.br +// pass one parameter, hello string with spaces world +.br +status = shell_(pi, "scr1", "\"hello string with spaces world\""); +.br + +.EE + +.IP "\fBint file_open(int pi, char *file, unsigned mode)\fP" +.IP "" 4 +This function returns a handle to a file opened in a specified mode. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +file: the file to open. +.br +mode: the file open mode. +.br + +.EE + +.br + +.br +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS, +PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR. + +.br + +.br +File + +.br + +.br +A file may only be opened if permission is granted by an entry in +/opt/pigpio/access. This is intended to allow remote access to files +in a more or less controlled manner. + +.br + +.br +Each entry in /opt/pigpio/access takes the form of a file path +which may contain wildcards followed by a single letter permission. +The permission may be R for read, W for write, U for read/write, +and N for no access. + +.br + +.br +Where more than one entry matches a file the most specific rule +applies. If no entry matches a file then access is denied. + +.br + +.br +Suppose /opt/pigpio/access contains the following entries + +.br + +.br + +.EX +/home/* n +.br +/home/pi/shared/dir_1/* w +.br +/home/pi/shared/dir_2/* r +.br +/home/pi/shared/dir_3/* u +.br +/home/pi/shared/dir_1/file.txt n +.br + +.EE + +.br + +.br +Files may be written in directory dir_1 with the exception +of file.txt. + +.br + +.br +Files may be read in directory dir_2. + +.br + +.br +Files may be read and written in directory dir_3. + +.br + +.br +If a directory allows read, write, or read/write access then files may +be created in that directory. + +.br + +.br +In an attempt to prevent risky permissions the following paths are +ignored in /opt/pigpio/access. + +.br + +.br + +.EX +a path containing .. +.br +a path containing only wildcards (*?) +.br +a path containing less than two non-wildcard parts +.br + +.EE + +.br + +.br +Mode + +.br + +.br +The mode may have the following values. + +.br + +.br +Macro Value Meaning +.br +PI_FILE_READ 1 open file for reading +.br +PI_FILE_WRITE 2 open file for writing +.br +PI_FILE_RW 3 open file for reading and writing +.br + +.br + +.br +The following values may be or'd into the mode. + +.br + +.br +Macro Value Meaning +.br +PI_FILE_APPEND 4 Writes append data to the end of the file +.br +PI_FILE_CREATE 8 The file is created if it doesn't exist +.br +PI_FILE_TRUNC 16 The file is truncated +.br + +.br + +.br +Newly created files are owned by root with permissions owner read and write. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int pi, handle, c; +.br + char buf[60000]; +.br + +.br + pi = pigpio_start(NULL, NULL); +.br + +.br + if (pi < 0) return 1; +.br + +.br + // assumes /opt/pigpio/access contains the following line +.br + // /ram/*.c r +.br + +.br + handle = file_open(pi, "/ram/pigpio.c", PI_FILE_READ); +.br + +.br + if (handle >= 0) +.br + { +.br + while ((c=file_read(pi, handle, buf, sizeof(buf)-1))) +.br + { +.br + buf[c] = 0; +.br + printf("%s", buf); +.br + } +.br + +.br + file_close(pi, handle); +.br + } +.br + +.br + pigpio_stop(pi); +.br +} +.br + +.EE + +.IP "\fBint file_close(int pi, unsigned handle)\fP" +.IP "" 4 +This function closes the file associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0 (as returned by \fBfile_open\fP). +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +.br + +.br +\fBExample\fP +.br + +.EX +file_close(pi, handle); +.br + +.EE + +.IP "\fBint file_write(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function writes count bytes from buf to the the file +associated with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0 (as returned by \fBfile_open\fP). +.br + buf: the array of bytes to write. +.br + count: the number of bytes to write. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, +PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE. + +.br + +.br +\fBExample\fP +.br + +.EX +if (file_write(pi, handle, buf, 100) == 0) +.br +{ +.br + // file written okay +.br +} +.br +else +.br +{ +.br + // error +.br +} +.br + +.EE + +.IP "\fBint file_read(int pi, unsigned handle, char *buf, unsigned count)\fP" +.IP "" 4 +This function reads up to count bytes from the the file +associated with handle and writes them to buf. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +handle: >=0 (as returned by \fBfile_open\fP). +.br + buf: an array to receive the read data. +.br + count: the maximum number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE. + +.br + +.br +\fBExample\fP +.br + +.EX + bytes = file_read(pi, handle, buf, sizeof(buf)); +.br + +.br + if (bytes >= 0) +.br + { +.br + // process read data +.br + } +.br + +.EE + +.IP "\fBint file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom)\fP" +.IP "" 4 +This function seeks to a position within the file associated +with handle. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + handle: >=0 (as returned by \fBfile_open\fP). +.br +seekOffset: the number of bytes to move. Positive offsets +.br + move forward, negative offsets backwards. +.br + seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1), +.br + or PI_FROM_END (2). +.br + +.EE + +.br + +.br +Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK. + +.br + +.br +\fBExample\fP +.br + +.EX +file_seek(pi, handle, 123, PI_FROM_START); // Start plus 123 +.br + +.br +size = file_seek(pi, handle, 0, PI_FROM_END); // End, return size +.br + +.br +pos = file_seek(pi, handle, 0, PI_FROM_CURRENT); // Current position +.br + +.EE + +.IP "\fBint file_list(int pi, char *fpat, char *buf, unsigned count)\fP" +.IP "" 4 +This function returns a list of files which match a pattern. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + fpat: file pattern to match. +.br + buf: an array to receive the matching file names. +.br +count: the maximum number of bytes to read. +.br + +.EE + +.br + +.br +Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS, +or PI_NO_FILE_MATCH. + +.br + +.br +The pattern must match an entry in /opt/pigpio/access. The pattern +may contain wildcards. See \fBfile_open\fP. + +.br + +.br +NOTE + +.br + +.br +The returned value is not the number of files, it is the number +of bytes in the buffer. The file names are separated by newline +characters. + +.br + +.br +\fBExample\fP +.br + +.EX +#include +.br +#include +.br + +.br +int main(int argc, char *argv[]) +.br +{ +.br + int pi, handle, c; +.br + char buf[60000]; +.br + +.br + pi = pigpio_start(NULL, NULL); +.br + +.br + if (pi < 0) return 1; +.br + +.br + // assumes /opt/pigpio/access contains the following line +.br + // /ram/*.c r +.br + +.br + c = file_list(pi, "/ram/p*.c", buf, sizeof(buf)); +.br + +.br + if (c >= 0) +.br + { +.br + buf[c] = 0; +.br + printf("%s", buf); +.br + } +.br + +.br + pigpio_stop(pi); +.br +} +.br + +.EE + +.IP "\fBint callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f)\fP" +.IP "" 4 +This function initialises a new callback. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + f: the callback function. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the GPIO, edge, and tick, whenever the +GPIO has the identified edge. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +edge 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.EE + +.IP "\fBint callback_ex(int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata)\fP" +.IP "" 4 +This function initialises a new callback. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + f: the callback function. +.br + userdata: a pointer to arbitrary user data. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the GPIO, edge, tick, and the userdata +pointer, whenever the GPIO has the identified edge. + +.br + +.br + +.EX +Parameter Value Meaning +.br + +.br +GPIO 0-31 The GPIO which has changed state +.br + +.br +edge 0-2 0 = change to low (a falling edge) +.br + 1 = change to high (a rising edge) +.br + 2 = no level change (a watchdog timeout) +.br + +.br +tick 32 bit The number of microseconds since boot +.br + WARNING: this wraps around from +.br + 4294967295 to 0 roughly every 72 minutes +.br + +.br +userdata pointer Pointer to an arbitrary object +.br + +.EE + +.IP "\fBint callback_cancel(unsigned callback_id)\fP" +.IP "" 4 +This function cancels a callback identified by its id. + +.br + +.br + +.EX +callback_id: >=0, as returned by a call to \fBcallback\fP or \fBcallback_ex\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise pigif_callback_not_found. + +.IP "\fBint wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout)\fP" +.IP "" 4 +This function waits for an edge on the GPIO for up to timeout +seconds. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +user_gpio: 0-31. +.br + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. +.br + timeout: >=0. +.br + +.EE + +.br + +.br +The function returns when the edge occurs or after the timeout. + +.br + +.br +Do not use this function for precise timing purposes, +the edge is only checked 20 times a second. Whenever +you need to know the accurate time of GPIO events use +a \fBcallback\fP function. + +.br + +.br +The function returns 1 if the edge occurred, otherwise 0. + +.IP "\fBint bsc_xfer(int pi, bsc_xfer_t *bscxfer)\fP" +.IP "" 4 +This function provides a low-level interface to the +SPI/I2C Slave peripheral. This peripheral allows the +Pi to act as a slave device on an I2C or SPI bus. + +.br + +.br +I can't get SPI to work properly. I tried with a +control word of 0x303 and swapped MISO and MOSI. + +.br + +.br +The function sets the BSC mode, writes any data in +the transmit buffer to the BSC transmit FIFO, and +copies any data in the BSC receive FIFO to the +receive buffer. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +bscxfer: a structure defining the transfer. +.br + +.br +typedef struct +.br +{ +.br + uint32_t control; // Write +.br + int rxCnt; // Read only +.br + char rxBuf[BSC_FIFO_SIZE]; // Read only +.br + int txCnt; // Write +.br + char txBuf[BSC_FIFO_SIZE]; // Write +.br +} bsc_xfer_t; +.br + +.EE + +.br + +.br +To start a transfer set control (see below) and copy the bytes to +be sent (if any) to txBuf and set the byte count in txCnt. + +.br + +.br +Upon return rxCnt will be set to the number of received bytes placed +in rxBuf. + +.br + +.br +The returned function value is the status of the transfer (see below). + +.br + +.br +If there was an error the status will be less than zero +(and will contain the error code). + +.br + +.br +The most significant word of the returned status contains the number +of bytes actually copied from txBuf to the BSC transmit FIFO (may be +less than requested if the FIFO already contained untransmitted data). + +.br + +.br +Note that the control word sets the BSC mode. The BSC will stay in +that mode until a different control word is sent. + +.br + +.br +The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode +and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You +need to swap MISO/MOSI between master and slave. + +.br + +.br +When a zero control word is received GPIO 18-21 will be reset +to INPUT mode. + +.br + +.br +control consists of the following bits. + +.br + +.br + +.EX +22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN +.br + +.EE + +.br + +.br +Bits 0-13 are copied unchanged to the BSC CR register. See +pages 163-165 of the Broadcom peripherals document for full +details. + +.br + +.br +aaaaaaa defines the I2C slave address (only relevant in I2C mode) +.br +IT invert transmit status flags +.br +HC enable host control +.br +TF enable test FIFO +.br +IR invert receive status flags +.br +RE enable receive +.br +TE enable transmit +.br +BK abort operation and clear FIFOs +.br +EC send control register as first I2C byte +.br +ES send status register as first I2C byte +.br +PL set SPI polarity high +.br +PH set SPI phase high +.br +I2 enable I2C mode +.br +SP enable SPI mode +.br +EN enable BSC peripheral +.br + +.br + +.br +The returned status has the following format + +.br + +.br + +.EX +20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + S S S S S R R R R R T T T T T RB TE RF TF RE TB +.br + +.EE + +.br + +.br +Bits 0-15 are copied unchanged from the BSC FR register. See +pages 165-166 of the Broadcom peripherals document for full +details. + +.br + +.br +SSSSS number of bytes successfully copied to transmit FIFO +.br +RRRRR number of bytes in receieve FIFO +.br +TTTTT number of bytes in transmit FIFO +.br +RB receive busy +.br +TE transmit FIFO empty +.br +RF receive FIFO full +.br +TF transmit FIFO full +.br +RE receive FIFO empty +.br +TB transmit busy +.br + +.br + +.br +The following example shows how to configure the BSC peripheral as +an I2C slave with address 0x13 and send four bytes. + +.br + +.br +\fBExample\fP +.br + +.EX +bsc_xfer_t xfer; +.br + +.br +xfer.control = (0x13<<16) | 0x305; +.br + +.br +memcpy(xfer.txBuf, "ABCD", 4); +.br +xfer.txCnt = 4; +.br + +.br +status = bsc_xfer(pi, &xfer); +.br + +.br +if (status >= 0) +.br +{ +.br + // process transfer +.br +} +.br + +.EE + +.IP "\fBint bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer)\fP" +.IP "" 4 +This function allows the Pi to act as a slave I2C device. + +.br + +.br +The data bytes (if any) are written to the BSC transmit +FIFO and the bytes in the BSC receive FIFO are returned. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +i2c_addr: 0-0x7F. +.br + bscxfer: a structure defining the transfer. +.br + +.br +typedef struct +.br +{ +.br + uint32_t control; // N/A +.br + int rxCnt; // Read only +.br + char rxBuf[BSC_FIFO_SIZE]; // Read only +.br + int txCnt; // Write +.br + char txBuf[BSC_FIFO_SIZE]; // Write +.br +} bsc_xfer_t; +.br + +.EE + +.br + +.br +txCnt is set to the number of bytes to be transmitted, possibly +zero. The data itself should be copied to txBuf. + +.br + +.br +Any received data will be written to rxBuf with rxCnt set. + +.br + +.br +See \fBbsc_xfer\fP for details of the returned status value. + +.br + +.br +If there was an error the status will be less than zero +(and will contain the error code). + +.br + +.br +Note that an i2c_address of 0 may be used to close +the BSC device and reassign the used GPIO (18/19) +as inputs. + +.IP "\fBint event_callback(int pi, unsigned event, evtCBFunc_t f)\fP" +.IP "" 4 +This function initialises an event callback. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +event: 0-31. +.br + f: the callback function. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the event id, and tick, whenever the +event occurs. + +.IP "\fBint event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *userdata)\fP" +.IP "" 4 +This function initialises an event callback. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + event: 0-31. +.br + f: the callback function. +.br +userdata: a pointer to arbitrary user data. +.br + +.EE + +.br + +.br +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +.br + +.br +The callback is called with the event id, the tick, and the userdata +pointer whenever the event occurs. + +.IP "\fBint event_callback_cancel(unsigned callback_id)\fP" +.IP "" 4 +This function cancels an event callback identified by its id. + +.br + +.br + +.EX +callback_id: >=0, as returned by a call to \fBevent_callback\fP or +.br +\fBevent_callback_ex\fP. +.br + +.EE + +.br + +.br +The function returns 0 if OK, otherwise pigif_callback_not_found. + +.IP "\fBint wait_for_event(int pi, unsigned event, double timeout)\fP" +.IP "" 4 +This function waits for an event for up to timeout seconds. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br + event: 0-31. +.br +timeout: >=0. +.br + +.EE + +.br + +.br +The function returns when the event occurs or after the timeout. + +.br + +.br +The function returns 1 if the event occurred, otherwise 0. + +.IP "\fBint event_trigger(int pi, unsigned event)\fP" +.IP "" 4 +This function signals the occurrence of an event. + +.br + +.br + +.EX + pi: >=0 (as returned by \fBpigpio_start\fP). +.br +event: 0-31. +.br + +.EE + +.br + +.br +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +.br + +.br +An event is a signal used to inform one or more consumers +to start an action. Each consumer which has registered an interest +in the event (e.g. by calling \fBevent_callback\fP) will be informed by +a callback. + +.br + +.br +One event, PI_EVENT_BSC (31) is predefined. This event is +auto generated on BSC slave activity. + +.br + +.br +The meaning of other events is arbitrary. + +.br + +.br +Note that other than its id and its tick there is no data associated +with an event. +.SH PARAMETERS + +.br + +.br + +.IP "\fBactive\fP: 0-1000000" 0 + +.br + +.br +The number of microseconds level changes are reported for once +a noise filter has been triggered (by \fBsteady\fP microseconds of +a stable level). + +.br + +.br + +.IP "\fB*addrStr\fP" 0 +A string specifying the host or IP address of the Pi running +the pigpio daemon. It may be NULL in which case localhost +is used unless overridden by the PIGPIO_ADDR environment +variable. + +.br + +.br + +.IP "\fBarg1\fP" 0 +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBarg2\fP" 0 +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +.br + +.br + +.IP "\fBargc\fP" 0 +The count of bytes passed to a user customised function. + +.br + +.br + +.IP "\fB*argx\fP" 0 +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +.br + +.br + +.IP "\fBbaud\fP" 0 +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +.br + +.br + +.IP "\fBbit\fP" 0 +A value of 0 or 1. + +.br + +.br + +.IP "\fBbits\fP" 0 +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +.br + +.br +A convenient way to set bit n is to or in (1<=0, as returned by a call to a callback function, one of + +.br + +.br +\fBcallback\fP +.br +\fBcallback_ex\fP +.br +\fBevent_callback\fP +.br +\fBevent_callback_ex\fP + +.br + +.br +The id is passed to \fBcallback_cancel\fP or \fBevent_callback_cancel\fP +to cancel the callback. + +.br + +.br + +.IP "\fBCBFunc_t\fP" 0 + +.EX +typedef void (*CBFunc_t) +.br + (int pi, unsigned user_gpio, unsigned level, uint32_t tick); +.br + +.EE + +.br + +.br + +.IP "\fBCBFuncEx_t\fP" 0 + +.EX +typedef void (*CBFuncEx_t) +.br + (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void * userdata); +.br + +.EE + +.br + +.br + +.IP "\fBchar\fP" 0 +A single character, an 8 bit quantity able to store 0-255. + +.br + +.br + +.IP "\fBclkfreq\fP: 4689-250000000 (250M)" 0 +The hardware clock frequency. + +.br + +.br + +.IP "\fBcount\fP" 0 +The number of bytes to be transferred in a file, I2C, SPI, or serial +command. + +.br + +.br + +.IP "\fBCS\fP" 0 +The GPIO used for the slave select signal when bit banging SPI. + +.br + +.br + +.IP "\fBdata_bits\fP: 1-32" 0 +The number of data bits in each character of serial data. + +.br + +.br + +.EX +#define PI_MIN_WAVE_DATABITS 1 +.br +#define PI_MAX_WAVE_DATABITS 32 +.br + +.EE + +.br + +.br + +.IP "\fBdouble\fP" 0 +A floating point number. + +.br + +.br + +.IP "\fBdutycycle\fP: 0-range" 0 +A number representing the ratio of on time to off time for PWM. + +.br + +.br +The number may vary between 0 and range (default 255) where +0 is off and range is fully on. + +.br + +.br + +.IP "\fBedge\fP" 0 +Used to identify a GPIO level transition of interest. A rising edge is +a level change from 0 to 1. A falling edge is a level change from 1 to 0. + +.br + +.br + +.EX +RISING_EDGE 0 +.br +FALLING_EDGE 1 +.br +EITHER_EDGE. 2 +.br + +.EE + +.br + +.br + +.IP "\fBerrnum\fP" 0 +A negative number indicating a function call failed and the nature +of the error. + +.br + +.br + +.IP "\fBevent\fP: 0-31" 0 +An event is a signal used to inform one or more consumers +to start an action. + +.br + +.br + +.IP "\fBevtCBFunc_t\fP" 0 + +.br + +.br + +.EX +typedef void (*evtCBFunc_t) +.br + (int pi, unsigned event, uint32_t tick); +.br + +.EE + +.br + +.br + +.IP "\fBevtCBFuncEx_t\fP" 0 + +.br + +.br + +.EX +typedef void (*evtCBFuncEx_t) +.br + (int pi, unsigned event, uint32_t tick, void *userdata); +.br + +.EE + +.br + +.br + +.IP "\fBf\fP" 0 +A function. + +.br + +.br + +.IP "\fB*file\fP" 0 +A full file path. To be accessible the path must match an entry in +/opt/pigpio/access. + +.br + +.br + +.IP "\fB*fpat\fP" 0 +A file path which may contain wildcards. To be accessible the path +must match an entry in /opt/pigpio/access. + +.br + +.br + +.IP "\fBfrequency\fP: >=0" 0 +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + +.br + +.br + +.IP "\fBgpio\fP" 0 +A Broadcom numbered GPIO, in the range 0-53. + +.br + +.br +There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through +GPIO53. + +.br + +.br +They are split into two banks. Bank 1 consists of GPIO0 through +GPIO31. Bank 2 consists of GPIO32 through GPIO53. + +.br + +.br +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +.br + +.br +See \fBget_hardware_revision\fP. + +.br + +.br +The user GPIO are marked with an X in the following table. + +.br + +.br + +.EX + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +.br +Type 1 X X - - X - - X X X X X - - X X +.br +Type 2 - - X X X - - X X X X X - - X X +.br +Type 3 X X X X X X X X X X X X X X +.br + +.br + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +.br +Type 1 - X X - - X X X X X - - - - - - +.br +Type 2 - X X - - - X X X X - X X X X X +.br +Type 3 X X X X X X X X X X X X - - - - +.br + +.EE + +.br + +.br + +.IP "\fBgpioPulse_t\fP" 0 + +.EX +typedef struct +.br +{ +.br + uint32_t gpioOn; +.br + uint32_t gpioOff; +.br + uint32_t usDelay; +.br +} gpioPulse_t; +.br + +.EE + +.br + +.br + +.IP "\fBgpioThreadFunc_t\fP" 0 + +.EX +typedef void *(gpioThreadFunc_t) (void *); +.br + +.EE + +.br + +.br + +.IP "\fBhandle\fP: >=0" 0 +A number referencing an object opened by one of + +.br + +.br +\fBfile_open\fP +.br +\fBi2c_open\fP +.br +\fBnotify_open\fP +.br +\fBserial_open\fP +.br +\fBspi_open\fP + +.br + +.br + +.IP "\fBi2c_addr\fP: 0-0x7F" 0 +The address of a device on the I2C bus. + +.br + +.br + +.IP "\fBi2c_bus\fP: >=0" 0 +An I2C bus number. + +.br + +.br + +.IP "\fBi2c_flags\fP: 0" 0 +Flags which modify an I2C open command. None are currently defined. + +.br + +.br + +.IP "\fBi2c_reg\fP: 0-255" 0 +A register of an I2C device. + +.br + +.br + +.IP "\fB*inBuf\fP" 0 +A buffer used to pass data to a function. + +.br + +.br + +.IP "\fBinLen\fP" 0 +The number of bytes of data in a buffer. + +.br + +.br + +.IP "\fBint\fP" 0 +A whole number, negative or positive. + +.br + +.br + +.IP "\fBint32_t\fP" 0 +A 32-bit signed value. + +.br + +.br + +.IP "\fBinvert\fP" 0 +A flag used to set normal or inverted bit bang serial data level logic. + +.br + +.br + +.IP "\fBlevel\fP" 0 +The level of a GPIO. Low or High. + +.br + +.br + +.EX +PI_OFF 0 +.br +PI_ON 1 +.br + +.br +PI_CLEAR 0 +.br +PI_SET 1 +.br + +.br +PI_LOW 0 +.br +PI_HIGH 1 +.br + +.EE + +.br + +.br +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See \fBset_watchdog\fP. + +.br + +.br + +.EX +PI_TIMEOUT 2 +.br + +.EE + +.br + +.br + +.IP "\fBMISO\fP" 0 +The GPIO used for the MISO signal when bit banging SPI. + +.br + +.br + +.IP "\fBmode\fP" 0 +1. The operational mode of a GPIO, normally INPUT or OUTPUT. + +.br + +.br + +.EX +PI_INPUT 0 +.br +PI_OUTPUT 1 +.br +PI_ALT0 4 +.br +PI_ALT1 5 +.br +PI_ALT2 6 +.br +PI_ALT3 7 +.br +PI_ALT4 3 +.br +PI_ALT5 2 +.br + +.EE + +.br + +.br +2. The mode of waveform transmission. + +.br + +.br + +.EX +PI_WAVE_MODE_ONE_SHOT 0 +.br +PI_WAVE_MODE_REPEAT 1 +.br +PI_WAVE_MODE_ONE_SHOT_SYNC 2 +.br +PI_WAVE_MODE_REPEAT_SYNC 3 +.br + +.EE + +.br + +.br +3. A file open mode. + +.br + +.br + +.EX +PI_FILE_READ 1 +.br +PI_FILE_WRITE 2 +.br +PI_FILE_RW 3 +.br + +.EE + +.br + +.br +The following values can be or'd into the mode. + +.br + +.br + +.EX +PI_FILE_APPEND 4 +.br +PI_FILE_CREATE 8 +.br +PI_FILE_TRUNC 16 +.br + +.EE + +.br + +.br + +.IP "\fBMOSI\fP" 0 +The GPIO used for the MOSI signal when bit banging SPI. + +.br + +.br + +.IP "\fBnumBytes\fP" 0 +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +.br + +.br + +.IP "\fBnumPar\fP: 0-10" 0 +The number of parameters passed to a script. + +.br + +.br + +.IP "\fBnumPulses\fP" 0 +The number of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBoffset\fP" 0 +The associated data starts this number of microseconds from the start of +the waveform. + +.br + +.br + +.IP "\fB*outBuf\fP" 0 +A buffer used to return data from a function. + +.br + +.br + +.IP "\fBoutLen\fP" 0 +The size in bytes of an output buffer. + +.br + +.br + +.IP "\fBpad\fP: 0-2" 0 +A set of GPIO which share common drivers. + +.br + +.br +Pad GPIO +.br +0 0-27 +.br +1 28-45 +.br +2 46-53 +.br + +.br + +.br + +.IP "\fBpadStrength\fP: 1-16" 0 +The mA which may be drawn from each GPIO whilst still guaranteeing the +high and low levels. + +.br + +.br + +.IP "\fB*param\fP" 0 +An array of script parameters. + +.br + +.br + +.IP "\fBpi\fP" 0 +An integer defining a connected Pi. The value is returned by +\fBpigpio_start\fP upon success. + +.br + +.br + +.IP "\fB*portStr\fP" 0 +A string specifying the port address used by the Pi running +the pigpio daemon. It may be NULL in which case "8888" +is used unless overridden by the PIGPIO_PORT environment +variable. + +.br + +.br + +.IP "\fB*pth\fP" 0 +A thread identifier, returned by \fBstart_thread\fP. + +.br + +.br + +.br + +.br + +.IP "\fBpthread_t\fP" 0 +A thread identifier. + +.br + +.br + +.IP "\fBpud\fP: 0-2" 0 +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. + +.EX +PI_PUD_OFF 0 +.br +PI_PUD_DOWN 1 +.br +PI_PUD_UP 2 +.br + +.EE + +.br + +.br + +.IP "\fBpulseLen\fP" 0 +1-100, the length of a trigger pulse in microseconds. + +.br + +.br + +.IP "\fB*pulses\fP" 0 +An array of pulses to be added to a waveform. + +.br + +.br + +.IP "\fBpulsewidth\fP: 0, 500-2500" 0 + +.EX +PI_SERVO_OFF 0 +.br +PI_MIN_SERVO_PULSEWIDTH 500 +.br +PI_MAX_SERVO_PULSEWIDTH 2500 +.br + +.EE + +.br + +.br + +.IP "\fBPWMduty\fP: 0-1000000 (1M)" 0 +The hardware PWM dutycycle. + +.br + +.br + +.EX +#define PI_HW_PWM_RANGE 1000000 +.br + +.EE + +.br + +.br + +.IP "\fBPWMfreq\fP: 1-125000000 (125M)" 0 +The hardware PWM frequency. + +.br + +.br + +.EX +#define PI_HW_PWM_MIN_FREQ 1 +.br +#define PI_HW_PWM_MAX_FREQ 125000000 +.br + +.EE + +.br + +.br + +.IP "\fBrange\fP: 25-40000" 0 +The permissible dutycycle values are 0-range. + +.br + +.br + +.EX +PI_MIN_DUTYCYCLE_RANGE 25 +.br +PI_MAX_DUTYCYCLE_RANGE 40000 +.br + +.EE + +.br + +.br + +.IP "\fB*retBuf\fP" 0 +A buffer to hold a number of bytes returned to a used customised function, + +.br + +.br + +.IP "\fBretMax\fP" 0 +The maximum number of bytes a user customised function should return. + +.br + +.br + +.br + +.br + +.IP "\fB*rxBuf\fP" 0 +A pointer to a buffer to receive data. + +.br + +.br + +.IP "\fBSCL\fP" 0 +The user GPIO to use for the clock when bit banging I2C. + +.br + +.br + +.IP "\fBSCLK\fP" 0 +The GPIO used for the SCLK signal when bit banging SPI. + +.br + +.br + +.IP "\fB*script\fP" 0 +A pointer to the text of a script. + +.br + +.br + +.IP "\fBscript_id\fP" 0 +An id of a stored script as returned by \fBstore_script\fP. + +.br + +.br + +.IP "\fB*scriptName\fP" 0 +The name of a \fBshell_\fP script to be executed. The script must be present in +/opt/pigpio/cgi and must have execute permission. + +.br + +.br + +.IP "\fB*scriptString\fP" 0 +The string to be passed to a \fBshell_\fP script to be executed. + +.br + +.br + +.IP "\fBSDA\fP" 0 +The user GPIO to use for data when bit banging I2C. + +.br + +.br + +.IP "\fBseconds\fP" 0 +The number of seconds. + +.br + +.br + +.IP "\fBseekFrom\fP" 0 + +.br + +.br + +.EX +PI_FROM_START 0 +.br +PI_FROM_CURRENT 1 +.br +PI_FROM_END 2 +.br + +.EE + +.br + +.br + +.IP "\fBseekOffset\fP" 0 +The number of bytes to move forward (positive) or backwards (negative) +from the seek position (start, current, or end of file). + +.br + +.br + +.IP "\fBser_flags\fP" 0 +Flags which modify a serial open command. None are currently defined. + +.br + +.br + +.IP "\fB*ser_tty\fP" 0 +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +.br + +.br + +.IP "\fBsize_t\fP" 0 +A standard type used to indicate the size of an object in bytes. + +.br + +.br + +.IP "\fBspi_channel\fP" 0 +A SPI channel, 0-2. + +.br + +.br + +.IP "\fBspi_flags\fP" 0 +See \fBspi_open\fP and \fBbb_spi_open\fP. + +.br + +.br + +.IP "\fBsteady\fP: 0-300000" 0 + +.br + +.br +The number of microseconds level changes must be stable for +before reporting the level changed (\fBset_glitch_filter\fP) or triggering +the active part of a noise filter (\fBset_noise_filter\fP). + +.br + +.br + +.IP "\fBstop_bits\fP: 2-8" 0 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +.br + +.br + +.EX +#define PI_MIN_WAVE_HALFSTOPBITS 2 +.br +#define PI_MAX_WAVE_HALFSTOPBITS 8 +.br + +.EE + +.br + +.br + +.IP "\fB*str\fP" 0 + An array of characters. + +.br + +.br + +.IP "\fBthread_func\fP" 0 +A function of type gpioThreadFunc_t used as the main function of a +thread. + +.br + +.br + +.IP "\fBtimeout\fP" 0 +A GPIO watchdog timeout in milliseconds. + +.br + +.br + +.EX +PI_MIN_WDOG_TIMEOUT 0 +.br +PI_MAX_WDOG_TIMEOUT 60000 +.br + +.EE + +.br + +.br + +.IP "\fB*txBuf\fP" 0 +An array of bytes to transmit. + +.br + +.br + +.IP "\fBuint32_t\fP: 0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF)" 0 +A 32-bit unsigned value. + +.br + +.br + +.IP "\fBunsigned\fP" 0 +A whole number >= 0. + +.br + +.br + +.IP "\fBuser_gpio\fP" 0 +0-31, a Broadcom numbered GPIO. + +.br + +.br +See \fBgpio\fP. + +.br + +.br + +.IP "\fB*userdata\fP" 0 + +.br + +.br +A pointer to arbitrary user data. This may be used to identify the instance. + +.br + +.br +You must ensure that the pointer is in scope at the time it is processed. If +it is a pointer to a global this is automatic. Do not pass the address of a +local variable. If you want to pass a transient object then use the +following technique. + +.br + +.br +In the calling function: + +.br + +.br + +.EX +user_type *userdata; +.br +.br +.br +user_type my_userdata; +.br + +.br +userdata = malloc(sizeof(user_type)); +.br +.br +.br +*userdata = my_userdata; +.br + +.EE + +.br + +.br +In the receiving function: + +.br + +.br + +.EX +user_type my_userdata = *(user_type*)userdata; +.br + +.br +free(userdata); +.br + +.EE + +.br + +.br + +.IP "\fBvoid\fP" 0 +Denoting no parameter is required + +.br + +.br + +.IP "\fBwave_add_*\fP" 0 +One of + +.br + +.br +\fBwave_add_new\fP +.br +\fBwave_add_generic\fP +.br +\fBwave_add_serial\fP + +.br + +.br + +.IP "\fBwave_id\fP" 0 +A number representing a waveform created by \fBwave_create\fP. + +.br + +.br + +.IP "\fBwave_send_*\fP" 0 +One of + +.br + +.br +\fBwave_send_once\fP +.br +\fBwave_send_repeat\fP + +.br + +.br + +.IP "\fBwVal\fP: 0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777)" 0 +A 16-bit word value. + +.br + +.br +.SH pigpiod_if2 Error Codes + +.EX + +.br +typedef enum +.br +{ +.br + pigif_bad_send = -2000, +.br + pigif_bad_recv = -2001, +.br + pigif_bad_getaddrinfo = -2002, +.br + pigif_bad_connect = -2003, +.br + pigif_bad_socket = -2004, +.br + pigif_bad_noib = -2005, +.br + pigif_duplicate_callback = -2006, +.br + pigif_bad_malloc = -2007, +.br + pigif_bad_callback = -2008, +.br + pigif_notify_failed = -2009, +.br + pigif_callback_not_found = -2010, +.br + pigif_unconnected_pi = -2011, +.br + pigif_too_many_pis = -2012, +.br +} pigifError_t; +.br + +.br + +.EE + +.SH SEE ALSO + +pigpiod(1), pig2vcd(1), pigs(1), pigpio(3), pigpiod_if(3) +.SH AUTHOR + +joan@abyz.me.uk diff --git a/thirdparty/PIGPIO/pigpiod_if2.c b/thirdparty/PIGPIO/pigpiod_if2.c new file mode 100644 index 0000000000..93efdb08cf --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if2.c @@ -0,0 +1,2131 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* PIGPIOD_IF2_VERSION 13 */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include "pigpio.h" +#include "command.h" + +#include "pigpiod_if2.h" + +#define PI_MAX_REPORTS_PER_READ 4096 + +#define STACK_SIZE (256*1024) + +#define MAX_PI 32 + +typedef void (*CBF_t) (); + +struct callback_s +{ + + int id; + int pi; + int gpio; + int edge; + CBF_t f; + void * user; + int ex; + callback_t *prev; + callback_t *next; +}; + +struct evtCallback_s +{ + + int id; + int pi; + int event; + CBF_t f; + void * user; + int ex; + evtCallback_t *prev; + evtCallback_t *next; +}; + +/* GLOBALS ---------------------------------------------------------------- */ + +static int gPiInUse [MAX_PI]; + +static int gPigCommand [MAX_PI]; +static int gPigHandle [MAX_PI]; +static int gPigNotify [MAX_PI]; + +static uint32_t gEventBits [MAX_PI]; +static uint32_t gNotifyBits [MAX_PI]; +static uint32_t gLastLevel [MAX_PI]; + +static pthread_t *gPthNotify [MAX_PI]; + +static pthread_mutex_t gCmdMutex [MAX_PI]; +static int gCancelState [MAX_PI]; + +static callback_t *gCallBackFirst = 0; +static callback_t *gCallBackLast = 0; + +static evtCallback_t *geCallBackFirst = 0; +static evtCallback_t *geCallBackLast = 0; + +/* PRIVATE ---------------------------------------------------------------- */ + +static void _pml(int pi) +{ + int cancelState; + + pthread_setcancelstate(PTHREAD_CANCEL_DISABLE, &cancelState); + pthread_mutex_lock(&gCmdMutex[pi]); + gCancelState[pi] = cancelState; +} + +static void _pmu(int pi) +{ + int cancelState; + + cancelState = gCancelState[pi]; + pthread_mutex_unlock(&gCmdMutex[pi]); + pthread_setcancelstate(cancelState, NULL); +} + +static int pigpio_command(int pi, int command, int p1, int p2, int rl) +{ + cmdCmd_t cmd; + + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) + return pigif_unconnected_pi; + + cmd.cmd = command; + cmd.p1 = p1; + cmd.p2 = p2; + cmd.res = 0; + + _pml(pi); + + if (send(gPigCommand[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd)) + { + _pmu(pi); + return pigif_bad_send; + } + + if (recv(gPigCommand[pi], &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd)) + { + _pmu(pi); + return pigif_bad_recv; + } + + if (rl) _pmu(pi); + + return cmd.res; +} + +static int pigpio_notify(int pi) +{ + cmdCmd_t cmd; + + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) + return pigif_unconnected_pi; + + cmd.cmd = PI_CMD_NOIB; + cmd.p1 = 0; + cmd.p2 = 0; + cmd.res = 0; + + _pml(pi); + + if (send(gPigNotify[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd)) + { + _pmu(pi); + return pigif_bad_send; + } + + if (recv(gPigNotify[pi], &cmd, sizeof(cmd), MSG_WAITALL) != sizeof(cmd)) + { + _pmu(pi); + return pigif_bad_recv; + } + + _pmu(pi); + + return cmd.res; +} + +static int pigpio_command_ext + (int pi, int command, int p1, int p2, int p3, + int extents, gpioExtent_t *ext, int rl) +{ + int i; + cmdCmd_t cmd; + + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) + return pigif_unconnected_pi; + + cmd.cmd = command; + cmd.p1 = p1; + cmd.p2 = p2; + cmd.p3 = p3; + + _pml(pi); + + if (send(gPigCommand[pi], &cmd, sizeof(cmd), 0) != sizeof(cmd)) + { + _pmu(pi); + return pigif_bad_send; + } + + for (i=0; iai_next) + { + sock = socket(rp->ai_family, rp->ai_socktype, rp->ai_protocol); + + if (sock == -1) continue; + + /* Disable the Nagle algorithm. */ + opt = 1; + setsockopt(sock, IPPROTO_TCP, TCP_NODELAY, (char*)&opt, sizeof(int)); + + if (connect(sock, rp->ai_addr, rp->ai_addrlen) != -1) break; + } + + freeaddrinfo(res); + + if (rp == NULL) return pigif_bad_connect; + + return sock; +} + +static void dispatch_notification(int pi, gpioReport_t *r) +{ + callback_t *p; + evtCallback_t *ep; + uint32_t changed; + int l, g; + +/* + printf("s=%4x f=%4x t=%10u l=%8x\n", + r->seqno, r->flags, r->tick, r->level); +*/ + + if (r->flags == 0) + { + changed = (r->level ^ gLastLevel[pi]) & gNotifyBits[pi]; + + gLastLevel[pi] = r->level; + + p = gCallBackFirst; + + while (p) + { + if (((p->pi) == pi) && (changed & (1<<(p->gpio)))) + { + if ((r->level) & (1<<(p->gpio))) l = 1; else l = 0; + if ((p->edge) ^ l) + { + if (p->ex) (p->f)(pi, p->gpio, l, r->tick, p->user); + else (p->f)(pi, p->gpio, l, r->tick); + } + } + p = p->next; + } + } + else + { + if ((r->flags) & PI_NTFY_FLAGS_WDOG) + { + g = (r->flags) & 31; + + p = gCallBackFirst; + + while (p) + { + if (((p->pi) == pi) && ((p->gpio) == g)) + { + if (p->ex) (p->f)(pi, g, PI_TIMEOUT, r->tick, p->user); + else (p->f)(pi, g, PI_TIMEOUT, r->tick); + } + p = p->next; + } + } + else if ((r->flags) & PI_NTFY_FLAGS_EVENT) + { + g = (r->flags) & 31; + + ep = geCallBackFirst; + + while (ep) + { + if (((ep->pi) == pi) && ((ep->event) == g)) + { + if (ep->ex) (ep->f)(pi, g, r->tick, ep->user); + else (ep->f)(pi, g, r->tick); + } + ep = ep->next; + } + } + } +} + +static void *pthNotifyThread(void *x) +{ + static int got = 0; + int pi; + int bytes, r; + gpioReport_t report[PI_MAX_REPORTS_PER_READ]; + + pi = *((int*)x); + free(x); /* memory allocated in pigpio_start */ + + while (1) + { + bytes = read(gPigNotify[pi], (char*)&report+got, sizeof(report)-got); + + if (bytes > 0) got += bytes; + else break; + + r = 0; + + while (got >= sizeof(gpioReport_t)) + { + dispatch_notification(pi, &report[r]); + + r++; + + got -= sizeof(gpioReport_t); + } + + /* copy any partial report to start of array */ + + if (got && r) report[0] = report[r]; + } + + fprintf(stderr, "notify thread for pi %d broke with read error %d\n", + pi, bytes); + + while (1) sleep(1); + + return NULL; +} + +static void findNotifyBits(int pi) +{ + callback_t *p; + uint32_t bits = 0; + + p = gCallBackFirst; + + while (p) + { + if (p->pi == pi) bits |= (1<<(p->gpio)); + p = p->next; + } + + if (bits != gNotifyBits[pi]) + { + gNotifyBits[pi] = bits; + pigpio_command(pi, PI_CMD_NB, gPigHandle[pi], gNotifyBits[pi], 1); + } +} + +static void _wfe( + int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *user) +{ + *(int *)user = 1; +} + +static int intCallback( + int pi, unsigned user_gpio, unsigned edge, void *f, void *user, int ex) +{ + static int id = 0; + callback_t *p; + + if ((user_gpio >=0) && (user_gpio < 32) && (edge >=0) && (edge <= 2) && f) + { + /* prevent duplicates */ + + p = gCallBackFirst; + + while (p) + { + if ((p->pi == pi) && + (p->gpio == user_gpio) && + (p->edge == edge) && + (p->f == f)) + { + return pigif_duplicate_callback; + } + p = p->next; + } + + p = malloc(sizeof(callback_t)); + + if (p) + { + if (!gCallBackFirst) gCallBackFirst = p; + + p->id = id++; + p->pi = pi; + p->gpio = user_gpio; + p->edge = edge; + p->f = f; + p->user = user; + p->ex = ex; + p->next = 0; + p->prev = gCallBackLast; + + if (p->prev) (p->prev)->next = p; + gCallBackLast = p; + + findNotifyBits(pi); + + return p->id; + } + + return pigif_bad_malloc; + } + + return pigif_bad_callback; +} + +static void findEventBits(int pi) +{ + evtCallback_t *ep; + uint32_t bits = 0; + + ep = geCallBackFirst; + + while (ep) + { + if (ep->pi == pi) bits |= (1<<(ep->event)); + ep = ep->next; + } + + if (bits != gEventBits[pi]) + { + gEventBits[pi] = bits; + pigpio_command(pi, PI_CMD_EVM, gPigHandle[pi], gEventBits[pi], 1); + } +} + +static void _ewfe( + int pi, unsigned event, uint32_t tick, void *user) +{ + *(int *)user = 1; +} + +static int intEventCallback( + int pi, unsigned event, void *f, void *user, int ex) +{ + static int id = 0; + evtCallback_t *ep; + + if ((event >=0) && (event < 32) && f) + { + /* prevent duplicates */ + + ep = geCallBackFirst; + + while (ep) + { + if ((ep->pi == pi) && + (ep->event == event) && + (ep->f == f)) + { + return pigif_duplicate_callback; + } + ep = ep->next; + } + + ep = malloc(sizeof(evtCallback_t)); + + if (ep) + { + if (!geCallBackFirst) geCallBackFirst = ep; + + ep->id = id++; + ep->pi = pi; + ep->event = event; + ep->f = f; + ep->user = user; + ep->ex = ex; + ep->next = 0; + ep->prev = geCallBackLast; + + if (ep->prev) (ep->prev)->next = ep; + geCallBackLast = ep; + + findEventBits(pi); + + return ep->id; + } + + return pigif_bad_malloc; + } + + return pigif_bad_callback; +} + +static int recvMax(int pi, void *buf, int bufsize, int sent) +{ + /* + Copy at most bufSize bytes from the receieved message to + buf. Discard the rest of the message. + */ + uint8_t scratch[4096]; + int remaining, fetch, count; + + if (sent < bufsize) count = sent; else count = bufsize; + + if (count) recv(gPigCommand[pi], buf, count, MSG_WAITALL); + + remaining = sent - count; + + while (remaining) + { + fetch = remaining; + if (fetch > sizeof(scratch)) fetch = sizeof(scratch); + recv(gPigCommand[pi], scratch, fetch, MSG_WAITALL); + remaining -= fetch; + } + + return count; +} + +/* PUBLIC ----------------------------------------------------------------- */ + +double time_time(void) +{ + struct timeval tv; + double t; + + gettimeofday(&tv, 0); + + t = (double)tv.tv_sec + ((double)tv.tv_usec / 1E6); + + return t; +} + +void time_sleep(double seconds) +{ + struct timespec ts, rem; + + if (seconds > 0.0) + { + ts.tv_sec = seconds; + ts.tv_nsec = (seconds-(double)ts.tv_sec) * 1E9; + + while (clock_nanosleep(CLOCK_REALTIME, 0, &ts, &rem)) + { + /* copy remaining time to ts */ + ts.tv_sec = rem.tv_sec; + ts.tv_nsec = rem.tv_nsec; + } + } +} + +char *pigpio_error(int errnum) +{ + if (errnum > -1000) return cmdErrStr(errnum); + else + { + switch(errnum) + { + case pigif_bad_send: + return "failed to send to pigpiod"; + case pigif_bad_recv: + return "failed to receive from pigpiod"; + case pigif_bad_getaddrinfo: + return "failed to find address of pigpiod"; + case pigif_bad_connect: + return "failed to connect to pigpiod"; + case pigif_bad_socket: + return "failed to create socket"; + case pigif_bad_noib: + return "failed to open notification in band"; + case pigif_duplicate_callback: + return "identical callback exists"; + case pigif_bad_malloc: + return "failed to malloc"; + case pigif_bad_callback: + return "bad callback parameter"; + case pigif_notify_failed: + return "failed to create notification thread"; + case pigif_callback_not_found: + return "callback not found"; + case pigif_unconnected_pi: + return "not connected to Pi"; + case pigif_too_many_pis: + return "too many connected Pis"; + + default: + return "unknown error"; + } + } +} + +unsigned pigpiod_if_version(void) +{ + return PIGPIOD_IF2_VERSION; +} + +pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata) +{ + pthread_t *pth; + pthread_attr_t pthAttr; + + pth = malloc(sizeof(pthread_t)); + + if (pth) + { + if (pthread_attr_init(&pthAttr)) + { + perror("pthread_attr_init failed"); + free(pth); + return NULL; + } + + if (pthread_attr_setstacksize(&pthAttr, STACK_SIZE)) + { + perror("pthread_attr_setstacksize failed"); + free(pth); + return NULL; + } + + if (pthread_create(pth, &pthAttr, thread_func, userdata)) + { + perror("pthread_create socket failed"); + free(pth); + return NULL; + } + } + return pth; +} + +void stop_thread(pthread_t *pth) +{ + if (pth) + { + pthread_cancel(*pth); + pthread_join(*pth, NULL); + free(pth); + } +} + +int pigpio_start(const char *addrStr, const char *portStr) +{ + int pi; + int *userdata; + + if ((!addrStr) || (strlen(addrStr) == 0)) + { + addrStr = "localhost"; + } + + for (pi=0; pi= MAX_PI) return pigif_too_many_pis; + + gPiInUse[pi] = 1; + + pthread_mutex_init(&gCmdMutex[pi], NULL); + + gPigCommand[pi] = pigpioOpenSocket(addrStr, portStr); + + if (gPigCommand[pi] >= 0) + { + gPigNotify[pi] = pigpioOpenSocket(addrStr, portStr); + + if (gPigNotify[pi] >= 0) + { + gPigHandle[pi] = pigpio_notify(pi); + + if (gPigHandle[pi] < 0) return pigif_bad_noib; + else + { + gLastLevel[pi] = read_bank_1(pi); + + /* must be freed by pthNotifyThread */ + userdata = malloc(sizeof(*userdata)); + *userdata = pi; + + gPthNotify[pi] = start_thread(pthNotifyThread, userdata); + + if (gPthNotify[pi]) return pi; + else return pigif_notify_failed; + + } + } + else return gPigNotify[pi]; + } + else return gPigCommand[pi]; +} + +void pigpio_stop(int pi) +{ + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) return; + + if (gPthNotify[pi]) + { + stop_thread(gPthNotify[pi]); + gPthNotify[pi] = 0; + } + + if (gPigCommand[pi] >= 0) + { + if (gPigHandle[pi] >= 0) + { + pigpio_command(pi, PI_CMD_NC, gPigHandle[pi], 0, 1); + gPigHandle[pi] = -1; + } + + close(gPigCommand[pi]); + gPigCommand[pi] = -1; + } + + if (gPigNotify[pi] >= 0) + { + close(gPigNotify[pi]); + gPigNotify[pi] = -1; + } + + gPiInUse[pi] = 0; +} + +int set_mode(int pi, unsigned gpio, unsigned mode) + {return pigpio_command(pi, PI_CMD_MODES, gpio, mode, 1);} + +int get_mode(int pi, unsigned gpio) + {return pigpio_command(pi, PI_CMD_MODEG, gpio, 0, 1);} + +int set_pull_up_down(int pi, unsigned gpio, unsigned pud) + {return pigpio_command(pi, PI_CMD_PUD, gpio, pud, 1);} + +int gpio_read(int pi, unsigned gpio) + {return pigpio_command(pi, PI_CMD_READ, gpio, 0, 1);} + +int gpio_write(int pi, unsigned gpio, unsigned level) + {return pigpio_command(pi, PI_CMD_WRITE, gpio, level, 1);} + +int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle) + {return pigpio_command(pi, PI_CMD_PWM, user_gpio, dutycycle, 1);} + +int get_PWM_dutycycle(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_GDC, user_gpio, 0, 1);} + +int set_PWM_range(int pi, unsigned user_gpio, unsigned range) + {return pigpio_command(pi, PI_CMD_PRS, user_gpio, range, 1);} + +int get_PWM_range(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_PRG, user_gpio, 0, 1);} + +int get_PWM_real_range(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_PRRG, user_gpio, 0, 1);} + +int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency) + {return pigpio_command(pi, PI_CMD_PFS, user_gpio, frequency, 1);} + +int get_PWM_frequency(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_PFG, user_gpio, 0, 1);} + +int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth) + {return pigpio_command(pi, PI_CMD_SERVO, user_gpio, pulsewidth, 1);} + +int get_servo_pulsewidth(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_GPW, user_gpio, 0, 1);} + +int notify_open(int pi) + {return pigpio_command(pi, PI_CMD_NO, 0, 0, 1);} + +int notify_begin(int pi, unsigned handle, uint32_t bits) + {return pigpio_command(pi, PI_CMD_NB, handle, bits, 1);} + +int notify_pause(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_NB, handle, 0, 1);} + +int notify_close(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_NC, handle, 0, 1);} + +int set_watchdog(int pi, unsigned user_gpio, unsigned timeout) + {return pigpio_command(pi, PI_CMD_WDOG, user_gpio, timeout, 1);} + +uint32_t read_bank_1(int pi) + {return pigpio_command(pi, PI_CMD_BR1, 0, 0, 1);} + +uint32_t read_bank_2(int pi) + {return pigpio_command(pi, PI_CMD_BR2, 0, 0, 1);} + +int clear_bank_1(int pi, uint32_t levels) + {return pigpio_command(pi, PI_CMD_BC1, levels, 0, 1);} + +int clear_bank_2(int pi, uint32_t levels) + {return pigpio_command(pi, PI_CMD_BC2, levels, 0, 1);} + +int set_bank_1(int pi, uint32_t levels) + {return pigpio_command(pi, PI_CMD_BS1, levels, 0, 1);} + +int set_bank_2(int pi, uint32_t levels) + {return pigpio_command(pi, PI_CMD_BS2, levels, 0, 1);} + +int hardware_clock(int pi, unsigned gpio, unsigned frequency) + {return pigpio_command(pi, PI_CMD_HC, gpio, frequency, 1);} + +int hardware_PWM(int pi, unsigned gpio, unsigned frequency, uint32_t dutycycle) +{ + gpioExtent_t ext[1]; + + /* + p1=gpio + p2=frequency + p3=4 + ## extension ## + uint32_t dutycycle + */ + + ext[0].size = sizeof(dutycycle); + ext[0].ptr = &dutycycle; + + return pigpio_command_ext( + pi, PI_CMD_HP, gpio, frequency, sizeof(dutycycle), 1, ext, 1); +} + +uint32_t get_current_tick(int pi) + {return pigpio_command(pi, PI_CMD_TICK, 0, 0, 1);} + +uint32_t get_hardware_revision(int pi) + {return pigpio_command(pi, PI_CMD_HWVER, 0, 0, 1);} + +uint32_t get_pigpio_version(int pi) + {return pigpio_command(pi, PI_CMD_PIGPV, 0, 0, 1);} + +int wave_clear(int pi) + {return pigpio_command(pi, PI_CMD_WVCLR, 0, 0, 1);} + +int wave_add_new(int pi) + {return pigpio_command(pi, PI_CMD_WVNEW, 0, 0, 1);} + +int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses) +{ + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=pulses*sizeof(gpioPulse_t) + ## extension ## + gpioPulse_t[] pulses + */ + + if (!numPulses) return 0; + + ext[0].size = numPulses * sizeof(gpioPulse_t); + ext[0].ptr = pulses; + + return pigpio_command_ext( + pi, PI_CMD_WVAG, 0, 0, ext[0].size, 1, ext, 1); +} + +int wave_add_serial( + int pi, unsigned user_gpio, unsigned baud, uint32_t databits, + uint32_t stophalfbits, uint32_t offset, unsigned numChar, char *str) +{ + uint8_t buf[12]; + gpioExtent_t ext[2]; + + /* + p1=user_gpio + p2=baud + p3=len+12 + ## extension ## + uint32_t databits + uint32_t stophalfbits + uint32_t offset + char[len] str + */ + + if (!numChar) return 0; + + memcpy(buf, &databits, 4); + memcpy(buf+4, &stophalfbits, 4); + memcpy(buf+8, &offset, 4); + + ext[0].size = sizeof(buf); + ext[0].ptr = buf; + + ext[1].size = numChar; + ext[1].ptr = str; + + return pigpio_command_ext(pi, PI_CMD_WVAS, + user_gpio, baud, numChar+sizeof(buf), 2, ext, 1); +} + +int wave_create(int pi) + {return pigpio_command(pi, PI_CMD_WVCRE, 0, 0, 1);} + +int wave_delete(int pi, unsigned wave_id) + {return pigpio_command(pi, PI_CMD_WVDEL, wave_id, 0, 1);} + +int wave_tx_start(int pi) /* DEPRECATED */ + {return pigpio_command(pi, PI_CMD_WVGO, 0, 0, 1);} + +int wave_tx_repeat(int pi) /* DEPRECATED */ + {return pigpio_command(pi, PI_CMD_WVGOR, 0, 0, 1);} + +int wave_send_once(int pi, unsigned wave_id) + {return pigpio_command(pi, PI_CMD_WVTX, wave_id, 0, 1);} + +int wave_send_repeat(int pi, unsigned wave_id) + {return pigpio_command(pi, PI_CMD_WVTXR, wave_id, 0, 1);} + +int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode) + {return pigpio_command(pi, PI_CMD_WVTXM, wave_id, mode, 1);} + +int wave_chain(int pi, char *buf, unsigned bufSize) +{ + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=bufSize + ## extension ## + char buf[bufSize] + */ + + ext[0].size = bufSize; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_WVCHA, 0, 0, bufSize, 1, ext, 1); +} + +int wave_tx_at(int pi) + {return pigpio_command(pi, PI_CMD_WVTAT, 0, 0, 1);} + +int wave_tx_busy(int pi) + {return pigpio_command(pi, PI_CMD_WVBSY, 0, 0, 1);} + +int wave_tx_stop(int pi) + {return pigpio_command(pi, PI_CMD_WVHLT, 0, 0, 1);} + +int wave_get_micros(int pi) + {return pigpio_command(pi, PI_CMD_WVSM, 0, 0, 1);} + +int wave_get_high_micros(int pi) + {return pigpio_command(pi, PI_CMD_WVSM, 1, 0, 1);} + +int wave_get_max_micros(int pi) + {return pigpio_command(pi, PI_CMD_WVSM, 2, 0, 1);} + +int wave_get_pulses(int pi) + {return pigpio_command(pi, PI_CMD_WVSP, 0, 0, 1);} + +int wave_get_high_pulses(int pi) + {return pigpio_command(pi, PI_CMD_WVSP, 1, 0, 1);} + +int wave_get_max_pulses(int pi) + {return pigpio_command(pi, PI_CMD_WVSP, 2, 0, 1);} + +int wave_get_cbs(int pi) + {return pigpio_command(pi, PI_CMD_WVSC, 0, 0, 1);} + +int wave_get_high_cbs(int pi) + {return pigpio_command(pi, PI_CMD_WVSC, 1, 0, 1);} + +int wave_get_max_cbs(int pi) + {return pigpio_command(pi, PI_CMD_WVSC, 2, 0, 1);} + +int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, uint32_t level) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=pulseLen + p3=4 + ## extension ## + unsigned level + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &level; + + return pigpio_command_ext( + pi, PI_CMD_TRIG, user_gpio, pulseLen, 4, 1, ext, 1); +} + +int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady) + {return pigpio_command(pi, PI_CMD_FG, user_gpio, steady, 1);} + +int set_noise_filter(int pi, unsigned user_gpio, unsigned steady, unsigned active) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=steady + p3=4 + ## extension ## + unsigned active + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &active; + + return pigpio_command_ext( + pi, PI_CMD_FN, user_gpio, steady, 4, 1, ext, 1); +} + +int store_script(int pi, char *script) +{ + unsigned len; + gpioExtent_t ext[1]; + + /* + p1=0 + p2=0 + p3=len + ## extension ## + char[len] script + */ + + len = strlen(script); + + if (!len) return 0; + + ext[0].size = len; + ext[0].ptr = script; + + return pigpio_command_ext(pi, PI_CMD_PROC, 0, 0, len, 1, ext, 1); +} + +int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param) +{ + gpioExtent_t ext[1]; + + /* + p1=script id + p2=0 + p3=numPar * 4 + ## extension ## + uint32_t[numPar] pars + */ + + ext[0].size = 4 * numPar; + ext[0].ptr = param; + + return pigpio_command_ext + (pi, PI_CMD_PROCR, script_id, 0, numPar*4, 1, ext, 1); +} + +int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param) +{ + gpioExtent_t ext[1]; + + /* + p1=script id + p2=0 + p3=numPar * 4 + ## extension ## + uint32_t[numPar] pars + */ + + ext[0].size = 4 * numPar; + ext[0].ptr = param; + + return pigpio_command_ext + (pi, PI_CMD_PROCU, script_id, 0, numPar*4, 1, ext, 1); +} + +int script_status(int pi, unsigned script_id, uint32_t *param) +{ + int status; + uint32_t p[PI_MAX_SCRIPT_PARAMS+1]; /* space for script status */ + + status = pigpio_command(pi, PI_CMD_PROCP, script_id, 0, 0); + + if (status > 0) + { + recvMax(pi, p, sizeof(p), status); + status = p[0]; + if (param) memcpy(param, p+1, sizeof(p)-4); + } + + _pmu(pi); + + return status; +} + +int stop_script(int pi, unsigned script_id) + {return pigpio_command(pi, PI_CMD_PROCS, script_id, 0, 1);} + +int delete_script(int pi, unsigned script_id) + {return pigpio_command(pi, PI_CMD_PROCD, script_id, 0, 1);} + +int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, uint32_t bbBits) +{ + gpioExtent_t ext[1]; + + /* + p1=user_gpio + p2=baud + p3=4 + ## extension ## + unsigned bbBits + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &bbBits; + + return pigpio_command_ext( + pi, PI_CMD_SLRO, user_gpio, baud, 4, 1, ext, 1); +} + +int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize) +{ + int bytes; + + bytes = pigpio_command(pi, PI_CMD_SLR, user_gpio, bufSize, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, bufSize, bytes); + } + + _pmu(pi); + + return bytes; +} + +int bb_serial_read_close(int pi, unsigned user_gpio) + {return pigpio_command(pi, PI_CMD_SLRC, user_gpio, 0, 1);} + +int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert) + {return pigpio_command(pi, PI_CMD_SLRI, user_gpio, invert, 1);} + +int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, uint32_t i2c_flags) +{ + gpioExtent_t ext[1]; + + /* + p1=i2c_bus + p2=i2c_addr + p3=4 + ## extension ## + uint32_t i2c_flags + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &i2c_flags; + + return pigpio_command_ext + (pi, PI_CMD_I2CO, i2c_bus, i2c_addr, 4, 1, ext, 1); +} + +int i2c_close(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_I2CC, handle, 0, 1);} + +int i2c_write_quick(int pi, unsigned handle, unsigned bit) + {return pigpio_command(pi, PI_CMD_I2CWQ, handle, bit, 1);} + +int i2c_write_byte(int pi, unsigned handle, unsigned val) + {return pigpio_command(pi, PI_CMD_I2CWS, handle, val, 1);} + +int i2c_read_byte(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_I2CRS, handle, 0, 1);} + +int i2c_write_byte_data(int pi, unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (pi, PI_CMD_I2CWB, handle, reg, 4, 1, ext, 1); +} + +int i2c_write_word_data(int pi, unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (pi, PI_CMD_I2CWW, handle, reg, 4, 1, ext, 1); +} + +int i2c_read_byte_data(int pi, unsigned handle, unsigned reg) + {return pigpio_command(pi, PI_CMD_I2CRB, handle, reg, 1);} + +int i2c_read_word_data(int pi, unsigned handle, unsigned reg) + {return pigpio_command(pi, PI_CMD_I2CRW, handle, reg, 1);} + +int i2c_process_call(int pi, unsigned handle, unsigned reg, uint32_t val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &val; + + return pigpio_command_ext + (pi, PI_CMD_I2CPK, handle, reg, 4, 1, ext, 1); +} + +int i2c_write_block_data( + int pi, unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_I2CWK, handle, reg, count, 1, ext, 1); +} + +int i2c_read_block_data(int pi, unsigned handle, unsigned reg, char *buf) +{ + int bytes; + + bytes = pigpio_command(pi, PI_CMD_I2CRK, handle, reg, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, 32, bytes); + } + + _pmu(pi); + + return bytes; +} + +int i2c_block_process_call( + int pi, unsigned handle, unsigned reg, char *buf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + bytes = pigpio_command_ext + (pi, PI_CMD_I2CPK, handle, reg, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, 32, bytes); + } + + _pmu(pi); + + return bytes; +} + +int i2c_read_i2c_block_data( + int pi, unsigned handle, unsigned reg, char *buf, uint32_t count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t count + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &count; + + bytes = pigpio_command_ext + (pi, PI_CMD_I2CRI, handle, reg, 4, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + + +int i2c_write_i2c_block_data( + int pi, unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_I2CWI, handle, reg, count, 1, ext, 1); +} + +int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command(pi, PI_CMD_I2CRD, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_I2CWD, handle, 0, count, 1, ext, 1); +} + +int i2c_zip( + int pi, + unsigned handle, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=inLen + ## extension ## + char inBuf[inLen] + */ + + ext[0].size = inLen; + ext[0].ptr = inBuf; + + bytes = pigpio_command_ext + (pi, PI_CMD_I2CZ, handle, 0, inLen, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, outBuf, outLen, bytes); + } + + _pmu(pi); + + return bytes; +} + +int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud) +{ + gpioExtent_t ext[1]; + + /* + p1=SDA + p2=SCL + p3=4 + ## extension ## + uint32_t baud + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &baud; + + return pigpio_command_ext + (pi, PI_CMD_BI2CO, SDA, SCL, 4, 1, ext, 1); +} + +int bb_i2c_close(int pi, unsigned SDA) + {return pigpio_command(pi, PI_CMD_BI2CC, SDA, 0, 1);} + +int bb_i2c_zip( + int pi, + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=SDA + p2=0 + p3=inLen + ## extension ## + char inBuf[inLen] + */ + + ext[0].size = inLen; + ext[0].ptr = inBuf; + + bytes = pigpio_command_ext + (pi, PI_CMD_BI2CZ, SDA, 0, inLen, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, outBuf, outLen, bytes); + } + + _pmu(pi); + + return bytes; +} + +int bb_spi_open( + int pi, + unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, + unsigned baud, unsigned spiFlags) +{ + uint8_t buf[20]; + gpioExtent_t ext[1]; + + /* + p1=CS + p2=0 + p3=20 + ## extension ## + uint32_t MISO + uint32_t MOSI + uint32_t SCLK + uint32_t baud + uint32_t spiFlags + */ + + ext[0].size = 20; + ext[0].ptr = &buf; + + memcpy(buf + 0, &MISO, 4); + memcpy(buf + 4, &MOSI, 4); + memcpy(buf + 8, &SCLK, 4); + memcpy(buf + 12, &baud, 4); + memcpy(buf + 16, &spiFlags, 4); + + return pigpio_command_ext + (pi, PI_CMD_BSPIO, CS, 0, 20, 1, ext, 1); +} + +int bb_spi_close(int pi, unsigned CS) + {return pigpio_command(pi, PI_CMD_BSPIC, CS, 0, 1);} + +int bb_spi_xfer( + int pi, + unsigned CS, + char *txBuf, + char *rxBuf, + unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=CS + p2=0 + p3=count + ## extension ## + char txBuf[count] + */ + + ext[0].size = count; + ext[0].ptr = txBuf; + + bytes = pigpio_command_ext + (pi, PI_CMD_BSPIX, CS, 0, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, rxBuf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int spi_open(int pi, unsigned channel, unsigned speed, uint32_t flags) +{ + gpioExtent_t ext[1]; + + /* + p1=channel + p2=speed + p3=4 + ## extension ## + uint32_t flags + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &flags; + + return pigpio_command_ext + (pi, PI_CMD_SPIO, channel, speed, 4, 1, ext, 1); +} + +int spi_close(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_SPIC, handle, 0, 1);} + +int spi_read(int pi, unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (pi, PI_CMD_SPIR, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int spi_write(int pi, unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_SPIW, handle, 0, count, 1, ext, 1); +} + +int spi_xfer(int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = txBuf; + + bytes = pigpio_command_ext + (pi, PI_CMD_SPIX, handle, 0, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, rxBuf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int serial_open(int pi, char *dev, unsigned baud, unsigned flags) +{ + int len; + gpioExtent_t ext[1]; + + len = strlen(dev); + + /* + p1=baud + p2=flags + p3=len + ## extension ## + char dev[len] + */ + + ext[0].size = len; + ext[0].ptr = dev; + + return pigpio_command_ext + (pi, PI_CMD_SERO, baud, flags, len, 1, ext, 1); +} + +int serial_close(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_SERC, handle, 0, 1);} + +int serial_write_byte(int pi, unsigned handle, unsigned val) + {return pigpio_command(pi, PI_CMD_SERWB, handle, val, 1);} + +int serial_read_byte(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_SERRB, handle, 0, 1);} + +int serial_write(int pi, unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_SERW, handle, 0, count, 1, ext, 1); +} + +int serial_read(int pi, unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (pi, PI_CMD_SERR, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int serial_data_available(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_SERDA, handle, 0, 1);} + +int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=arg1 + p2=arg2 + p3=count + ## extension ## + char argx[count] + */ + + ext[0].size = count; + ext[0].ptr = argx; + + return pigpio_command_ext( + pi, PI_CMD_CF1, arg1, arg2, count, 1, ext, 1); +} + + +int custom_2(int pi, unsigned arg1, char *argx, unsigned count, + char *retBuf, uint32_t retMax) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=arg1 + p2=retMax + p3=count + ## extension ## + char argx[count] + */ + + ext[0].size = count; + ext[0].ptr = argx; + + bytes = pigpio_command_ext + (pi, PI_CMD_CF2, arg1, retMax, count, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, retBuf, retMax, bytes); + } + + _pmu(pi); + + return bytes; +} + +int get_pad_strength(int pi, unsigned pad) + {return pigpio_command(pi, PI_CMD_PADG, pad, 0, 1);} + +int set_pad_strength(int pi, unsigned pad, unsigned padStrength) + {return pigpio_command(pi, PI_CMD_PADS, pad, padStrength, 1);} + +int shell_(int pi, char *scriptName, char *scriptString) +{ + int ln, ls; + gpioExtent_t ext[2]; + + ln = strlen(scriptName); + ls = strlen(scriptString); + /* + p1=len(scriptName) + p2=0 + p3=len(scriptName) + len(scriptString) + 1 + ## extension ## + char[] + */ + + ext[0].size = ln + 1; /* include null byte */ + ext[0].ptr = scriptName; + + ext[1].size = ls; + ext[1].ptr = scriptString; + + return pigpio_command_ext + (pi, PI_CMD_SHELL, ln, 0, ln+ls+1, 2, ext, 1); +} + +int file_open(int pi, char *file, unsigned mode) +{ + int len; + gpioExtent_t ext[1]; + + len = strlen(file); + + /* + p1=mode + p2=0 + p3=len + ## extension ## + char file[len] + */ + + ext[0].size = len; + ext[0].ptr = file; + + return pigpio_command_ext + (pi, PI_CMD_FO, mode, 0, len, 1, ext, 1); +} + +int file_close(int pi, unsigned handle) + {return pigpio_command(pi, PI_CMD_FC, handle, 0, 1);} + +int file_write(int pi, unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (pi, PI_CMD_FW, handle, 0, count, 1, ext, 1); +} + +int file_read(int pi, unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (pi, PI_CMD_FR, handle, count, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=seekOffset + p3=4 + ## extension ## + uint32_t seekFrom + */ + + ext[0].size = sizeof(uint32_t); + ext[0].ptr = &seekFrom; + + return pigpio_command_ext + (pi, PI_CMD_FS, handle, seekOffset, 4, 1, ext, 1); +} + +int file_list(int pi, char *fpat, char *buf, unsigned count) +{ + int len; + int bytes; + gpioExtent_t ext[1]; + + len = strlen(fpat); + + /* + p1=60000 + p2=0 + p3=len + ## extension ## + char fpat[len] + */ + + ext[0].size = len; + ext[0].ptr = fpat; + + bytes = pigpio_command_ext(pi, PI_CMD_FL, 60000, 0, len, 1, ext, 0); + + if (bytes > 0) + { + bytes = recvMax(pi, buf, count, bytes); + } + + _pmu(pi); + + return bytes; +} + +int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f) + {return intCallback(pi, user_gpio, edge, f, 0, 0);} + +int callback_ex( + int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *user) + {return intCallback(pi, user_gpio, edge, f, user, 1);} + +int callback_cancel(unsigned id) +{ + callback_t *p; + int pi; + + p = gCallBackFirst; + + while (p) + { + if (p->id == id) + { + pi = p->pi; + + if (p->prev) {p->prev->next = p->next;} + else {gCallBackFirst = p->next;} + + if (p->next) {p->next->prev = p->prev;} + else {gCallBackLast = p->prev;} + + free(p); + + findNotifyBits(pi); + + return 0; + } + p = p->next; + } + return pigif_callback_not_found; +} + +int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout) +{ + int triggered = 0; + int id; + double due; + + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) + return pigif_unconnected_pi; + + if (timeout <= 0.0) return 0; + + due = time_time() + timeout; + + id = callback_ex(pi, user_gpio, edge, _wfe, &triggered); + + while (!triggered && (time_time() < due)) time_sleep(0.05); + + callback_cancel(id); + + return triggered; +} + +int bsc_xfer(int pi, bsc_xfer_t *bscxfer) +{ + int bytes; + int status; + gpioExtent_t ext[1]; + + /* + p1=control + p2=0 + p3=len + ## extension ## + char buf[len] + */ + + ext[0].size = bscxfer->txCnt; + ext[0].ptr = bscxfer->txBuf; + + bytes = pigpio_command_ext + (pi, PI_CMD_BSCX, bscxfer->control, 0, bscxfer->txCnt, 1, ext, 0); + + if (bytes > 0) + { + recvMax(pi, &status, 4, 4); + status = ntohl(status); + bytes -= 4; + bytes = recvMax(pi, bscxfer->rxBuf, sizeof(bscxfer->rxBuf), bytes); + bscxfer->rxCnt = bytes; + } + else + { + status = bytes; + } + + _pmu(pi); + + return status; +} + + +int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer) +{ + int control = 0; + + if (i2c_addr) control = (i2c_addr<<16) | 0x305; + bscxfer->control = control; + return bsc_xfer(pi, bscxfer); +} + + +int event_callback(int pi, unsigned event, evtCBFunc_t f) + {return intEventCallback(pi, event, f, 0, 0);} + +int event_callback_ex( + int pi, unsigned event, evtCBFuncEx_t f, void *user) + {return intEventCallback(pi, event, f, user, 1);} + +int event_callback_cancel(unsigned id) +{ + evtCallback_t *ep; + int pi; + + ep = geCallBackFirst; + + while (ep) + { + if (ep->id == id) + { + pi = ep->pi; + + if (ep->prev) {ep->prev->next = ep->next;} + else {geCallBackFirst = ep->next;} + + if (ep->next) {ep->next->prev = ep->prev;} + else {geCallBackLast = ep->prev;} + + free(ep); + + findEventBits(pi); + + return 0; + } + ep = ep->next; + } + return pigif_callback_not_found; +} + +int wait_for_event(int pi, unsigned event, double timeout) +{ + int triggered = 0; + int id; + double due; + + if ((pi < 0) || (pi >= MAX_PI) || !gPiInUse[pi]) + return pigif_unconnected_pi; + + if (timeout <= 0.0) return 0; + + due = time_time() + timeout; + + id = event_callback_ex(pi, event, _ewfe, &triggered); + + while (!triggered && (time_time() < due)) time_sleep(0.05); + + event_callback_cancel(id); + + return triggered; +} + +int event_trigger(int pi, unsigned event) + {return pigpio_command(pi, PI_CMD_EVM, event, 0, 1);} + diff --git a/thirdparty/PIGPIO/pigpiod_if2.h b/thirdparty/PIGPIO/pigpiod_if2.h new file mode 100644 index 0000000000..c609c25210 --- /dev/null +++ b/thirdparty/PIGPIO/pigpiod_if2.h @@ -0,0 +1,4249 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +#ifndef PIGPIOD_IF2_H +#define PIGPIOD_IF2_H + +#include "pigpio.h" + +#define PIGPIOD_IF2_VERSION 13 + +/*TEXT + +pigpiod_if2 is a C library for the Raspberry which allows control +of the GPIO via the socket interface to the pigpio daemon. + +*Features* + +o hardware timed PWM on any of GPIO 0-31 + +o hardware timed servo pulses on any of GPIO 0-31 + +o callbacks when any of GPIO 0-31 change state + +o callbacks at timed intervals + +o reading/writing all of the GPIO in a bank as one operation + +o individually setting GPIO modes, reading and writing + +o notifications when any of GPIO 0-31 change state + +o the construction of output waveforms with microsecond timing + +o rudimentary permission control over GPIO + +o a simple interface to start and stop new threads + +o I2C, SPI, and serial link wrappers + +o creating and running scripts on the pigpio daemon + +*GPIO* + +ALL GPIO are identified by their Broadcom number. + +*Notes* + +The PWM and servo pulses are timed using the DMA and PWM/PCM peripherals. + +*Usage* + +Include in your source files. + +Assuming your source is in prog.c use the following command to build + +. . +gcc -Wall -pthread -o prog prog.c -lpigpiod_if2 -lrt +. . + +to run make sure the pigpio daemon is running + +. . +sudo pigpiod + + ./prog # sudo is not required to run programs linked to pigpiod_if2 +. . + +For examples see x_pigpiod_if2.c within the pigpio archive file. + +*Notes* + +All the functions which return an int return < 0 on error + +TEXT*/ + +/*OVERVIEW + +ESSENTIAL + +pigpio_start Connects to a pigpio daemon +pigpio_stop Disconnects from a pigpio daemon + +BEGINNER + +set_mode Set a GPIO mode +get_mode Get a GPIO mode + +set_pull_up_down Set/clear GPIO pull up/down resistor + +gpio_read Read a GPIO +gpio_write Write a GPIO + +set_PWM_dutycycle Start/stop PWM pulses on a GPIO +get_PWM_dutycycle Get the PWM dutycycle in use on a GPIO + +set_servo_pulsewidth Start/stop servo pulses on a GPIO +get_servo_pulsewidth Get the servo pulsewidth in use on a GPIO + +callback Create GPIO level change callback +callback_ex Create GPIO level change callback, extended +callback_cancel Cancel a callback +wait_for_edge Wait for GPIO level change + +INTERMEDIATE + +gpio_trigger Send a trigger pulse to a GPIO. + +set_watchdog Set a watchdog on a GPIO. + +set_PWM_range Configure PWM range for a GPIO +get_PWM_range Get configured PWM range for a GPIO + +set_PWM_frequency Configure PWM frequency for a GPIO +get_PWM_frequency Get configured PWM frequency for a GPIO + +read_bank_1 Read all GPIO in bank 1 +read_bank_2 Read all GPIO in bank 2 + +clear_bank_1 Clear selected GPIO in bank 1 +clear_bank_2 Clear selected GPIO in bank 2 + +set_bank_1 Set selected GPIO in bank 1 +set_bank_2 Set selected GPIO in bank 2 + +start_thread Start a new thread +stop_thread Stop a previously started thread + +ADVANCED + +get_PWM_real_range Get underlying PWM range for a GPIO + +notify_open Request a notification handle +notify_begin Start notifications for selected GPIO +notify_pause Pause notifications +notify_close Close a notification + +bb_serial_read_open Opens a GPIO for bit bang serial reads +bb_serial_read Reads bit bang serial data from a GPIO +bb_serial_read_close Closes a GPIO for bit bang serial reads +bb_serial_invert Invert serial logic (1 invert, 0 normal) + +hardware_clock Start hardware clock on supported GPIO +hardware_PWM Start hardware PWM on supported GPIO + +set_glitch_filter Set a glitch filter on a GPIO +set_noise_filter Set a noise filter on a GPIO + +get_pad_strength Gets a pads drive strength +set_pad_strength Sets a pads drive strength + +shell_ Executes a shell command + +SCRIPTS + +store_script Store a script +run_script Run a stored script +update_script Set a scripts parameters +script_status Get script status and parameters +stop_script Stop a running script +delete_script Delete a stored script + +WAVES + +wave_clear Deletes all waveforms + +wave_add_new Starts a new waveform +wave_add_generic Adds a series of pulses to the waveform +wave_add_serial Adds serial data to the waveform + +wave_create Creates a waveform from added data +wave_delete Deletes one or more waveforms + +wave_send_once Transmits a waveform once +wave_send_repeat Transmits a waveform repeatedly +wave_send_using_mode Transmits a waveform in the chosen mode + +wave_chain Transmits a chain of waveforms + +wave_tx_at Returns the current transmitting waveform +wave_tx_busy Checks to see if the waveform has ended +wave_tx_stop Aborts the current waveform + +wave_get_micros Length in microseconds of the current waveform +wave_get_high_micros Length of longest waveform so far +wave_get_max_micros Absolute maximum allowed micros + +wave_get_pulses Length in pulses of the current waveform +wave_get_high_pulses Length of longest waveform so far +wave_get_max_pulses Absolute maximum allowed pulses + +wave_get_cbs Length in cbs of the current waveform +wave_get_high_cbs Length of longest waveform so far +wave_get_max_cbs Absolute maximum allowed cbs + +I2C + +i2c_open Opens an I2C device +i2c_close Closes an I2C device + +i2c_write_quick smbus write quick +i2c_write_byte smbus write byte +i2c_read_byte smbus read byte +i2c_write_byte_data smbus write byte data +i2c_write_word_data smbus write word data +i2c_read_byte_data smbus read byte data +i2c_read_word_data smbus read word data +i2c_process_call smbus process call +i2c_write_block_data smbus write block data +i2c_read_block_data smbus read block data +i2c_block_process_call smbus block process call + +i2c_write_i2c_block_data smbus write I2C block data +i2c_read_i2c_block_data smbus read I2C block data + +i2c_read_device Reads the raw I2C device +i2c_write_device Writes the raw I2C device + +i2c_zip Performs multiple I2C transactions + +bb_i2c_open Opens GPIO for bit banging I2C +bb_i2c_close Closes GPIO for bit banging I2C +bb_i2c_zip Performs multiple bit banged I2C transactions + +SPI + +spi_open Opens a SPI device +spi_close Closes a SPI device + +spi_read Reads bytes from a SPI device +spi_write Writes bytes to a SPI device +spi_xfer Transfers bytes with a SPI device + +bb_spi_open Opens GPIO for bit banging SPI +bb_spi_close Closes GPIO for bit banging SPI +bb_spi_xfer Transfers bytes with bit banging SPI + +I2C/SPI_SLAVE + +bsc_xfer I2C/SPI as slave transfer +bsc_i2c I2C as slave transfer + +SERIAL + +serial_open Opens a serial device +serial_close Closes a serial device + +serial_write_byte Writes a byte to a serial device +serial_read_byte Reads a byte from a serial device +serial_write Writes bytes to a serial device +serial_read Reads bytes from a serial device + +serial_data_available Returns number of bytes ready to be read + +FILES + +file_open Opens a file +file_close Closes a file +file_read Reads bytes from a file +file_write Writes bytes to a file +file_seek Seeks to a position within a file +file_list List files which match a pattern + +EVENTS + +event_callback Sets a callback for an event +event_callback_ex Sets a callback for an event, extended +event_callback_cancel Cancel an event callback +event_trigger Triggers an event +wait_for_event Wait for an event + +CUSTOM + +custom_1 User custom function 1 +custom_2 User custom function 2 + +UTILITIES + +get_current_tick Get current tick (microseconds) + +get_hardware_revision Get hardware revision +get_pigpio_version Get the pigpio version +pigpiod_if_version Get the pigpiod_if2 version + +pigpio_error Get a text description of an error code. + +time_sleep Sleeps for a float number of seconds +time_time Float number of seconds since the epoch + +OVERVIEW*/ + +#ifdef __cplusplus +extern "C" { +#endif + +typedef void (*CBFunc_t) + (int pi, unsigned user_gpio, unsigned level, uint32_t tick); + +typedef void (*CBFuncEx_t) + (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void *userdata); + +typedef struct callback_s callback_t; + +typedef void (*evtCBFunc_t) + (int pi, unsigned event, uint32_t tick); + +typedef void (*evtCBFuncEx_t) + (int pi, unsigned event, uint32_t tick, void *userdata); + +typedef struct evtCallback_s evtCallback_t; + +/*F*/ +double time_time(void); +/*D +Return the current time in seconds since the Epoch. +D*/ + +/*F*/ +void time_sleep(double seconds); +/*D +Delay execution for a given number of seconds. + +. . +seconds: the number of seconds to delay. +. . +D*/ + +/*F*/ +char *pigpio_error(int errnum); +/*D +Return a text description for an error code. + +. . +errnum: the error code. +. . +D*/ + +/*F*/ +unsigned pigpiod_if_version(void); +/*D +Return the pigpiod_if2 version. +D*/ + +/*F*/ +pthread_t *start_thread(gpioThreadFunc_t thread_func, void *userdata); +/*D +Starts a new thread of execution with thread_func as the main routine. + +. . +thread_func: the main function for the new thread. + userdata: a pointer to an arbitrary argument. +. . + +Returns a pointer to pthread_t if OK, otherwise NULL. + +The function is passed the single argument userdata. + +The thread can be cancelled by passing the pointer to pthread_t to +[*stop_thread*]. +D*/ + +/*F*/ +void stop_thread(pthread_t *pth); +/*D +Cancels the thread pointed at by pth. + +. . +pth: the thread to be stopped. +. . + +No value is returned. + +The thread to be stopped should have been started with [*start_thread*]. +D*/ + +/*F*/ +int pigpio_start(const char *addrStr, const char *portStr); +/*D +Connect to the pigpio daemon. Reserving command and +notification streams. + +. . +addrStr: specifies the host or IP address of the Pi running the + pigpio daemon. It may be NULL in which case localhost + is used unless overridden by the PIGPIO_ADDR environment + variable. + +portStr: specifies the port address used by the Pi running the + pigpio daemon. It may be NULL in which case "8888" + is used unless overridden by the PIGPIO_PORT environment + variable. +. . + +Returns an integer value greater than or equal to zero if OK. + +This value is passed to the GPIO routines to specify the Pi +to be operated on. +D*/ + +/*F*/ +void pigpio_stop(int pi); +/*D +Terminates the connection to a pigpio daemon and releases +resources used by the library. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int set_mode(int pi, unsigned gpio, unsigned mode); +/*D +Set the GPIO mode. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +gpio: 0-53. +mode: PI_INPUT, PI_OUTPUT, PI_ALT0, PI_ALT1, + PI_ALT2, PI_ALT3, PI_ALT4, PI_ALT5. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_MODE, +or PI_NOT_PERMITTED. +D*/ + +/*F*/ +int get_mode(int pi, unsigned gpio); +/*D +Get the GPIO mode. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +gpio: 0-53. +. . + +Returns the GPIO mode if OK, otherwise PI_BAD_GPIO. +D*/ + +/*F*/ +int set_pull_up_down(int pi, unsigned gpio, unsigned pud); +/*D +Set or clear the GPIO pull-up/down resistor. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +gpio: 0-53. + pud: PI_PUD_UP, PI_PUD_DOWN, PI_PUD_OFF. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_PUD, +or PI_NOT_PERMITTED. +D*/ + +/*F*/ +int gpio_read(int pi, unsigned gpio); +/*D +Read the GPIO level. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +gpio:0-53. +. . + +Returns the GPIO level if OK, otherwise PI_BAD_GPIO. +D*/ + +/*F*/ +int gpio_write(int pi, unsigned gpio, unsigned level); +/*D +Write the GPIO level. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + gpio: 0-53. +level: 0, 1. +. . + +Returns 0 if OK, otherwise PI_BAD_GPIO, PI_BAD_LEVEL, +or PI_NOT_PERMITTED. + +Notes + +If PWM or servo pulses are active on the GPIO they are switched off. +D*/ + +/*F*/ +int set_PWM_dutycycle(int pi, unsigned user_gpio, unsigned dutycycle); +/*D +Start (non-zero dutycycle) or stop (0) PWM pulses on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +dutycycle: 0-range (range defaults to 255). +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYCYCLE, +or PI_NOT_PERMITTED. +Notes + +The [*set_PWM_range*] function may be used to change the +default range of 255. +D*/ + +/*F*/ +int get_PWM_dutycycle(int pi, unsigned user_gpio); +/*D +Return the PWM dutycycle in use on a GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_PWM_GPIO. + +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see [*get_PWM_range*]). + +If a hardware clock is active on the GPIO the reported dutycycle +will be 500000 (500k) out of 1000000 (1M). + +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). +D*/ + +/*F*/ +int set_PWM_range(int pi, unsigned user_gpio, unsigned range); +/*D +Set the range of PWM values to be used on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + range: 25-40000. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_DUTYRANGE, +or PI_NOT_PERMITTED. + +Notes + +If PWM is currently active on the GPIO its dutycycle will be +scaled to reflect the new range. + +The real range, the number of steps between fully off and fully on +for each of the 18 available GPIO frequencies is + +. . + 25(#1), 50(#2), 100(#3), 125(#4), 200(#5), 250(#6), + 400(#7), 500(#8), 625(#9), 800(#10), 1000(#11), 1250(#12), +2000(#13), 2500(#14), 4000(#15), 5000(#16), 10000(#17), 20000(#18) +. . + +The real value set by set_PWM_range is (dutycycle * real range) / range. +D*/ + +/*F*/ +int get_PWM_range(int pi, unsigned user_gpio); +/*D +Get the range of PWM values being used on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +. . + +Returns the dutycycle range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +If a hardware clock or hardware PWM is active on the GPIO the +reported range will be 1000000 (1M). +D*/ + +/*F*/ +int get_PWM_real_range(int pi, unsigned user_gpio); +/*D +Get the real underlying range of PWM values being used on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +. . + +Returns the real range used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. + +If a hardware clock is active on the GPIO the reported +real range will be 1000000 (1M). + +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +D*/ + +/*F*/ +int set_PWM_frequency(int pi, unsigned user_gpio, unsigned frequency); +/*D +Set the frequency (in Hz) of the PWM to be used on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +frequency: >=0 (Hz). +. . + +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO or PI_NOT_PERMITTED. + +If PWM is currently active on the GPIO it will be switched +off and then back on at the new frequency. + +Each GPIO can be independently set to one of 18 different +PWM frequencies. + +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The +sample rate is set when the pigpio daemon is started. + +The frequencies for each sample rate are: + +. . + Hertz + + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 + 1250 1000 800 500 400 250 200 100 50 + + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 + 625 500 400 250 200 125 100 50 25 + + 4: 10000 5000 2500 2000 1250 1000 625 500 400 + 313 250 200 125 100 63 50 25 13 +sample + rate + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 + 250 200 160 100 80 50 40 20 10 + + 8: 5000 2500 1250 1000 625 500 313 250 200 + 156 125 100 63 50 31 25 13 6 + + 10: 4000 2000 1000 800 500 400 250 200 160 + 125 100 80 50 40 25 20 10 5 +. . +D*/ + +/*F*/ +int get_PWM_frequency(int pi, unsigned user_gpio); +/*D +Get the frequency of PWM being used on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +. . + +For normal PWM the frequency will be that defined for the GPIO by +[*set_PWM_frequency*]. + +If a hardware clock is active on the GPIO the reported frequency +will be that set by [*hardware_clock*]. + +If hardware PWM is active on the GPIO the reported frequency +will be that set by [*hardware_PWM*]. + +Returns the frequency (in hertz) used for the GPIO if OK, +otherwise PI_BAD_USER_GPIO. +D*/ + +/*F*/ +int set_servo_pulsewidth(int pi, unsigned user_gpio, unsigned pulsewidth); +/*D +Start (500-2500) or stop (0) servo pulses on the GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + user_gpio: 0-31. +pulsewidth: 0 (off), 500 (anti-clockwise) - 2500 (clockwise). +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_PULSEWIDTH or +PI_NOT_PERMITTED. + +The selected pulsewidth will continue to be transmitted until +changed by a subsequent call to set_servo_pulsewidth. + +The pulsewidths supported by servos varies and should probably be +determined by experiment. A value of 1500 should always be safe and +represents the mid-point of rotation. + +You can DAMAGE a servo if you command it to move beyond its limits. + +OTHER UPDATE RATES: + +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. + +. . +Update Rate (Hz) 50 100 200 400 500 +1E6/Hz 20000 10000 5000 2500 2000 +. . + +Firstly set the desired PWM frequency using [*set_PWM_frequency*]. + +Then set the PWM range using [*set_PWM_range*] to 1E6/Hz. +Doing this allows you to use units of microseconds when setting +the servo pulsewidth. + +E.g. If you want to update a servo connected to GPIO 25 at 400Hz + +. . +set_PWM_frequency(25, 400); +set_PWM_range(25, 2500); +. . + +Thereafter use the [*set_PWM_dutycycle*] function to move the servo, +e.g. set_PWM_dutycycle(25, 1500) will set a 1500 us pulse. +D*/ + +/*F*/ +int get_servo_pulsewidth(int pi, unsigned user_gpio); +/*D +Return the servo pulsewidth in use on a GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERVO_GPIO. +D*/ + +/*F*/ +int notify_open(int pi); +/*D +Get a free notification handle. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. + +A notification is a method for being notified of GPIO state +changes via a pipe. + +Pipes are only accessible from the local machine so this function +serves no purpose if you are using the library from a remote machine. +The in-built (socket) notifications provided by [*callback*] +should be used instead. + +Notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). +E.g. if the function returns 15 then the notifications must be +read from /dev/pigpio15. +D*/ + +/*F*/ +int notify_begin(int pi, unsigned handle, uint32_t bits); +/*D +Start notifications on a previously opened handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: 0-31 (as returned by [*notify_open*]) + bits: a mask indicating the GPIO to be notified. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +The notification sends state changes for each GPIO whose +corresponding bit in bits is set. + +Each notification occupies 12 bytes in the fifo as follows: + +. . +typedef struct +{ + uint16_t seqno; + uint16_t flags; + uint32_t tick; + uint32_t level; +} gpioReport_t; +. . + +seqno: starts at 0 each time the handle is opened and then increments +by one for each report. + +flags: three flags are defined, PI_NTFY_FLAGS_WDOG, +PI_NTFY_FLAGS_ALIVE, and PI_NTFY_FLAGS_EVENT. + +If bit 5 is set (PI_NTFY_FLAGS_WDOG) then bits 0-4 of the flags +indicate a GPIO which has had a watchdog timeout. + +If bit 6 is set (PI_NTFY_FLAGS_ALIVE) this indicates a keep alive +signal on the pipe/socket and is sent once a minute in the absence +of other notification activity. + +If bit 7 is set (PI_NTFY_FLAGS_EVENT) then bits 0-4 of the flags +indicate an event which has been triggered. + +tick: the number of microseconds since system boot. It wraps around +after 1h12m. + +level: indicates the level of each GPIO. If bit 1<=0 (as returned by [*pigpio_start*]). +handle: 0-31 (as returned by [*notify_open*]) +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +Notifications for the handle are suspended until +[*notify_begin*] is called again. +D*/ + +/*F*/ +int notify_close(int pi, unsigned handle); +/*D +Stop notifications on a previously opened handle and +release the handle for reuse. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: 0-31 (as returned by [*notify_open*]) +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int set_watchdog(int pi, unsigned user_gpio, unsigned timeout); +/*D +Sets a watchdog for a GPIO. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + timeout: 0-60000. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO +or PI_BAD_WDOG_TIMEOUT. + +The watchdog is nominally in milliseconds. + +Only one watchdog may be registered per GPIO. + +The watchdog may be cancelled by setting timeout to 0. + +Once a watchdog has been started callbacks for the GPIO will be +triggered every timeout interval after the last GPIO activity. + +The callback will receive the special level PI_TIMEOUT. +D*/ + +/*F*/ +int set_glitch_filter(int pi, unsigned user_gpio, unsigned steady); +/*D +Sets a glitch filter on a GPIO. + +Level changes on the GPIO are not reported unless the level +has been stable for at least [*steady*] microseconds. The +level is then reported. Level changes of less than +[*steady*] microseconds are ignored. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31 + steady: 0-300000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +This filter affects the GPIO samples returned to callbacks set up +with [*callback*], [*callback_ex*] and [*wait_for_edge*]. + +It does not affect levels read by [*gpio_read*], +[*read_bank_1*], or [*read_bank_2*]. + +Each (stable) edge will be timestamped [*steady*] microseconds +after it was first detected. +D*/ + +/*F*/ +int set_noise_filter( + int pi, unsigned user_gpio, unsigned steady, unsigned active); +/*D +Sets a noise filter on a GPIO. + +Level changes on the GPIO are ignored until a level which has +been stable for [*steady*] microseconds is detected. Level changes +on the GPIO are then reported for [*active*] microseconds after +which the process repeats. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31 + steady: 0-300000 + active: 0-1000000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_BAD_FILTER. + +This filter affects the GPIO samples returned to callbacks set up +with [*callback*], [*callback_ex*] and [*wait_for_edge*]. + +It does not affect levels read by [*gpio_read*], +[*read_bank_1*], or [*read_bank_2*]. + +Level changes before and after the active period may +be reported. Your software must be designed to cope with +such reports. +D*/ + +/*F*/ +uint32_t read_bank_1(int pi); +/*D +Read the levels of the bank 1 GPIO (GPIO 0-31). + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +The returned 32 bit integer has a bit set if the corresponding +GPIO is logic 1. GPIO n has bit value (1<=0 (as returned by [*pigpio_start*]). +. . + +The returned 32 bit integer has a bit set if the corresponding +GPIO is logic 1. GPIO n has bit value (1<<(n-32)). +D*/ + +/*F*/ +int clear_bank_1(int pi, uint32_t bits); +/*D +Clears GPIO 0-31 if the corresponding bit in bits is set. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +bits: a bit mask with 1 set if the corresponding GPIO is + to be cleared. +. . + +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. +D*/ + +/*F*/ +int clear_bank_2(int pi, uint32_t bits); +/*D +Clears GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +bits: a bit mask with 1 set if the corresponding GPIO is + to be cleared. +. . + +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. +D*/ + +/*F*/ +int set_bank_1(int pi, uint32_t bits); +/*D +Sets GPIO 0-31 if the corresponding bit in bits is set. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +bits: a bit mask with 1 set if the corresponding GPIO is + to be set. +. . + +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. +D*/ + +/*F*/ +int set_bank_2(int pi, uint32_t bits); +/*D +Sets GPIO 32-53 if the corresponding bit (0-21) in bits is set. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +bits: a bit mask with 1 set if the corresponding GPIO is + to be set. +. . + +Returns 0 if OK, otherwise PI_SOME_PERMITTED. + +A status of PI_SOME_PERMITTED indicates that the user is not +allowed to write to one or more of the GPIO. +D*/ + + +/*F*/ +int hardware_clock(int pi, unsigned gpio, unsigned clkfreq); +/*D +Starts a hardware clock on a GPIO at the specified frequency. +Frequencies above 30MHz are unlikely to work. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + gpio: see description +frequency: 0 (off) or 4689-250000000 (250M) +. . + +Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO, +PI_NOT_HCLK_GPIO, PI_BAD_HCLK_FREQ,or PI_BAD_HCLK_PASS. + +The same clock is available on multiple GPIO. The latest +frequency setting will be used by all GPIO which share a clock. + +The GPIO must be one of the following. + +. . +4 clock 0 All models +5 clock 1 All models but A and B (reserved for system use) +6 clock 2 All models but A and B +20 clock 0 All models but A and B +21 clock 1 All models but A and Rev.2 B (reserved for system use) + +32 clock 0 Compute module only +34 clock 0 Compute module only +42 clock 1 Compute module only (reserved for system use) +43 clock 2 Compute module only +44 clock 1 Compute module only (reserved for system use) +. . + +Access to clock 1 is protected by a password as its use will likely +crash the Pi. The password is given by or'ing 0x5A000000 with the +GPIO number. +D*/ + + +/*F*/ +int hardware_PWM(int pi, unsigned gpio, unsigned PWMfreq, uint32_t PWMduty); +/*D +Starts hardware PWM on a GPIO at the specified frequency and dutycycle. +Frequencies above 30MHz are unlikely to work. + +NOTE: Any waveform started by [*wave_send_**] or [*wave_chain*] +will be cancelled. + +This function is only valid if the pigpio main clock is PCM. The +main clock defaults to PCM but may be overridden when the pigpio +daemon is started (option -t). + +. . + pi: >=0 (as returned by [*pigpio_start*]). + gpio: see descripton +PWMfreq: 0 (off) or 1-125000000 (125M) +PWMduty: 0 (off) to 1000000 (1M)(fully on) +. . + +Returns 0 if OK, otherwise PI_NOT_PERMITTED, PI_BAD_GPIO, +PI_NOT_HPWM_GPIO, PI_BAD_HPWM_DUTY, PI_BAD_HPWM_FREQ, +or PI_HPWM_ILLEGAL. + +The same PWM channel is available on multiple GPIO. The latest +frequency and dutycycle setting will be used by all GPIO which +share a PWM channel. + +The GPIO must be one of the following. + +. . +12 PWM channel 0 All models but A and B +13 PWM channel 1 All models but A and B +18 PWM channel 0 All models +19 PWM channel 1 All models but A and B + +40 PWM channel 0 Compute module only +41 PWM channel 1 Compute module only +45 PWM channel 1 Compute module only +52 PWM channel 0 Compute module only +53 PWM channel 1 Compute module only +. . + +The actual number of steps beween off and fully on is the +integral part of 250 million divided by PWMfreq. + +The actual frequency set is 250 million / steps. + +There will only be a million steps for a PWMfreq of 250. +Lower frequencies will have more steps and higher +frequencies will have fewer steps. PWMduty is +automatically scaled to take this into account. +D*/ + + +/*F*/ +uint32_t get_current_tick(int pi); +/*D +Gets the current system tick. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Tick is the number of microseconds since system boot. + +As tick is an unsigned 32 bit quantity it wraps around after +2**32 microseconds, which is approximately 1 hour 12 minutes. + +D*/ + +/*F*/ +uint32_t get_hardware_revision(int pi); +/*D +Get the Pi's hardware revision number. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +The hardware revision is the last few characters on the Revision line +of /proc/cpuinfo. + +If the hardware revision can not be found or is not a valid +hexadecimal number the function returns 0. + +The revision number can be used to determine the assignment of GPIO +to pins (see [*gpio*]). + +There are at least three types of board. + +Type 1 boards have hardware revision numbers of 2 and 3. + +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. + +Type 3 boards have hardware revision numbers of 16 or greater. +D*/ + +/*F*/ +uint32_t get_pigpio_version(int pi); +/*D +Returns the pigpio version. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + + +/*F*/ +int wave_clear(int pi); +/*D +This function clears all waveforms and any data added by calls to the +[*wave_add_**] functions. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Returns 0 if OK. +D*/ + +/*F*/ +int wave_add_new(int pi); +/*D +This function starts a new empty waveform. You wouldn't normally need +to call this function as it is automatically called after a waveform is +created with the [*wave_create*] function. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Returns 0 if OK. +D*/ + +/*F*/ +int wave_add_generic(int pi, unsigned numPulses, gpioPulse_t *pulses); +/*D +This function adds a number of pulses to the current waveform. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +numPulses: the number of pulses. + pulses: an array of pulses. +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. + +The pulses are interleaved in time order within the existing waveform +(if any). + +Merging allows the waveform to be built in parts, that is the settings +for GPIO#1 can be added, and then GPIO#2 etc. + +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist solely of a delay. +D*/ + +/*F*/ +int wave_add_serial + (int pi, unsigned user_gpio, unsigned baud, unsigned data_bits, + unsigned stop_bits, unsigned offset, unsigned numBytes, char *str); +/*D +This function adds a waveform representing serial data to the +existing waveform (if any). The serial data starts offset +microseconds from the start of the waveform. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + baud: 50-1000000 +data_bits: number of data bits (1-32) +stop_bits: number of stop half bits (2-8) + offset: >=0 + numBytes: >=1 + str: an array of chars. +. . + +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_BAD_DATABITS, +PI_BAD_STOP_BITS, PI_TOO_MANY_CHARS, PI_BAD_SER_OFFSET, +or PI_TOO_MANY_PULSES. + +NOTES: + +The serial data is formatted as one start bit, [*data_bits*] data bits, +and [*stop_bits*]/2 stop bits. + +It is legal to add serial data streams with different baud rates to +the same waveform. + +[*numBytes*] is the number of bytes of data in str. + +The bytes required for each character depend upon [*data_bits*]. + +For [*data_bits*] 1-8 there will be one byte per character. +For [*data_bits*] 9-16 there will be two bytes per character. +For [*data_bits*] 17-32 there will be four bytes per character. +D*/ + +/*F*/ +int wave_create(int pi); +/*D +This function creates a waveform from the data provided by the prior +calls to the [*wave_add_**] functions. Upon success a wave id +greater than or equal to 0 is returned, otherwise PI_EMPTY_WAVEFORM, +PI_TOO_MANY_CBS, PI_TOO_MANY_OOL, or PI_NO_WAVEFORM_ID. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +The data provided by the [*wave_add_**] functions is consumed by this +function. + +As many waveforms may be created as there is space available. The +wave id is passed to [*wave_send_**] to specify the waveform to transmit. + +Normal usage would be + +Step 1. [*wave_clear*] to clear all waveforms and added data. + +Step 2. [*wave_add_**] calls to supply the waveform data. + +Step 3. [*wave_create*] to create the waveform and get a unique id + +Repeat steps 2 and 3 as needed. + +Step 4. [*wave_send_**] with the id of the waveform to transmit. + +A waveform comprises one or more pulses. Each pulse consists of a +[*gpioPulse_t*] structure. + +. . +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; +. . + +The fields specify + +1) the GPIO to be switched on at the start of the pulse. +2) the GPIO to be switched off at the start of the pulse. +3) the delay in microseconds before the next pulse. + +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). + +When a waveform is started each pulse is executed in order with the +specified delay between the pulse and the next. + +Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, +PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. +D*/ + + +/*F*/ +int wave_delete(int pi, unsigned wave_id); +/*D +This function deletes the waveform with id wave_id. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +wave_id: >=0, as returned by [*wave_create*]. +. . + +Wave ids are allocated in order, 0, 1, 2, etc. + +The wave is flagged for deletion. The resources used by the wave +will only be reused when either of the following apply. + +- all waves with higher numbered wave ids have been deleted or have +been flagged for deletion. + +- a new wave is created which uses exactly the same resources as +the current wave (see the C source for gpioWaveCreate for details). + +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. +D*/ + + +/*F*/ +int wave_send_once(int pi, unsigned wave_id); +/*D +This function transmits the waveform with id wave_id. The waveform +is sent once. + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +wave_id: >=0, as returned by [*wave_create*]. +. . + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + + +/*F*/ +int wave_send_repeat(int pi, unsigned wave_id); +/*D +This function transmits the waveform with id wave_id. The waveform +cycles until cancelled (either by the sending of a new waveform or +by [*wave_tx_stop*]). + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +wave_id: >=0, as returned by [*wave_create*]. +. . + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + + +/*F*/ +int wave_send_using_mode(int pi, unsigned wave_id, unsigned mode); +/*D +Transmits the waveform with id wave_id using mode mode. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +wave_id: >=0, as returned by [*wave_create*]. + mode: PI_WAVE_MODE_ONE_SHOT, PI_WAVE_MODE_REPEAT, + PI_WAVE_MODE_ONE_SHOT_SYNC, or PI_WAVE_MODE_REPEAT_SYNC. +. . + +PI_WAVE_MODE_ONE_SHOT: same as [*wave_send_once*]. + +PI_WAVE_MODE_REPEAT same as [*wave_send_repeat*]. + +PI_WAVE_MODE_ONE_SHOT_SYNC same as [*wave_send_once*] but tries +to sync with the previous waveform. + +PI_WAVE_MODE_REPEAT_SYNC same as [*wave_send_repeat*] but tries +to sync with the previous waveform. + +WARNING: bad things may happen if you delete the previous +waveform before it has been synced to the new waveform. + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +D*/ + +/*F*/ +int wave_chain(int pi, char *buf, unsigned bufSize); +/*D +This function transmits a chain of waveforms. + +NOTE: Any hardware PWM started by [*hardware_PWM*] will be cancelled. + +The waves to be transmitted are specified by the contents of buf +which contains an ordered list of [*wave_id*]s and optional command +codes and related data. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + buf: pointer to the wave_ids and optional command codes +bufSize: the number of bytes in buf +. . + +Returns 0 if OK, otherwise PI_CHAIN_NESTING, PI_CHAIN_LOOP_CNT, PI_BAD_CHAIN_LOOP, PI_BAD_CHAIN_CMD, PI_CHAIN_COUNTER, +PI_BAD_CHAIN_DELAY, PI_CHAIN_TOO_BIG, or PI_BAD_WAVE_ID. + +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +Delays between waves may be added with the delay command. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +Loop Start @ 255 0 @ Identify start of a wave block +Loop Repeat @ 255 1 x y @ loop x + y*256 times +Delay @ 255 2 x y @ delay x + y*256 microseconds +Loop Forever @ 255 3 @ loop forever + +If present Loop Forever must be the last entry in the chain. + +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +... +#include +#include + +#define WAVES 5 +#define GPIO 4 + +int main(int argc, char *argv[]) +{ + int i, pi, wid[WAVES]; + + pi = pigpio_start(0, 0); + if (pi<0) return -1; + + set_mode(pi, GPIO, PI_OUTPUT); + + for (i=0; i=0 (as returned by [*pigpio_start*]). +. . + +Returns the waveform id or one of the following special values: + +PI_WAVE_NOT_FOUND (9998) - transmitted wave not found. +PI_NO_TX_WAVE (9999) - no wave being transmitted. +D*/ + +/*F*/ +int wave_tx_busy(int pi); +/*D +This function checks to see if a waveform is currently being +transmitted. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Returns 1 if a waveform is currently being transmitted, otherwise 0. +D*/ + +/*F*/ +int wave_tx_stop(int pi); +/*D +This function stops the transmission of the current waveform. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . + +Returns 0 if OK. + +This function is intended to stop a waveform started with the repeat mode. +D*/ + +/*F*/ +int wave_get_micros(int pi); +/*D +This function returns the length in microseconds of the current +waveform. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_high_micros(int pi); +/*D +This function returns the length in microseconds of the longest waveform +created since the pigpio daemon was started. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_max_micros(int pi); +/*D +This function returns the maximum possible size of a waveform in +microseconds. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_pulses(int pi); +/*D +This function returns the length in pulses of the current waveform. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_high_pulses(int pi); +/*D +This function returns the length in pulses of the longest waveform +created since the pigpio daemon was started. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_max_pulses(int pi); +/*D +This function returns the maximum possible size of a waveform in pulses. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_cbs(int pi); +/*D +This function returns the length in DMA control blocks of the current +waveform. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_high_cbs(int pi); +/*D +This function returns the length in DMA control blocks of the longest +waveform created since the pigpio daemon was started. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int wave_get_max_cbs(int pi); +/*D +This function returns the maximum possible size of a waveform in DMA +control blocks. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +. . +D*/ + +/*F*/ +int gpio_trigger(int pi, unsigned user_gpio, unsigned pulseLen, unsigned level); +/*D +This function sends a trigger pulse to a GPIO. The GPIO is set to +level for pulseLen microseconds and then reset to not level. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + pulseLen: 1-100. + level: 0,1. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, +PI_BAD_PULSELEN, or PI_NOT_PERMITTED. +D*/ + +/*F*/ +int store_script(int pi, char *script); +/*D +This function stores a script for later execution. + +See [[http://abyz.me.uk/rpi/pigpio/pigs.html#Scripts]] for details. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script: the text of the script. +. . + +The function returns a script id if the script is valid, +otherwise PI_BAD_SCRIPT. +D*/ + +/*F*/ +int run_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param); +/*D +This function runs a stored script. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script_id: >=0, as returned by [*store_script*]. + numPar: 0-10, the number of parameters. + param: an array of parameters. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + +/*F*/ +int update_script(int pi, unsigned script_id, unsigned numPar, uint32_t *param); +/*D +This function sets the parameters of a script. The script may or +may not be running. The first numPar parameters of the script are +overwritten with the new values. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script_id: >=0, as returned by [*store_script*]. + numPar: 0-10, the number of parameters. + param: an array of parameters. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. + +param is an array of up to 10 parameters which may be referenced in +the script as p0 to p9. +D*/ + +/*F*/ +int script_status(int pi, unsigned script_id, uint32_t *param); +/*D +This function returns the run status of a stored script as well +as the current values of parameters 0 to 9. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script_id: >=0, as returned by [*store_script*]. + param: an array to hold the returned 10 parameters. +. . + +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. + +The run status may be + +. . +PI_SCRIPT_INITING +PI_SCRIPT_HALTED +PI_SCRIPT_RUNNING +PI_SCRIPT_WAITING +PI_SCRIPT_FAILED +. . + +The current value of script parameters 0 to 9 are returned in param. +D*/ + +/*F*/ +int stop_script(int pi, unsigned script_id); +/*D +This function stops a running script. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script_id: >=0, as returned by [*store_script*]. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + +/*F*/ +int delete_script(int pi, unsigned script_id); +/*D +This function deletes a stored script. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +script_id: >=0, as returned by [*store_script*]. +. . + +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +D*/ + +/*F*/ +int bb_serial_read_open(int pi, unsigned user_gpio, unsigned baud, unsigned data_bits); +/*D +This function opens a GPIO for bit bang reading of serial data. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + baud: 50-250000 +data_bits: 1-32 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, +or PI_GPIO_IN_USE. + +The serial data is returned in a cyclic buffer and is read using +bb_serial_read. + +It is the caller's responsibility to read data from the cyclic buffer +in a timely fashion. +D*/ + +/*F*/ +int bb_serial_read(int pi, unsigned user_gpio, void *buf, size_t bufSize); +/*D +This function copies up to bufSize bytes of data read from the +bit bang serial cyclic buffer to the buffer starting at buf. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. + buf: an array to receive the read bytes. + bufSize: >=0 +. . + +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. + +The bytes returned for each character depend upon the number of +data bits [*data_bits*] specified in the [*bb_serial_read_open*] command. + +For [*data_bits*] 1-8 there will be one byte per character. +For [*data_bits*] 9-16 there will be two bytes per character. +For [*data_bits*] 17-32 there will be four bytes per character. +D*/ + +/*F*/ +int bb_serial_read_close(int pi, unsigned user_gpio); +/*D +This function closes a GPIO for bit bang reading of serial data. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. +D*/ + +/*F*/ +int bb_serial_invert(int pi, unsigned user_gpio, unsigned invert); +/*D +This function inverts serial logic for big bang serial reads. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31, previously opened with [*bb_serial_read_open*]. + invert: 0-1, 1 invert, 0 normal. +. . + +Returns 0 if OK, otherwise PI_NOT_SERIAL_GPIO or PI_BAD_SER_INVERT. +D*/ + +/*F*/ +int i2c_open(int pi, unsigned i2c_bus, unsigned i2c_addr, unsigned i2c_flags); +/*D +This returns a handle for the device at address i2c_addr on bus i2c_bus. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + i2c_bus: >=0. + i2c_addr: 0-0x7F. +i2c_flags: 0. +. . + +No flags are currently defined. This parameter should be set to zero. + +Physically buses 0 and 1 are available on the Pi. Higher numbered buses +will be available if a kernel supported bus multiplexor is being used. + +The GPIO used are given in the following table. + + @ SDA @ SCL +I2C 0 @ 0 @ 1 +I2C 1 @ 2 @ 3 + +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. + +For the SMBus commands the low level transactions are shown at the end +of the function description. The following abbreviations are used. + +. . +S (1 bit) : Start bit +P (1 bit) : Stop bit +Rd/Wr (1 bit) : Read/Write bit. Rd equals 1, Wr equals 0. +A, NA (1 bit) : Accept and not accept bit. +Addr (7 bits): I2C 7 bit address. +i2c_reg (8 bits): A byte which often selects a register. +Data (8 bits): A data byte. +Count (8 bits): A byte defining the length of a block operation. + +[..]: Data sent by the device. +. . +D*/ + +/*F*/ +int i2c_close(int pi, unsigned handle); +/*D +This closes the I2C device associated with the handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int i2c_write_quick(int pi, unsigned handle, unsigned bit); +/*D +This sends a single bit (in the Rd/Wr bit) to the device associated +with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. + bit: 0-1, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Quick command. SMBus 2.0 5.5.1 +. . +S Addr bit [A] P +. . +D*/ + +/*F*/ +int i2c_write_byte(int pi, unsigned handle, unsigned bVal); +/*D +This sends a single byte to the device associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. + bVal: 0-0xFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Send byte. SMBus 2.0 5.5.2 +. . +S Addr Wr [A] bVal [A] P +. . +D*/ + +/*F*/ +int i2c_read_byte(int pi, unsigned handle); +/*D +This reads a single byte from the device associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. + +Receive byte. SMBus 2.0 5.5.3 +. . +S Addr Rd [A] [Data] NA P +. . +D*/ + +/*F*/ +int i2c_write_byte_data( + int pi, unsigned handle, unsigned i2c_reg, unsigned bVal); +/*D +This writes a single byte to the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + bVal: 0-0xFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write byte. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] i2c_reg [A] bVal [A] P +. . +D*/ + +/*F*/ +int i2c_write_word_data( + int pi, unsigned handle, unsigned i2c_reg, unsigned wVal); +/*D +This writes a single 16 bit word to the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + wVal: 0-0xFFFF, the value to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Write word. SMBus 2.0 5.5.4 +. . +S Addr Wr [A] i2c_reg [A] wval_Low [A] wVal_High [A] P +. . +D*/ + +/*F*/ +int i2c_read_byte_data(int pi, unsigned handle, unsigned i2c_reg); +/*D +This reads a single byte from the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. +. . + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read byte. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] i2c_reg [A] S Addr Rd [A] [Data] NA P +. . +D*/ + +/*F*/ +int i2c_read_word_data(int pi, unsigned handle, unsigned i2c_reg); +/*D +This reads a single 16 bit word from the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Read word. SMBus 2.0 5.5.5 +. . +S Addr Wr [A] i2c_reg [A] + S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + +/*F*/ +int i2c_process_call(int pi, unsigned handle, unsigned i2c_reg, unsigned wVal); +/*D +This writes 16 bits of data to the specified register of the device +associated with handle and and reads 16 bits of data in return. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write/read. + wVal: 0-0xFFFF, the value to write. +. . + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Process call. SMBus 2.0 5.5.6 +. . +S Addr Wr [A] i2c_reg [A] wVal_Low [A] wVal_High [A] + S Addr Rd [A] [DataLow] A [DataHigh] NA P +. . +D*/ + +/*F*/ +int i2c_write_block_data( + int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes up to 32 bytes to the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + buf: an array with the data to send. + count: 1-32, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +Block write. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] buf1 [A] ... + [A] bufn [A] P +. . +D*/ + +/*F*/ +int i2c_read_block_data(int pi, unsigned handle, unsigned i2c_reg, char *buf); +/*D +This reads a block of up to 32 bytes from the specified register of +the device associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. + buf: an array to receive the read data. +. . + +The amount of returned data is set by the device. + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +Block read. SMBus 2.0 5.5.7 +. . +S Addr Wr [A] i2c_reg [A] + S Addr Rd [A] [Count] A [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + +/*F*/ +int i2c_block_process_call( + int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write/read. + buf: an array with the data to send and to receive the read data. + count: 1-32, the number of bytes to write. +. . + + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +The smbus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. + +Block write-block read. SMBus 2.0 5.5.8 +. . +S Addr Wr [A] i2c_reg [A] count [A] buf0 [A] ... + S Addr Rd [A] [Count] A [Data] ... A P +. . +D*/ + +/*F*/ +int i2c_read_i2c_block_data( + int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to read. + buf: an array to receive the read data. + count: 1-32, the number of bytes to read. +. . + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +. . +S Addr Wr [A] i2c_reg [A] + S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + + +/*F*/ +int i2c_write_i2c_block_data( + int pi, unsigned handle, unsigned i2c_reg, char *buf, unsigned count); +/*D +This writes 1 to 32 bytes to the specified register of the device +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0, as returned by a call to [*i2c_open*]. +i2c_reg: 0-255, the register to write. + buf: the data to write. + count: 1-32, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +. . +S Addr Wr [A] i2c_reg [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +. . +D*/ + +/*F*/ +int i2c_read_device(int pi, unsigned handle, char *buf, unsigned count); +/*D +This reads count bytes from the raw device into buf. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. + buf: an array to receive the read data bytes. + count: >0, the number of bytes to read. +. . + +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. + +. . +S Addr Rd [A] [buf0] A [buf1] A ... A [bufn] NA P +. . +D*/ + +/*F*/ +int i2c_write_device(int pi, unsigned handle, char *buf, unsigned count); +/*D +This writes count bytes from buf to the raw device. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2c_open*]. + buf: an array containing the data bytes to write. + count: >0, the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. + +. . +S Addr Wr [A] buf0 [A] buf1 [A] ... [A] bufn [A] P +. . +D*/ + +/*F*/ +int i2c_zip( + int pi, + unsigned handle, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*i2cOpen*] + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_HANDLE, PI_BAD_POINTER, PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN. +PI_BAD_I2C_WLEN, or PI_BAD_I2C_SEG. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +On @ 2 @ Switch combined flag on +Off @ 3 @ Switch combined flag off +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address defaults to that associated with the handle. +The flags default to 0. The address and flags maintain their +previous value until updated. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53, write 0x32, read 6 bytes +Set address 0x1E, write 0x03, read 6 bytes +Set address 0x68, write 0x1B, read 8 bytes +End + +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +0x00 +... + +D*/ + +/*F*/ +int bb_i2c_open(int pi, unsigned SDA, unsigned SCL, unsigned baud); +/*D +This function selects a pair of GPIO for bit banging I2C at a +specified baud rate. + +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +o baud rates as low as 50 +o repeated starts +o clock stretching +o I2C on any pair of spare GPIO + +. . + pi: >=0 (as returned by [*pigpio_start*]). + SDA: 0-31 + SCL: 0-31 +baud: 50-500000 +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_I2C_BAUD, or +PI_GPIO_IN_USE. + +NOTE: + +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. +D*/ + +/*F*/ +int bb_i2c_close(int pi, unsigned SDA); +/*D +This function stops bit banging I2C on a pair of GPIO previously +opened with [*bb_i2c_open*]. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +SDA: 0-31, the SDA GPIO used in a prior call to [*bb_i2c_open*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_I2C_GPIO. +D*/ + +/*F*/ +int bb_i2c_zip( + int pi, + unsigned SDA, + char *inBuf, + unsigned inLen, + char *outBuf, + unsigned outLen); +/*D +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of inBuf +which contains the concatenated command codes and associated data. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + SDA: 0-31 (as used in a prior call to [*bb_i2c_open*]) + inBuf: pointer to the concatenated I2C commands, see below + inLen: size of command buffer +outBuf: pointer to buffer to hold returned data +outLen: size of output buffer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_I2C_GPIO, PI_BAD_POINTER, +PI_BAD_I2C_CMD, PI_BAD_I2C_RLEN, PI_BAD_I2C_WLEN, +PI_I2C_READ_FAILED, or PI_I2C_WRITE_FAILED. + +The following command codes are supported: + +Name @ Cmd & Data @ Meaning +End @ 0 @ No more commands +Escape @ 1 @ Next P is two bytes +Start @ 2 @ Start condition +Stop @ 3 @ Stop condition +Address @ 4 P @ Set I2C address to P +Flags @ 5 lsb msb @ Set I2C flags to lsb + (msb << 8) +Read @ 6 P @ Read P bytes of data +Write @ 7 P ... @ Write P bytes of data + +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +No flags are currently defined. + +The returned I2C data is stored in consecutive locations of outBuf. + +... +Set address 0x53 +start, write 0x32, (re)start, read 6 bytes, stop +Set address 0x1E +start, write 0x03, (re)start, read 6 bytes, stop +Set address 0x68 +start, write 0x1B, (re)start, read 8 bytes, stop +End + +0x04 0x53 +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 + +0x04 0x1E +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 + +0x04 0x68 +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 + +0x00 +... +D*/ + +/*F*/ +int bb_spi_open( + int pi, + unsigned CS, unsigned MISO, unsigned MOSI, unsigned SCLK, + unsigned baud, unsigned spi_flags); +/*D +This function selects a set of GPIO for bit banging SPI at a +specified baud rate. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + CS: 0-31 + MISO: 0-31 + MOSI: 0-31 + SCLK: 0-31 + baud: 50-250000 +spi_flags: see below +. . + +spi_flags consists of the least significant 22 bits. + +. . +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m +. . + +mm defines the SPI mode, defaults to 0 + +. . +Mode CPOL CPHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +p is 0 if CS is active low (default) and 1 for active high. + +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. + +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. + +The other bits in flags should be set to zero. + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_SPI_BAUD, or +PI_GPIO_IN_USE. + +If more than one device is connected to the SPI bus (defined by +SCLK, MOSI, and MISO) each must have its own CS. + +... +bb_spi_open(pi,10, MISO, MOSI, SCLK, 10000, 0); // device 1 +bb_spi_open(pi,11, MISO, MOSI, SCLK, 20000, 3); // device 2 +... +D*/ + +/*F*/ +int bb_spi_close(int pi, unsigned CS); +/*D +This function stops bit banging SPI on a set of GPIO +opened with [*bbSPIOpen*]. + +. . +pi: >=0 (as returned by [*pigpio_start*]). +CS: 0-31, the CS GPIO used in a prior call to [*bb_spi_open*] +. . + +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SPI_GPIO. +D*/ + +/*F*/ +int bb_spi_xfer( + int pi, + unsigned CS, + char *txBuf, + char *rxBuf, + unsigned count); +/*D +This function executes a bit banged SPI transfer. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + CS: 0-31 (as used in a prior call to [*bb_spi_open*]) +txBuf: pointer to buffer to hold data to be sent +rxBuf: pointer to buffer to hold returned data +count: size of data transfer +. . + +Returns >= 0 if OK (the number of bytes read), otherwise +PI_BAD_USER_GPIO, PI_NOT_SPI_GPIO or PI_BAD_POINTER. + +... +// gcc -Wall -pthread -o bb_spi_x_test bb_spi_x_test.c -lpigpiod_if2 +// ./bb_spi_x_test + +#include + +#include "pigpiod_if2.h" + +#define CE0 5 +#define CE1 6 +#define MISO 13 +#define MOSI 19 +#define SCLK 12 + +int main(int argc, char *argv[]) +{ + int i, pi, count, set_val, read_val; + unsigned char inBuf[3]; + char cmd1[] = {0, 0}; + char cmd2[] = {12, 0}; + char cmd3[] = {1, 128, 0}; + + if ((pi = pigpio_start(0, 0)) < 0) + { + fprintf(stderr, "pigpio initialisation failed (%d).\n", pi); + return 1; + } + + bb_spi_open(pi, CE0, MISO, MOSI, SCLK, 10000, 0); // MCP4251 DAC + bb_spi_open(pi, CE1, MISO, MOSI, SCLK, 20000, 3); // MCP3008 ADC + + for (i=0; i<256; i++) + { + cmd1[1] = i; + + count = bb_spi_xfer(pi, CE0, cmd1, (char *)inBuf, 2); // > DAC + + if (count == 2) + { + count = bb_spi_xfer(pi, CE0, cmd2, (char *)inBuf, 2); // < DAC + + if (count == 2) + { + set_val = inBuf[1]; + + count = bb_spi_xfer(pi, CE1, cmd3, (char *)inBuf, 3); // < ADC + + if (count == 3) + { + read_val = ((inBuf[1]&3)<<8) | inBuf[2]; + printf("%d %d\n", set_val, read_val); + } + } + } + } + + bb_spi_close(pi, CE0); + bb_spi_close(pi, CE1); + + pigpio_stop(pi); +} +... +D*/ + +/*F*/ +int spi_open(int pi, unsigned spi_channel, unsigned baud, unsigned spi_flags); +/*D +This function returns a handle for the SPI device on the channel. +Data will be transferred at baud bits per second. The flags may +be used to modify the default behaviour of 4-wire operation, mode 0, +active low chip select. + +The Pi has two SPI peripherals: main and auxiliary. + +The main SPI has two chip selects (channels), the auxiliary has +three. + +The auxiliary SPI is available on all models but the A and B. + +The GPIO used are given in the following table. + + @ MISO @ MOSI @ SCLK @ CE0 @ CE1 @ CE2 +Main SPI @ 9 @ 10 @ 11 @ 8 @ 7 @ - +Aux SPI @ 19 @ 20 @ 21 @ 18 @ 17 @ 16 + +. . + pi: >=0 (as returned by [*pigpio_start*]). +spi_channel: 0-1 (0-2 for the auxiliary SPI). + baud: 32K-125M (values above 30M are unlikely to work). + spi_flags: see below. +. . + +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, PI_NO_AUX_SPI, or PI_SPI_OPEN_FAILED. + +spi_flags consists of the least significant 22 bits. + +. . +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +. . + +mm defines the SPI mode. + +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +. . +Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +px is 0 if CEx is active low (default) and 1 for active high. + +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +A is 0 for the main SPI, 1 for the auxiliary SPI. + +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +The [*spi_read*], [*spi_write*], and [*spi_xfer*] functions +transfer data packed into 1, 2, or 4 bytes according to +the word size in bits. + +For bits 1-8 there will be one byte per character. +For bits 9-16 there will be two bytes per character. +For bits 17-32 there will be four bytes per character. + +Multi-byte transfers are made in least significant byte first order. + +E.g. to transfer 32 11-bit words buf should contain 64 bytes +and count should be 64. + +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +The other bits in flags should be set to zero. +D*/ + +/*F*/ +int spi_close(int pi, unsigned handle); +/*D +This functions closes the SPI device identified by the handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*spi_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int spi_read(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function reads count bytes of data from the SPI +device associated with the handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*spi_open*]. + buf: an array to receive the read data bytes. + count: the number of bytes to read. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int spi_write(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*spi_open*]. + buf: the data bytes to write. + count: the number of bytes to write. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int spi_xfer( + int pi, unsigned handle, char *txBuf, char *rxBuf, unsigned count); +/*D +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. Simultaneously count bytes of +data are read from the device and placed in rxBuf. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*spi_open*]. + txBuf: the data bytes to write. + rxBuf: the received data bytes. + count: the number of bytes to transfer. +. . + +Returns the number of bytes transferred if OK, otherwise +PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or PI_SPI_XFER_FAILED. +D*/ + +/*F*/ +int serial_open(int pi, char *ser_tty, unsigned baud, unsigned ser_flags); +/*D +This function opens a serial device at a specified baud rate +with specified flags. The device name must start with +/dev/tty or /dev/serial. + + +. . + pi: >=0 (as returned by [*pigpio_start*]). + ser_tty: the serial device to open. + baud: the baud rate in bits per second, see below. +ser_flags: 0. +. . + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. + +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +No flags are currently defined. This parameter should be set to zero. +D*/ + +/*F*/ +int serial_close(int pi, unsigned handle); +/*D +This function closes the serial device associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int serial_write_byte(int pi, unsigned handle, unsigned bVal); +/*D +This function writes bVal to the serial port associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + +/*F*/ +int serial_read_byte(int pi, unsigned handle); +/*D +This function reads a byte from the serial port associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. + +If no data is ready PI_SER_READ_NO_DATA is returned. +D*/ + +/*F*/ +int serial_write(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes from buf to the the serial port +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. + buf: the array of bytes to write. + count: the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +D*/ + +/*F*/ +int serial_read(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function reads up to count bytes from the the serial port +associated with handle and writes them to buf. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. + buf: an array to receive the read data. + count: the maximum number of bytes to read. +. . + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED. + +If no data is ready zero is returned. +D*/ + +/*F*/ +int serial_data_available(int pi, unsigned handle); +/*D +Returns the number of bytes available to be read from the +device associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0, as returned by a call to [*serial_open*]. +. . + +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. +D*/ + +/*F*/ +int custom_1(int pi, unsigned arg1, unsigned arg2, char *argx, unsigned argc); +/*D +This function is available for user customisation. + +It returns a single integer value. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +arg1: >=0 +arg2: >=0 +argx: extra (byte) arguments +argc: number of extra arguments +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. +D*/ + + +/*F*/ +int custom_2(int pi, unsigned arg1, char *argx, unsigned argc, + char *retBuf, unsigned retMax); +/*D +This function is available for user customisation. + +It differs from custom_1 in that it returns an array of bytes +rather than just an integer. + +The return value is an integer indicating the number of returned bytes. +. . + pi: >=0 (as returned by [*pigpio_start*]). + arg1: >=0 + argc: extra (byte) arguments + count: number of extra arguments +retBuf: buffer for returned data +retMax: maximum number of bytes to return +. . + +Returns >= 0 if OK, less than 0 indicates a user defined error. + +Note, the number of returned bytes will be retMax or less. +D*/ + +/*F*/ +int get_pad_strength(int pi, unsigned pad); +/*D +This function returns the pad drive strength in mA. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +pad: 0-2, the pad to get. +. . + +Returns the pad drive strength if OK, otherwise PI_BAD_PAD. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +... +strength = get_pad_strength(pi, 0); // get pad 0 strength +... +D*/ + + +/*F*/ +int set_pad_strength(int pi, unsigned pad, unsigned padStrength); +/*D +This function sets the pad drive strength in mA. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + pad: 0-2, the pad to set. +padStrength: 1-16 mA. +. . + +Returns 0 if OK, otherwise PI_BAD_PAD, or PI_BAD_STRENGTH. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +... +set_pad_strength(pi, 0, 10); // set pad 0 strength to 10 mA +... +D*/ + + +/*F*/ +int shell_(int pi, char *scriptName, char *scriptString); +/*D +This function uses the system call to execute a shell script +with the given string as its parameter. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + scriptName: the name of the script, only alphanumeric characters, + '-' and '_' are allowed in the name. +scriptString: the string to pass to the script. +. . + +The exit status of the system call is returned if OK, otherwise +PI_BAD_SHELL_STATUS. + +scriptName must exist in /opt/pigpio/cgi and must be executable. + +The returned exit status is normally 256 times that set by the +shell script exit function. If the script can't be found 32512 will +be returned. + +The following table gives some example returned statuses. + +Script exit status @ Returned system call status +1 @ 256 +5 @ 1280 +10 @ 2560 +200 @ 51200 +script not found @ 32512 + +... +// pass two parameters, hello and world +status = shell_(pi, "scr1", "hello world"); + +// pass three parameters, hello, string with spaces, and world +status = shell_(pi, "scr1", "hello 'string with spaces' world"); + +// pass one parameter, hello string with spaces world +status = shell_(pi, "scr1", "\"hello string with spaces world\""); +... +D*/ + +#pragma GCC diagnostic push + +#pragma GCC diagnostic ignored "-Wcomment" + +/*F*/ +int file_open(int pi, char *file, unsigned mode); +/*D +This function returns a handle to a file opened in a specified mode. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +file: the file to open. +mode: the file open mode. +. . + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, PI_NO_FILE_ACCESS, +PI_BAD_FILE_MODE, PI_FILE_OPEN_FAILED, or PI_FILE_IS_A_DIR. + +File + +A file may only be opened if permission is granted by an entry in +/opt/pigpio/access. This is intended to allow remote access to files +in a more or less controlled manner. + +Each entry in /opt/pigpio/access takes the form of a file path +which may contain wildcards followed by a single letter permission. +The permission may be R for read, W for write, U for read/write, +and N for no access. + +Where more than one entry matches a file the most specific rule +applies. If no entry matches a file then access is denied. + +Suppose /opt/pigpio/access contains the following entries + +. . +/home/* n +/home/pi/shared/dir_1/* w +/home/pi/shared/dir_2/* r +/home/pi/shared/dir_3/* u +/home/pi/shared/dir_1/file.txt n +. . + +Files may be written in directory dir_1 with the exception +of file.txt. + +Files may be read in directory dir_2. + +Files may be read and written in directory dir_3. + +If a directory allows read, write, or read/write access then files may +be created in that directory. + +In an attempt to prevent risky permissions the following paths are +ignored in /opt/pigpio/access. + +. . +a path containing .. +a path containing only wildcards (*?) +a path containing less than two non-wildcard parts +. . + +Mode + +The mode may have the following values. + +Macro @ Value @ Meaning +PI_FILE_READ @ 1 @ open file for reading +PI_FILE_WRITE @ 2 @ open file for writing +PI_FILE_RW @ 3 @ open file for reading and writing + +The following values may be or'd into the mode. + +Macro @ Value @ Meaning +PI_FILE_APPEND @ 4 @ Writes append data to the end of the file +PI_FILE_CREATE @ 8 @ The file is created if it doesn't exist +PI_FILE_TRUNC @ 16 @ The file is truncated + +Newly created files are owned by root with permissions owner read and write. + +... +#include +#include + +int main(int argc, char *argv[]) +{ + int pi, handle, c; + char buf[60000]; + + pi = pigpio_start(NULL, NULL); + + if (pi < 0) return 1; + + // assumes /opt/pigpio/access contains the following line + // /ram/*.c r + + handle = file_open(pi, "/ram/pigpio.c", PI_FILE_READ); + + if (handle >= 0) + { + while ((c=file_read(pi, handle, buf, sizeof(buf)-1))) + { + buf[c] = 0; + printf("%s", buf); + } + + file_close(pi, handle); + } + + pigpio_stop(pi); +} +... +D*/ + +#pragma GCC diagnostic pop + +/*F*/ +int file_close(int pi, unsigned handle); +/*D +This function closes the file associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0 (as returned by [*file_open*]). +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE. + +... +file_close(pi, handle); +... +D*/ + + +/*F*/ +int file_write(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function writes count bytes from buf to the the file +associated with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0 (as returned by [*file_open*]). + buf: the array of bytes to write. + count: the number of bytes to write. +. . + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, +PI_FILE_NOT_WOPEN, or PI_BAD_FILE_WRITE. + +... +if (file_write(pi, handle, buf, 100) == 0) +{ + // file written okay +} +else +{ + // error +} +... +D*/ + + +/*F*/ +int file_read(int pi, unsigned handle, char *buf, unsigned count); +/*D +This function reads up to count bytes from the the file +associated with handle and writes them to buf. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +handle: >=0 (as returned by [*file_open*]). + buf: an array to receive the read data. + count: the maximum number of bytes to read. +. . + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, PI_FILE_NOT_ROPEN, or PI_BAD_FILE_WRITE. + +... + bytes = file_read(pi, handle, buf, sizeof(buf)); + + if (bytes >= 0) + { + // process read data + } +... +D*/ + + +/*F*/ +int file_seek(int pi, unsigned handle, int32_t seekOffset, int seekFrom); +/*D +This function seeks to a position within the file associated +with handle. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + handle: >=0 (as returned by [*file_open*]). +seekOffset: the number of bytes to move. Positive offsets + move forward, negative offsets backwards. + seekFrom: one of PI_FROM_START (0), PI_FROM_CURRENT (1), + or PI_FROM_END (2). +. . + +Returns the new byte position within the file (>=0) if OK, otherwise PI_BAD_HANDLE, or PI_BAD_FILE_SEEK. + +... +file_seek(pi, handle, 123, PI_FROM_START); // Start plus 123 + +size = file_seek(pi, handle, 0, PI_FROM_END); // End, return size + +pos = file_seek(pi, handle, 0, PI_FROM_CURRENT); // Current position +... +D*/ + +#pragma GCC diagnostic push + +#pragma GCC diagnostic ignored "-Wcomment" + +/*F*/ +int file_list(int pi, char *fpat, char *buf, unsigned count); +/*D +This function returns a list of files which match a pattern. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + fpat: file pattern to match. + buf: an array to receive the matching file names. +count: the maximum number of bytes to read. +. . + +Returns the number of returned bytes if OK, otherwise PI_NO_FILE_ACCESS, +or PI_NO_FILE_MATCH. + +The pattern must match an entry in /opt/pigpio/access. The pattern +may contain wildcards. See [*file_open*]. + +NOTE + +The returned value is not the number of files, it is the number +of bytes in the buffer. The file names are separated by newline +characters. + +... +#include +#include + +int main(int argc, char *argv[]) +{ + int pi, handle, c; + char buf[60000]; + + pi = pigpio_start(NULL, NULL); + + if (pi < 0) return 1; + + // assumes /opt/pigpio/access contains the following line + // /ram/*.c r + + c = file_list(pi, "/ram/p*.c", buf, sizeof(buf)); + + if (c >= 0) + { + buf[c] = 0; + printf("%s", buf); + } + + pigpio_stop(pi); +} +... +D*/ + +#pragma GCC diagnostic pop + + +/*F*/ +int callback(int pi, unsigned user_gpio, unsigned edge, CBFunc_t f); +/*D +This function initialises a new callback. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + f: the callback function. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the GPIO, edge, and tick, whenever the +GPIO has the identified edge. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +edge 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes +. . +D*/ + +/*F*/ +int callback_ex + (int pi, unsigned user_gpio, unsigned edge, CBFuncEx_t f, void *userdata); +/*D +This function initialises a new callback. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + f: the callback function. + userdata: a pointer to arbitrary user data. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the GPIO, edge, tick, and the userdata +pointer, whenever the GPIO has the identified edge. + +. . +Parameter Value Meaning + +GPIO 0-31 The GPIO which has changed state + +edge 0-2 0 = change to low (a falling edge) + 1 = change to high (a rising edge) + 2 = no level change (a watchdog timeout) + +tick 32 bit The number of microseconds since boot + WARNING: this wraps around from + 4294967295 to 0 roughly every 72 minutes + +userdata pointer Pointer to an arbitrary object +. . +D*/ + +/*F*/ +int callback_cancel(unsigned callback_id); +/*D +This function cancels a callback identified by its id. + +. . +callback_id: >=0, as returned by a call to [*callback*] or [*callback_ex*]. +. . + +The function returns 0 if OK, otherwise pigif_callback_not_found. +D*/ + +/*F*/ +int wait_for_edge(int pi, unsigned user_gpio, unsigned edge, double timeout); +/*D +This function waits for an edge on the GPIO for up to timeout +seconds. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +user_gpio: 0-31. + edge: RISING_EDGE, FALLING_EDGE, or EITHER_EDGE. + timeout: >=0. +. . + +The function returns when the edge occurs or after the timeout. + +Do not use this function for precise timing purposes, +the edge is only checked 20 times a second. Whenever +you need to know the accurate time of GPIO events use +a [*callback*] function. + +The function returns 1 if the edge occurred, otherwise 0. +D*/ + +/*F*/ +int bsc_xfer(int pi, bsc_xfer_t *bscxfer); +/*D +This function provides a low-level interface to the +SPI/I2C Slave peripheral. This peripheral allows the +Pi to act as a slave device on an I2C or SPI bus. + +I can't get SPI to work properly. I tried with a +control word of 0x303 and swapped MISO and MOSI. + +The function sets the BSC mode, writes any data in +the transmit buffer to the BSC transmit FIFO, and +copies any data in the BSC receive FIFO to the +receive buffer. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +bscxfer: a structure defining the transfer. + +typedef struct +{ + uint32_t control; // Write + int rxCnt; // Read only + char rxBuf[BSC_FIFO_SIZE]; // Read only + int txCnt; // Write + char txBuf[BSC_FIFO_SIZE]; // Write +} bsc_xfer_t; +. . + +To start a transfer set control (see below) and copy the bytes to +be sent (if any) to txBuf and set the byte count in txCnt. + +Upon return rxCnt will be set to the number of received bytes placed +in rxBuf. + +The returned function value is the status of the transfer (see below). + +If there was an error the status will be less than zero +(and will contain the error code). + +The most significant word of the returned status contains the number +of bytes actually copied from txBuf to the BSC transmit FIFO (may be +less than requested if the FIFO already contained untransmitted data). + +Note that the control word sets the BSC mode. The BSC will stay in +that mode until a different control word is sent. + +The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode +and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You +need to swap MISO/MOSI between master and slave. + +When a zero control word is received GPIO 18-21 will be reset +to INPUT mode. + +control consists of the following bits. + +. . +22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN +. . + +Bits 0-13 are copied unchanged to the BSC CR register. See +pages 163-165 of the Broadcom peripherals document for full +details. + +aaaaaaa @ defines the I2C slave address (only relevant in I2C mode) +IT @ invert transmit status flags +HC @ enable host control +TF @ enable test FIFO +IR @ invert receive status flags +RE @ enable receive +TE @ enable transmit +BK @ abort operation and clear FIFOs +EC @ send control register as first I2C byte +ES @ send status register as first I2C byte +PL @ set SPI polarity high +PH @ set SPI phase high +I2 @ enable I2C mode +SP @ enable SPI mode +EN @ enable BSC peripheral + +The returned status has the following format + +. . +20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 + S S S S S R R R R R T T T T T RB TE RF TF RE TB +. . + +Bits 0-15 are copied unchanged from the BSC FR register. See +pages 165-166 of the Broadcom peripherals document for full +details. + +SSSSS @ number of bytes successfully copied to transmit FIFO +RRRRR @ number of bytes in receieve FIFO +TTTTT @ number of bytes in transmit FIFO +RB @ receive busy +TE @ transmit FIFO empty +RF @ receive FIFO full +TF @ transmit FIFO full +RE @ receive FIFO empty +TB @ transmit busy + +The following example shows how to configure the BSC peripheral as +an I2C slave with address 0x13 and send four bytes. + +... +bsc_xfer_t xfer; + +xfer.control = (0x13<<16) | 0x305; + +memcpy(xfer.txBuf, "ABCD", 4); +xfer.txCnt = 4; + +status = bsc_xfer(pi, &xfer); + +if (status >= 0) +{ + // process transfer +} +... +D*/ + +/*F*/ +int bsc_i2c(int pi, int i2c_addr, bsc_xfer_t *bscxfer); +/*D +This function allows the Pi to act as a slave I2C device. + +The data bytes (if any) are written to the BSC transmit +FIFO and the bytes in the BSC receive FIFO are returned. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +i2c_addr: 0-0x7F. + bscxfer: a structure defining the transfer. + +typedef struct +{ + uint32_t control; // N/A + int rxCnt; // Read only + char rxBuf[BSC_FIFO_SIZE]; // Read only + int txCnt; // Write + char txBuf[BSC_FIFO_SIZE]; // Write +} bsc_xfer_t; +. . + +txCnt is set to the number of bytes to be transmitted, possibly +zero. The data itself should be copied to txBuf. + +Any received data will be written to rxBuf with rxCnt set. + +See [*bsc_xfer*] for details of the returned status value. + +If there was an error the status will be less than zero +(and will contain the error code). + +Note that an i2c_address of 0 may be used to close +the BSC device and reassign the used GPIO (18/19) +as inputs. +D*/ + +/*F*/ +int event_callback(int pi, unsigned event, evtCBFunc_t f); +/*D +This function initialises an event callback. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +event: 0-31. + f: the callback function. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the event id, and tick, whenever the +event occurs. +D*/ + +/*F*/ +int event_callback_ex(int pi, unsigned event, evtCBFuncEx_t f, void *userdata); +/*D +This function initialises an event callback. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + event: 0-31. + f: the callback function. +userdata: a pointer to arbitrary user data. +. . + +The function returns a callback id if OK, otherwise pigif_bad_malloc, +pigif_duplicate_callback, or pigif_bad_callback. + +The callback is called with the event id, the tick, and the userdata +pointer whenever the event occurs. +D*/ + +/*F*/ +int event_callback_cancel(unsigned callback_id); +/*D +This function cancels an event callback identified by its id. + +. . +callback_id: >=0, as returned by a call to [*event_callback*] or +[*event_callback_ex*]. +. . + +The function returns 0 if OK, otherwise pigif_callback_not_found. +D*/ + +/*F*/ +int wait_for_event(int pi, unsigned event, double timeout); +/*D +This function waits for an event for up to timeout seconds. + +. . + pi: >=0 (as returned by [*pigpio_start*]). + event: 0-31. +timeout: >=0. +. . + +The function returns when the event occurs or after the timeout. + +The function returns 1 if the event occurred, otherwise 0. +D*/ + +/*F*/ +int event_trigger(int pi, unsigned event); +/*D +This function signals the occurrence of an event. + +. . + pi: >=0 (as returned by [*pigpio_start*]). +event: 0-31. +. . + +Returns 0 if OK, otherwise PI_BAD_EVENT_ID. + +An event is a signal used to inform one or more consumers +to start an action. Each consumer which has registered an interest +in the event (e.g. by calling [*event_callback*]) will be informed by +a callback. + +One event, PI_EVENT_BSC (31) is predefined. This event is +auto generated on BSC slave activity. + +The meaning of other events is arbitrary. + +Note that other than its id and its tick there is no data associated +with an event. +D*/ + +/*PARAMS + +active :: 0-1000000 + +The number of microseconds level changes are reported for once +a noise filter has been triggered (by [*steady*] microseconds of +a stable level). + +*addrStr:: +A string specifying the host or IP address of the Pi running +the pigpio daemon. It may be NULL in which case localhost +is used unless overridden by the PIGPIO_ADDR environment +variable. + +arg1:: +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +arg2:: +An unsigned argument passed to a user customised function. Its +meaning is defined by the customiser. + +argc:: +The count of bytes passed to a user customised function. + +*argx:: +A pointer to an array of bytes passed to a user customised function. +Its meaning and content is defined by the customiser. + +baud:: +The speed of serial communication (I2C, SPI, serial link, waves) in +bits per second. + +bit:: +A value of 0 or 1. + +bits:: +A value used to select GPIO. If bit n of bits is set then GPIO n is +selected. + +A convenient way to set bit n is to or in (1<=0, as returned by a call to a callback function, one of + +[*callback*] +[*callback_ex*] +[*event_callback*] +[*event_callback_ex*] + +The id is passed to [*callback_cancel*] or [*event_callback_cancel*] +to cancel the callback. + +CBFunc_t:: +. . +typedef void (*CBFunc_t) + (int pi, unsigned user_gpio, unsigned level, uint32_t tick); +. . + +CBFuncEx_t:: +. . +typedef void (*CBFuncEx_t) + (int pi, unsigned user_gpio, unsigned level, uint32_t tick, void * userdata); +. . + +char:: +A single character, an 8 bit quantity able to store 0-255. + +clkfreq::4689-250000000 (250M) +The hardware clock frequency. + +count:: +The number of bytes to be transferred in a file, I2C, SPI, or serial +command. + +CS:: +The GPIO used for the slave select signal when bit banging SPI. + +data_bits::1-32 +The number of data bits in each character of serial data. + +. . +#define PI_MIN_WAVE_DATABITS 1 +#define PI_MAX_WAVE_DATABITS 32 +. . + +double:: +A floating point number. + +dutycycle::0-range +A number representing the ratio of on time to off time for PWM. + +The number may vary between 0 and range (default 255) where +0 is off and range is fully on. + +edge:: +Used to identify a GPIO level transition of interest. A rising edge is +a level change from 0 to 1. A falling edge is a level change from 1 to 0. + +. . +RISING_EDGE 0 +FALLING_EDGE 1 +EITHER_EDGE. 2 +. . + +errnum:: +A negative number indicating a function call failed and the nature +of the error. + +event::0-31 +An event is a signal used to inform one or more consumers +to start an action. + +evtCBFunc_t:: + +. . +typedef void (*evtCBFunc_t) + (int pi, unsigned event, uint32_t tick); +. . + +evtCBFuncEx_t:: + +. . +typedef void (*evtCBFuncEx_t) + (int pi, unsigned event, uint32_t tick, void *userdata); +. . + +f:: +A function. + +*file:: +A full file path. To be accessible the path must match an entry in +/opt/pigpio/access. + +*fpat:: +A file path which may contain wildcards. To be accessible the path +must match an entry in /opt/pigpio/access. + +frequency::>=0 +The number of times a GPIO is swiched on and off per second. This +can be set per GPIO and may be as little as 5Hz or as much as +40KHz. The GPIO will be on for a proportion of the time as defined +by its dutycycle. + +gpio:: +A Broadcom numbered GPIO, in the range 0-53. + +There are 54 General Purpose Input Outputs (GPIO) named GPIO0 through +GPIO53. + +They are split into two banks. Bank 1 consists of GPIO0 through +GPIO31. Bank 2 consists of GPIO32 through GPIO53. + +All the GPIO which are safe for the user to read and write are in +bank 1. Not all GPIO in bank 1 are safe though. Type 1 boards +have 17 safe GPIO. Type 2 boards have 21. Type 3 boards have 26. + +See [*get_hardware_revision*]. + +The user GPIO are marked with an X in the following table. + +. . + 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +Type 1 X X - - X - - X X X X X - - X X +Type 2 - - X X X - - X X X X X - - X X +Type 3 X X X X X X X X X X X X X X + + 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 +Type 1 - X X - - X X X X X - - - - - - +Type 2 - X X - - - X X X X - X X X X X +Type 3 X X X X X X X X X X X X - - - - +. . + +gpioPulse_t:: +. . +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; +. . + +gpioThreadFunc_t:: +. . +typedef void *(gpioThreadFunc_t) (void *); +. . + +handle::>=0 +A number referencing an object opened by one of + +[*file_open*] +[*i2c_open*] +[*notify_open*] +[*serial_open*] +[*spi_open*] + +i2c_addr::0-0x7F +The address of a device on the I2C bus. + +i2c_bus::>=0 +An I2C bus number. + +i2c_flags::0 +Flags which modify an I2C open command. None are currently defined. + +i2c_reg:: 0-255 +A register of an I2C device. + +*inBuf:: +A buffer used to pass data to a function. + +inLen:: +The number of bytes of data in a buffer. + +int:: +A whole number, negative or positive. + +int32_t:: +A 32-bit signed value. + +invert:: +A flag used to set normal or inverted bit bang serial data level logic. + +level:: +The level of a GPIO. Low or High. + +. . +PI_OFF 0 +PI_ON 1 + +PI_CLEAR 0 +PI_SET 1 + +PI_LOW 0 +PI_HIGH 1 +. . + +There is one exception. If a watchdog expires on a GPIO the level will be +reported as PI_TIMEOUT. See [*set_watchdog*]. + +. . +PI_TIMEOUT 2 +. . + +MISO:: +The GPIO used for the MISO signal when bit banging SPI. + +mode:: +1. The operational mode of a GPIO, normally INPUT or OUTPUT. + +. . +PI_INPUT 0 +PI_OUTPUT 1 +PI_ALT0 4 +PI_ALT1 5 +PI_ALT2 6 +PI_ALT3 7 +PI_ALT4 3 +PI_ALT5 2 +. . + +2. The mode of waveform transmission. + +. . +PI_WAVE_MODE_ONE_SHOT 0 +PI_WAVE_MODE_REPEAT 1 +PI_WAVE_MODE_ONE_SHOT_SYNC 2 +PI_WAVE_MODE_REPEAT_SYNC 3 +. . + +3. A file open mode. + +. . +PI_FILE_READ 1 +PI_FILE_WRITE 2 +PI_FILE_RW 3 +. . + +The following values can be or'd into the mode. + +. . +PI_FILE_APPEND 4 +PI_FILE_CREATE 8 +PI_FILE_TRUNC 16 +. . + +MOSI:: +The GPIO used for the MOSI signal when bit banging SPI. + +numBytes:: +The number of bytes used to store characters in a string. Depending +on the number of bits per character there may be 1, 2, or 4 bytes +per character. + +numPar:: 0-10 +The number of parameters passed to a script. + +numPulses:: +The number of pulses to be added to a waveform. + +offset:: +The associated data starts this number of microseconds from the start of +the waveform. + +*outBuf:: +A buffer used to return data from a function. + +outLen:: +The size in bytes of an output buffer. + +pad:: 0-2 +A set of GPIO which share common drivers. + +Pad @ GPIO +0 @ 0-27 +1 @ 28-45 +2 @ 46-53 + +padStrength:: 1-16 +The mA which may be drawn from each GPIO whilst still guaranteeing the +high and low levels. + +*param:: +An array of script parameters. + +pi:: +An integer defining a connected Pi. The value is returned by +[*pigpio_start*] upon success. + +*portStr:: +A string specifying the port address used by the Pi running +the pigpio daemon. It may be NULL in which case "8888" +is used unless overridden by the PIGPIO_PORT environment +variable. + +*pth:: +A thread identifier, returned by [*start_thread*]. + + +pthread_t:: +A thread identifier. + +pud::0-2 +The setting of the pull up/down resistor for a GPIO, which may be off, +pull-up, or pull-down. +. . +PI_PUD_OFF 0 +PI_PUD_DOWN 1 +PI_PUD_UP 2 +. . + +pulseLen:: +1-100, the length of a trigger pulse in microseconds. + +*pulses:: +An array of pulses to be added to a waveform. + +pulsewidth::0, 500-2500 +. . +PI_SERVO_OFF 0 +PI_MIN_SERVO_PULSEWIDTH 500 +PI_MAX_SERVO_PULSEWIDTH 2500 +. . + +PWMduty::0-1000000 (1M) +The hardware PWM dutycycle. + +. . +#define PI_HW_PWM_RANGE 1000000 +. . + +PWMfreq::1-125000000 (125M) +The hardware PWM frequency. + +. . +#define PI_HW_PWM_MIN_FREQ 1 +#define PI_HW_PWM_MAX_FREQ 125000000 +. . + +range::25-40000 +The permissible dutycycle values are 0-range. + +. . +PI_MIN_DUTYCYCLE_RANGE 25 +PI_MAX_DUTYCYCLE_RANGE 40000 +. . + +*retBuf:: +A buffer to hold a number of bytes returned to a used customised function, + +retMax:: +The maximum number of bytes a user customised function should return. + + +*rxBuf:: +A pointer to a buffer to receive data. + +SCL:: +The user GPIO to use for the clock when bit banging I2C. + +SCLK:: +The GPIO used for the SCLK signal when bit banging SPI. + +*script:: +A pointer to the text of a script. + +script_id:: +An id of a stored script as returned by [*store_script*]. + +*scriptName:: +The name of a [*shell_*] script to be executed. The script must be present in +/opt/pigpio/cgi and must have execute permission. + +*scriptString:: +The string to be passed to a [*shell_*] script to be executed. + +SDA:: +The user GPIO to use for data when bit banging I2C. + +seconds:: +The number of seconds. + +seekFrom:: + +. . +PI_FROM_START 0 +PI_FROM_CURRENT 1 +PI_FROM_END 2 +. . + +seekOffset:: +The number of bytes to move forward (positive) or backwards (negative) +from the seek position (start, current, or end of file). + +ser_flags:: +Flags which modify a serial open command. None are currently defined. + +*ser_tty:: +The name of a serial tty device, e.g. /dev/ttyAMA0, /dev/ttyUSB0, /dev/tty1. + +size_t:: +A standard type used to indicate the size of an object in bytes. + +spi_channel:: +A SPI channel, 0-2. + +spi_flags:: +See [*spi_open*] and [*bb_spi_open*]. + +steady:: 0-300000 + +The number of microseconds level changes must be stable for +before reporting the level changed ([*set_glitch_filter*]) or triggering +the active part of a noise filter ([*set_noise_filter*]). + +stop_bits::2-8 +The number of (half) stop bits to be used when adding serial data +to a waveform. + +. . +#define PI_MIN_WAVE_HALFSTOPBITS 2 +#define PI_MAX_WAVE_HALFSTOPBITS 8 +. . + +*str:: + An array of characters. + +thread_func:: +A function of type gpioThreadFunc_t used as the main function of a +thread. + +timeout:: +A GPIO watchdog timeout in milliseconds. + +. . +PI_MIN_WDOG_TIMEOUT 0 +PI_MAX_WDOG_TIMEOUT 60000 +. . + +*txBuf:: +An array of bytes to transmit. + +uint32_t::0-0-4,294,967,295 (Hex 0x0-0xFFFFFFFF) +A 32-bit unsigned value. + +unsigned:: +A whole number >= 0. + +user_gpio:: +0-31, a Broadcom numbered GPIO. + +See [*gpio*]. + +*userdata:: + +A pointer to arbitrary user data. This may be used to identify the instance. + +You must ensure that the pointer is in scope at the time it is processed. If +it is a pointer to a global this is automatic. Do not pass the address of a +local variable. If you want to pass a transient object then use the +following technique. + +In the calling function: + +. . +user_type *userdata; +user_type my_userdata; + +userdata = malloc(sizeof(user_type)); +*userdata = my_userdata; +. . + +In the receiving function: + +. . +user_type my_userdata = *(user_type*)userdata; + +free(userdata); +. . + +void:: +Denoting no parameter is required + +wave_add_*:: +One of + +[*wave_add_new*] +[*wave_add_generic*] +[*wave_add_serial*] + +wave_id:: +A number representing a waveform created by [*wave_create*]. + +wave_send_*:: +One of + +[*wave_send_once*] +[*wave_send_repeat*] + +wVal::0-65535 (Hex 0x0-0xFFFF, Octal 0-0177777) +A 16-bit word value. + +PARAMS*/ + +/*DEF_S pigpiod_if2 Error Codes*/ + +typedef enum +{ + pigif_bad_send = -2000, + pigif_bad_recv = -2001, + pigif_bad_getaddrinfo = -2002, + pigif_bad_connect = -2003, + pigif_bad_socket = -2004, + pigif_bad_noib = -2005, + pigif_duplicate_callback = -2006, + pigif_bad_malloc = -2007, + pigif_bad_callback = -2008, + pigif_notify_failed = -2009, + pigif_callback_not_found = -2010, + pigif_unconnected_pi = -2011, + pigif_too_many_pis = -2012, +} pigifError_t; + +/*DEF_E*/ + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/thirdparty/PIGPIO/pigs.1 b/thirdparty/PIGPIO/pigs.1 new file mode 100644 index 0000000000..ebb07772a2 --- /dev/null +++ b/thirdparty/PIGPIO/pigs.1 @@ -0,0 +1,5829 @@ + +." Process this file with +." groff -man -Tascii foo.1 +." +.TH pigs 1 2012-2018 Linux "pigpio archive" +.SH NAME +pigs - command line socket access to the pigpio daemon. + +/dev/pigpio - command line pipe access to the pigpio daemon. + +.SH SYNOPSIS + +.B sudo pigpiod + +then + +.B pigs {command}+ + +or + +.B "echo {command}+ >/dev/pigpio" + +.SH DESCRIPTION + +.ad l + +.nh + + +.br +The socket and pipe interfaces allow control of the GPIO by passing +messages to the running pigpio library. + +.br +The normal way to start the pigpio library would be as a daemon during boot. + +.br + +.EX +sudo pigpiod +.br + +.EE + +.br +pigs is a program and internally uses the socket interface to pigpio +whereas /dev/pigpio uses the pipe interface. + +.br +.SS Features +.br +o hardware timed PWM on any of GPIO 0-31 + +.br +o hardware timed servo pulses on any of GPIO 0-31 + +.br +o reading/writing all of the GPIO in a bank as one operation + +.br +o individually setting GPIO modes, reading and writing + +.br +o notifications when any of GPIO 0-31 change state + +.br +o the construction of output waveforms with microsecond timing + +.br +o I2C, SPI, and serial link wrappers + +.br +o creating and running scripts on the pigpio daemon + +.br +.SS GPIO +.br +ALL GPIO are identified by their Broadcom number. + +.br +.SS Usage +.br +pigs and the socket interface share the same commands and are invoked in +a similar fashion from the command line. + +.br +The pigpio library must be running, either by running a program linked +with the library or starting the pigpio daemon (sudo pigpiod). + +.br +pigs {command}+ + +.br +echo "{command}+" >/dev/pigpio + +.br +pigs will show the result of the command on screen. + +.br +The pigs process returns an exit status (which can be displayed with +the command echo $?). + +.br + +.EX +PIGS_OK 0 +.br +PIGS_CONNECT_ERR 255 +.br +PIGS_OPTION_ERR 254 +.br +PIGS_SCRIPT_ERR 253 +.br +.br +.br + +.EE + +.br +The results of /dev/pigpio commands need to be read from /dev/pigout, +e.g. cat /dev/pigout (try cat /dev/pigout& so that all subsequent +results are shown on screen). + +.br +In both cases if an error was detected a message will have been written +to /dev/pigerr (try cat /dev/pigerr&). This is likely to be more +informative than the message returned by pigs or the error code +returned by the pipe interface. + +.br +Several commands may be entered on a line. If present PROC and PARSE must +be the last command on a line. + +.br +E.g. + +.br + +.EX +pigs w 22 1 mils 1000 w 22 0 +.br + +.EE + +.br +is equivalent to + +.br + +.EX +pigs w 22 1 +.br +pigs mils 1000 +.br +pigs w 22 0 +.br + +.EE + +.br +and + +.br + +.EX +echo "m 4 w w 4 0 mils 250 m 4 r r 4" >/dev/pigpio +.br + +.EE + +.br +is equivalent to + +.br + +.EX +echo "m 4 w" >/dev/pigpio +.br +echo "w 4 0" >/dev/pigpio +.br +echo "mils 250" >/dev/pigpio +.br +echo "m 4 r" >/dev/pigpio +.br +echo "r 4" >/dev/pigpio +.br + +.EE + +.br +.SS Notes +.br +The examples from now on will show the pigs interface but the same +commands will also work on the pipe interface. + +.br +pigs does not show the status of successful commands unless the +command itself returns data. The status (0) will be returned to +pigs but will be discarded. + +.br +The status/data of each command sent to the pipe interface should +be read from /dev/pigout. + +.br +When a command takes a number as a parameter it may be entered as hex +(precede by 0x), octal (precede by 0), or decimal. + +.br +E.g. 23 is 23 decimal, 0x100 is 256 decimal, 070 is 56 decimal. + +.br +Some commands can return a variable number of data bytes. By +default this data is displayed as decimal. The pigs -a option +can be used to force the display as ASCII and the pigs -x +option can be used to force the display as hex. + +.br +E.g. assuming the transmitted serial data is the letters ABCDEONM + +.br + +.EX +$ pigs slr 4 100 +.br +8 65 66 67 68 69 79 78 77 +.br + +.br +$ pigs -a slr 4 100 +.br +8 ABCDEONM +.br + +.br +$ pigs -x slr 4 100 +.br +8 41 42 43 44 45 4f 4e 4d +.br + +.EE + +.br + +.SH COMMANDS + +.br + +.IP "\fBBC1 bits\fP - Clear specified GPIO in bank 1" +.IP "" 4 +This command clears (sets low) the GPIO specified by \fBbits\fP in bank 1. +Bank 1 consists of GPIO 0-31. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bc1 0x400010 # clear GPIO 4 (1<<4) and 22 (1<<22) +.br + +.br +$ pigs bc1 32 # clear GPIO 5 (1<<5) +.br +-42 +.br +ERROR: no permission to update one or more GPIO +.br + +.EE + +.br + +.IP "\fBBC2 bits\fP - Clear specified GPIO in bank 2" +.IP "" 4 +This command clears (sets low) the GPIO specified by \fBbits\fP in bank 2. +Bank 2 consists of GPIO 32-53. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bc2 0x8000 # clear GPIO 47 (activity LED on A+/B+/Pi2/Pi3) +.br + +.br +$ pigs bc2 1 # clear GPIO 32 (first in bank 2) +.br +-42 +.br +ERROR: no permission to update one or more GPIO +.br + +.EE + +.br + +.IP "\fBBI2CC sda\fP - Close bit bang I2C" +.IP "" 4 +This command signals that bit banging I2C on \fBsda\fP (and \fBscl\fP) is no +longer required. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bi2cc 5 +.br + +.EE + +.br + +.IP "\fBBI2CO sda scl b\fP - Open bit bang I2C" +.IP "" 4 +This command signals that GPIO \fBsda\fP and \fBscl\fP are to be used +for bit banging I2C at \fBb\fP baud. + +.br +Bit banging I2C allows for certain operations which are not possible +with the standard I2C driver. + +.br +o baud rates as low as 50 +.br +o repeated starts +.br +o clock stretching +.br +o I2C on any pair of spare GPIO + +.br +The baud rate may be between 50 and 500000 bits per second. + +.br +The GPIO used for SDA and SCL must have pull-ups to 3V3 connected. As +a guide the hardware pull-ups on pins 3 and 5 are 1k8 in value. + +.br + +.IP "\fBBI2CZ sda bvs\fP - I2C bit bang multiple transactions" +.IP "" 4 +This function executes a sequence of bit banged I2C operations. The +operations to be performed are specified by the contents of \fBbvs\fP +which contains the concatenated command codes and associated data. + +.br +The following command codes are supported: + +.br + +.EX +Name Cmd & Data Meaning +End 0 No more commands +Escape 1 Next P is two bytes +Start 2 Start condition +Stop 3 Stop condition +Address 4 P Set I2C address to P +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +Read 6 P Read P bytes of data +Write 7 P ... Write P bytes of data + +.EE + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br +The address and flags default to 0. The address and flags maintain +their previous value until updated. + +.br +No flags are currently defined. + +.br + +\fBExample\fP +.br + +.EX +Set address 0x53 +.br +start, write 0x32, (re)start, read 6 bytes, stop +.br +Set address 0x1E +.br +start, write 0x03, (re)start, read 6 bytes, stop +.br +Set address 0x68 +.br +start, write 0x1B, (re)start, read 8 bytes, stop +.br +End +.br + +.br +0x04 0x53 +.br +0x02 0x07 0x01 0x32 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x1E +.br +0x02 0x07 0x01 0x03 0x02 0x06 0x06 0x03 +.br + +.br +0x04 0x68 +.br +0x02 0x07 0x01 0x1B 0x02 0x06 0x08 0x03 +.br + +.br +0x00 +.br + +.EE + +.br + +.IP "\fBBR1 \fP - Read bank 1 GPIO" +.IP "" 4 +This command read GPIO 0-31 (bank 1) and returns the levels as a +32-bit hexadecimal value. + +.br + +\fBExample\fP +.br + +.EX +$ pigs br1 +.br +1001C1CF +.br + +.EE + +.br + +.IP "\fBBR2 \fP - Read bank 2 GPIO" +.IP "" 4 +This command read GPIO 32-53 (bank 2) and returns the levels as a +32-bit hexadecimal value. + +.br + +\fBExample\fP +.br + +.EX +$ pigs br2 +.br +003F0000 +.br + +.EE + +.br + +.IP "\fBBS1 bits\fP - Set specified GPIO in bank 1" +.IP "" 4 +This command sets (sets high) the GPIO specified by \fBbits\fP in bank 1. +Bank 1 consists of GPIO 0-31. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bs1 16 # set GPIO 4 (1<<4) +.br + +.br +$ pigs bs1 1 # set GPIO 1 (1<<0) +.br +-42 +.br +ERROR: no permission to update one or more GPIO +.br + +.EE + +.br + +.IP "\fBBS2 bits\fP - Set specified GPIO in bank 2" +.IP "" 4 +This command sets (sets high) the GPIO specified by \fBbits\fP in bank 2. +Bank 2 consists of GPIO 32-53. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bs2 0x40 # set GPIO 38 (enable high current mode A+/B+/Pi2/Pi3) +.br + +.br +$ pigs bs2 1 # set GPIO 32 (first in bank 2) +.br +-42 +.br +ERROR: no permission to update one or more GPIO +.br + +.EE + +.br + +.IP "\fBBSCX bctl bvs\fP - BSC I2C/SPI transfer" +.IP "" 4 + +.br +This command performs a BSC I2C/SPI slave transfer as defined by +\fBbctl\fP with data \fBbvs\fP. + +.br +I can't get SPI to work properly. I tried with a +control word of 0x303 and swapped MISO and MOSI. + +.br +The command sets the BSC mode and writes any data \fBbvs\fP +to the BSC transmit FIFO. It returns the data count (at least 1 +for the status word), the status word, followed by any data bytes +read from the BSC receive FIFO. + +.br +Note that the control word sets the BSC mode. The BSC will stay in +that mode until a different control word is sent. + +.br +For I2C use a control word of (I2C address << 16) + 0x305. + +.br +E.g. to talk as I2C slave with address 0x13 use 0x130305. + +.br +The BSC peripheral uses GPIO 18 (SDA) and 19 (SCL) in I2C mode +and GPIO 18 (MOSI), 19 (SCLK), 20 (MISO), and 21 (CE) in SPI mode. You +need to swap MISO/MOSI between master and slave. + +.br +When a zero control word is received GPIO 18-21 will be reset +to INPUT mode. + +.br +The control word consists of the following bits. + +.br + +.EX +22 21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + a a a a a a a - - IT HC TF IR RE TE BK EC ES PL PH I2 SP EN +.br + +.EE + +.br +Bits 0-13 are copied unchanged to the BSC CR register. See +pages 163-165 of the Broadcom peripherals document for full +details. + +.br + +.EX +aaaaaaa defines the I2C slave address (only relevant in I2C mode) +IT invert transmit status flags +HC enable host control +TF enable test FIFO +IR invert receive status flags +RE enable receive +TE enable transmit +BK abort operation and clear FIFOs +EC send control register as first I2C byte +ES send status register as first I2C byte +PL set SPI polarity high +PH set SPI phase high +I2 enable I2C mode +SP enable SPI mode +EN enable BSC peripheral + +.EE + +.br +The returned status has the following format + +.br + +.EX +20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + S S S S S R R R R R T T T T T RB TE RF TF RE TB +.br + +.EE + +.br +Bits 0-15 are copied unchanged from the BSC FR register. See +pages 165-166 of the Broadcom peripherals document for full +details. + +.br + +.EX +SSSSS number of bytes successfully copied to transmit FIFO +RRRRR number of bytes in receieve FIFO +TTTTT number of bytes in transmit FIFO +RB receive busy +TE transmit FIFO empty +RF receive FIFO full +TF transmit FIFO full +RE receive FIFO empty +TB transmit busy + +.EE + +.br +This example assumes that GPIO 2/3 are connected to GPIO 18/19. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bscx 0x130305 # start BSC as I2C slave 0x13 +.br +1 18 +.br + +.br +$ i2cdetect -y 1 +.br + 0 1 2 3 4 5 6 7 8 9 a b c d e f +.br +00: -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +10: -- -- -- 13 -- -- -- -- -- -- -- -- -- -- -- -- +.br +20: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +30: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +40: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +50: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +60: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- +.br +70: -- -- -- -- -- -- -- -- +.br + +.br +$ pigs i2co 1 0x13 0 # get handle for device 0x13 on bus 1 +.br +0 +.br + +.br +$ pigs i2cwd 0 90 87 51 9 23 # write 5 bytes +.br + +.br +$ pigs bscx 0x130305 # check for data +.br +6 18 90 87 51 9 23 +.br + +.br +$ pigs bscx 0x130305 11 13 15 17 # check for data and send 4 bytes +.br +1 262338 +.br + +.br +$ pigs i2crd 0 4 # read 4 bytes +.br +4 11 13 15 17 +.br + +.br +$ pigs i2cwd 0 90 87 51 9 23 # write 5 bytes +.br +$ pigs bscx 0x130305 11 13 15 17 # check for data and send 4 bytes +.br +6 262338 90 87 51 9 23 +.br + +.br +$ pigs i2crd 0 4 +.br +4 11 13 15 17 +.br + +.br +$ pigs bscx 0x130305 22 33 44 55 66 +.br +1 327938 +.br +$ pigs i2crd 0 5 +.br +5 22 33 44 55 66 +.br + +.EE + +.br + +.IP "\fBBSPIC cs\fP - Close bit bang SPI" +.IP "" 4 + +.br +This command stops bit banging SPI on a set of GPIO +opened with \fBBSPIO\fP. + +.br +The set of GPIO is specifed by \fBcs\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bspic 10 +.br + +.br +$ pigs bspic 10 +.br +-142 +.br +ERROR: no bit bang SPI in progress on GPIO +.br + +.EE + +.br + +.IP "\fBBSPIO cs miso mosi sclk b spf\fP - Open bit bang SPI" +.IP "" 4 + +.br +This command starts bit banging SPI on a group of GPIO with slave +select \fBcs\fP, MISO \fBmiso\fP, MOSI \fBmosi\fP, and clock \fBsclk\fP. + +.br +Data will be transferred at baud \fBb\fP bits per second (which may +be set in the range 50-250000). + +.br +The flags \fBspf\fP may be used to modify the default behaviour of +mode 0, active low chip select. + +.br +The flags consists of the least significant 22 bits. + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + 0 0 0 0 0 0 R T 0 0 0 0 0 0 0 0 0 0 0 p m m +.br + +.EE + +.br +mm defines the SPI mode. + +.br + +.EX +Mode POL PHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br +p is 0 if CS is active low (default) and 1 for active high. + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. + +.br +The other bits in flags should be set to zero. + +.br +Upon success 0 is returned. On error a negative status code +will be returned. + +.br +If more than one device is connected to the SPI bus (defined by +SCLK, MOSI, and MISO) each must have its own CS. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bspio 9 11 12 13 50000 0 +.br + +.br +$ pigs bspio 10 11 12 13 50000 0 +.br + +.br +$ pigs bspio 29 19 20 21 50000 0 # GPIO 29 not avaialble on this Pi +.br +-41 +.br +ERROR: no permission to update GPIO +.br + +.EE + +.br + +.IP "\fBBSPIX cs bvs\fP - SPI bit bang transfer" +.IP "" 4 + +.br +This command writes bytes \fBbvs\fP to the bit bang SPI device +associated with slave select \fBcs\fP. It returns the same +number of bytes read from the device. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs bspio 5 13 19 12 10000 0 # MCP4251 DAC +.br +$ pigs bspio 6 13 19 12 20000 3 # MCP3008 ADC +.br + +.br +$ pigs bspix 5 0 16 # set DAC to 16 +.br +2 255 255 +.br + +.br +$ pigs bspix 5 12 0 # read back DAC +.br +2 254 16 +.br + +.br +$ pigs bspix 6 1 128 0 # read ADC input 0 +.br +3 0 3 184 # 952 +.br + +.br +$ pigs bspix 5 0 240 # set DAC to 240 +.br +2 255 255 +.br + +.br +$ pigs bspix 5 12 0 # read back DAC +.br +2 254 240 +.br + +.br +$ pigs bspix 6 1 128 0 # read ADC input 0 +.br +3 0 0 63 # 63 +.br + +.br +$ pigs bspix 5 0 128 # set DAC to 128 +.br +2 255 255 +.br + +.br +$ pigs bspix 5 12 0 # read back DAC +.br +2 254 128 +.br + +.br +$ pigs bspix 6 1 128 0 # read ADC input 0 +.br +3 0 1 255 # 511 +.br + +.br +$ pigs bspic 5 # close SPI CS 5 +.br +$ pigs bspic 6 # close SPI CS 6 +.br + +.br +$ pigs bspic 5 # try to close SPI CS 5 again +.br +-142 +.br +ERROR: no bit bang SPI in progress on GPIO +.br + +.EE + +.br + +.br + +.IP "\fBCF1 uvs\fP - Custom function 1" +.IP "" 4 + +.br +This command calls a user customised function. The meaning of +any paramaters and the returned value is defined by the +customiser. + +.br + +.IP "\fBCF2 uvs\fP - Custom function 2" +.IP "" 4 + +.br +This command calls a user customised function. The meaning of +any paramaters and the returned value is defined by the +customiser. + +.br + +.IP "\fBCGI \fP - Configuration get internals" +.IP "" 4 +This command returns the value of the internal library +configuration settings. + +.br + +.IP "\fBCSI v\fP - Configuration set internals" +.IP "" 4 +This command sets the value of the internal library +configuration settings to \fBv\fP. + +.br + +.IP "\fBEVM h bits\fP - Set events to monitor" +.IP "" 4 +This command starts event reporting on handle \fBh\fP (returned by +a prior call to \fBNO\fP). + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The notification gets reports for each event specified by \fBbits\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs evm 0 -1 # Shorthand for events 0-31. +.br +$ pigs evm 0 0xf0 # Get notifications for events 4-7. +.br + +.br +$ pigs evm 1 0xf +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBEVT event\fP - Trigger event" +.IP "" 4 +This command triggers event \fBevent\fP. + +.br +One event, number 31, is predefined. This event is +auto generated on BSC slave activity. + +.br + +\fBExample\fP +.br + +.EX +$ pigs evt 12 +.br +$ pigs evt 5 +.br + +.br +$ pigs evt 32 +.br +-143 +.br +ERROR: bad event id +.br + +.EE + +.br + +.IP "\fBFC h\fP - Close file handle" +.IP "" 4 +This command closes a file handle \fBh\fP previously opened with \fBFO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fc 0 # First close okay. +.br + +.br +$ pigs fc 0 # Second fails. +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBFG u stdy\fP - Set a glitch filter on a GPIO" +.IP "" 4 + +.br +Level changes on the GPIO \fBu\fP are not reported unless the level +has been stable for at least \fBstdy\fP microseconds. The +level is then reported. Level changes of less than \fBstdy\fP +microseconds are ignored. + +.br +The filter only affects callbacks (including pipe notifications). + +.br +The \fBR/READ\fP, \fBBR1\fP, and \fBBR2\fP commands are not affected. + +.br +Note, each (stable) edge will be timestamped \fBstdy\fP microseconds +after it was first detected. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fg 4 250 +.br + +.br +$ pigs fg 4 1000000 +.br +-125 +.br +ERROR: bad filter parameter +.br + +.EE + +.br + +.IP "\fBFL pat num\fP - List files which match pattern" +.IP "" 4 +This command returns a list of the files matching \fBpat\fP. Up +to \fBnum\fP bytes may be returned. + +.br +Upon success the count of returned bytes followed by the matching +files is returned. On error a negative status code will be returned. + +.br +A newline (0x0a) character separates each file name. + +.br +Only files which have a matching entry in /opt/pigpio/access may +be listed. + +.br +Suppose /opt/pigpio/access contains + +.br +/sys/bus/w1/devices/28*/w1_slave r + +.br + +\fBExample\fP +.br + +.EX +$ pigs -a fl "/sys/bus/w1/devices/28*/w1_slave" 5000 +.br +90 /sys/bus/w1/devices/28-000005d34cd2/w1_slave +.br +/sys/bus/w1/devices/28-001414abbeff/w1_slave +.br + +.br +$ pigs -a fl "/sys/bus/*" 5000 +.br +ERROR: no permission to access file +.br +-137 +.br + +.EE + +.br + +.IP "\fBFN u stdy actv\fP - Set a noise filter on a GPIO" +.IP "" 4 + +.br +Level changes on the GPIO \fBu\fP are ignored until a level which has +been stable for \fBstdy\fP microseconds is detected. Level +changes on the GPIO are then reported for \fBactv\fP microseconds +after which the process repeats. + +.br +The filter only affects callbacks (including pipe notifications). + +.br +The \fBR/READ\fP, \fBBR1\fP, and \fBBR2\fP commands are not affected. + +.br +Note, level changes before and after the active period may +be reported. Your software must be designed to cope with +such reports. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fn 7 250 1000 +.br + +.br +$ pigs fn 7 2500000 1000 +.br +-125 +.br +ERROR: bad filter parameter +.br + +.EE + +.br + +.IP "\fBFO file mode\fP - Open a file in mode" +.IP "" 4 +This function returns a handle to a file \fBfile\fP opened +in a specified mode \fBmode\fP. + +.br +Upon success a handle (>=0) is returned. On error a negative status code +will be returned. + +.br +File + +.br +A file may only be opened if permission is granted by an entry in +/opt/pigpio/access. This is intended to allow remote access to files +in a more or less controlled manner. + +.br +Each entry in /opt/pigpio/access takes the form of a file path +which may contain wildcards followed by a single letter permission. +The permission may be R for read, W for write, U for read/write, +and N for no access. + +.br +Where more than one entry matches a file the most specific rule +applies. If no entry matches a file then access is denied. + +.br +Suppose /opt/pigpio/access contains the following entries + +.br + +.EX +/home/* n +.br +/home/pi/shared/dir_1/* w +.br +/home/pi/shared/dir_2/* r +.br +/home/pi/shared/dir_3/* u +.br +/home/pi/shared/dir_1/file.txt n +.br + +.EE + +.br +Files may be written in directory dir_1 with the exception +of file.txt. + +.br +Files may be read in directory dir_2. + +.br +Files may be read and written in directory dir_3. + +.br +If a directory allows read, write, or read/write access then files may +be created in that directory. + +.br +In an attempt to prevent risky permissions the following paths are +ignored in /opt/pigpio/access. + +.br + +.EX +a path containing .. +.br +a path containing only wildcards (*?) +.br +a path containing less than two non-wildcard parts +.br + +.EE + +.br +Mode + +.br +The mode may have the following values. + +.br + +.EX + Value Meaning +READ 1 open file for reading +WRITE 2 open file for writing +RW 3 open file for reading and writing + +.EE + +.br +The following values may be or'd into the mode. + +.br + +.EX + Value Meaning +APPEND 4 All writes append data to the end of the file +CREATE 8 The file is created if it doesn't exist +TRUNC 16 The file is truncated + +.EE + +.br +Newly created files are owned by root with permissions owner read and write. + +.br + +\fBExample\fP +.br + +.EX +$ ls /ram/*.c +.br +/ram/command.c /ram/pigpiod.c /ram/pigs.c +.br +/ram/x_pigpiod_if.c /ram/pig2vcd.c /ram/pigpiod_if2.c +.br +/ram/x_pigpio.c /ram/x_repeat.c /ram/pigpio.c +.br +/ram/pigpiod_if.c /ram/x_pigpiod_if2.c +.br + +.br +# assumes /opt/pigpio/access contains the following line +.br +# /ram/*.c r +.br + +.br +$ pigs fo /ram/pigpio.c 1 +.br +0 +.br + +.br +$ pigs fo /ram/new.c 1 +.br +-128 +.br +ERROR: file open failed +.br + +.br +$ pigs fo /ram/new.c 9 +.br +1 +.br + +.br +$ ls /ram/*.c -l +.br +-rw-r--r-- 1 joan joan 42923 Jul 10 11:22 /ram/command.c +.br +-rw------- 1 root root 0 Jul 10 16:54 /ram/new.c +.br +-rw-r--r-- 1 joan joan 2971 Jul 10 11:22 /ram/pig2vcd.c +.br +-rw------- 1 joan joan 296235 Jul 10 11:22 /ram/pigpio.c +.br +-rw-r--r-- 1 joan joan 9266 Jul 10 11:22 /ram/pigpiod.c +.br +-rw-r--r-- 1 joan joan 37331 Jul 10 11:22 /ram/pigpiod_if2.c +.br +-rw-r--r-- 1 joan joan 33088 Jul 10 11:22 /ram/pigpiod_if.c +.br +-rw-r--r-- 1 joan joan 7990 Jul 10 11:22 /ram/pigs.c +.br +-rw-r--r-- 1 joan joan 19970 Jul 10 11:22 /ram/x_pigpio.c +.br +-rw-r--r-- 1 joan joan 20804 Jul 10 11:22 /ram/x_pigpiod_if2.c +.br +-rw-r--r-- 1 joan joan 19844 Jul 10 11:22 /ram/x_pigpiod_if.c +.br +-rw-r--r-- 1 joan joan 19907 Jul 10 11:22 /ram/x_repeat.c +.br + +.EE + +.br + +.IP "\fBFR h num\fP - Read bytes from file handle" +.IP "" 4 +This command returns up to \fBnum\fP bytes of data read from the +file associated with handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fr 0 10 +.br +5 48 49 128 144 255 +.br + +.br +$ pigs fr 0 10 +.br +0 +.br + +.EE + +.br + +.IP "\fBFS h num from\fP - Seek to file handle position" +.IP "" 4 +This command seeks to a position within the file associated +with handle \fBh\fP. + +.br +The number of bytes to move is \fBnum\fP. Positive offsets +move forward, negative offsets backwards. The move start +position is determined by \fBfrom\fP as follows. + +.br + +.EX + From +0 start +1 current position +2 end + +.EE + +.br +Upon success the new byte position within the file (>=0) is +returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fs 0 200 0 # Seek to start of file plus 200 +.br +200 +.br + +.br +$ pigs fs 0 0 1 # Return current position +.br +200 +.br + +.br +$ pigs fs 0 0 2 # Seek to end of file, return size +.br +296235 +.br + +.EE + +.br + +.IP "\fBFW h bvs\fP - Write bytes to file handle" +.IP "" 4 +This command writes bytes \fBbvs\fP to the file +associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs fw 0 23 45 67 89 +.br + +.EE + +.br + +.IP "\fBGDC u\fP - Get GPIO PWM dutycycle" +.IP "" 4 + +.br +This command returns the PWM dutycycle in use on GPIO \fBu\fP. + +.br +Upon success the dutycycle is returned. On error a negative +status code will be returned. + +.br +For normal PWM the dutycycle will be out of the defined range +for the GPIO (see \fBPRG\fP). + +.br +If a hardware clock is active on the GPIO the reported +dutycycle will be 500000 (500k) out of 1000000 (1M). + +.br +If hardware PWM is active on the GPIO the reported dutycycle +will be out of a 1000000 (1M). + +.br + +\fBExample\fP +.br + +.EX +$ pigs p 4 129 +.br +$ pigs gdc 4 +.br +129 +.br + +.br +pigs gdc 5 +.br +-92 +.br +ERROR: GPIO is not in use for PWM +.br + +.EE + +.br + +.IP "\fBGPW u\fP - Get GPIO servo pulsewidth" +.IP "" 4 + +.br +This command returns the servo pulsewidth in use on GPIO \fBu\fP. + +.br +Upon success the servo pulsewidth is returned. On error a negative +status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs s 4 1235 +.br +$ pigs gpw 4 +.br +1235 +.br + +.br +$ pigs gpw 9 +.br +-93 +.br +ERROR: GPIO is not in use for servo pulses +.br + +.EE + +.br + +.IP "\fBH/HELP \fP - Display command help" +.IP "" 4 +This command displays a brief list of the commands and their parameters. + +.br + +\fBExample\fP +.br + +.EX +$ pigs h +.br + +.br +$ pigs help +.br + +.EE + +.br + +.IP "\fBHC g cf\fP - Set hardware clock frequency" +.IP "" 4 +This command sets the hardware clock associated with GPIO \fBg\fP to +frequency \fBcf\fP. Frequencies above 30MHz are unlikely to work. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs hc 4 5000 # start a 5 KHz clock on GPIO 4 (clock 0) +.br + +.br +$ pigs hc 5 5000000 # start a 5 MHz clcok on GPIO 5 (clock 1) +.br +-99 +.br +ERROR: need password to use hardware clock 1 +.br + +.EE + +.br +The same clock is available on multiple GPIO. The latest +frequency setting will be used by all GPIO which share a clock. + +.br +The GPIO must be one of the following. + +.br + +.EX +4 clock 0 All models +5 clock 1 All models but A and B (reserved for system use) +6 clock 2 All models but A and B +20 clock 0 All models but A and B +21 clock 1 All models but A and B Rev.2 (reserved for system use) + +.EE + +.br + +.EX +32 clock 0 Compute module only +34 clock 0 Compute module only +42 clock 1 Compute module only (reserved for system use) +43 clock 2 Compute module only +44 clock 1 Compute module only (reserved for system use) + +.EE + +.br +Access to clock 1 is protected by a password as its use will +likely crash the Pi. The password is given by or'ing 0x5A000000 +with the GPIO number. + +.br + +.IP "\fBHP g pf pdc\fP - Set hardware PWM frequency and dutycycle" +.IP "" 4 +This command sets the hardware PWM associated with GPIO \fBg\fP to +frequency \fBpf\fP with dutycycle \fBpdc\fP. Frequencies above 30MHz +are unlikely to work. + +.br +NOTE: Any waveform started by \fBWVTX\fP, \fBWVTXR\fP, or \fBWVCHA\fP +will be cancelled. + +.br +This function is only valid if the pigpio main clock is PCM. The +main clock defaults to PCM but may be overridden when the pigpio +daemon is started (option -t). + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +.EX +$ pigs hp 18 100 800000 # 80% dutycycle +.br + +.br +$ pigs hp 19 100 200000 # 20% dutycycle +.br + +.br +$ pigs hp 19 125000001 100000 +.br +-96 +.br +ERROR: hardware PWM frequency not 1-125M +.br + +.EE + +.br +The same PWM channel is available on multiple GPIO. The latest +frequency and dutycycle setting will be used by all GPIO which +share a PWM channel. + +.br +The GPIO must be one of the following. + +.br + +.EX +12 PWM channel 0 All models but A and B +13 PWM channel 1 All models but A and B +18 PWM channel 0 All models +19 PWM channel 1 All models but A and B + +.EE + +.br + +.EX +40 PWM channel 0 Compute module only +41 PWM channel 1 Compute module only +45 PWM channel 1 Compute module only +52 PWM channel 0 Compute module only +53 PWM channel 1 Compute module only + +.EE + +.br +The actual number of steps beween off and fully on is the +integral part of 250 million divided by \fBpf\fP. + +.br +The actual frequency set is 250 million / steps. + +.br +There will only be a million steps for a \fBpf\fP of 250. +Lower frequencies will have more steps and higher +frequencies will have fewer steps. \fBpdc\fP is +automatically scaled to take this into account. + +.br + +.IP "\fBHWVER \fP - Get hardware version" +.IP "" 4 +This command returns the hardware revision of the Pi. + +.br +The hardware revision is found in the last 4 characters on the revision +line of /proc/cpuinfo. + +.br +If the hardware revision can not be found or is not a valid hexadecimal +number the command returns 0. + +.br +The revision number can be used to determine the assignment of GPIO +to pins (see \fBg\fP). + +.br +There are currently three types of board. + +.br +Type 1 boards have hardware revision numbers of 2 and 3. + +.br +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. + +.br +Type 3 boards have hardware revision numbers of 16 or greater. + +.br +for "Revision : 0002" the command returns 2. + +.br +for "Revision : 000f" the command returns 15. + +.br +for "Revision : 000g" the command returns 0. + +.br + +\fBExample\fP +.br + +.EX +$ pigs hwver # On a B+ +.br +16 +.br + +.EE + +.br + +.IP "\fBI2CC h\fP - Close I2C handle" +.IP "" 4 +This command closes an I2C handle \fBh\fP previously opened with \fBI2CO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cc 0 # First close okay. +.br + +.br +$ pigs i2cc 0 # Second fails. +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBI2CO ib id if\fP - Open I2C bus and device with flags" +.IP "" 4 +This command returns a handle to access device \fBid\fP on I2C bus \fBib\fP. +The device is opened with flags \fBif\fP. + +.br +Physically buses 0 and 1 are available on the Pi. Higher +numbered buses will be available if a kernel supported bus +multiplexor is being used. + +.br +The GPIO used are given in the following table. + +.br + +.EX + SDA SCL +I2C 0 0 1 +I2C 1 2 3 + +.EE + +.br +No flags are currently defined. The parameter \fBif\fP should be 0. + +.br +Upon success the next free handle (>=0) is returned. On error a +negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2co 1 0x70 0 # Bus 1, device 0x70, flags 0. +.br +0 +.br + +.br +$ pigs i2co 1 0x53 0 # Bus 1, device 0x53, flags 0. +.br +1 +.br + +.EE + +.br + +.IP "\fBI2CPC h r wv\fP - smb Process Call: exchange register with word" +.IP "" 4 +This command writes \fBwv\fP to register \fBr\fP of the I2C device +associated with handle \fBh\fP and returns a 16-bit word read from the +device. + +.br +Upon success a value between 0 and 65535 will be returned. On error +a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cpc 0 37 43210 +.br +39933 +.br + +.br +$ pigs i2cpc 0 256 43210 +.br +ERROR: bad i2c/spi/ser parameter +.br +-81 +.br + +.EE + +.br + +.IP "\fBI2CPK h r bvs\fP - smb Block Process Call: exchange data bytes with register" +.IP "" 4 + +.br +This command writes the data bytes \fBbvs\fP to register \fBr\fP of the I2C device +associated with handle \fBh\fP and returns a device specific number of bytes. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cpk 0 0 0x11 0x12 +.br +6 0 0 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBI2CRB h r\fP - smb Read Byte Data: read byte from register" +.IP "" 4 + +.br +This command returns a single byte read from register \fBr\fP of the I2C device +associated with handle \fBh\fP. + +.br +Upon success a value between 0 and 255 will be returned. On error +a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2crb 0 0 +.br +6 +.br + +.EE + +.br + +.IP "\fBI2CRD h num\fP - i2c Read bytes" +.IP "" 4 + +.br +This command returns \fBnum\fP bytes read from the I2C device associated with +handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br +This command operates on the raw I2C device. The maximum value of the +parameter \fBnum\fP is dependent on the I2C drivers and the device +itself. pigs imposes a limit of about 8000 bytes. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2crd 0 16 +.br +16 6 24 0 0 0 0 0 0 0 0 0 0 0 0 32 78 +.br + +.EE + +.br + +.IP "\fBI2CRI h r num\fP - smb Read I2C Block Data: read bytes from register" +.IP "" 4 + +.br +This command returns \fBnum\fP bytes from register \fBr\fP of the I2C device +associated with handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br +The parameter \fBnum\fP may be 1-32. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cri 0 0 16 +.br +16 237 155 155 155 155 155 155 155 155 155 155 155 155 155 155 155 +.br + +.EE + +.br + +.IP "\fBI2CRK h r\fP - smb Read Block Data: read data from register" +.IP "" 4 + +.br +This command returns between 1 and 32 bytes read from register \fBr\fP of +the I2C device associated with handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br +The number of bytes of returned data is specific to the device and +register. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2crk 0 0 +.br +6 0 0 0 0 0 0 +.br + +.br +$ pigs i2crk 0 1 +.br +24 0 0 0 0 0 0 0 0 0 0 0 0 120 222 105 215 128 87 195 217 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBI2CRS h\fP - smb Read Byte: read byte" +.IP "" 4 + +.br +This command returns a single byte read from the I2C device +associated with handle \fBh\fP. + +.br +Upon success a value between 0 and 255 will be returned. On error +a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2crs 0 +.br +0 +.br + +.EE + +.br + +.IP "\fBI2CRW h r\fP - smb Read Word Data: read word from register" +.IP "" 4 + +.br +This command returns a single 16 bit word read from register \fBr\fP of +the I2C device associated with handle \fBh\fP. + +.br +Upon success a value between 0 and 65535 will be returned. On error +a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2crw 0 0 +.br +6150 +.br + +.EE + +.br + +.IP "\fBI2CWB h r bv\fP - smb Write Byte Data: write byte to register" +.IP "" 4 + +.br +This command writes a single byte \fBbv\fP to register \fBr\fP of the +I2C device associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cwb 0 10 0x54 +.br + +.EE + +.br + +.IP "\fBI2CWD h bvs\fP - i2c Write data" +.IP "" 4 + +.br +This command writes a block of bytes \fBbvs\fP to the I2C device +associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The number of bytes which may be written in one transaction is +dependent on the I2C drivers and the device itself. pigs imposes +a limit of about 500 bytes. + +.br +This command operates on the raw I2C device. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cwd 0 0x01 0x02 0x03 0x04 +.br + +.EE + +.br + +.IP "\fBI2CWI h r bvs\fP - smb Write I2C Block Data" +.IP "" 4 + +.br +This command writes between 1 and 32 bytes \fBbvs\fP to register \fBr\fP of +the I2C device associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cwi 0 4 0x01 0x04 0xc0 +.br + +.EE + +.br + +.IP "\fBI2CWK h r bvs\fP - smb Write Block Data: write data to register" +.IP "" 4 + +.br +This command writes between 1 and 32 bytes \fBbvs\fP to register \fBr\fP of +the I2C device associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +pigs i2cwk 0 4 0x01 0x04 0xc0 +.br + +.EE + +.br + +.IP "\fBI2CWQ h bit\fP - smb Write Quick: write bit" +.IP "" 4 + +.br +This command writes a single \fBbit\fP to the I2C device associated +with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cwq 0 1 +.br + +.EE + +.br + +.IP "\fBI2CWS h bv\fP - smb Write Byte: write byte" +.IP "" 4 + +.br +This command writes a single byte \fBbv\fP to the I2C device associated +with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cws 0 0x12 +.br + +.br +$ pigs i2cws 0 0xff +.br +-82 +.br +ERROR: I2C write failed +.br + +.EE + +.br + +.IP "\fBI2CWW h r wv\fP - smb Write Word Data: write word to register" +.IP "" 4 + +.br +This command writes a single 16 bit word \fBwv\fP to register \fBr\fP of +the I2C device associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs i2cww 0 0 0xffff +.br + +.EE + +.br + +.IP "\fBI2CZ h bvs\fP - Performs multiple I2C transactions" +.IP "" 4 +This command executes a sequence of I2C operations. The +operations to be performed are specified by the contents of \fBbvs\fP +which contains the concatenated command codes and associated data. + +.br +The following command codes are supported: + +.br + +.EX +Name Cmd & Data Meaning +End 0 No more commands +Escape 1 Next P is two bytes +On 2 Switch combined flag on +Off 3 Switch combined flag off +Address 4 P Set I2C address to P +Flags 5 lsb msb Set I2C flags to lsb + (msb << 8) +Read 6 P Read P bytes of data +Write 7 P ... Write P bytes of data + +.EE + +.br +The address, read, and write commands take a parameter P. +Normally P is one byte (0-255). If the command is preceded by +the Escape command then P is two bytes (0-65535, least significant +byte first). + +.br +The address defaults to that associated with the handle \fBh\fP. +The flags default to 0. The address and flags maintain their +previous value until updated. + +.br + +\fBExample\fP +.br + +.EX +Set address 0x53, write 0x32, read 6 bytes +.br +Set address 0x1E, write 0x03, read 6 bytes +.br +Set address 0x68, write 0x1B, read 8 bytes +.br +End +.br + +.br +0x04 0x53 0x07 0x01 0x32 0x06 0x06 +.br +0x04 0x1E 0x07 0x01 0x03 0x06 0x06 +.br +0x04 0x68 0x07 0x01 0x1B 0x06 0x08 +.br +0x00 +.br + +.EE + +.br + +.br + +.IP "\fBM/MODES g m\fP - Set GPIO mode" +.IP "" 4 + +.br +This command sets GPIO \fBg\fP to mode \fBm\fP, typically input (read) +or output (write). + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +Each GPIO can be configured to be in one of 8 different modes. The modes +are named Input, Output, ALT0, ALT1, ALT2, ALT3, ALT4, and ALT5. + +.br +To set the mode use the code for the mode. + +.br + +.EX +Mode Input Output ALT0 ALT1 ALT2 ALT3 ALT4 ALT5 +Code R W 0 1 2 3 4 5 + +.EE + +.br + +\fBExample\fP +.br + +.EX +$ pigs m 4 r # Input (read) +.br +$ pigs m 4 w # Output (write) +.br +$ pigs m 4 0 # ALT 0 +.br +$ pigs m 4 5 # ALT 5 +.br + +.EE + +.br + +.IP "\fBMG/MODEG g\fP - Get GPIO mode" +.IP "" 4 + +.br +This command returns the current mode of GPIO \fBg\fP. + +.br +Upon success the value of the GPIO mode is returned. +On error a negative status code will be returned. + +.br + +.EX +Value 0 1 2 3 4 5 6 7 +Mode Input Output ALT5 ALT4 ALT0 ALT1 ALT2 ALT3 + +.EE + +.br + +\fBExample\fP +.br + +.EX +$ pigs mg 4 +.br +1 +.br + +.EE + +.br + +.IP "\fBMICS v\fP - Microseconds delay" +.IP "" 4 +This command delays execution for \fBv\fP microseconds. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The main use of this command is expected to be within \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs mics 20 # Delay 20 microseconds. +.br +$ pigs mics 1000000 # Delay 1 second. +.br + +.br +$ pigs mics 2000000 +.br +-64 +.br +ERROR: bad MICS delay (too large) +.br + +.EE + +.br + +.IP "\fBMILS v\fP - Milliseconds delay" +.IP "" 4 + +.br +This command delays execution for \fBv\fP milliseconds. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs mils 2000 # Delay 2 seconds. +.br + +.br +$ pigs mils 61000 +.br +-65 +.br +ERROR: bad MILS delay (too large) +.br + +.EE + +.br + +.IP "\fBNB h bits\fP - Start notification" +.IP "" 4 + +.br +This command starts notifications on handle \fBh\fP returned by +a prior call to \fBNO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The notification gets state changes for each GPIO specified by \fBbits\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs nb 0 -1 # Shorthand for GPIO 0-31. +.br +$ pigs nb 0 0xf0 # Get notifications for GPIO 4-7. +.br + +.br +$ pigs nb 1 0xf +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBNC h\fP - Close notification" +.IP "" 4 + +.br +This command stops notifications on handle \fBh\fP returned by +a prior call to \fBNO\fP and releases the handle for reuse. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs nc 0 # First call succeeds. +.br + +.br +$ pigs nc 1 # Second call fails. +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBNO \fP - Request a notification" +.IP "" 4 + +.br +This command requests a free notification handle. + +.br +A notification is a method for being notified of GPIO state changes via a pipe. + +.br +Upon success the command returns a handle greater than or equal to zero. +On error a negative status code will be returned. + +.br +Notifications for handle x will be available at the pipe named /dev/pigpiox +(where x is the handle number). + +.br +E.g. if the command returns 15 then the notifications must be read +from /dev/pigpio15. + +.br + +\fBExample\fP +.br + +.EX +$ pigs no +.br +0 +.br + +.EE + +.br + +.IP "\fBNP h\fP - Pause notification" +.IP "" 4 + +.br +This command pauses notifications on handle \fBh\fP returned by +a prior call to \fBNO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +Notifications for the handle are suspended until a new \fBNB\fP command +is given for the handle. + +.br + +\fBExample\fP +.br + +.EX +$ pigs np 0 +.br + +.EE + +.br + +.IP "\fBP/PWM u v\fP - Set GPIO PWM value" +.IP "" 4 + +.br +This command starts PWM on GPIO \fBu\fP with dutycycle \fBv\fP. The dutycycle +varies from 0 (off) to range (fully on). The range defaults to 255. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +This and the servo functionality use the DMA and PWM or PCM peripherals +to control and schedule the pulsewidths and dutycycles. + +.br +The \fBPRS\fP command may be used to change the default range of 255. + +.br + +\fBExample\fP +.br + +.EX +$ pigs p 4 64 # Start PWM on GPIO 4 with 25% dutycycle +.br +$ pigs p 4 128 # 50% +.br +$ pigs p 4 192 # 75% +.br +$ pigs p 4 255 # 100% +.br + +.EE + +.br + +.IP "\fBPADG pad\fP - Get pad drive strength" +.IP "" 4 + +.br +This command gets the \fBpad\fP drive strength \fBpadma\fP in mA. + +.br +Returns the pad drive strength if OK. On error a negative status code +will be returned. + +.br + +.EX +Pad GPIO +0 0-27 +1 28-45 +2 46-53 + +.EE + +.br + +\fBExample\fP +.br + +.EX +$ pigs padg 0 +.br +8 +.br +$ pigs pads 0 16 +.br +$ pigs padg 0 +.br +16 +.br +pigs padg 3 +.br +-126 +.br +ERROR: bad pad number +.br + +.EE + +.br + +.IP "\fBPADS pad padma\fP - Set pad drive strength" +.IP "" 4 + +.br +This command sets the \fBpad\fP drive strength \fBpadma\fP in mA. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +.EX +Pad GPIO +0 0-27 +1 28-45 +2 46-53 + +.EE + +.br + +\fBExample\fP +.br + +.EX +$ pigs pads 0 16 +.br +$ pigs padg 0 +.br +16 +.br +$ pigs pads 0 17 +.br +-127 +.br +ERROR: bad pad drive strength +.br + +.EE + +.br + +.IP "\fBPARSE t\fP - Validate script" +.IP "" 4 + +.br +Validates the text \fBt\fP of a script without storing the script. + +.br +Upon success nothing is returned. On error a list of detected +script errors will be given. + +.br +See \fBScripts\fP. + +.br +This command may be used to find script syntax faults. + +.br + +\fBExample\fP +.br + +.EX +$ pigs parse tag 100 w 22 1 mils 200 w 22 0 mils 800 jmp 100 +.br + +.br +$ pigs parse tag 0 w 22 1 mills 50 w 22 0 dcr p10 jp 99 +.br +Unknown command: mills +.br +Unknown command: 50 +.br +Bad parameter to dcr +.br +Can't resolve tag 99 +.br + +.EE + +.br + +.IP "\fBPFG u\fP - Get GPIO PWM frequency" +.IP "" 4 + +.br +This command returns the PWM frequency in Hz used for GPIO \fBu\fP. + +.br +Upon success the PWM frequency is returned. On error a negative +status code will be returned. + +.br +For normal PWM the frequency will be that defined for the GPIO +by \fBPFS\fP. + +.br +If a hardware clock is active on the GPIO the reported frequency +will be that set by \fBHC\fP. + +.br +If hardware PWM is active on the GPIO the reported frequency +will be that set by \fBHP\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs pfg 4 +.br +800 +.br + +.br +$ pigs pfg 34 +.br +ERROR: GPIO not 0-31 +.br +-2 +.br + +.EE + +.br + +.IP "\fBPFS u v\fP - Set GPIO PWM frequency" +.IP "" 4 +This command sets the PWM frequency \fBv\fP to be used for GPIO \fBu\fP. + +.br +The numerically closest frequency to \fBv\fP will be selected. + +.br +Upon success the new frequency is returned. On error a negative status code +will be returned. + +.br +If PWM is currently active on the GPIO it will be +switched off and then back on at the new frequency. + +.br +Each GPIO can be independently set to one of 18 different PWM +frequencies. + +.br +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). The +sample rate is set when the pigpio daemon is started. + +.br +The frequencies for each sample rate are: + +.br + +.EX + Hertz +.br + +.br + 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 +.br + 1250 1000 800 500 400 250 200 100 50 +.br + +.br + 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 +.br + 625 500 400 250 200 125 100 50 25 +.br + +.br + 4: 10000 5000 2500 2000 1250 1000 625 500 400 +.br + 313 250 200 125 100 63 50 25 13 +.br +sample +.br + rate +.br + (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 +.br + 250 200 160 100 80 50 40 20 10 +.br + +.br + 8: 5000 2500 1250 1000 625 500 313 250 200 +.br + 156 125 100 63 50 31 25 13 6 +.br + +.br + 10: 4000 2000 1000 800 500 400 250 200 160 +.br + 125 100 80 50 40 25 20 10 5 +.br + +.EE + +.br + +\fBExample\fP +.br + +.EX +pigs pfs 4 0 # 0 selects the lowest frequency. +.br +10 +.br + +.br +$ pigs pfs 4 1000 # Set 1000Hz PWM. +.br +1000 +.br + +.br +$ pigs pfs 4 100000 # Very big number selects the highest frequency. +.br +8000 +.br + +.EE + +.br + +.IP "\fBPIGPV \fP - Get pigpio library version" +.IP "" 4 + +.br +This command returns the pigpio library version. + +.br + +\fBExample\fP +.br + +.EX +$ pigs pigpv +.br +17 +.br + +.EE + +.br + +.IP "\fBPRG u\fP - Get GPIO PWM range" +.IP "" 4 + +.br +This command returns the dutycycle range for GPIO \fBu\fP. + +.br +Upon success the range is returned. On error a negative status code +will be returned. + +.br +If a hardware clock or hardware PWM is active on the GPIO the reported +range will be 1000000 (1M). + +.br + +\fBExample\fP +.br + +.EX +$ pigs prg 4 +.br +255 +.br + +.EE + +.br + +.IP "\fBPROC t\fP - Store script" +.IP "" 4 + +.br +This command stores a script \fBt\fP for later execution. + +.br +If the script is valid a script id (>=0) is returned which is passed +to the other script commands. On error a negative status code +will be returned. + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs proc tag 123 w 4 0 mils 200 w 4 1 mils 300 dcr p0 jp 123 +.br +0 +.br + +.br +$ pigs proc tag 123 w 4 0 mils 5 w 4 1 mils 5 jmp 12 +.br +ERROR: script has unresolved tag +.br +-63 +.br + +.EE + +.br + +.IP "\fBPROCD sid\fP - Delete script" +.IP "" 4 + +.br +This command deletes script \fBsid\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs procd 1 +.br + +.br +$ pigs procd 1 +.br +ERROR: unknown script id +.br +-48 +.br + +.EE + +.br + +.IP "\fBPROCP sid\fP - Get script status and parameters" +.IP "" 4 + +.br +This command returns the status of script \fBsid\fP as well as the +current value of its 10 parameters. + +.br +Upon success the script status and parameters are returned. +On error a negative status code will be returned. + +.br +The script status may be one of + +.br + +.EX +0 being initialised +1 halted +2 running +3 waiting +4 failed + +.EE + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs procp 0 +.br +1 0 0 0 0 0 0 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBPROCR sid pars\fP - Run script" +.IP "" 4 + +.br +This command runs stored script \fBsid\fP passing it up to 10 optional +parameters. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs proc tag 123 w 4 0 mils 200 w 4 1 mils 300 dcr p0 jp 123 +.br +0 +.br + +.br +$ pigs procr 0 50 # Run script 0 with parameter 0 of 50. +.br + +.br +$ pigs procp 0 +.br +2 44 0 0 0 0 0 0 0 0 0 +.br +$ pigs procp 0 +.br +2 37 0 0 0 0 0 0 0 0 0 +.br +$ pigs procp 0 +.br +2 10 0 0 0 0 0 0 0 0 0 +.br +$ pigs procp 0 +.br +2 5 0 0 0 0 0 0 0 0 0 +.br +$ pigs procp 0 +.br +2 2 0 0 0 0 0 0 0 0 0 +.br +$ pigs procp 0 +.br +1 -1 0 0 0 0 0 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBPROCS sid\fP - Stop script" +.IP "" 4 + +.br +This command stops a running script \fBsid\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs procs 0 +.br + +.br +$ pigs procs 1 +.br +-48 +.br +ERROR: unknown script id +.br + +.EE + +.br + +.IP "\fBPROCU sid pars\fP - Set script parameters" +.IP "" 4 + +.br +This command sets the parameters of a stored script \fBsid\fP passing +it up to 10 parameters. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +See \fBScripts\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs proc tag 0 hp 18 p0 p1 mils 1000 jmp 0 +.br +0 +.br +$ pigs procu 0 50 500000 +.br +$ pigs procr 0 +.br +$ pigs procu 0 100 +.br +$ pigs procu 0 200 +.br +$ pigs procu 0 200 100000 +.br + +.EE + +.br + +.IP "\fBPRRG u\fP - Get GPIO PWM real range" +.IP "" 4 + +.br +This command returns the real underlying range used by GPIO \fBu\fP. + +.br +If a hardware clock is active on the GPIO the reported +real range will be 1000000 (1M). + +.br +If hardware PWM is active on the GPIO the reported real range +will be approximately 250M divided by the set PWM frequency. + +.br +On error a negative status code will be returned. + +.br +See \fBPRS\fP. + +.br + +\fBExample\fP +.br + +.EX +$ pigs prrg 17 +.br +250 +.br + +.br +$ pigs pfs 17 0 +.br +10 +.br +$ pigs prrg 17 +.br +20000 +.br + +.br +$ pigs pfs 17 100000 +.br +8000 +.br +$ pigs prrg 17 +.br +25 +.br + +.EE + +.br + +.IP "\fBPRS u v\fP - Set GPIO PWM range" +.IP "" 4 + +.br +This command sets the dutycycle range \fBv\fP to be used for GPIO \fBu\fP. +Subsequent uses of command \fBP/PWM\fP will use a dutycycle between 0 (off) +and \fBv\fP (fully on). + +.br +Upon success the real underlying range used by the GPIO is returned. +On error a negative status code will be returned. + +.br +If PWM is currently active on the GPIO its dutycycle will be scaled to +reflect the new range. + +.br +The real range, the number of steps between fully off and fully on +for each frequency, is given in the following table. + +.br + +.EX + #1 #2 #3 #4 #5 #6 #7 #8 #9 + 25 50 100 125 200 250 400 500 625 + +#10 #11 #12 #13 #14 #15 #16 #17 #18 +800 1000 1250 2000 2500 4000 5000 10000 20000 + +.EE + +.br +The real value set by \fBPRS\fP is (dutycycle * real range) / range. + +.br +See \fBPRRG\fP + +.br + +\fBExample\fP +.br + +.EX +$ pigs prs 18 1000 +.br +250 +.br + +.EE + +.br + +.IP "\fBPUD g p\fP - Set GPIO pull up/down" +.IP "" 4 + +.br +This command sets the internal pull/up down for GPIO \fBg\fP to mode \fBp\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The mode may be pull-down (D), pull-up (U), or off (O). + +.br + +\fBExample\fP +.br + +.EX +$ pigs pud 4 d # Set pull-down on GPIO 4. +.br +$ pigs pud 4 u # Set pull-up on GPIO 4. +.br +$ pigs pud 4 o # No pull-up/down on GPIO 4. +.br + +.EE + +.br + +.IP "\fBR/READ g\fP - Read GPIO level" +.IP "" 4 + +.br +This reads the current level of GPIO \fBg\fP. + +.br +Upon success the current level is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs r 17 # Get level of GPIO 17. +.br +0 +.br + +.br +$ pigs r 4 # Get level of GPIO 4. +.br +1 +.br + +.EE + +.br + +.IP "\fBS/SERVO u v\fP - Set GPIO servo pulsewidth" +.IP "" 4 + +.br +This command starts servo pulses of \fBv\fP microseconds on GPIO \fBu\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The servo pulsewidth may be 0 (off), 500 (most anti-clockwise) +to 2500 (most clockwise). + +.br +The range supported by servos varies and should probably be determined +by experiment. Generally values between 1000-2000 should be safe. +A value of 1500 should always be safe and represents +the mid-point of rotation. + +.br +You can DAMAGE a servo if you command it to move beyond its limits. + +.br + +\fBExample\fP +.br + +.EX +$ pigs SERVO 17 1500 +.br + +.EE + +.br +This example causes an on pulse of 1500 microseconds duration to be +transmitted on GPIO 17 at a rate of 50 times per second. + +.br +This will command a servo connected to GPIO 17 to rotate to its mid-point. + +.br + +\fBExample\fP +.br + +.EX +pigs s 17 0 # Switch servo pulses off. +.br + +.EE + +.br + +.IP "\fBSERC h\fP - Close serial handle" +.IP "" 4 + +.br +This command closes a serial handle \fBh\fP previously opened with \fBSERO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serc 0 # First close okay. +.br + +.br +$ pigs serc 0 # Second close gives error. +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBSERDA h\fP - Check for serial data ready to read" +.IP "" 4 + +.br +This command returns the number of bytes of data available +to be read from the serial device associated with handle \fBh\fP. + +.br +Upon success the count of bytes available to be read is +returned (which may be 0). On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serda 0 +.br +0 +.br + +.EE + +.br + +.IP "\fBSERO dev b sef\fP - Open serial device dev at baud b with flags" +.IP "" 4 + +.br +This command opens the serial \fBdev\fP at \fBb\fP bits per second. + +.br +No flags are currently defined. \fBsef\fP should be set to zero. + +.br +Upon success a handle (>=0) is returned. On error a negative status code +will be returned. + +.br +The device name must start with /dev/tty or /dev/serial. + +.br + +.br +The baud rate must be one of 50, 75, 110, 134, 150, +200, 300, 600, 1200, 1800, 2400, 4800, 9600, 19200, +38400, 57600, 115200, or 230400. + +.br + +\fBExample\fP +.br + +.EX +$ pigs sero /dev/ttyAMA0 9600 0 +.br +0 +.br + +.br +$ pigs sero /dev/tty1 38400 0 +.br +1 +.br + +.EE + +.br + +.IP "\fBSERR h num\fP - Read bytes from serial handle" +.IP "" 4 + +.br +This command returns up to \fBnum\fP bytes of data read from the +serial device associated with handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serr 0 10 +.br +5 48 49 128 144 255 +.br + +.br +$ pigs serr 0 10 +.br +0 +.br + +.EE + +.br + +.IP "\fBSERRB \fP - Read byte from serial handle" +.IP "" 4 + +.br +This command returns a byte of data read from the serial +device associated with handle \fBh\fP. + +.br +Upon success a number between 0 and 255 is returned. +On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serrb 0 +.br +23 +.br +$ pigs serrb 0 +.br +45 +.br + +.EE + +.br + +.IP "\fBSERW h bvs\fP - Write bytes to serial handle" +.IP "" 4 + +.br +This command writes bytes \fBbvs\fP to the serial device +associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serw 0 23 45 67 89 +.br + +.EE + +.br + +.IP "\fBSERWB h bv\fP - Write byte to serial handle" +.IP "" 4 + +.br +This command writes a single byte \fBbv\fP to the serial device +associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs serwb 0 23 +.br +$ pigs serwb 0 0xf0 +.br + +.EE + +.br + +.IP "\fBSHELL name str\fP - Execute a shell command" +.IP "" 4 + +.br +This command uses the system call to execute a shell script \fBname\fP +with the given string \fBstr\fP as its parameter. + +.br +The exit status of the system call is returned if OK, otherwise +PI_BAD_SHELL_STATUS. + +.br +\fBname\fP must exist in /opt/pigpio/cgi and must be executable. + +.br +The returned exit status is normally 256 times that set +by the shell script exit function. If the script can't +be found 32512 will be returned. + +.br +The following table gives some example returned statuses. + +.br + +.EX +Script exit status Returned system call status +1 256 +5 1280 +10 2560 +200 51200 +script not found 32512 + +.EE + +.br + +\fBExample\fP +.br + +.EX +# pass two parameters, hello and world +.br +$ pigs shell scr1 hello world +.br +256 +.br + +.br +# pass three parameters, hello, string with spaces, and world +.br +$ pigs shell scr1 "hello 'string with spaces' world" +.br +256 +.br + +.br +# pass one parameter, hello string with spaces world +.br +$ pigs shell scr1 "\"hello string with spaces world\"" +.br +256 +.br + +.br +# non-existent script +.br +$ pigs shell scr78 par1 +.br +32512 +.br + +.EE + +.br + +.IP "\fBSLR u num\fP - Read bit bang serial data from GPIO" +.IP "" 4 + +.br +This command returns up to \fBnum\fP bytes of bit bang serial data +read from GPIO \fBu\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br +The GPIO \fBu\fP should have been initialised with the \fBSLRO\fP command. + +.br +The bytes returned for each character depend upon the number of +data bits \fBdb\fP specified in the \fBSLRO\fP command. + +.br +For \fBdb\fP 1-8 there will be one byte per character. +.br +For \fBdb\fP 9-16 there will be two bytes per character. +.br +For \fBdb\fP 17-32 there will be four bytes per character. + +.br + +\fBExample\fP +.br + +.EX +$ pigs slr 15 20 +.br +6 1 0 23 45 89 0 +.br + +.EE + +.br + +.IP "\fBSLRC u\fP - Close GPIO for bit bang serial data" +.IP "" 4 + +.br +This command closes GPIO \fBu\fP for reading bit bang serial data. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs slrc 23 +.br + +.br +$ pigs slrc 23 +.br +-38 +.br +ERROR: no serial read in progress on GPIO +.br + +.EE + +.br + +.IP "\fBSLRI u v\fP - Sets bit bang serial data logic levels" +.IP "" 4 + +.br +This command sets the logic level for reading bit bang serial data +on GPIO \fBu\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The invert parameter \fBv\fP is 1 for inverted signal, 0 for normal. + +.br + +\fBExample\fP +.br + +.EX +$ pigs slri 17 1 # invert logic on GPIO 17 +.br + +.br +$ pigs slri 23 0 # use normal logic on GPIO 23 +.br + +.EE + +.br + +.IP "\fBSLRO u b db\fP - Open GPIO for bit bang serial data" +.IP "" 4 + +.br +This command opens GPIO \fBu\fP for reading bit bang serial data +at \fBb\fP baud and \fBdb\fP data bits. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The baud rate may be between 50 and 250000 bits per second. + +.br +The received data is held in a cyclic buffer. + +.br +It is the user's responsibility to read the data (with \fBSLR\fP) +in a timely fashion. + +.br + +\fBExample\fP +.br + +.EX +$ pigs slro 23 19200 8 +.br + +.br +$ pigs slro 23 19200 8 +.br +-50 +.br +ERROR: GPIO already in use +.br + +.EE + +.br + +.IP "\fBSPIC h\fP - SPI close handle" +.IP "" 4 + +.br +This command closes the SPI handle \fBh\fP returned by a prior +call to \fBSPIO\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs spic 1 +.br + +.br +$ pigs spic 1 +.br +-25 +.br +ERROR: unknown handle +.br + +.EE + +.br + +.IP "\fBSPIO c b spf\fP - SPI open channel at baud b with flags" +.IP "" 4 + +.br +This command returns a handle to a SPI device on channel \fBc\fP. + +.br +Data will be transferred at \fBb\fP bits per second. The flags \fBspf\fP +may be used to modify the default behaviour of 4-wire operation, +mode 0, active low chip select. + +.br +Speeds between 32kbps and 125Mbps are allowed. Speeds above 30Mbps +are unlikely to work. + +.br +The Pi has two SPI peripherals: main and auxiliary. + +.br +The main SPI has two chip selects (channels), the auxiliary has +three. + +.br +The auxiliary SPI is available on all models but the A and B. + +.br +The GPIO used are given in the following table. + +.br + +.EX + MISO MOSI SCLK CE0 CE1 CE2 +Main SPI 9 10 11 8 7 - +Aux SPI 19 20 21 18 17 16 + +.EE + +.br +The flags consists of the least significant 22 bits. + +.br + +.EX +21 20 19 18 17 16 15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0 +.br + b b b b b b R T n n n n W A u2 u1 u0 p2 p1 p0 m m +.br + +.EE + +.br +mm defines the SPI mode. + +.br +Warning: modes 1 and 3 do not appear to work on the auxiliary SPI. + +.br + +.EX +Mode POL PHA +.br + 0 0 0 +.br + 1 0 1 +.br + 2 1 0 +.br + 3 1 1 +.br + +.EE + +.br +px is 0 if CEx is active low (default) and 1 for active high. + +.br +ux is 0 if the CEx GPIO is reserved for SPI (default) and 1 otherwise. + +.br +A is 0 for the main SPI, 1 for the auxiliary SPI. + +.br +W is 0 if the device is not 3-wire, 1 if the device is 3-wire. Main +SPI only. + +.br +nnnn defines the number of bytes (0-15) to write before switching +the MOSI line to MISO to read data. This field is ignored +if W is not set. Main SPI only. + +.br +T is 1 if the least significant bit is transmitted on MOSI first, the +default (0) shifts the most significant bit out first. Auxiliary SPI +only. + +.br +R is 1 if the least significant bit is received on MISO first, the +default (0) receives the most significant bit first. Auxiliary SPI +only. + +.br +bbbbbb defines the word size in bits (0-32). The default (0) +sets 8 bits per word. Auxiliary SPI only. + +.br +The \fBSPIR\fP, \fBSPIW\fP, and \fBSPIX\fP commands transfer data +packed into 1, 2, or 4 bytes according to the word size in bits. + +.br +For bits 1-8 there will be one byte per character. +.br +For bits 9-16 there will be two bytes per character. +.br +For bits 17-32 there will be four bytes per character. + +.br +Multi-byte transfers are made in least significant byte first order. + +.br +E.g. to transfer 32 11-bit words 64 bytes need to be sent. + +.br +E.g. to transfer the 14 bit value 0x1ABC send the bytes 0xBC followed +by 0x1A. + +.br +The other bits in flags should be set to zero. + +.br +Upon success a handle (>=0) is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs spio 0 100000 3 # Open channel 0 at 100kbps in mode 3. +.br +0 +.br + +.br +$ pigs spio 0 32000 256 # Open channel 0 of auxiliary spi at 32kbps. +.br +1 +.br + +.EE + +.br + +.IP "\fBSPIR h num\fP - SPI read bytes from handle" +.IP "" 4 + +.br +This command returns \fBnum\fP bytes read from the SPI device +associated with handle \fBh\fP. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs spir 0 10 # Read 10 bytes from the SPI device. +.br +10 0 0 0 0 0 0 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBSPIW h bvs\fP - SPI write bytes to handle" +.IP "" 4 + +.br +This command writes bytes \fBbvs\fP to the SPI device +associated with handle \fBh\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs spiw 0 0x22 0x33 0xcc 0xff +.br + +.EE + +.br + +.IP "\fBSPIX h bvs\fP - SPI transfer bytes to handle" +.IP "" 4 + +.br +This command writes bytes \fBbvs\fP to the SPI device +associated with handle \fBh\fP. It returns the same +number of bytes read from the device. + +.br +Upon success the count of returned bytes followed by the bytes themselves +is returned. On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs spix 0 0x22 0x33 0xcc 0xff +.br +4 0 0 0 0 +.br + +.EE + +.br + +.IP "\fBT/TICK \fP - Get current tick" +.IP "" 4 + +.br +This command returns the current system tick. + +.br +Tick is the number of microseconds since system boot. + +.br +As tick is an unsigned 32 bit quantity it wraps around after 2^32 microseconds, +which is approximately 1 hour 12 minutes. + +.br + +\fBExample\fP +.br + +.EX +$ pigs t mils 1000 t +.br +3691823946 +.br +3692833987 +.br + +.EE + +.br + +.IP "\fBTRIG u pl L\fP - Send a trigger pulse" +.IP "" 4 + +.br +This command sends a trigger pulse of \fBpl\fP microseconds at level \fBL\fP +to GPIO \fBu\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The GPIO is set to not level at the end of the pulse. + +.br + +\fBExample\fP +.br + +.EX +$ pigs trig 4 10 1 +.br + +.br +$ pigs trig 4 51 1 +.br +-46 +.br +ERROR: trigger pulse > 50 microseconds +.br + +.EE + +.br + +.IP "\fBW/WRITE g L\fP - Write GPIO level" +.IP "" 4 + +.br +This command sets GPIO \fBg\fP to level \fBL\fP. The level may be 0 +(low, off, clear) or 1 (high, on, set). + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs w 23 0 +.br +$ pigs w 23 1 +.br + +.br +$ pigs w 23 2 +.br +-5 +.br +ERROR: level not 0-1 +.br + +.EE + +.br + +.IP "\fBWDOG u v\fP - Set GPIO watchdog" +.IP "" 4 + +.br +This command sets a watchdog of \fBv\fP milliseconds on GPIO \fBu\fP. + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br +The watchdog is nominally in milliseconds. + +.br +One watchdog may be registered per GPIO. + +.br +The watchdog may be cancelled by setting timeout to 0. + +.br +Once a watchdog has been started monitors of the GPIO +will be triggered every timeout interval after the last +GPIO activity. The watchdog expiry will be indicated by +a special TIMEOUT value. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wdog 23 90000 +.br +-15 +.br +ERROR: timeout not 0-60000 +.br + +.br +$ pigs wdog 23 9000 +.br + +.EE + +.br +This example causes a report to be written to any notification pipes +listening on GPIO 23 whenever GPIO 23 changes state or approximately +every 9000 ms. + +.br + +.IP "\fBWVAG trips\fP - Add generic pulses to waveform" +.IP "" 4 + +.br +This command adds 1 one or more triplets \fBtrips\fP of GPIO on, GPIO off, +delay to the existing waveform (if any). + +.br +Upon success the total number of pulses in the waveform so far is +returned. On error a negative status code will be returned. + +.br +The triplets will be added at the start of the existing waveform. If +they are to start offset from the start then the first triplet should +consist solely of a delay i.e. 0 0 offset. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvag 0x10 0x80 1000 0x80 0x10 9000 +.br +2 +.br + +.br +$ pigs wvag 0 0 10000 0x10 0x80 1000 0x80 0x10 9000 +.br +4 +.br + +.EE + +.br + +.IP "\fBWVAS u b db sb o bvs\fP - Add serial data to waveform" +.IP "" 4 + +.br +This command adds a waveform representing serial data \fBbvs\fP to +GPIO \fBu\fP at \fBb\fP baud to the existing waveform (if any). +The serial data starts \fBo\fP microseconds from the start of the +waveform. + +.br +Upon success the total number of pulses in the waveform so far is +returned. On error a negative status code will be returned. + +.br +The serial data is formatted as one start bit, \fBdb\fP data bits, and +\fBsb\fP/2 stop bits. + +.br +The baud rate may be between 50 and 1000000 bits per second. + +.br +It is legal to add serial data streams with different baud rates to +the same waveform. + +.br +The bytes required for each character depend upon \fBdb\fP. + +.br +For \fBdb\fP 1-8 there will be one byte per character. +.br +For \fBdb\fP 9-16 there will be two bytes per character. +.br +For \fBdb\fP 17-32 there will be four bytes per character. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvas 4 9600 8 2 0 0x30 0x31 0x32 0x33 +.br +23 +.br + +.br +$ pigs wvas 7 38400 8 2 0 0x41 0x42 +.br +35 +.br + +.EE + +.br + +.IP "\fBWVTAT \fP - Returns the current transmitting waveform" +.IP "" 4 + +.br +This command returns the id of the waveform currently +being transmitted. + +.br +Returns the waveform id or one of the following special +values: + +.br +9998 - transmitted wave not found +.br +9999 - no wave being transmitted + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvtat +.br +9999 +.br + +.EE + +.br + +.IP "\fBWVBSY \fP - Check if waveform is being transmitted" +.IP "" 4 + +.br +This command checks to see if a waveform is currently being transmitted. + +.br +Returns 1 if a waveform is currently being transmitted, otherwise 0. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvbsy +.br +0 +.br + +.EE + +.br + +.IP "\fBWVCHA bvs\fP - Transmits a chain of waveforms" +.IP "" 4 + +.br +This command transmits a chain of waveforms. + +.br +NOTE: Any hardware PWM started by \fBHP\fP will +be cancelled. + +.br +The waves to be transmitted are specified by the contents of +\fBbvs\fP which contains an ordered list of wave_ids and optional +command codes and related data. + +.br +Upon success 0 is returned. On error a negative status code +will be returned. + +.br +Each wave is transmitted in the order specified. A wave may +occur multiple times per chain. + +.br +A blocks of waves may be transmitted multiple times by using +the loop commands. The block is bracketed by loop start and +end commands. Loops may be nested. + +.br +Delays between waves may be added with the delay command. + +.br +The following command codes are supported: + +.br + +.EX +Name Cmd & Data Meaning +Loop Start 255 0 Identify start of a wave block +Loop Repeat 255 1 x y loop x + y*256 times +Delay 255 2 x y delay x + y*256 microseconds +Loop Forever 255 3 loop forever + +.EE + +.br +If present Loop Forever must be the last entry in the chain. + +.br +The code is currently dimensioned to support a chain with roughly +600 entries and 20 loop counters. + +.br + +\fBExample\fP +.br + +.EX +#!/bin/bash +.br + +.br +GPIO=4 +.br +WAVES=5 +.br + +.br +pigs m $GPIO w +.br + +.br +for ((i=0; i<$WAVES; i++)) +.br +do +.br + pigs wvag $((1<=0) is returned. On error a negative status +code will be returned. + +.br +The data provided by the \fBWVAG\fP and \fBWVAS\fP commands is +consumed by this command. + +.br +As many waveforms may be created as there is space available. +The wave id is passed to \fBWVTX\fP or \fBWVTXR\fP to specify the +waveform to transmit. + +.br +Normal usage would be + +.br +Step 1. \fBWVCLR\fP to clear all waveforms and added data. + +.br +Step 2. \fBWVAG\fP/\fBWVAS\fP calls to supply the waveform data. + +.br +Step 3. \fBWVCRE\fP to create the waveform and get a unique id. + +.br +Repeat steps 2 and 3 as needed. + +.br +Step 4. \fBWVTX\fP or \fBWVTXR\fP with the id of the waveform to transmit. + +.br +A waveform comprises of one or more pulses. + +.br +A pulse specifies + +.br +1) the GPIO to be switched on at the start of the pulse. +.br +2) the GPIO to be switched off at the start of the pulse. +.br +3) the delay in microseconds before the next pulse. + +.br +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). + +.br +When a waveform is started each pulse is executed in order with +the specified delay between the pulse and the next. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvas 4 9600 0 23 45 67 89 90 +.br +37 +.br +$ pigs wvcre +.br +0 +.br + +.br +$ pigs wvcre +.br +-69 +.br +ERROR: attempt to create an empty waveform +.br + +.EE + +.br + +.IP "\fBWVDEL wid\fP - Delete selected waveform" +.IP "" 4 + +.br +This command deletes the waveform with id \fBwid\fP. + +.br +The wave is flagged for deletion. The resources used by the wave +will only be reused when either of the following apply. + +.br +- all waves with higher numbered wave ids have been deleted or have +been flagged for deletion. + +.br +- a new wave is created which uses exactly the same resources as +the current wave (see the C source for gpioWaveCreate for details). + +.br +Upon success nothing is returned. On error a negative status code +will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvdel 0 +.br + +.br +$ pigs wvdel 0 +.br +-66 +.br +ERROR: non existent wave id +.br + +.EE + +.br + +.IP "\fBWVHLT \fP - Stop waveform" +.IP "" 4 + +.br +This command aborts the transmission of the current waveform. + +.br +Nothing is returned. + +.br +This command is intended to stop a waveform started in the repeat mode. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvhlt +.br + +.EE + +.br + +.IP "\fBWVNEW \fP - Initialise a new waveform" +.IP "" 4 + +.br +This clears any existing waveform data ready for the creation of a new +waveform. + +.br +Nothing is returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvnew +.br + +.EE + +.br + +.IP "\fBWVSC ws\fP - Get waveform DMA CB stats" +.IP "" 4 + +.br +The statistic requested by \fBws\fP is returned. + +.br +\fBws\fP identifies the subcommand as follows. + +.br +0 Get Cbs +.br +1 Get High Cbs +.br +2 Get Max Cbs + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvas 4 9600 0 23 45 67 89 90 +.br +37 +.br + +.br +$ pigs wvsc 0 +.br +74 +.br +$ pigs wvsc 1 +.br +74 +.br +$ pigs wvsc 2 +.br +25016 +.br + +.EE + +.br + +.IP "\fBWVSM ws\fP - Get waveform time stats" +.IP "" 4 + +.br +The statistic requested by \fBws\fP is returned. + +.br +\fBws\fP identifies the subcommand as follows. + +.br +0 Get Micros +.br +1 Get High Micros +.br +2 Get Max Micros + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvsm 0 +.br +5314 +.br +$ pigs wvsm 1 +.br +5314 +.br +$ pigs wvsm 2 +.br +1800000000 +.br + +.EE + +.br + +.IP "\fBWVSP ws\fP - Get waveform pulse stats" +.IP "" 4 + +.br +The statistic requested by \fBws\fP is returned. + +.br +\fBws\fP identifies the subcommand as follows. + +.br +0 Get Pulses +.br +1 Get High Pulses +.br +2 Get Max Pulses + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvsp 0 +.br +37 +.br +$ pigs wvsp 1 +.br +37 +.br +$ pigs wvsp 2 +.br +12000 +.br + +.EE + +.br + +.IP "\fBWVTX wid\fP - Transmits waveform once" +.IP "" 4 + +.br +This command transmits the waveform with id \fBwid\fP once. + +.br +NOTE: Any hardware PWM started by \fBHP\fP will be cancelled. + +.br +Upon success the number of DMA control blocks in the waveform is returned. +On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvtx 1 +.br +75 +.br + +.br +$ pigs wvtx 2 +.br +-66 +.br +ERROR: non existent wave id +.br + +.EE + +.br + +.IP "\fBWVTXM wid wmde\fP - Transmits waveform using mode" +.IP "" 4 + +.br +This command transmits the waveform with id \fBwid\fP using mode \fBwmde\fP. + +.br +The mode may be send once (0), send repeatedly (1), send once but +first sync with previous wave (2), or send repeatedly but first +sync with previous wave (3). + +.br +WARNING: bad things may happen if you delete the previous +waveform before it has been synced to the new waveform. + +.br +NOTE: Any hardware PWM started by \fBHP\fP will be cancelled. + +.br +Upon success the number of DMA control blocks in the waveform is returned. +On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvtxm 1 3 +.br +75 +.br + +.br +$ pigs wvtxm 2 0 +.br +-66 +.br +ERROR: non existent wave id +.br + +.EE + +.br + +.IP "\fBWVTXR wid\fP - Transmits waveform repeatedly" +.IP "" 4 + +.br +This command transmits the waveform with id \fBwid\fP repeatedly. + +.br +NOTE: Any hardware PWM started by \fBHP\fP will be cancelled. + +.br +Upon success the number of DMA control blocks in the waveform is returned. +On error a negative status code will be returned. + +.br + +\fBExample\fP +.br + +.EX +$ pigs wvtxr 1 +.br +75 +.br + +.br +$ pigs wvtxr 2 +.br +-66 +.br +ERROR: non existent wave id +.br + +.EE + +.br + +.SH PARAMETERS + +.br + +.IP "\fBactv\fP - 0-1000000" 0 + +.br +The number of microseconds level changes are reported for once +a noise filter has been triggered (by \fBstdy\fP microseconds of +a stable level). + +.br + +.IP "\fBb\fP - baud" 0 +The command expects the baud rate in bits per second for +the transmission of serial data (I2C/SPI/serial link, waves). + +.br + +.IP "\fBbctl\fP - BSC control word" 0 +The command expects a BSC control word, see \fBBSCX\fP. + +.br + +.IP "\fBbit\fP - bit value (0-1)" 0 +The command expects 0 or 1. + +.br + +.IP "\fBbits\fP - a bit mask" 0 +A mask is used to select one or more GPIO. A GPIO is selected +if bit (1<=0)" 0 +The command expects a handle. + +.br +A handle is a number referencing an object opened by one of \fBFO\fP, +\fBI2CO\fP, \fBNO\fP, \fBSERO\fP, \fBSPIO\fP. + +.br + +.IP "\fBib\fP - I2C bus (>=0)" 0 +The command expects an I2C bus number. + +.br + +.IP "\fBid\fP - I2C device (0-0x7F)" 0 +The command expects the address of an I2C device. + +.br + +.IP "\fBif\fP - I2C flags (0)" 0 +The command expects an I2C flags value. No flags are currently defined. + +.br + +.IP "\fBL\fP - level (0-1)" 0 +The command expects a GPIO level. + +.br + +.IP "\fBm\fP - mode (RW540123)" 0 +The command expects a mode character. + +.br +Each GPIO can be configured to be in one of 8 different modes. The modes +are named Input, Output, ALT0, ALT1, ALT2, ALT3, ALT4, and ALT5. + +.br +To set the mode use the code for the mode. + +.br +The value is returned by the mode get command. + +.br + +.EX +Mode Input Output ALT0 ALT1 ALT2 ALT3 ALT4 ALT5 +Code R W 0 1 2 3 4 5 +Value 0 1 4 5 6 7 3 2 + +.EE + +.br + +.IP "\fBmiso\fP - GPIO (0-31)" 0 +The GPIO used for the MISO signal when bit banging SPI. + +.br + +.IP "\fBmode\fP - file open mode" 0 +One of the following values. + +.br + +.EX + Value Meaning +READ 1 open file for reading +WRITE 2 open file for writing +RW 3 open file for reading and writing + +.EE + +.br +The following values can be or'd into the mode. + +.br + +.EX + Value Meaning +APPEND 4 All writes append data to the end of the file +CREATE 8 The file is created if it doesn't exist +TRUNC 16 The file is truncated + +.EE + +.br + +.IP "\fBmosi\fP - GPIO (0-31)" 0 +The GPIO used for the MOSI signal when bit banging SPI. + +.br + +.IP "\fBname\fP - the name of a script" 0 +Only alphanumeric characters, '-' and '_' are allowed in the name. + +.br + +.IP "\fBnum\fP - maximum number of bytes to return (1-)" 0 +The command expects the maximum number of bytes to return. + +.br +For the I2C and SPI commands the requested number of bytes will always +be returned. + +.br +For the serial and file commands the smaller of the number of +bytes available to be read (which may be zero) and \fBnum\fP bytes +will be returned. + +.br + +.IP "\fBo\fP - offset (>=0)" 0 +Serial data is stored offset microseconds from the start of the waveform. + +.br + +.IP "\fBp\fP - PUD (ODU)" 0 +The command expects a PUD character. + +.br +Each GPIO can be configured to use or not use an internal pull up or +pull down resistor. This is useful to provide a default state for inputs. + +.br +A pull up will default the input to 1 (high). + +.br +A pull down will default the input to 0 (low). + +.br +To set the pull up down state use the command character for the state. + +.br + +.EX +Pull Up Down Off Pull Down Pull Up +Command Character O D U + +.EE + +.br +There is no mechanism to read the pull up down state. + +.br + +.IP "\fBpad\fP - 0-2" 0 +A set of GPIO which share common drivers. + +.br + +.EX +Pad GPIO +0 0-27 +1 28-45 +2 46-53 + +.EE + +.br + +.IP "\fBpadma\fP - 1-16" 0 +The mA which may be drawn from each GPIO whilst still guaranteeing the +high and low levels. + +.br + +.IP "\fBpars\fP - script parameters" 0 +The command expects 0 to 10 numbers as parameters to be passed to the script. + +.br + +.IP "\fBpat\fP - a file name pattern" 0 +A file path which may contain wildcards. To be accessible the path +must match an entry in /opt/pigpio/access. + +.br + +.IP "\fBpdc\fP - hardware PWM dutycycle (0-1000000)" 0 +The command expects a dutycycle. + +.br + +.IP "\fBpf\fP - hardware PWM frequency (1-125M)" 0 +The command expects a frequency. + +.br + +.IP "\fBpl\fP - pulse length (1-100)" 0 +The command expects a pulse length in microseconds. + +.br + +.IP "\fBr\fP - register (0-255)" 0 +The command expects an I2C register number. + +.br + +.IP "\fBsb\fP - serial stop (half) bits (2-8)" 0 +The command expects the number of stop (half) bits per serial character. + +.br + +.IP "\fBscl\fP - user GPIO (0-31)" 0 +The command expects the number of the GPIO to be used for SCL +when bit banging I2C. + +.br + +.IP "\fBsclk\fP - user GPIO (0-31)" 0 +The GPIO used for the SCLK signal when bit banging SPI. + +.br + +.IP "\fBsda\fP - user GPIO (0-31)" 0 +The command expects the number of the GPIO to be used for SDA +when bit banging I2C. + +.br + +.IP "\fBsef\fP - serial flags (32 bits)" 0 +The command expects a flag value. No serial flags are currently defined. + +.br + +.IP "\fBsid\fP - script id (>= 0)" 0 +The command expects a script id as returned by a call to \fBPROC\fP. + +.br + +.IP "\fBspf\fP - SPI flags (32 bits)" 0 +See \fBSPIO\fP and \fBBSPIO\fP. + +.br + +.IP "\fBstdy\fP - 0-300000" 0 + +.br +The number of microseconds level changes must be stable for +before reporting the level changed (\fBFG\fP) or triggering +the active part of a noise filter (\fBFN\fP). + +.br + +.IP "\fBstr\fP - a string" 0 +The command expects a string. + +.br + +.IP "\fBt\fP - a string" 0 +The command expects a string. + +.br + +.IP "\fBtrips\fP - triplets" 0 +The command expects 1 or more triplets of GPIO on, GPIO off, delay. + +.br +E.g. 0x400000 0 100000 0 0x400000 900000 defines two pulses as follows + +.br + +.EX + GPIO on GPIO off delay +0x400000 (GPIO 22) 0 (None) 100000 (1/10th s) + 0 (None) 0x400000 (GPIO 22) 900000 (9/10th s) + +.EE + +.br + +.IP "\fBu\fP - user GPIO (0-31)" 0 +The command expects the number of a user GPIO. + +.br +A number of commands are restricted to GPIO in bank 1, +in particular the PWM commands, the servo command, +the watchdog command, and the notification command. + +.br +It is your responsibility to ensure that the PWM and servo commands +are only used on safe GPIO. + +.br +See \fBg\fP + +.br + +.IP "\fBuvs\fP - values" 0 +The command expects an arbitrary number of >=0 values (possibly none). +Any after the first two must be <= 255. + +.br + +.IP "\fBv\fP - value" 0 +The command expects a number. + +.br + +.IP "\fBwid\fP - wave id (>=0)" 0 +The command expects a wave id. + +.br +When a waveform is created it is given an id (0, 1, 2, ...). + +.br + +.IP "\fBwmde\fP - mode (0-3)" 0 +The command expects a wave transmission mode. + +.br +0 = send once +.br +1 = send repeatedly +.br +2 = send once but first sync with previous wave +.br +3 = send repeatedly but first sync with previous wave +.br + +.br + +.IP "\fBws\fP - wave stats sucommand (0-2)" 0 +The command expects a subcommand. + +.br +0 = current value. +.br +1 = highest value so far. +.br +2 = maximum possible value. + +.br + +.IP "\fBwv\fP - word value (0-65535)" 0 +The command expects a word value. + +.br + +.SH SCRIPTS + +.br +Scripts are programs to be stored and executed by the pigpio daemon. +They are intended to mitigate any performance problems associated with +the pigpio daemon server/client model. + +.br +.SS Example +.br +A trivial example might be useful. Suppose you want to toggle a GPIO +on and off as fast as possible. + +.br +From the command line you could write + +.br + +.EX +for ((i=0; i<1000;i++)); do pigs w 22 1 w 22 0; done +.br + +.EE + +.br +Timing that you will see it takes about 14 seconds, or roughly +70 toggles per second. + +.br +Using the pigpio Python module you could use code such as + +.br + +.EX +#!/usr/bin/env python +.br + +.br +import time +.br + +.br +import pigpio +.br + +.br +PIN=4 +.br + +.br +TOGGLE=10000 +.br + +.br +pi = pigpio.pi() # Connect to local Pi. +.br + +.br +s = time.time() +.br + +.br +for i in range(TOGGLE): +.br + pi.write(PIN, 1) +.br + pi.write(PIN, 0) +.br + +.br +e = time.time() +.br + +.br +print("pigpio did {} toggles per second".format(int(TOGGLE/(e-s)))) +.br + +.br +pi.stop() +.br + +.EE + +.br +Timing that shows a speed improvement to roughly 800 toggles per second. + +.br +Now let's use a script. + +.br + +.EX +pigs proc tag 999 w 22 1 w 22 0 dcr p0 jp 999 +.br + +.EE + +.br +Ignore the details for now. + +.br +Let's time the script running. + +.br +Again, ignore the details for now. + +.br + +.EX +time (pigs procr 0 10000000; while a=$(pigs procp 0); [[ ${a::1} -eq 2 ]];\ +.br + do sleep 0.2; done) +.br + +.EE + +.br +The script takes roughly 12 seconds to complete, or 800,000 toggles per second. + +.br +That is the advantage of a stored script. + +.br +Some details. + +.br + +.EX +pigs proc tag 999 w 22 1 w 22 0 dcr p0 jp 999 +.br + +.EE + +.br +proc introduces a script. Everything after proc is part of the script. +.br +tag 999 names the current position in the script. +.br +w 22 1 writes 1 to GPIO 22. +.br +w 22 0 writes 0 to GPIO 22. +.br +dcr p0 decrements parameter 0. +.br +jp 999 jumps to tag 999 if the result is positive. + +.br + +.EX +time (pigs procr 0 10000000; while a=$(pigs procp 0); [[ ${a::1} -eq 2 ]];\ +.br + do sleep 0.2; done) +.br + +.EE + +.br +pigs procr 0 10000000 starts script 0 with parameter 0 of 10 million. + +.br +The rest is bash apart from + +.br +pigs procp 0 asks for the status and parameters of script 0. +The status will be 2 while the script is running and 1 when it is complete. + +.br +.SS Virtual machine +.br +A script runs within a virtual machine with + +.br +a 32 bit accumulator A. +.br +a flags register F. +.br +a program counter PC. + +.br +Each script has + +.br +10 parameters named 0 through 9. +.br +150 variables named 0 through 149. +.br +50 labels which are named by any unique number. + +.br +.SS Commands +.br +All the normal pigs commands may be used within a script. However +commands which return more than an integer will be of little use. + +.br +The following commands are only legal within a script. + +.br + +.EX +Command Description Definition +ADD x Add x to accumulator A+=x; F=A +AND x And x with accumulator A&=x; F=A +CALL L Call subroutine at tag L push(PC+1); PC=L +CMP x Compare x with accumulator F=A-x +DCR y Decrement register --*y; F=*y +DCRA Decrement accumulator --A; F=A +DIV x Divide x into accumulator A/=x; F=A +EVTWT Wait for an event to occur A=wait(x); F=A +HALT Halt Halt +INR y Increment register ++*y; F=*y +INRA Increment accumulator ++A; F=A +JM L Jump if minus to tag L if (F<0) PC=L +JMP L Jump to tag L PC=L +JNZ L Jump if non-zero to tag L if (F) PC=L +JP L Jump if positive to tag L if (F>=0) PC=L +JZ L Jump if zero to tag L if (!F) PC=L +LD y x Load register with x *y=x +LDA x Load accumulator with x A=x +MLT x Multiply x with accumulator A*=x; F=A +MOD x Modulus x with accumulator A%=x; F=A +OR x Or x with accumulator A|=x; F=A +POP y Pop register y=pop() +POPA Pop accumulator A=pop() +PUSH y Push register push(y) +PUSHA Push accumulator push(A) +RET Return from subroutine PC=pop() +RL y x Rotate left register x bits *y<<=x; F=*y +RLA x Rotate left accumulator x bits A<<=x; F=A +RR y x Rotate right register x bits *y>>=x; F=*y +RRA x Rotate right accumulator x bits A>>=x; F=A +STA y Store accumulator in register y=A +SUB x Subtract x from accumulator A-=x; F=A +SYS str Run external script (/opt/pigpio/cgi/str) system(str); F=A +TAG L Label the current script position N/A +WAIT x Wait for a GPIO in x to change state A=wait(x); F=A +X y1 y2 Exchange contents of registers y1 and y2 t=*y1;*y1=*y2;*y2=t +XA y Exchange contents of accumulator and register t=A;A=*y;*y=t +XOR x Xor x with accumulator A^=x; F=A + +.EE + +.br +x may be a constant, a parameter (p0-p9), or a variable (v0-v149). + +.br +y may be a parameter (p0-p9), or a variable (v0-v149). If p or v isn't +specified y is assumed to be a variable. + +.br +The EVTWT command parameter is a bit-mask with 1 set for events of interest. + +.br +The WAIT command parameter is a bit-mask with 1 set for GPIO of interest. + +.br +The SYS script receives two unsigned parameters: the accumulator A and +the current GPIO levels. + +.br + +.SH SEE ALSO + +pigpiod(1), pig2vcd(1), pigpio(3), pigpiod_if(3), pigpiod_if2(3) +.SH AUTHOR + +joan@abyz.me.uk diff --git a/thirdparty/PIGPIO/pigs.c b/thirdparty/PIGPIO/pigs.c new file mode 100644 index 0000000000..4ae97eb8b0 --- /dev/null +++ b/thirdparty/PIGPIO/pigs.c @@ -0,0 +1,393 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* +This version is for pigpio version 67+ +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "pigpio.h" +#include "command.h" +#include "pigs.h" + +/* +This program provides a socket interface to some of +the commands available from pigpio. +*/ + +char command_buf[CMD_MAX_EXTENSION]; +char response_buf[CMD_MAX_EXTENSION]; + +int printFlags = 0; + +int status = PIGS_OK; + +#define SOCKET_OPEN_FAILED -1 + +#define PRINT_HEX 1 +#define PRINT_ASCII 2 + +void report(int err, char *fmt, ...) +{ + char buf[128]; + va_list ap; + + if (err > status) status = err; + + va_start(ap, fmt); + vsnprintf(buf, sizeof(buf), fmt, ap); + va_end(ap); + + fprintf(stderr, "%s\n", buf); + + fflush(stderr); +} + +static int initOpts(int argc, char *argv[]) +{ + int opt, args; + + opterr = 0; + + args = 1; + + while ((opt = getopt(argc, argv, "ax")) != -1) + { + switch (opt) + { + case 'a': + printFlags |= PRINT_ASCII; + args++; + break; + + case 'x': + printFlags |= PRINT_HEX; + args++; + break; + + default: + args++; + report(PIGS_OPTION_ERR, "ERROR: bad option %c", optopt); + } + } + return args; +} + +static int openSocket(void) +{ + int sock, err; + struct addrinfo hints, *res, *rp; + const char *addrStr, *portStr; + + portStr = getenv(PI_ENVPORT); + + if (!portStr) portStr = PI_DEFAULT_SOCKET_PORT_STR; + + addrStr = getenv(PI_ENVADDR); + + if (!addrStr) addrStr = PI_DEFAULT_SOCKET_ADDR_STR; + + memset (&hints, 0, sizeof (hints)); + + hints.ai_family = PF_UNSPEC; + hints.ai_socktype = SOCK_STREAM; + hints.ai_flags |= AI_CANONNAME; + + err = getaddrinfo(addrStr, portStr, &hints, &res); + + if (err) return SOCKET_OPEN_FAILED; + + for (rp=res; rp!=NULL; rp=rp->ai_next) + { + sock = socket(rp->ai_family, rp->ai_socktype, rp->ai_protocol); + + if (sock == -1) continue; + + if (connect(sock, rp->ai_addr, rp->ai_addrlen) != -1) break; + } + + freeaddrinfo(res); + + if (rp == NULL) return SOCKET_OPEN_FAILED; + + return sock; +} + +void print_result(int sock, int rv, cmdCmd_t cmd) +{ + int i, r, ch; + uint32_t *p; + + r = cmd.res; + + switch (rv) + { + case 0: + case 1: + if (r < 0) + { + printf("%d\n", r); + report(PIGS_SCRIPT_ERR, "ERROR: %s", cmdErrStr(r)); + } + break; + + case 2: + printf("%d\n", r); + if (r < 0) report(PIGS_SCRIPT_ERR, "ERROR: %s", cmdErrStr(r)); + break; + + case 3: + printf("%08X\n", cmd.res); + break; + + case 4: + printf("%u\n", cmd.res); + break; + + case 5: + printf("%s", cmdUsage); + break; + + case 6: /* + BI2CZ CF2 FL FR I2CPK I2CRD I2CRI I2CRK + I2CZ SERR SLR SPIX SPIR + */ + printf("%d", r); + if (r < 0) report(PIGS_SCRIPT_ERR, "ERROR: %s", cmdErrStr(r)); + if (r > 0) + { + if (printFlags == PRINT_ASCII) printf(" "); + + for (i=0; i 4) + { + if (printFlags == PRINT_ASCII) printf(" "); + + for (i=4; i 0) + { + recv(sock, response_buf, res, MSG_WAITALL); + response_buf[res] = 0; + } + break; + } +} + +int main(int argc , char *argv[]) +{ + int sock, command; + int args, idx, i, pp, l, len; + cmdCmd_t cmd; + uint32_t p[CMD_P_ARR]; + cmdCtlParse_t ctl; + cmdScript_t s; + char v[CMD_MAX_EXTENSION]; + + sock = openSocket(); + + args = initOpts(argc, argv); + + command_buf[0] = 0; + l = 0; + pp = 0; + + for (i=args; i= 0) && (ctl.eaten < len)) + { + if ((idx=cmdParse(command_buf, p, CMD_MAX_EXTENSION, v, &ctl)) >= 0) + { + command = p[0]; + + if (command < PI_CMD_SCRIPT) + { + if (command == PI_CMD_HELP) + { + printf("%s", cmdUsage); + } + else if (command == PI_CMD_PARSE) + { + cmdParseScript(v, &s, 1); + if (s.par) free (s.par); + } + else + { + cmd.cmd = command; + cmd.p1 = p[1]; + cmd.p2 = p[2]; + cmd.p3 = p[3]; + + if (sock != SOCKET_OPEN_FAILED) + { + if (send(sock, &cmd, sizeof(cmdCmd_t), 0) == + sizeof(cmdCmd_t)) + { + if (p[3]) send(sock, v, p[3], 0); /* send extensions */ + + if (recv(sock, &cmd, sizeof(cmdCmd_t), MSG_WAITALL) == + sizeof(cmdCmd_t)) + { + get_extensions(sock, command, cmd.res); + + print_result(sock, cmdInfo[idx].rv, cmd); + } + else report(PIGS_CONNECT_ERR, "socket receive failed"); + } + else report(PIGS_CONNECT_ERR, "socket send failed"); + } + else report(PIGS_CONNECT_ERR, "socket connect failed"); + } + } + else report(PIGS_SCRIPT_ERR, + "%s only allowed within a script", cmdInfo[idx].name); + } + else + { + if (idx == CMD_UNKNOWN_CMD) + report(PIGS_SCRIPT_ERR, + "%s? unknown command, pigs h for help", cmdStr()); + else + report(PIGS_SCRIPT_ERR, + "%s: bad parameter, pigs h for help", cmdStr()); + } + } + + if (sock >= 0) close(sock); + + return status; +} + diff --git a/thirdparty/PIGPIO/pigs.h b/thirdparty/PIGPIO/pigs.h new file mode 100644 index 0000000000..16cfcdde7e --- /dev/null +++ b/thirdparty/PIGPIO/pigs.h @@ -0,0 +1,41 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. + +In jurisdictions that recognize copyright laws, the author or authors +of this software dedicate any and all copyright interest in the +software to the public domain. We make this dedication for the benefit +of the public at large and to the detriment of our heirs and +successors. We intend this dedication to be an overt act of +relinquishment in perpetuity of all present and future rights to this +software under copyright law. + +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 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. + +For more information, please refer to +*/ + +/* +This version is for pigpio version 67+ +*/ + +#ifndef PIGS_H +#define PIGS_H + +#define PIGS_OK 0 +#define PIGS_CONNECT_ERR 255 +#define PIGS_OPTION_ERR 254 +#define PIGS_SCRIPT_ERR 253 + +#endif + diff --git a/thirdparty/PIGPIO/setup.py b/thirdparty/PIGPIO/setup.py new file mode 100644 index 0000000000..9de06d230b --- /dev/null +++ b/thirdparty/PIGPIO/setup.py @@ -0,0 +1,23 @@ +#!/usr/bin/env python + +from distutils.core import setup + +setup(name='pigpio', + version='1.42', + author='joan', + author_email='joan@abyz.me.uk', + maintainer='joan', + maintainer_email='joan@abyz.me.uk', + url='http://abyz.me.uk/rpi/pigpio/python.html', + description='Raspberry Pi GPIO module', + long_description='Raspberry Pi Python module to access the pigpio daemon', + download_url='http://abyz.me.uk/rpi/pigpio/pigpio.zip', + license='unlicense.org', + py_modules=['pigpio'], + keywords=['raspberrypi', 'gpio',], + classifiers=[ + "Programming Language :: Python :: 2", + "Programming Language :: Python :: 3", + ] + ) + diff --git a/thirdparty/PIGPIO/x_pigpio.c b/thirdparty/PIGPIO/x_pigpio.c new file mode 100644 index 0000000000..c51732a354 --- /dev/null +++ b/thirdparty/PIGPIO/x_pigpio.c @@ -0,0 +1,905 @@ +/* +gcc -Wall -pthread -o x_pigpio x_pigpio.c -lpigpio +sudo ./x_pigpio + +*** WARNING ************************************************ +* * +* All the tests make extensive use of gpio 25 (pin 22). * +* Ensure that either nothing or just a LED is connected to * +* gpio 25 before running any of the tests. * +* * +* Some tests are statistical in nature and so may on * +* occasion fail. Repeated failures on the same test or * +* many failures in a group of tests indicate a problem. * +************************************************************ +*/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "pigpio.h" + +#define USERDATA 18249013 + +#define GPIO 25 + +void CHECK(int t, int st, int got, int expect, int pc, char *desc) +{ + if ((got >= (((1E2-pc)*expect)/1E2)) && (got <= (((1E2+pc)*expect)/1E2))) + { + printf("TEST %2d.%-2d PASS (%s: %d)\n", t, st, desc, expect); + } + else + { + fprintf(stderr, + "TEST %2d.%-2d FAILED got %d (%s: %d)\n", + t, st, got, desc, expect); + } +} + +void t0() +{ + printf("\nTesting pigpio C I/F\n"); + + printf("pigpio version %d.\n", gpioVersion()); + + printf("Hardware revision %d.\n", gpioHardwareRevision()); +} + +void t1() +{ + int v; + + printf("Mode/PUD/read/write tests.\n"); + + gpioSetMode(GPIO, PI_INPUT); + v = gpioGetMode(GPIO); + CHECK(1, 1, v, 0, 0, "set mode, get mode"); + + gpioSetPullUpDown(GPIO, PI_PUD_UP); + v = gpioRead(GPIO); + CHECK(1, 2, v, 1, 0, "set pull up down, read"); + + gpioSetPullUpDown(GPIO, PI_PUD_DOWN); + v = gpioRead(GPIO); + CHECK(1, 3, v, 0, 0, "set pull up down, read"); + + gpioWrite(GPIO, PI_LOW); + v = gpioGetMode(GPIO); + CHECK(1, 4, v, 1, 0, "write, get mode"); + + v = gpioRead(GPIO); + CHECK(1, 5, v, 0, 0, "read"); + + gpioWrite(GPIO, PI_HIGH); + gpioDelay(1); /* 1 micro delay to let GPIO reach level reliably */ + v = gpioRead(GPIO); + CHECK(1, 6, v, 1, 0, "write, read"); +} + +int t2_count; + +void t2cb(int gpio, int level, uint32_t tick) +{ + t2_count++; +} + +void t2() +{ + int dc, f, r, rr, oc; + + printf("PWM dutycycle/range/frequency tests.\n"); + + gpioSetPWMrange(GPIO, 255); + gpioSetPWMfrequency(GPIO, 0); + f = gpioGetPWMfrequency(GPIO); + CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency"); + + t2_count=0; + + gpioSetAlertFunc(GPIO, t2cb); + + gpioPWM(GPIO, 0); + dc = gpioGetPWMdutycycle(GPIO); + CHECK(2, 2, dc, 0, 0, "get PWM dutycycle"); + + time_sleep(0.5); /* allow old notifications to flush */ + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 3, f, 0, 0, "set PWM dutycycle, callback"); + + gpioPWM(GPIO, 128); + dc = gpioGetPWMdutycycle(GPIO); + CHECK(2, 4, dc, 128, 0, "get PWM dutycycle"); + + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 5, f, 40, 5, "set PWM dutycycle, callback"); + + gpioSetPWMfrequency(GPIO, 100); + f = gpioGetPWMfrequency(GPIO); + CHECK(2, 6, f, 100, 0, "set/get PWM frequency"); + + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 7, f, 400, 1, "callback"); + + gpioSetPWMfrequency(GPIO, 1000); + f = gpioGetPWMfrequency(GPIO); + CHECK(2, 8, f, 1000, 0, "set/get PWM frequency"); + + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 9, f, 4000, 1, "callback"); + + r = gpioGetPWMrange(GPIO); + CHECK(2, 10, r, 255, 0, "get PWM range"); + + rr = gpioGetPWMrealRange(GPIO); + CHECK(2, 11, rr, 200, 0, "get PWM real range"); + + gpioSetPWMrange(GPIO, 2000); + r = gpioGetPWMrange(GPIO); + CHECK(2, 12, r, 2000, 0, "set/get PWM range"); + + rr = gpioGetPWMrealRange(GPIO); + CHECK(2, 13, rr, 200, 0, "get PWM real range"); + + gpioPWM(GPIO, 0); +} + +int t3_val; +int t3_reset; +int t3_count; +uint32_t t3_tick; +float t3_on; +float t3_off; + +void t3cbf(int gpio, int level, uint32_t tick, void *userdata) +{ + static int unreported = 1; + + uint32_t td; + int *val; + + val = userdata; + + if (*val != USERDATA) + { + if (unreported) + { + fprintf + ( + stderr, + "unexpected userdata %d (expected %d)\n", + *val, USERDATA + ); + } + unreported = 0; + } + + if (t3_reset) + { + t3_count = 0; + t3_on = 0.0; + t3_off = 0.0; + t3_reset = 0; + } + else + { + td = tick - t3_tick; + + if (level == 0) t3_on += td; + else t3_off += td; + } + + t3_count ++; + t3_tick = tick; +} + +void t3() +{ + int f, rr; + + float on, off; + + int t, v; + + int pw[3]={500, 1500, 2500}; + int dc[4]={20, 40, 60, 80}; + + printf("PWM/Servo pulse accuracy tests.\n"); + + t3_val = USERDATA; + t3_reset=1; + t3_count=0; + t3_tick=0; + t3_on=0.0; + t3_off=0.0; + + gpioSetAlertFuncEx(GPIO, t3cbf, &t3_val); /* test extended alert */ + + for (t=0; t<3; t++) + { + gpioServo(GPIO, pw[t]); + v = gpioGetServoPulsewidth(GPIO); + CHECK(3, t+t+1, v, pw[t], 0, "get servo pulsewidth"); + + time_sleep(1); + t3_reset = 1; + time_sleep(4); + on = t3_on; + off = t3_off; + CHECK(3, t+t+2, (1E3*(on+off))/on, 2E7/pw[t], 1, + "set servo pulsewidth"); + } + + gpioServo(GPIO, 0); + gpioSetPWMfrequency(GPIO, 1000); + f = gpioGetPWMfrequency(GPIO); + CHECK(3, 7, f, 1000, 0, "set/get PWM frequency"); + + rr = gpioSetPWMrange(GPIO, 100); + CHECK(3, 8, rr, 200, 0, "set PWM range"); + + for (t=0; t<4; t++) + { + gpioPWM(GPIO, dc[t]); + v = gpioGetPWMdutycycle(GPIO); + CHECK(3, t+t+9, v, dc[t], 0, "get PWM dutycycle"); + + time_sleep(1); + t3_reset = 1; + time_sleep(2); + on = t3_on; + off = t3_off; + CHECK(3, t+t+10, (1E3*on)/(on+off), 1E1*dc[t], 1, + "set PWM dutycycle"); + } + + gpioPWM(GPIO, 0); +} + +void t4() +{ + int h, e, f, n, s, b, l, seq_ok, toggle_ok; + gpioReport_t r; + char p[32]; + + printf("Pipe notification tests.\n"); + + gpioSetPWMfrequency(GPIO, 0); + gpioPWM(GPIO, 0); + gpioSetPWMrange(GPIO, 100); + + h = gpioNotifyOpen(); + + sprintf(p, "/dev/pigpio%d", h); + f = open(p, O_RDONLY); + + e = gpioNotifyBegin(h, (1< 0) text[c] = 0; + CHECK(5, 11, strcmp(TEXT, text), 0, 0, "wave tx busy, serial read"); + + e = gpioSerialReadClose(GPIO); + CHECK(5, 12, e, 0, 0, "serial read close"); + + c = gpioWaveGetMicros(); + CHECK(5, 13, c, 6158148, 0, "wave get micros"); + + c = gpioWaveGetHighMicros(); + CHECK(5, 14, c, 6158148, 0, "wave get high micros"); + + c = gpioWaveGetMaxMicros(); + CHECK(5, 15, c, 1800000000, 0, "wave get max micros"); + + c = gpioWaveGetPulses(); + CHECK(5, 16, c, 3405, 0, "wave get pulses"); + + c = gpioWaveGetHighPulses(); + CHECK(5, 17, c, 3405, 0, "wave get high pulses"); + + c = gpioWaveGetMaxPulses(); + CHECK(5, 18, c, 12000, 0, "wave get max pulses"); + + c = gpioWaveGetCbs(); + if (e < 6963) CHECK(5, 19, c, 6810, 0, "wave get cbs"); + else CHECK(5, 19, c, 7115, 0, "wave get cbs"); + + c = gpioWaveGetHighCbs(); + if (e < 6963) CHECK(5, 20, c, 6810, 0, "wave get high cbs"); + else CHECK(5, 20, c, 7115, 0, "wave get high cbs"); + + c = gpioWaveGetMaxCbs(); + CHECK(5, 21, c, 25016, 0, "wave get max cbs"); +} + +int t6_count; +int t6_on; +uint32_t t6_on_tick; + +void t6cbf(int gpio, int level, uint32_t tick) +{ + if (level == 1) + { + t6_on_tick = tick; + t6_count++; + } + else + { + if (t6_on_tick) t6_on += (tick - t6_on_tick); + } +} + +void t6() +{ + int tp, t, p; + + printf("Trigger tests\n"); + + gpioWrite(GPIO, PI_LOW); + + tp = 0; + + t6_count=0; + t6_on=0; + t6_on_tick=0; + + gpioSetAlertFunc(GPIO, t6cbf); + + for (t=0; t<5; t++) + { + time_sleep(0.1); + p = 10 + (t*10); + tp += p; + gpioTrigger(GPIO, p, 1); + } + + time_sleep(0.2); + + CHECK(6, 1, t6_count, 5, 0, "gpio trigger count"); + + CHECK(6, 2, t6_on, tp, 25, "gpio trigger pulse length"); +} + +int t7_count; + +void t7cbf(int gpio, int level, uint32_t tick) +{ + if (level == PI_TIMEOUT) t7_count++; +} + +void t7() +{ + int c, oc; + + printf("Watchdog tests.\n"); + + t7_count=0; + + /* type of edge shouldn't matter for watchdogs */ + gpioSetAlertFunc(GPIO, t7cbf); + + gpioSetWatchdog(GPIO, 50); /* 50 ms, 20 per second */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 1, c, 39, 5, "set watchdog on count"); + + gpioSetWatchdog(GPIO, 0); /* 0 switches watchdog off */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 2, c, 0, 1, "set watchdog off count"); +} + +void t8() +{ + int v; + + printf("Bank read/write tests.\n"); + + gpioWrite(GPIO, 0); + v = gpioRead_Bits_0_31() & (1<= 0) text[b] = 0; + CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read"); + + b = serReadByte(h); + CHECK(10, 8, b, 0xAA, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 9, b, 0x55, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 10, b, 0x00, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 11, b, 0xFF, 0, "serial read byte"); + + b = serDataAvailable(h); + CHECK(10, 12, b, 0, 0, "serial data availabe"); + + e = serClose(h); + CHECK(10, 13, e, 0, 0, "serial close"); +} + +void tb() +{ + int h, e, b, len; + char *exp; + char buf[128]; + + printf("SMBus / I2C tests."); + + /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */ + + h = i2cOpen(1, 0x53, 0); + CHECK(11, 1, h, 0, 0, "i2cOpen"); + + e = i2cWriteDevice(h, "\x00", 1); /* move to known register */ + CHECK(11, 2, e, 0, 0, "i2cWriteDevice"); + + b = i2cReadDevice(h, buf, 1); + CHECK(11, 3, b, 1, 0, "i2cReadDevice"); + CHECK(11, 4, buf[0], 0xE5, 0, "i2cReadDevice"); + + b = i2cReadByte(h); + CHECK(11, 5, b, 0xE5, 0, "i2cReadByte"); + + b = i2cReadByteData(h, 0); + CHECK(11, 6, b, 0xE5, 0, "i2cReadByteData"); + + b = i2cReadByteData(h, 48); + CHECK(11, 7, b, 2, 0, "i2cReadByteData"); + + exp = "\x1D[aBcDeFgHjKM]"; + len = strlen(exp); + + e = i2cWriteDevice(h, exp, len); + CHECK(11, 8, e, 0, 0, "i2cWriteDevice"); + + e = i2cWriteDevice(h, "\x1D", 1); + b = i2cReadDevice(h, buf, len-1); + CHECK(11, 9, b, len-1, 0, "i2cReadDevice"); + CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2cReadDevice"); + + if (strncmp(buf, exp+1, len-1)) + printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1); + + e = i2cWriteByteData(h, 0x1d, 0xAA); + CHECK(11, 11, e, 0, 0, "i2cWriteByteData"); + + b = i2cReadByteData(h, 0x1d); + CHECK(11, 12, b, 0xAA, 0, "i2cReadByteData"); + + e = i2cWriteByteData(h, 0x1d, 0x55); + CHECK(11, 13, e, 0, 0, "i2cWriteByteData"); + + b = i2cReadByteData(h, 0x1d); + CHECK(11, 14, b, 0x55, 0, "i2cReadByteData"); + + exp = "[1234567890#]"; + len = strlen(exp); + + e = i2cWriteBlockData(h, 0x1C, exp, len); + CHECK(11, 15, e, 0, 0, "i2c writeBlockData"); + + e = i2cWriteDevice(h, "\x1D", 1); + b = i2cReadDevice(h, buf, len); + CHECK(11, 16, b, len, 0, "i2cReadDevice"); + CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2cReadDevice"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + b = i2cReadI2CBlockData(h, 0x1D, buf, len); + CHECK(11, 18, b, len, 0, "i2cReadI2CBlockData"); + CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2cReadI2CBlockData"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + exp = "(-+=;:,<>!%)"; + len = strlen(exp); + + e = i2cWriteI2CBlockData(h, 0x1D, exp, len); + CHECK(11, 20, e, 0, 0, "i2cWriteI2CBlockData"); + + b = i2cReadI2CBlockData(h, 0x1D, buf, len); + CHECK(11, 21, b, len, 0, "i2cReadI2CBlockData"); + CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2cReadI2CBlockData"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + e = i2cClose(h); + CHECK(11, 23, e, 0, 0, "i2cClose"); +} + +void tc() +{ + int h, x, b, e; + char txBuf[8], rxBuf[8]; + + printf("SPI tests."); + + /* this test requires a MCP3202 on SPI channel 1 */ + + h = spiOpen(1, 50000, 0); + CHECK(12, 1, h, 0, 0, "spiOpen"); + + sprintf(txBuf, "\x01\x80"); + + for (x=0; x<5; x++) + { + b = spiXfer(h, txBuf, rxBuf, 3); + CHECK(12, 2, b, 3, 0, "spiXfer"); + if (b == 3) + { + time_sleep(1.0); + printf("%d ", ((rxBuf[1]&0x0F)*256)|rxBuf[2]); + } + } + + e = spiClose(h); + CHECK(12, 99, e, 0, 0, "spiClose"); +} + +int main(int argc, char *argv[]) +{ + int i, t, c, status; + + char test[64]={0,}; + + if (argc > 1) + { + t = 0; + + for (i=0; i 0x03000000: + + if type(r) == type(""): + r = bytearray(r, 'latin-1') + + if type(s) == type(""): + s = bytearray(s, 'latin-1') + + if r != s: + print(r, s) + return 0 + + else: + return 1 + +def CHECK(t, st, got, expect, pc, desc): + if got >= (((1E2-pc)*expect)/1E2) and got <= (((1E2+pc)*expect)/1E2): + print("TEST {:2d}.{:<2d} PASS ({}: {:d})".format(t, st, desc, expect)) + else: + print("TEST {:2d}.{:<2d} FAILED got {:d} ({}: {:d})". + format(t, st, got, desc, expect)) + +def t0(): + + print("\nTesting pigpio Python module {}".format(pigpio.VERSION)) + + print("Python {}".format(sys.version.replace("\n", " "))) + + print("pigpio version {}.".format(pi.get_pigpio_version())) + + print("Hardware revision {}.".format(pi.get_hardware_revision())) + +def t1(): + + print("Mode/PUD/read/write tests.") + + pi.set_mode(GPIO, pigpio.INPUT) + v = pi.get_mode(GPIO) + CHECK(1, 1, v, 0, 0, "set mode, get mode") + + pi.set_pull_up_down(GPIO, pigpio.PUD_UP) + v = pi.read(GPIO) + CHECK(1, 2, v, 1, 0, "set pull up down, read") + + pi.set_pull_up_down(GPIO, pigpio.PUD_DOWN) + v = pi.read(GPIO) + CHECK(1, 3, v, 0, 0, "set pull up down, read") + + pi.write(GPIO, pigpio.LOW) + v = pi.get_mode(GPIO) + CHECK(1, 4, v, 1, 0, "write, get mode") + + v = pi.read(GPIO) + CHECK(1, 5, v, 0, 0, "read") + + pi.write(GPIO, pigpio.HIGH) + v = pi.read(GPIO) + CHECK(1, 6, v, 1, 0, "write, read") + +t2_count=0 + +def t2cbf(gpio, level, tick): + global t2_count + t2_count += 1 + +def t2(): + + global t2_count + + print("PWM dutycycle/range/frequency tests.") + + pi.set_PWM_range(GPIO, 255) + pi.set_PWM_frequency(GPIO,0) + f = pi.get_PWM_frequency(GPIO) + CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency") + + t2cb = pi.callback(GPIO, pigpio.EITHER_EDGE, t2cbf) + + pi.set_PWM_dutycycle(GPIO, 0) + dc = pi.get_PWM_dutycycle(GPIO) + CHECK(2, 2, dc, 0, 0, "get PWM dutycycle") + + time.sleep(0.5) # allow old notifications to flush + oc = t2_count + time.sleep(2) + f = t2_count - oc + CHECK(2, 3, f, 0, 0, "set PWM dutycycle, callback") + + pi.set_PWM_dutycycle(GPIO, 128) + dc = pi.get_PWM_dutycycle(GPIO) + CHECK(2, 4, dc, 128, 0, "get PWM dutycycle") + + time.sleep(1) + oc = t2_count + time.sleep(2) + f = t2_count - oc + CHECK(2, 5, f, 40, 10, "set PWM dutycycle, callback") + + pi.set_PWM_frequency(GPIO,100) + f = pi.get_PWM_frequency(GPIO) + CHECK(2, 6, f, 100, 0, "set/get PWM frequency") + + time.sleep(1) + oc = t2_count + time.sleep(2) + f = t2_count - oc + CHECK(2, 7, f, 400, 5, "callback") + + pi.set_PWM_frequency(GPIO,1000) + f = pi.get_PWM_frequency(GPIO) + CHECK(2, 8, f, 1000, 0, "set/get PWM frequency") + + time.sleep(1) + oc = t2_count + time.sleep(2) + f = t2_count - oc + CHECK(2, 9, f, 4000, 5, "callback") + + r = pi.get_PWM_range(GPIO) + CHECK(2, 10, r, 255, 0, "get PWM range") + + rr = pi.get_PWM_real_range(GPIO) + CHECK(2, 11, rr, 200, 0, "get PWM real range") + + pi.set_PWM_range(GPIO, 2000) + r = pi.get_PWM_range(GPIO) + CHECK(2, 12, r, 2000, 0, "set/get PWM range") + + rr = pi.get_PWM_real_range(GPIO) + CHECK(2, 13, rr, 200, 0, "get PWM real range") + + pi.set_PWM_dutycycle(GPIO, 0) + + t2cb.cancel() + +t3_reset=True +t3_count=0 +t3_tick=0 +t3_on=0.0 +t3_off=0.0 + +def t3cbf(gpio, level, tick): + global t3_reset, t3_count, t3_tick, t3_on, t3_off + + if t3_reset: + t3_count = 0 + t3_on = 0.0 + t3_off = 0.0 + t3_reset = False + else: + td = pigpio.tickDiff(t3_tick, tick) + + if level == 0: + t3_on += td + else: + t3_off += td + + t3_count += 1 + t3_tick = tick + +def t3(): + + global t3_reset, t3_count, t3_on, t3_off + + pw=[500.0, 1500.0, 2500.0] + dc=[0.2, 0.4, 0.6, 0.8] + + print("PWM/Servo pulse accuracy tests.") + + t3cb = pi.callback(GPIO, pigpio.EITHER_EDGE, t3cbf) + + t = 0 + for x in pw: + t += 1 + pi.set_servo_pulsewidth(GPIO, x) + v = pi.get_servo_pulsewidth(GPIO) + CHECK(3, t, v, int(x), 0, "get servo pulsewidth") + + t += 1 + time.sleep(1) + t3_reset = True + time.sleep(4) + c = t3_count + on = t3_on + off = t3_off + CHECK(3, t, int((1E3*(on+off))/on), int(2E7/x), 1, "set servo pulsewidth") + + + pi.set_servo_pulsewidth(GPIO, 0) + pi.set_PWM_frequency(GPIO, 1000) + f = pi.get_PWM_frequency(GPIO) + CHECK(3, 7, f, 1000, 0, "set/get PWM frequency") + + rr = pi.set_PWM_range(GPIO, 100) + CHECK(3, 8, rr, 200, 0, "set PWM range") + + t = 8 + for x in dc: + t += 1 + pi.set_PWM_dutycycle(GPIO, x*100) + v = pi.get_PWM_dutycycle(GPIO) + CHECK(3, t, v, int(x*100), 0, "get PWM dutycycle") + + t += 1 + time.sleep(1) + t3_reset = True + time.sleep(2) + c = t3_count + on = t3_on + off = t3_off + CHECK(3, t, int((1E3*on)/(on+off)), int(1E3*x), 1, "set PWM dutycycle") + + pi.set_PWM_dutycycle(GPIO, 0) + + t3cb.cancel() + +def t4(): + + print("Pipe notification tests.") + + pi.set_PWM_frequency(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_range(GPIO, 100) + + h = pi.notify_open() + e = pi.notify_begin(h, (1<=0, 1, 0, "serial open") + + (b, s) = pi.serial_read(h, 1000) # flush buffer + + b = pi.serial_data_available(h) + CHECK(10, 2, b, 0, 0, "serial data available") + + TEXT = """ +To be, or not to be, that is the question- +Whether 'tis Nobler in the mind to suffer +The Slings and Arrows of outrageous Fortune, +Or to take Arms against a Sea of troubles, +""" + e = pi.serial_write(h, TEXT) + CHECK(10, 3, e, 0, 0, "serial write") + + e = pi.serial_write_byte(h, 0xAA) + e = pi.serial_write_byte(h, 0x55) + e = pi.serial_write_byte(h, 0x00) + e = pi.serial_write_byte(h, 0xFF) + + CHECK(10, 4, e, 0, 0, "serial write byte") + + time.sleep(0.1) # allow time for transmission + + b = pi.serial_data_available(h) + CHECK(10, 5, b, len(TEXT)+4, 0, "serial data available") + + (b, text) = pi.serial_read(h, len(TEXT)) + CHECK(10, 6, b, len(TEXT), 0, "serial read") + CHECK(10, 7, STRCMP(text, TEXT), True, 0, "serial read") + + b = pi.serial_read_byte(h) + CHECK(10, 8, b, 0xAA, 0, "serial read byte") + + b = pi.serial_read_byte(h) + CHECK(10, 9, b, 0x55, 0, "serial read byte") + + b = pi.serial_read_byte(h) + CHECK(10, 10, b, 0x00, 0, "serial read byte") + + b = pi.serial_read_byte(h) + CHECK(10, 11, b, 0xFF, 0, "serial read byte") + + b = pi.serial_data_available(h) + CHECK(10, 12, b, 0, 0, "serial data available") + + e = pi.serial_close(h) + CHECK(10, 13, e, 0, 0, "serial close") + +def tb(): + print("SMBus / I2C tests.") + + # this test requires an ADXL345 on I2C bus 1 addr 0x53 + + h = pi.i2c_open(1, 0x53) + CHECK(11, 1, h>=0, 1, 0, "i2c open") + + e = pi.i2c_write_device(h, "\x00") # move to known register + CHECK(11, 2, e, 0, 0, "i2c write device") + + (b, d) = pi.i2c_read_device(h, 1) + CHECK(11, 3, b, 1, 0, "i2c read device") + CHECK(11, 4, ord(d), 0xE5, 0, "i2c read device") + + b = pi.i2c_read_byte(h) + CHECK(11, 5, b, 0xE5, 0, "i2c read byte") + + b = pi.i2c_read_byte_data(h, 0) + CHECK(11, 6, b, 0xE5, 0, "i2c read byte data") + + b = pi.i2c_read_byte_data(h, 48) + CHECK(11, 7, b, 2, 0, "i2c read byte data") + + exp = b"[aB\x08cD\xAAgHj\xFD]" + + e = pi.i2c_write_device(h, b'\x1D'+ exp) + CHECK(11, 8, e, 0, 0, "i2c write device") + + e = pi.i2c_write_device(h, '\x1D') + (b, d) = pi.i2c_read_device(h, 12) + CHECK(11, 9, b, 12, 0, "i2c read device") + CHECK(11, 10, STRCMP(d, exp), True, 0, "i2c read device") + + e = pi.i2c_write_byte_data(h, 0x1d, 0xAA) + CHECK(11, 11, e, 0, 0, "i2c write byte data") + + b = pi.i2c_read_byte_data(h, 0x1d) + CHECK(11, 12, b, 0xAA, 0, "i2c read byte data") + + e = pi.i2c_write_byte_data(h, 0x1d, 0x55) + CHECK(11, 13, e, 0, 0, "i2c write byte data") + + b = pi.i2c_read_byte_data(h, 0x1d) + CHECK(11, 14, b, 0x55, 0, "i2c read byte data") + + exp = "[1234567890#]" + + e = pi.i2c_write_block_data(h, 0x1C, exp) + CHECK(11, 15, e, 0, 0, "i2c write block data") + + e = pi.i2c_write_device(h, '\x1D') + (b, d) = pi.i2c_read_device(h, 13) + CHECK(11, 16, b, 13, 0, "i2c read device") + CHECK(11, 17, STRCMP(d, exp), True, 0, "i2c read device") + + (b, d) = pi.i2c_read_i2c_block_data(h, 0x1D, 13) + CHECK(11, 18, b, 13, 0, "i2c read i2c block data") + CHECK(11, 19, STRCMP(d, exp), True, 0, "i2c read i2c block data") + + expl = [0x01, 0x05, 0x06, 0x07, 0x09, 0x1B, 0x99, 0xAA, 0xBB, 0xCC] + exp = "\x01\x05\x06\x07\x09\x1B\x99\xAA\xBB\xCC" + + e = pi.i2c_write_i2c_block_data(h, 0x1D, expl) + CHECK(11, 20, e, 0, 0, "i2c write i2c block data") + + (b, d) = pi.i2c_read_i2c_block_data(h, 0x1D, 10) + CHECK(11, 21, b, 10, 0, "i2c read i2c block data") + CHECK(11, 22, STRCMP(d, exp), True, 0, "i2c read i2c block data") + + e = pi.i2c_close(h) + CHECK(11, 23, e, 0, 0, "i2c close") + +def tca(b, d): + if b == 3: + c1 = d[1] & 0x0F + c2 = d[2] + time.sleep(1.0) + print((c1*256)+c2) + +def tc(): + print("SPI tests.") + + # this test requires a MCP3202 on SPI channel 1 + + h = pi.spi_open(1, 50000) + CHECK(12, 1, h>=0, 1, 0, "spi open") + + (b, d) = pi.spi_xfer(h, [1,128,0]) + CHECK(12, 2, b, 3, 0, "spi xfer") + tca(b, d) + + (b, d) = pi.spi_xfer(h, "\x01\x80\x00") + CHECK(12, 2, b, 3, 0, "spi xfer") + tca(b, d) + + (b, d) = pi.spi_xfer(h, b"\x01\x80\x00") + CHECK(12, 2, b, 3, 0, "spi xfer") + tca(b, d) + + (b, d) = pi.spi_xfer(h, '\x01\x80\x00') + CHECK(12, 2, b, 3, 0, "spi xfer") + tca(b, d) + + (b, d) = pi.spi_xfer(h, b'\x01\x80\x00') + CHECK(12, 2, b, 3, 0, "spi xfer") + tca(b, d) + + e = pi.spi_close(h) + CHECK(12, 99, e, 0, 0, "spi close") + +def td(): + + print("Wavechains & filter tests.") + + tdcb = pi.callback(GPIO) + + pi.set_mode(GPIO, pigpio.OUTPUT) + + pi.write(GPIO, pigpio.LOW) + + e = pi.wave_clear() + CHECK(13, 1, e, 0, 0, "callback, set mode, wave clear") + + wf = [] + + wf.append(pigpio.pulse(1< 1: + tests = "" + for C in sys.argv[1]: + c = C.lower() + if c not in tests: + tests += c + +else: + tests = "0123456789d" + +pi = pigpio.pi() + +if pi.connected: + print("Connected to pigpio daemon.") + + if '0' in tests: t0() + if '1' in tests: t1() + if '2' in tests: t2() + if '3' in tests: t3() + if '4' in tests: t4() + if '5' in tests: t5() + if '6' in tests: t6() + if '7' in tests: t7() + if '8' in tests: t8() + if '9' in tests: t9() + if 'a' in tests: ta() + if 'b' in tests: tb() + if 'c' in tests: tc() + if 'd' in tests: td() + +pi.stop() + diff --git a/thirdparty/PIGPIO/x_pigpiod_if.c b/thirdparty/PIGPIO/x_pigpiod_if.c new file mode 100644 index 0000000000..ae4d7a5437 --- /dev/null +++ b/thirdparty/PIGPIO/x_pigpiod_if.c @@ -0,0 +1,875 @@ +/* +gcc -Wall -pthread -o x_pigpiod_if x_pigpiod_if.c -lpigpiod_if +./x_pigpiod_if + +*** WARNING ************************************************ +* * +* All the tests make extensive use of gpio 25 (pin 22). * +* Ensure that either nothing or just a LED is connected to * +* gpio 25 before running any of the tests. * +* * +* Some tests are statistical in nature and so may on * +* occasion fail. Repeated failures on the same test or * +* many failures in a group of tests indicate a problem. * +************************************************************ +*/ + +#include +#include +#include +#include +#include +#include +#include + +#include "pigpiod_if.h" + +#define GPIO 25 + +void CHECK(int t, int st, int got, int expect, int pc, char *desc) +{ + if ((got >= (((1E2-pc)*expect)/1E2)) && (got <= (((1E2+pc)*expect)/1E2))) + { + printf("TEST %2d.%-2d PASS (%s: %d)\n", t, st, desc, expect); + } + else + { + fprintf(stderr, + "TEST %2d.%-2d FAILED got %d (%s: %d)\n", + t, st, got, desc, expect); + } +} + +void t0() +{ + printf("\nTesting pigpiod C I/F 1\n"); + + printf("pigpio version %d.\n", get_pigpio_version()); + + printf("Hardware revision %d.\n", get_hardware_revision()); +} + +void t1() +{ + int v; + + printf("Mode/PUD/read/write tests.\n"); + + set_mode(GPIO, PI_INPUT); + v = get_mode(GPIO); + CHECK(1, 1, v, 0, 0, "set mode, get mode"); + + set_pull_up_down(GPIO, PI_PUD_UP); + v = gpio_read(GPIO); + CHECK(1, 2, v, 1, 0, "set pull up down, read"); + + set_pull_up_down(GPIO, PI_PUD_DOWN); + v = gpio_read(GPIO); + CHECK(1, 3, v, 0, 0, "set pull up down, read"); + + gpio_write(GPIO, PI_LOW); + v = get_mode(GPIO); + CHECK(1, 4, v, 1, 0, "write, get mode"); + + v = gpio_read(GPIO); + CHECK(1, 5, v, 0, 0, "read"); + + gpio_write(GPIO, PI_HIGH); + v = gpio_read(GPIO); + CHECK(1, 6, v, 1, 0, "write, read"); +} + +int t2_count=0; + +void t2cb(unsigned gpio, unsigned level, uint32_t tick) +{ + t2_count++; +} + +void t2() +{ + int dc, f, r, rr, oc; + + printf("PWM dutycycle/range/frequency tests.\n"); + + set_PWM_range(GPIO, 255); + set_PWM_frequency(GPIO, 0); + f = get_PWM_frequency(GPIO); + CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency"); + + callback(GPIO, EITHER_EDGE, t2cb); + + set_PWM_dutycycle(GPIO, 0); + dc = get_PWM_dutycycle(GPIO); + CHECK(2, 2, dc, 0, 0, "get PWM dutycycle"); + + time_sleep(0.5); /* allow old notifications to flush */ + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 3, f, 0, 0, "set PWM dutycycle, callback"); + + set_PWM_dutycycle(GPIO, 128); + dc = get_PWM_dutycycle(GPIO); + CHECK(2, 4, dc, 128, 0, "get PWM dutycycle"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 5, f, 40, 5, "set PWM dutycycle, callback"); + + set_PWM_frequency(GPIO, 100); + f = get_PWM_frequency(GPIO); + CHECK(2, 6, f, 100, 0, "set/get PWM frequency"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 7, f, 400, 1, "callback"); + + set_PWM_frequency(GPIO, 1000); + f = get_PWM_frequency(GPIO); + CHECK(2, 8, f, 1000, 0, "set/get PWM frequency"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 9, f, 4000, 1, "callback"); + + r = get_PWM_range(GPIO); + CHECK(2, 10, r, 255, 0, "get PWM range"); + + rr = get_PWM_real_range(GPIO); + CHECK(2, 11, rr, 200, 0, "get PWM real range"); + + set_PWM_range(GPIO, 2000); + r = get_PWM_range(GPIO); + CHECK(2, 12, r, 2000, 0, "set/get PWM range"); + + rr = get_PWM_real_range(GPIO); + CHECK(2, 13, rr, 200, 0, "get PWM real range"); + + set_PWM_dutycycle(GPIO, 0); +} + +int t3_reset=1; +int t3_count=0; +uint32_t t3_tick=0; +float t3_on=0.0; +float t3_off=0.0; + +void t3cbf(unsigned gpio, unsigned level, uint32_t tick) +{ + uint32_t td; + + if (t3_reset) + { + t3_count = 0; + t3_on = 0.0; + t3_off = 0.0; + t3_reset = 0; + } + else + { + td = tick - t3_tick; + + if (level == 0) t3_on += td; + else t3_off += td; + } + + t3_count ++; + t3_tick = tick; +} + +void t3() +{ + int pw[3]={500, 1500, 2500}; + int dc[4]={20, 40, 60, 80}; + + int f, rr, v; + float on, off; + + int t; + + printf("PWM/Servo pulse accuracy tests.\n"); + + callback(GPIO, EITHER_EDGE, t3cbf); + + for (t=0; t<3; t++) + { + set_servo_pulsewidth(GPIO, pw[t]); + v = get_servo_pulsewidth(GPIO); + CHECK(3, t+t+1, v, pw[t], 0, "get servo pulsewidth"); + + time_sleep(1); + t3_reset = 1; + time_sleep(4); + on = t3_on; + off = t3_off; + CHECK(3, t+t+2, (1000.0*(on+off))/on, 20000000.0/pw[t], 1, + "set servo pulsewidth"); + } + + set_servo_pulsewidth(GPIO, 0); + set_PWM_frequency(GPIO, 1000); + f = get_PWM_frequency(GPIO); + CHECK(3, 7, f, 1000, 0, "set/get PWM frequency"); + + rr = set_PWM_range(GPIO, 100); + CHECK(3, 8, rr, 200, 0, "set PWM range"); + + for (t=0; t<4; t++) + { + set_PWM_dutycycle(GPIO, dc[t]); + v = get_PWM_dutycycle(GPIO); + CHECK(3, t+t+9, v, dc[t], 0, "get PWM dutycycle"); + + time_sleep(1); + t3_reset = 1; + time_sleep(2); + on = t3_on; + off = t3_off; + CHECK(3, t+t+10, (1000.0*on)/(on+off), 10.0*dc[t], 1, + "set PWM dutycycle"); + } + + set_PWM_dutycycle(GPIO, 0); + +} + +void t4() +{ + int h, e, f, n, s, b, l, seq_ok, toggle_ok; + gpioReport_t r; + char p[32]; + + printf("Pipe notification tests.\n"); + + set_PWM_frequency(GPIO, 0); + set_PWM_dutycycle(GPIO, 0); + set_PWM_range(GPIO, 100); + + h = notify_open(); + + sprintf(p, "/dev/pigpio%d", h); + f = open(p, O_RDONLY); + + e = notify_begin(h, (1< 0) text[c] = 0; /* null terminate string */ + CHECK(5, 11, strcmp(TEXT, text), 0, 0, "wave tx busy, serial read"); + + e = bb_serial_read_close(GPIO); + CHECK(5, 12, e, 0, 0, "serial read close"); + + c = wave_get_micros(); + CHECK(5, 13, c, 6158148, 0, "wave get micros"); + + c = wave_get_high_micros(); + if (c > 6158148) c = 6158148; + CHECK(5, 14, c, 6158148, 0, "wave get high micros"); + + c = wave_get_max_micros(); + CHECK(5, 15, c, 1800000000, 0, "wave get max micros"); + + c = wave_get_pulses(); + CHECK(5, 16, c, 3405, 0, "wave get pulses"); + + c = wave_get_high_pulses(); + CHECK(5, 17, c, 3405, 0, "wave get high pulses"); + + c = wave_get_max_pulses(); + CHECK(5, 18, c, 12000, 0, "wave get max pulses"); + + c = wave_get_cbs(); + if (c < 6963) CHECK(5, 19, c, 6810, 0, "wave get cbs"); + else CHECK(5, 19, c, 7115, 0, "wave get cbs"); + + c = wave_get_high_cbs(); + if (c < 6963) CHECK(5, 20, c, 6810, 0, "wave get high cbs"); + else CHECK(5, 20, c, 7115, 0, "wave get high cbs"); + + c = wave_get_max_cbs(); + CHECK(5, 21, c, 25016, 0, "wave get max cbs"); +} + +int t6_count=0; +int t6_on=0; +uint32_t t6_on_tick=0; + +void t6cbf(unsigned gpio, unsigned level, uint32_t tick) +{ + if (level == 1) + { + t6_on_tick = tick; + t6_count++; + } + else + { + if (t6_on_tick) t6_on += (tick - t6_on_tick); + } +} + +void t6() +{ + int tp, t, p; + + printf("Trigger tests.\n"); + + gpio_write(GPIO, PI_LOW); + + tp = 0; + + callback(GPIO, EITHER_EDGE, t6cbf); + + time_sleep(0.2); + + for (t=0; t<5; t++) + { + time_sleep(0.1); + p = 10 + (t*10); + tp += p; + gpio_trigger(GPIO, p, 1); + } + + time_sleep(0.5); + + CHECK(6, 1, t6_count, 5, 0, "gpio trigger count"); + + CHECK(6, 2, t6_on, tp, 25, "gpio trigger pulse length"); +} + +int t7_count=0; + +void t7cbf(unsigned gpio, unsigned level, uint32_t tick) +{ + if (level == PI_TIMEOUT) t7_count++; +} + +void t7() +{ + int c, oc; + + printf("Watchdog tests.\n"); + + /* type of edge shouldn't matter for watchdogs */ + callback(GPIO, FALLING_EDGE, t7cbf); + + set_watchdog(GPIO, 50); /* 50 ms, 20 per second */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 1, c, 39, 5, "set watchdog on count"); + + set_watchdog(GPIO, 0); /* 0 switches watchdog off */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 2, c, 0, 1, "set watchdog off count"); +} + +void t8() +{ + int v; + + printf("Bank read/write tests.\n"); + + gpio_write(GPIO, 0); + v = read_bank_1() & (1<= 0) text[b] = 0; + CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read"); + + b = serial_read_byte(h); + CHECK(10, 8, b, 0xAA, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 9, b, 0x55, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 10, b, 0x00, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 11, b, 0xFF, 0, "serial read byte"); + + b = serial_data_available(h); + CHECK(10, 12, b, 0, 0, "serial data availabe"); + + e = serial_close(h); + CHECK(10, 13, e, 0, 0, "serial close"); +} + +void tb() +{ + int h, e, b, len; + char *exp; + char buf[128]; + + printf("SMBus / I2C tests."); + + /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */ + + h = i2c_open(1, 0x53, 0); + CHECK(11, 1, h, 0, 0, "i2c open"); + + e = i2c_write_device(h, "\x00", 1); /* move to known register */ + CHECK(11, 2, e, 0, 0, "i2c write device"); + + b = i2c_read_device(h, buf, 1); + CHECK(11, 3, b, 1, 0, "i2c read device"); + CHECK(11, 4, buf[0], 0xE5, 0, "i2c read device"); + + b = i2c_read_byte(h); + CHECK(11, 5, b, 0xE5, 0, "i2c read byte"); + + b = i2c_read_byte_data(h, 0); + CHECK(11, 6, b, 0xE5, 0, "i2c read byte data"); + + b = i2c_read_byte_data(h, 48); + CHECK(11, 7, b, 2, 0, "i2c read byte data"); + + exp = "\x1D[aBcDeFgHjKM]"; + len = strlen(exp); + + e = i2c_write_device(h, exp, len); + CHECK(11, 8, e, 0, 0, "i2c write device"); + + e = i2c_write_device(h, "\x1D", 1); + b = i2c_read_device(h, buf, len-1); + CHECK(11, 9, b, len-1, 0, "i2c read device"); + CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2c read device"); + + if (strncmp(buf, exp+1, len-1)) + printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1); + + e = i2c_write_byte_data(h, 0x1d, 0xAA); + CHECK(11, 11, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(h, 0x1d); + CHECK(11, 12, b, 0xAA, 0, "i2c read byte data"); + + e = i2c_write_byte_data(h, 0x1d, 0x55); + CHECK(11, 13, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(h, 0x1d); + CHECK(11, 14, b, 0x55, 0, "i2c read byte data"); + + exp = "[1234567890#]"; + len = strlen(exp); + + e = i2c_write_block_data(h, 0x1C, exp, len); + CHECK(11, 15, e, 0, 0, "i2c write block data"); + + e = i2c_write_device(h, "\x1D", 1); + b = i2c_read_device(h, buf, len); + CHECK(11, 16, b, len, 0, "i2c read device"); + CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2c read device"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + b = i2c_read_i2c_block_data(h, 0x1D, buf, len); + CHECK(11, 18, b, len, 0, "i2c read i2c block data"); + CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + exp = "(-+=;:,<>!%)"; + len = strlen(exp); + + e = i2c_write_i2c_block_data(h, 0x1D, exp, len); + CHECK(11, 20, e, 0, 0, "i2c write i2c block data"); + + b = i2c_read_i2c_block_data(h, 0x1D, buf, len); + CHECK(11, 21, b, len, 0, "i2c read i2c block data"); + CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + e = i2c_close(h); + CHECK(11, 23, e, 0, 0, "i2c close"); +} + +void tc() +{ + int h, x, b, e; + char buf[128]; + + printf("SPI tests."); + + /* this test requires a MCP3202 on SPI channel 1 */ + + h = spi_open(1, 50000, 0); + CHECK(12, 1, h, 0, 0, "spi open"); + + + for (x=0; x<5; x++) + { + sprintf(buf, "\x01\x80"); + b = spi_xfer(h, buf, buf, 3); + CHECK(12, 2, b, 3, 0, "spi xfer"); + if (b == 3) + { + time_sleep(1.0); + printf("%d ", ((buf[1]&0x0F)*256)|buf[2]); + } + } + + e = spi_close(h); + CHECK(12, 99, e, 0, 0, "spi close"); +} + + +int main(int argc, char *argv[]) +{ + int i, t, c, status; + + char test[64]={0,}; + + if (argc > 1) + { + t = 0; + + for (i=0; i +#include +#include +#include +#include +#include +#include + +#include "pigpiod_if2.h" + +#define GPIO 25 + +void CHECK(int t, int st, int got, int expect, int pc, char *desc) +{ + if ((got >= (((1E2-pc)*expect)/1E2)) && (got <= (((1E2+pc)*expect)/1E2))) + { + printf("TEST %2d.%-2d PASS (%s: %d)\n", t, st, desc, expect); + } + else + { + fprintf(stderr, + "TEST %2d.%-2d FAILED got %d (%s: %d)\n", + t, st, got, desc, expect); + } +} + +void t0(int pi) +{ + printf("\nTesting pigpiod C I/F 2\n"); + + printf("pigpio version %d.\n", get_pigpio_version(pi)); + + printf("Hardware revision %d.\n", get_hardware_revision(pi)); +} + +void t1(int pi) +{ + int v; + + printf("Mode/PUD/read/write tests.\n"); + + set_mode(pi, GPIO, PI_INPUT); + v = get_mode(pi, GPIO); + CHECK(1, 1, v, 0, 0, "set mode, get mode"); + + set_pull_up_down(pi, GPIO, PI_PUD_UP); + v = gpio_read(pi, GPIO); + CHECK(1, 2, v, 1, 0, "set pull up down, read"); + + set_pull_up_down(pi, GPIO, PI_PUD_DOWN); + v = gpio_read(pi, GPIO); + CHECK(1, 3, v, 0, 0, "set pull up down, read"); + + gpio_write(pi, GPIO, PI_LOW); + v = get_mode(pi, GPIO); + CHECK(1, 4, v, 1, 0, "write, get mode"); + + v = gpio_read(pi, GPIO); + CHECK(1, 5, v, 0, 0, "read"); + + gpio_write(pi, GPIO, PI_HIGH); + v = gpio_read(pi, GPIO); + CHECK(1, 6, v, 1, 0, "write, read"); +} + +int t2_count=0; + +void t2cb(int pi, unsigned gpio, unsigned level, uint32_t tick) +{ + t2_count++; +} + +void t2(int pi) +{ + int dc, f, r, rr, oc, id; + + printf("PWM dutycycle/range/frequency tests.\n"); + + set_PWM_range(pi, GPIO, 255); + set_PWM_frequency(pi, GPIO, 0); + f = get_PWM_frequency(pi, GPIO); + CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency"); + + id = callback(pi, GPIO, EITHER_EDGE, t2cb); + + set_PWM_dutycycle(pi, GPIO, 0); + dc = get_PWM_dutycycle(pi, GPIO); + CHECK(2, 2, dc, 0, 0, "get PWM dutycycle"); + + time_sleep(0.5); /* allow old notifications to flush */ + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 3, f, 0, 0, "set PWM dutycycle, callback"); + + set_PWM_dutycycle(pi, GPIO, 128); + dc = get_PWM_dutycycle(pi, GPIO); + CHECK(2, 4, dc, 128, 0, "get PWM dutycycle"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 5, f, 40, 5, "set PWM dutycycle, callback"); + + set_PWM_frequency(pi, GPIO, 100); + f = get_PWM_frequency(pi, GPIO); + CHECK(2, 6, f, 100, 0, "set/get PWM frequency"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 7, f, 400, 1, "callback"); + + set_PWM_frequency(pi, GPIO, 1000); + f = get_PWM_frequency(pi, GPIO); + CHECK(2, 8, f, 1000, 0, "set/get PWM frequency"); + + time_sleep(0.2); + oc = t2_count; + time_sleep(2); + f = t2_count - oc; + CHECK(2, 9, f, 4000, 1, "callback"); + + r = get_PWM_range(pi, GPIO); + CHECK(2, 10, r, 255, 0, "get PWM range"); + + rr = get_PWM_real_range(pi, GPIO); + CHECK(2, 11, rr, 200, 0, "get PWM real range"); + + set_PWM_range(pi, GPIO, 2000); + r = get_PWM_range(pi, GPIO); + CHECK(2, 12, r, 2000, 0, "set/get PWM range"); + + rr = get_PWM_real_range(pi, GPIO); + CHECK(2, 13, rr, 200, 0, "get PWM real range"); + + set_PWM_dutycycle(pi, GPIO, 0); + + callback_cancel(id); +} + +int t3_reset=1; +int t3_count=0; +uint32_t t3_tick=0; +float t3_on=0.0; +float t3_off=0.0; + +void t3cbf(int pi, unsigned gpio, unsigned level, uint32_t tick) +{ + uint32_t td; + +// printf("pi=%d g=%d l=%d t=%u\n", pi, gpio, level, tick); + if (t3_reset) + { + t3_count = 0; + t3_on = 0.0; + t3_off = 0.0; + t3_reset = 0; + } + else + { + td = tick - t3_tick; + + if (level == 0) t3_on += td; + else t3_off += td; + } + + t3_count ++; + t3_tick = tick; +} + +void t3(int pi) +{ + int pw[3]={500, 1500, 2500}; + int dc[4]={20, 40, 60, 80}; + + int f, rr, v; + float on, off; + + int t, id; + + printf("PWM/Servo pulse accuracy tests.\n"); + + id = callback(pi, GPIO, EITHER_EDGE, t3cbf); + + for (t=0; t<3; t++) + { + set_servo_pulsewidth(pi, GPIO, pw[t]); + v = get_servo_pulsewidth(pi, GPIO); + CHECK(3, t+t+1, v, pw[t], 0, "get servo pulsewidth"); + + time_sleep(1); + t3_reset = 1; + time_sleep(4); + on = t3_on; + off = t3_off; + CHECK(3, t+t+2, (1000.0*(on+off))/on, 20000000.0/pw[t], 1, + "set servo pulsewidth"); + } + + set_servo_pulsewidth(pi, GPIO, 0); + set_PWM_frequency(pi, GPIO, 1000); + f = get_PWM_frequency(pi, GPIO); + CHECK(3, 7, f, 1000, 0, "set/get PWM frequency"); + + rr = set_PWM_range(pi, GPIO, 100); + CHECK(3, 8, rr, 200, 0, "set PWM range"); + + for (t=0; t<4; t++) + { + set_PWM_dutycycle(pi, GPIO, dc[t]); + v = get_PWM_dutycycle(pi, GPIO); + CHECK(3, t+t+9, v, dc[t], 0, "get PWM dutycycle"); + + time_sleep(1); + t3_reset = 1; + time_sleep(2); + on = t3_on; + off = t3_off; + CHECK(3, t+t+10, (1000.0*on)/(on+off), 10.0*dc[t], 1, + "set PWM dutycycle"); + } + + set_PWM_dutycycle(pi, GPIO, 0); + + callback_cancel(id); +} + +void t4(int pi) +{ + int h, e, f, n, s, b, l, seq_ok, toggle_ok; + gpioReport_t r; + char p[32]; + + printf("Pipe notification tests.\n"); + + set_PWM_frequency(pi, GPIO, 0); + set_PWM_dutycycle(pi, GPIO, 0); + set_PWM_range(pi, GPIO, 100); + + h = notify_open(pi); + + sprintf(p, "/dev/pigpio%d", h); + f = open(p, O_RDONLY); + + e = notify_begin(pi, h, (1< 0) text[c] = 0; /* null terminate string */ + CHECK(5, 11, strcmp(TEXT, text), 0, 0, "wave tx busy, serial read"); + + e = bb_serial_read_close(pi, GPIO); + CHECK(5, 12, e, 0, 0, "serial read close"); + + c = wave_get_micros(pi); + CHECK(5, 13, c, 6158148, 0, "wave get micros"); + + c = wave_get_high_micros(pi); + if (c > 6158148) c = 6158148; + CHECK(5, 14, c, 6158148, 0, "wave get high micros"); + + c = wave_get_max_micros(pi); + CHECK(5, 15, c, 1800000000, 0, "wave get max micros"); + + c = wave_get_pulses(pi); + CHECK(5, 16, c, 3405, 0, "wave get pulses"); + + c = wave_get_high_pulses(pi); + CHECK(5, 17, c, 3405, 0, "wave get high pulses"); + + c = wave_get_max_pulses(pi); + CHECK(5, 18, c, 12000, 0, "wave get max pulses"); + + c = wave_get_cbs(pi); + if (c < 6963) CHECK(5, 19, c, 6810, 0, "wave get cbs"); + else CHECK(5, 19, c, 7115, 0, "wave get cbs"); + + c = wave_get_high_cbs(pi); + if (c < 6963) CHECK(5, 20, c, 6810, 0, "wave get high cbs"); + else CHECK(5, 20, c, 7115, 0, "wave get high cbs"); + + c = wave_get_max_cbs(pi); + CHECK(5, 21, c, 25016, 0, "wave get max cbs"); + + callback_cancel(id); +} + +int t6_count=0; +int t6_on=0; +uint32_t t6_on_tick=0; + +void t6cbf(int pi, unsigned gpio, unsigned level, uint32_t tick) +{ + if (level == 1) + { + t6_on_tick = tick; + t6_count++; + } + else + { + if (t6_on_tick) t6_on += (tick - t6_on_tick); + } +} + +void t6(int pi) +{ + int tp, t, p, id; + + printf("Trigger tests.\n"); + + gpio_write(pi, GPIO, PI_LOW); + + tp = 0; + + id = callback(pi, GPIO, EITHER_EDGE, t6cbf); + + time_sleep(0.2); + + for (t=0; t<5; t++) + { + time_sleep(0.1); + p = 10 + (t*10); + tp += p; + gpio_trigger(pi, GPIO, p, 1); + } + + time_sleep(0.5); + + CHECK(6, 1, t6_count, 5, 0, "gpio trigger count"); + + CHECK(6, 2, t6_on, tp, 25, "gpio trigger pulse length"); + + callback_cancel(id); +} + +int t7_count=0; + +void t7cbf(int pi, unsigned gpio, unsigned level, uint32_t tick) +{ + if (level == PI_TIMEOUT) t7_count++; +} + +void t7(int pi) +{ + int c, oc, id; + + printf("Watchdog tests.\n"); + + /* type of edge shouldn't matter for watchdogs */ + id = callback(pi, GPIO, FALLING_EDGE, t7cbf); + + set_watchdog(pi, GPIO, 50); /* 50 ms, 20 per second */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 1, c, 39, 5, "set watchdog on count"); + + set_watchdog(pi, GPIO, 0); /* 0 switches watchdog off */ + time_sleep(0.5); + oc = t7_count; + time_sleep(2); + c = t7_count - oc; + CHECK(7, 2, c, 0, 1, "set watchdog off count"); + + callback_cancel(id); +} + +void t8(int pi) +{ + int v; + + printf("Bank read/write tests.\n"); + + gpio_write(pi, GPIO, 0); + v = read_bank_1(pi) & (1<= 0) text[b] = 0; + CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read"); + + b = serial_read_byte(pi, h); + CHECK(10, 8, b, 0xAA, 0, "serial read byte"); + + b = serial_read_byte(pi, h); + CHECK(10, 9, b, 0x55, 0, "serial read byte"); + + b = serial_read_byte(pi, h); + CHECK(10, 10, b, 0x00, 0, "serial read byte"); + + b = serial_read_byte(pi, h); + CHECK(10, 11, b, 0xFF, 0, "serial read byte"); + + b = serial_data_available(pi, h); + CHECK(10, 12, b, 0, 0, "serial data availabe"); + + e = serial_close(pi, h); + CHECK(10, 13, e, 0, 0, "serial close"); +} + +void tb(int pi) +{ + int h, e, b, len; + char *exp; + char buf[128]; + + printf("SMBus / I2C tests."); + + /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */ + + h = i2c_open(pi, 1, 0x53, 0); + CHECK(11, 1, h, 0, 0, "i2c open"); + + e = i2c_write_device(pi, h, "\x00", 1); /* move to known register */ + CHECK(11, 2, e, 0, 0, "i2c write device"); + + b = i2c_read_device(pi, h, buf, 1); + CHECK(11, 3, b, 1, 0, "i2c read device"); + CHECK(11, 4, buf[0], 0xE5, 0, "i2c read device"); + + b = i2c_read_byte(pi, h); + CHECK(11, 5, b, 0xE5, 0, "i2c read byte"); + + b = i2c_read_byte_data(pi, h, 0); + CHECK(11, 6, b, 0xE5, 0, "i2c read byte data"); + + b = i2c_read_byte_data(pi, h, 48); + CHECK(11, 7, b, 2, 0, "i2c read byte data"); + + exp = "\x1D[aBcDeFgHjKM]"; + len = strlen(exp); + + e = i2c_write_device(pi, h, exp, len); + CHECK(11, 8, e, 0, 0, "i2c write device"); + + e = i2c_write_device(pi, h, "\x1D", 1); + b = i2c_read_device(pi, h, buf, len-1); + CHECK(11, 9, b, len-1, 0, "i2c read device"); + CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2c read device"); + + if (strncmp(buf, exp+1, len-1)) + printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1); + + e = i2c_write_byte_data(pi, h, 0x1d, 0xAA); + CHECK(11, 11, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(pi, h, 0x1d); + CHECK(11, 12, b, 0xAA, 0, "i2c read byte data"); + + e = i2c_write_byte_data(pi, h, 0x1d, 0x55); + CHECK(11, 13, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(pi, h, 0x1d); + CHECK(11, 14, b, 0x55, 0, "i2c read byte data"); + + exp = "[1234567890#]"; + len = strlen(exp); + + e = i2c_write_block_data(pi, h, 0x1C, exp, len); + CHECK(11, 15, e, 0, 0, "i2c write block data"); + + e = i2c_write_device(pi, h, "\x1D", 1); + b = i2c_read_device(pi, h, buf, len); + CHECK(11, 16, b, len, 0, "i2c read device"); + CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2c read device"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + b = i2c_read_i2c_block_data(pi, h, 0x1D, buf, len); + CHECK(11, 18, b, len, 0, "i2c read i2c block data"); + CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + exp = "(-+=;:,<>!%)"; + len = strlen(exp); + + e = i2c_write_i2c_block_data(pi, h, 0x1D, exp, len); + CHECK(11, 20, e, 0, 0, "i2c write i2c block data"); + + b = i2c_read_i2c_block_data(pi, h, 0x1D, buf, len); + CHECK(11, 21, b, len, 0, "i2c read i2c block data"); + CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + e = i2c_close(pi, h); + CHECK(11, 23, e, 0, 0, "i2c close"); +} + +void tc(int pi) +{ + int h, x, b, e; + char buf[128]; + + printf("SPI tests."); + + /* this test requires a MCP3202 on SPI channel 1 */ + + h = spi_open(pi, 1, 50000, 0); + CHECK(12, 1, h, 0, 0, "spi open"); + + + for (x=0; x<5; x++) + { + sprintf(buf, "\x01\x80"); + b = spi_xfer(pi, h, buf, buf, 3); + CHECK(12, 2, b, 3, 0, "spi xfer"); + if (b == 3) + { + time_sleep(1.0); + printf("%d ", ((buf[1]&0x0F)*256)|buf[2]); + } + } + + e = spi_close(pi, h); + CHECK(12, 99, e, 0, 0, "spi close"); +} + + +int main(int argc, char *argv[]) +{ + int i, t, c, pi; + + char test[64]={0,}; + + if (argc > 1) + { + t = 0; + + for (i=0; i/dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 h /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 p /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 -a v /dev/pigpio +read -t 1 s /dev/pigpio +sleep 0.1 +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 w /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +echo "tick" >/dev/pigpio +read -t 1 t1 /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 w /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s /dev/pigpio +read -t 1 s 0 0 0 - + diff --git a/tools/proto2python.sh b/tools/proto2python.sh index d0310bfcb4..3f96cd6e35 100755 --- a/tools/proto2python.sh +++ b/tools/proto2python.sh @@ -1,13 +1,26 @@ -#!/usr/bin/env sh +#!/bin/bash + +set -e + +PROTO_FOLDER='../cpprevolve/revolve/gazebo/msgs' +GAZEBO_PROTO_FOLDER='/home/matteo/Tools/gazebo/include/gazebo-10/gazebo/msgs/proto/' +PY_PROTOBUF_FOLDER='../pyrevolve/spec/msgs/' # Generate Python protobuf files -protoc -I ../cpprevolve/revolve/msgs \ - -I /usr/local/include/gazebo-9/gazebo/msgs/proto \ - --python_out=../pyrevolve/spec/msgs/ \ - ../cpprevolve/revolve/msgs/*.proto +protoc -I ${PROTO_FOLDER} \ + -I ${GAZEBO_PROTO_FOLDER} \ + --python_out=${PY_PROTOBUF_FOLDER} \ + ${PROTO_FOLDER}/*.proto # Correctly reference imported Gazebo messages -sed -E 's/import vector3d_pb2/from pygazebo.msg import vector3d_pb2/g' ../revolve/spec/msgs/*.py -sed -E 's/import pose_pb2/from pygazebo.msg import pose_pb2/g' ../revolve/spec/msgs/*.py -sed -E 's/import time_pb2/from pygazebo.msg import time_pb2/g' ../revolve/spec/msgs/*.py -sed -E 's/import model_pb2/from pygazebo.msg import model_pb2/g' ../revolve/spec/msgs/*.py +sed -i -E 's/import vector3d_pb2/from pygazebo.msg import vector3d_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py +sed -i -E 's/import pose_pb2/from pygazebo.msg import pose_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py +sed -i -E 's/import time_pb2/from pygazebo.msg import time_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py +sed -i -E 's/import model_pb2/from pygazebo.msg import model_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py + +sed -i -E 's/import body_pb2/from . import body_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py +sed -i -E 's/import parameter_pb2/from . import parameter_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py +sed -i -E 's/import neural_net_pb2/from . import neural_net_pb2/g' ${PY_PROTOBUF_FOLDER}/*.py + +#it wont write the improt correctly. gotta change 'import' to 'from . import' +#in some cases 'from pygazebo.msg import' \ No newline at end of file diff --git a/worlds/plane.ensure_contacts.world b/worlds/plane.ensure_contacts.world new file mode 100644 index 0000000000..0b067dc965 --- /dev/null +++ b/worlds/plane.ensure_contacts.world @@ -0,0 +1,43 @@ + + + + + 0 + 0 + + + + 0.005 + + + 2000 + + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + world + + + + + + + + + model://sun + + + model://tol_ground + + + + + diff --git a/worlds/gait-learning.realtime.world b/worlds/plane.realtime.world similarity index 86% rename from worlds/gait-learning.realtime.world rename to worlds/plane.realtime.world index cf9398b240..5864bebad4 100644 --- a/worlds/gait-learning.realtime.world +++ b/worlds/plane.realtime.world @@ -9,11 +9,8 @@ 0.001 - - - - 1000 + 800 diff --git a/worlds/gait-learning.world b/worlds/plane.unmanaged.world similarity index 96% rename from worlds/gait-learning.world rename to worlds/plane.unmanaged.world index b824e269d1..bf63bd53cf 100644 --- a/worlds/gait-learning.world +++ b/worlds/plane.unmanaged.world @@ -7,7 +7,7 @@ - 0.005 + 0.02 0.0 diff --git a/worlds/plane.world b/worlds/plane.world new file mode 100644 index 0000000000..07330739c3 --- /dev/null +++ b/worlds/plane.world @@ -0,0 +1,43 @@ + + + + + 0 + 0 + + + + 0.005 + + + 0 + + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + world + + + + + + + + + model://sun + + + model://tol_ground + + + + + diff --git a/worlds/planobstacles.realtime.world b/worlds/planobstacles.realtime.world new file mode 100644 index 0000000000..991747d10f --- /dev/null +++ b/worlds/planobstacles.realtime.world @@ -0,0 +1,7632 @@ + + + + + 0 + 0 + + + 0.003 + + + 1000 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + -1 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.57 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.14 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.29 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.72 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + + model://sun + + + model://tol_ground + + + + diff --git a/worlds/planobstacles.world b/worlds/planobstacles.world new file mode 100644 index 0000000000..ffa4a71a82 --- /dev/null +++ b/worlds/planobstacles.world @@ -0,0 +1,7632 @@ + + + + + 0 + 0 + + + 0.003 + + + 0.0 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + -1 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -1 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.93 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.75 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.82 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.57 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.5 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.57 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.32 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.25 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + -0.14 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.14 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + -0.0699999999999999 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.11 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.0400000000000001 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.29 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.36 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.29 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.54 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.61 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.72 -1 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.87 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.74 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.61 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.48 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.35 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 -0.22 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 -0.0899999999999999 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.0400000000000001 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.17 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.3 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.43 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.56 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.69 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.72 0.82 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.79 0.95 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.01 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.01 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.93 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.8 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.67 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.54 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.41 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.28 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 -0.15 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 -0.02 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.11 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.24 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.37 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.5 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.63 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.97 0.76 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + 0.9 0.89 0 0 0 0 + + + 1 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0.03 0.03 0.02 + + + 10 + + + + + + + + + + + + + + 0.03 0.03 0.02 + + + + + + + 0 + 0 + 1 + + + + + model://sun + + + model://tol_ground + + + + diff --git a/worlds/tilted10.realtime.world b/worlds/tilted10.realtime.world new file mode 100644 index 0000000000..d863a30fad --- /dev/null +++ b/worlds/tilted10.realtime.world @@ -0,0 +1,41 @@ + + + + + 0 + 0 + + + 0.003 + + + 1000 + + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted10 + + + + + diff --git a/worlds/tilted10.world b/worlds/tilted10.world new file mode 100644 index 0000000000..be0e7b5695 --- /dev/null +++ b/worlds/tilted10.world @@ -0,0 +1,40 @@ + + + + + 0 + 0 + + + 0.003 + + + 0 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted10 + + + + + diff --git a/worlds/tilted15.realtime.world b/worlds/tilted15.realtime.world new file mode 100644 index 0000000000..ee342f03b6 --- /dev/null +++ b/worlds/tilted15.realtime.world @@ -0,0 +1,41 @@ + + + + + 0 + 0 + + + 0.003 + + + 1000 + + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted15 + + + + + diff --git a/worlds/tilted15.world b/worlds/tilted15.world new file mode 100644 index 0000000000..caa8c554e2 --- /dev/null +++ b/worlds/tilted15.world @@ -0,0 +1,40 @@ + + + + + 0 + 0 + + + 0.003 + + + 0 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted15 + + + + + diff --git a/worlds/tilted5.realtime.world b/worlds/tilted5.realtime.world new file mode 100644 index 0000000000..9324164ab7 --- /dev/null +++ b/worlds/tilted5.realtime.world @@ -0,0 +1,40 @@ + + + + + 0 + 0 + + + 0.003 + + + 1000 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted5 + + + + + diff --git a/worlds/tilted5.world b/worlds/tilted5.world new file mode 100644 index 0000000000..45fa5e9d45 --- /dev/null +++ b/worlds/tilted5.world @@ -0,0 +1,40 @@ + + + + + 0 + 0 + + + 0.003 + + + 0 + + + + 0.1 + 10e-6 + + + 100 + 1e-8 + + + quick + + + + + + + + model://sun + + + model://tilted5 + + + + +