diff --git a/.github/README.md b/.github/README.md new file mode 120000 index 0000000..d18b8ba --- /dev/null +++ b/.github/README.md @@ -0,0 +1 @@ +../README-NAO.md \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt old mode 100644 new mode 100755 index 4ae72d5..29f2730 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,8 +1,9 @@ ################################################################################ # Copyright 2013-2014 EPFL # # Copyright 2013-2014 Quentin Bonnard # +# Copyright 2016 Bahar Irfan # # # -# This file is part of chilitags. # +# This file was modified to implement Chilitags on NAO robot. # # # # Chilitags is free software: you can redistribute it and/or modify # # it under the terms of the Lesser GNU General Public License as # @@ -26,7 +27,7 @@ set(CPACK_PACKAGE_VERSION_MAJOR "2") set(CPACK_PACKAGE_VERSION_MINOR "0") set(CPACK_PACKAGE_VERSION_PATCH "0") -add_definitions(-std=c++11) +add_definitions(-std=gnu++11) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/") find_package(OpenCV REQUIRED ) include_directories(${OpenCV_INCLUDE_DIRS}) @@ -37,6 +38,7 @@ message(STATUS "OpenCV version: ${OpenCV_VERSION}") ########################################## option(WITH_SAMPLES "Build demos" OFF) +option(WITH_NAOMODULE "Build module for NAO" OFF) option(WITH_TESTS "Build tests" OFF) option(WITH_JNI_BINDINGS "Build JNI bindings compatible with ordinary Java and Android" OFF) option(WITH_INVERTED_TAGS "Support for 'inverted' tags" OFF) @@ -103,6 +105,10 @@ if (WITH_SAMPLES) add_subdirectory(samples) endif() +if (WITH_NAOMODULE) + add_subdirectory(naoModule) +endif() + if(WITH_TESTS) add_subdirectory(test) endif() diff --git a/README-NAO.md b/README-NAO.md new file mode 100755 index 0000000..badff8d --- /dev/null +++ b/README-NAO.md @@ -0,0 +1,267 @@ +# ChilitagsModule: Chilitags for NAO Robot + +ChilitagsModule implements Chilitags (Bonnard et al., 2013) on a NAO robot (SoftBank Robotics Europe, France). Chilitags are 2D fiducial markers to detect objects and determine their positions. ChilitagsModule was tested on NAOqi 2.1 and 2.4 on a NAO robot. While Pepper robot (SoftBank Robotics Europe, France) also has a NAOqi operating system, ChilitagsModule was not tested on it. + +For looking and pointing at objects with Chilitags using a NAO robot, see B. Irfan (2016), "Robust Pointing with NAO Robot", `https://github.com/birfan/NAOpointing`, which uses ChilitagsModule. + +## Install Chilitags and ChilitagsModule on NAO Using Precompiled Libraries + +* Open Choregraphe. From Connection -> Advanced, choose file transfer. + +* Upload the precompiled ChilitagsModule files in *naoModule/compiled_files* to the robot (9 files). + +* Connect to the robot using terminal (e.g. via putty from Windows). + +* Run the following commands: + +``` + $ su (password is root) + $ mv /usr/lib/libstdc++.so /usr/lib/libstdc++_nao.so + $ mv /usr/lib/libstdc++.so.6 /usr/lib/libstdc++_nao.so.6 + $ mv /usr/lib/libstdc++.so.6.0.14 /usr/lib/libstdc++_nao.so.6.0.14 + $ mkdir dev + $ cd dev + $ mkdir bin + $ mkdir lib + $ cd ../.. + $ scp libchilitagsmodule.so /home/nao/dev/lib + $ scp testchilitagsmodule* /home/nao/dev/bin + $ scp libchilitags.so /usr/lib + $ scp libchilitags_static.a /usr/lib + $ scp libstdc++.so* /usr/lib + + $ nano naoqi/preferences/autoload.ini +``` + +* Add the following line under [user] + +``` + /home/nao/dev/lib/libchilitagsmodule.so +``` + +* Save and close the file (Ctrl + Alt + X), and restart naoqi + +``` + $ nao restart +``` + +* Test the module by running + +``` + $ python dev/bin/testchilitagsmodule.py +``` + +* Then present Chilitags number 8 to NAO to retrieve the info. + + +## Install Chilitags and ChilitagsModule on NAO Using OpenNAO (Compile from Source) + +Use the following instructions for compiling Chilitags and ChilitagsModule for NAO robot (using OpenNAO) and running the module on the robot, if the precompiled libraries do not work. + +* Download OpenNAO OS VirtualBox and C++ NAOqi cross toolchain for Linux 32 from Software (OR use the *libnaoqi_files* folder in *naoModule* folder provided instead of the toolchain) in + + + http://community.aldebaran.com + + +* Setup OpenNAO using VirtualBox + + +* Clone Chilitags and ChilitagsModule to OpenNAO: + + + git clone https://github.com/birfan/chilitags + +``` + $ cd chilitags +``` + +* Use the *naoModule/libnaoqi_files* folder to copy the files to *include*, *lib*, *bin*, *share/cmake* and *share/naoqi* (copy the naoqi folder completely) to */usr/local/include*, */usr/local/lib*, */usr/local/share*, */usr/local/bin*, respectively. + + OR in the cross toolchain folder, go to *libnaoqi* folder and copy the files that contain "al" and "qi", along with "rttools" and "naoqi" from localhost to virtual (OpenNAO) to the respective places as above. + +### Configure GCC to C++11 + +* In OpenNAO: + +``` + $ mkdir src + + $ mkdir dev +``` + +On local computer: + + +* Get gcc-5.3.0 + + +* Copy the folder to OpenNAO: + +``` + $ scp -P 2222 -r gcc-5.3.0/ nao@localhost:/home/nao/src/ +``` + +On OpenNAO: + +``` + $ cd src/gcc-5.3.0 + + $ mkdir build && cd build + + $ ../configure --enable-languages=c,c++ + + $ sudo make -j8 + + $ sudo make install exec_prefix=/usr/local +``` + + +* Export the local library path to update the gcc + +``` + $ export "LD_LIBRARY_PATH=/usr/local/lib" +``` + +* In chilitags/CMakeLists.txt, change the add_definitions for c++11 to the format below: + +``` + add_definitions(-std=gnu++11) +``` + +### Compile Chilitags + +In *chilitags/build* folder: + +* To run it locally on the NAO: + +``` + $ cmake .. -DCMAKE_CXX_COMPILER="/usr/local/bin/c++" -DCMAKE_C_COMPILER="/usr/local/bin/gcc" -DCMAKE_CXX_FLAGS_RELEASE="-O3 -DNDEBUG -D_GLIBCXX_USE_CXX11_ABI=0 -s -mtune=atom -mssse3 -mfpmath=sse" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG -s -mtune=atom -mssse3 -mfpmath=sse" -DWITH_NAOMODULE=ON -DWITH_TOOLS=ON -DCMAKE_BUILD_TYPE=Release -DCHILITAGSMODULE_IS_REMOTE=OFF +``` + +* To run it remotely from OpenNAO: + +``` + $ cmake .. -DCMAKE_CXX_COMPILER="/usr/local/bin/c++" -DCMAKE_C_COMPILER="/usr/local/bin/gcc" -DCMAKE_CXX_FLAGS_RELEASE="-O3 -DNDEBUG -D_GLIBCXX_USE_CXX11_ABI=0 -s -mtune=atom -mssse3 -mfpmath=sse" -DCMAKE_C_FLAGS_RELEASE="-O3 -DNDEBUG -s -mtune=atom -mssse3 -mfpmath=sse" -DWITH_NAOMODULE=ON -DWITH_TOOLS=ON -DCMAKE_BUILD_TYPE=Release -DCHILITAGSMODULE_IS_REMOTE=ON +``` + +### Rename Old Libraries On NAO + +To be able to revert to the default libraries in case of any problems, rename the libraries on NAO: + +``` + $ mkdir dev && cd dev + + $ mkdir bin && mkdir lib + + $ sudo mv /usr/lib/libstdc++.so /usr/lib/libstdc++_nao.so + + $ sudo mv /usr/lib/libstdc++.so.6 /usr/lib/libstdc++_nao.so.6 + + $ sudo mv /usr/lib/libstdc++.so.6.0.14 /usr/lib/libstdc++_nao.so.6.0.14 +``` + +## Run Chilitags on NAO Locally: + + +* Send the code from OpenNAO to NAO: + +``` + $ cd chilitags/build/naoModule + + $ scp libchilitagsmodule.so nao@robotIP:/home/nao/dev/lib + + $ scp testchilitagsmodule* nao@robotIP:/home/nao/dev/bin + + $ cd ../src + + $ scp libchilitags.so nao@robotIP:/usr/lib + + $ scp libchilitags_static.a nao@robotIP:/usr/lib + + $ cd /usr/local/lib + + $ scp libstdc++.so* nao@robotIP:/usr/lib +``` + +* On NAO: + +``` + $ nano naoqi/preferences/autoload.ini +``` + +* Add the following line under [user] + +``` + /home/nao/dev/lib/libchilitagsmodule.so +``` + +* Save and close the file, and restart naoqi + +``` + $ nao restart +``` + +* When the robot starts (and all the modules load) + +``` + $ cd dev/bin + + $ ./testchilitagsmodule "127.0.0.1" +``` + OR + +``` + $ python testchilitagsmodule.py +``` + +## Run Chilitags Remotely (from OpenNAO): + +(Comment /home/nao/dev/lib/libchilitagsmodule.so in the *autoload.ini* file, if previously added and restart Nao) + +``` + $ cd chilitags/build/naoModule + + $ ./chilitagsmodule --pip robotIP --pport 9559 + + $ ./testchilitagsmodule robotIP +``` + OR + +``` + $ python testchilitagsmodule.py +``` + +## Coding style + +This repository uses `uncrustify`, a tool that does automatic code formatting based on a predefined configuration defined in `uncrustify.cfg` (updated according to version 0.71.0) to keep the code formatting consistent with Chilitags. + +## License + +ChilitagsModule is released under GNU Lesser General Public License v3.0 (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). Cite the following if using this work: + + * Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of Plymouth, UK. `https://github.com/birfan/chilitags`. 2016. + + * Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg. CHILI, EPFL, Switzerland. `http://chili.epfl.ch/software`. 2013. + +``` + @misc{chilitagsModule, + title = {Chilitags for NAO Robot}, + author={Irfan, Bahar and Lemaignan, S\'{e}verin}, + publisher={University of Plymouth, UK}, + url={https://github.com/birfan/chilitags}, + year={2016} + } + + @misc{chilitags, + title = {Chilitags 2: Robust Fiducial Markers for Augmented Reality and Robotics.}, + author={Bonnard, Quentin and Lemaignan, S\'{e}verin and Zufferey, Guillaume and Mazzei, Andrea and Cuendet, S\'{e}bastien and Li, Nan and \"{O}zg\"{u}r, Ayberk and Dillenbourg, Pierre}, + publisher={CHILI, EPFL, Switzerland}, + url={http://chili.epfl.ch/software}, + year={2013} + } +``` + +## Contact + +If you need further information about using Chilitags with the NAO robot, contact Bahar Irfan: bahar.irfan (at) plymouth (dot) ac (dot) uk (the most recent contact information is available at [personal website](https://www.baharirfan.com)). diff --git a/README.md b/README.md index 2c750ad..e3cfe35 100644 --- a/README.md +++ b/README.md @@ -154,6 +154,9 @@ in its source code. Specific instructions for building Chilitags for Android can be found under [README-ANDROID.md](README-ANDROID.md). +Specific instructions for building Chilitags for NAO robot can be found under +[README-NAO.md](README-NAO.md), which was developed by B. Irfan and S. Lemaignan. + ### Coding style This repository uses `uncrustify`, a tool that does automatic code formatting based on a predefined configuration defined in `uncrustify.cfg`. diff --git a/naoModule/CMakeLists.txt b/naoModule/CMakeLists.txt new file mode 100755 index 0000000..8188d42 --- /dev/null +++ b/naoModule/CMakeLists.txt @@ -0,0 +1,164 @@ +################################################################################ +# Copyright (c) 2016-present, Bahar Irfan. All rights reserved. # +# # +# This file is part of ChilitagsModule for NAO robot. # +# # +# Please cite the following work if using this work: # +# # +# Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of # +# Plymouth, UK. https://github.com/birfan/chilitags. 2016. # +# # +# Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, # +# S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg. # +# CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. # +# # +# Chilitags is free software: you can redistribute it and/or modify # +# it under the terms of the Lesser GNU General Public License as # +# published by the Free Software Foundation, either version 3 of the # +# License, or (at your option) any later version. # +# # +# Chilitags is distributed in the hope that it will be useful, # +# but WITHOUT ANY WARRANTY; without even the implied warranty of # +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the # +# GNU Lesser General Public License for more details. # +# # +# ChilitagsModule is released under GNU Lesser General Public License v3.0 # +# (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should # +# have received a copy of the GNU Lesser General Public License along with # +# Chilitags. If not, see . # +################################################################################ + +find_package(ALCOMMON REQUIRED) +find_package(ALVISION REQUIRED) +find_package(ALPROXIES REQUIRED) +find_package(ALVALUE REQUIRED) +find_package(ALERROR REQUIRED) + +find_package(QIMESSAGING REQUIRED) +find_package(QITYPE REQUIRED) +find_package(QI REQUIRED) +find_package(QIBUILD REQUIRED) + +find_package(BOOST REQUIRED ) +find_package(BOOST_SYSTEM REQUIRED ) +find_package(BOOST_FILESYSTEM REQUIRED ) + +include_directories(${BOOST_INCLUDE_DIRS} + ${ALCOMMON_INCLUDE_DIRS} + ${ALVISION_INCLUDE_DIRS} + ${ALPROXIES_INCLUDE_DIRS} + ${ALVALUE_INCLUDE_DIRS} + ${ALERROR_INCLUDE_DIRS} +Â ${QI_INCLUDE_DIRS} + ${QIMESSAGING_INCLUDE_DIRS} + ${QITYPE_INCLUDE_DIRS} + ${QIBUILD_INCLUDE_DIRS} + ) + +add_executable( calibrate_nao tagEstimation/camera_calibration_nao.cpp) + +target_link_libraries( calibrate_nao + + ${OpenCV_LIBS} + + ${BOOST_FILESYSTEM_LIBRARIES} + ${BOOST_SYSTEM_LIBRARIES} + + ${ALCOMMON_LIBRARIES} + ${ALVISION_LIBRARIES} + ${ALPROXIES_LIBRARIES} + ${ALVALUE_LIBRARIES} + ${ALERROR_LIBRARIES} + + ${QIMESSAGING_LIBRARIES} + ${QITYPE_LIBRARIES} + ${QI_LIBRARIES} + ) + +install(TARGETS calibrate_nao + + RUNTIME DESTINATION bin + + ) + +# Create an option to make is possible compiling the module +# as a remote executable, or as a local shared library +option(CHILITAGSMODULE_IS_REMOTE +# "module is compiled as a remote module (ON or OFF)" + OFF) + +# Create a list of source files +set(_srcs + chilitagsmodule/chilitagsmodule.cpp + chilitagsmodule/chilitagsmodule.hpp + chilitagsmodule/main.cpp + tagEstimation/estimate3d_nao.cpp + tagEstimation/estimate3d_nao.hpp +) + +if(CHILITAGSMODULE_IS_REMOTE) + # Add a compile flag because code changes a little bit + # when we are compiling an executable + # This will let you use #ifdef HELLOWORLD_IS_REMOTE + # in the C++ code + add_definitions( " -DCHILITAGSMODULE_IS_REMOTE ") + + # Create an executable + add_executable(chilitagsmodule ${_srcs}) +else() + # Create a plugin, that is a shared library, and make + # sure it is built in lib/naoqi, so that the naoqi executable + # can find it later + add_library(chilitagsmodule SHARED ${_srcs}) +endif() + +# Tell CMake that sayhelloworld depends on ALCOMMON and +# ALPROXIES. +# This will set the libraries to link sayhelloworld with, +# the include paths, and so on + +target_link_libraries(chilitagsmodule chilitags chilitags_static) + +target_link_libraries(chilitagsmodule ${OpenCV_LIBS} + + ${ALCOMMON_LIBRARIES} + ${ALPROXIES_LIBRARIES} + ${ALVALUE_LIBRARIES} + ${ALVISION_LIBRARIES} + + ${QI_LIBRARIES} + ${QIBUILD_LIBRARIES} + ) + + +if(CHILITAGSMODULE_IS_REMOTE) + # Add a compile flag because code changes a little bit + # when we are compiling an executable + # This will let you use #ifdef HELLOWORLD_IS_REMOTE + # in the C++ code + install(TARGETS chilitagsmodule + RUNTIME DESTINATION bin + ) +else() + # Create a plugin, that is a shared library, and make + # sure it is built in lib/naoqi, so that the naoqi executable + # can find it later + install(TARGETS chilitagsmodule + LIBRARY DESTINATION lib + ) +endif() + + +# Also create a simple executable capable of creating +# a proxy to the helloworld module +add_executable(testchilitagsmodule chilitagsmodule/testchilitagsmodule.cpp) + +target_link_libraries(testchilitagsmodule ${ALCOMMON_LIBRARIES} + ${ALPROXIES_LIBRARIES} + ${QI_LIBRARIES} + ${QIBUILD_LIBRARIES} + ) + +install(TARGETS testchilitagsmodule + RUNTIME DESTINATION bin + ) diff --git a/naoModule/chilitagsmodule/.DS_Store b/naoModule/chilitagsmodule/.DS_Store new file mode 100644 index 0000000..ca37ca7 Binary files /dev/null and b/naoModule/chilitagsmodule/.DS_Store differ diff --git a/naoModule/chilitagsmodule/chilitagsmodule.cpp b/naoModule/chilitagsmodule/chilitagsmodule.cpp new file mode 100644 index 0000000..712cc21 --- /dev/null +++ b/naoModule/chilitagsmodule/chilitagsmodule.cpp @@ -0,0 +1,168 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This file contains the class for ChilitagsModule (Chilitags for NAO Robot).* +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ + +#include "chilitagsmodule.hpp" +#include +#include +#include +#include +#include + +using namespace AL; + +ChilitagsModule::ChilitagsModule(boost::shared_ptr broker, const std::string& name) : + ALModule(broker, name) +{ + /** Describe the module here. This will appear on the webpage*/ + setModuleDescription("Chilitags module for estimating the 3d position of the tag and the transformation matrix between chili tag and the nao camera."); + + functionName("subscribeCameraRemote", getName(), "Subscribe to the camera remotely by giving IP, port, and camera index."); + addParam("robotIp", "IP of the robot"); + addParam("robotPort", "Port of the robot"); + addParam("cameraIndex", "0 for top camera, 1 for bottom (default)"); + BIND_METHOD(ChilitagsModule::subscribeCameraRemote); + + functionName("subscribeCameraLocal", getName(), "Subscribe to the camera locally (on the robot), by giving camera index."); + addParam("cameraIndex", "0 for top camera, 1 for bottom (default)"); + BIND_METHOD(ChilitagsModule::subscribeCameraLocal); + + functionName("subscribeCameraDefault", getName(), "Subscribe to the bottom camera on the robot."); + BIND_METHOD(ChilitagsModule::subscribeCamera); + + functionName("unsubscribeCamera", getName(), "Unsubscribe from the camera."); + BIND_METHOD(ChilitagsModule::unsubscribeCamera); + + functionName("setCameraResolution640x480", getName(), "Set the camera resolution to 640x480 (optional function, default is 320x240)."); + BIND_METHOD(ChilitagsModule::setCameraResolution640x480); + + functionName("setCameraResolution320x240", getName(), "Set the camera resolution to 320x240 (needed to reset if the resolution has changed)."); + BIND_METHOD(ChilitagsModule::setCameraResolution320x240); + + functionName("setDefaultTagSize", getName(), "Set the default tag size for Chilitags. Default is 30 mm. Call this method (if you need to) before calling estimate functions."); + addParam("tagSize", "The tag size to set for the Chilitags (in mm)"); + BIND_METHOD(ChilitagsModule::setDefaultTagSize); + + functionName("readTagConfiguration", getName(), "Read the configuration of Chilitags from a YAML file. See 'tag_configuration_sample.yml' for an example."); + addParam("configFilename", "Configuration file name for tags"); + BIND_METHOD(ChilitagsModule::readTagConfiguration); + + functionName("resetTagSettings", getName(), "Reset tag settings: tag size is 30 mm and no configuration file is used."); + BIND_METHOD(ChilitagsModule::resetTagSettings); + + functionName("estimatePosGivenTag", getName(), "Get a vector of a 17-element vector corresponding to the transformation matrix between the given chilitag and the nao camera"); + addParam("estimatePosGivenTag", "Give a specific tag to search for"); + BIND_METHOD(ChilitagsModule::estimatePosGivenTag); + + functionName("estimatePosAllTags", getName(), "Get a vector of 17-element vectors corresponding to the transformation matrix between the chilitag and the nao camera for each visible chilitag"); + BIND_METHOD(ChilitagsModule::estimatePosAllTags); + +} + +ChilitagsModule::~ChilitagsModule() { +} +void ChilitagsModule::init() +{ + /** Init is called just after construction. + * + * Here we call sayHello, so that the module does something + * without us having to explicitly call sayHello from somewhere else. + */ +} + +void ChilitagsModule::subscribeCameraRemote(std::string robotIp, int robotPort, int cameraIndex) +{ + ET.subscribeCamera(robotIp, robotPort, cameraIndex); + std::string camType = "bottom"; //cameraIndex = 1 + if(cameraIndex == 0) { + camType = "top"; + } + qiLogInfo("module.example") << "Subscribed "<< camType << " camera at " << robotIp << ":" << robotPort<< std::endl; + +} + +void ChilitagsModule::subscribeCameraLocal(int cameraIndex) +{ + std::string robotIp = "127.0.0.1"; + int robotPort = 9559; + subscribeCameraRemote(robotIp, robotPort, cameraIndex); +} + +void ChilitagsModule::subscribeCamera() +{ + int cameraIndex = 1; //bottom camera + subscribeCameraLocal(cameraIndex); +} + +void ChilitagsModule::setCameraResolution640x480() +{ + ET.setCameraResolution(1); +} + +void ChilitagsModule::setCameraResolution320x240() +{ + ET.setCameraResolution(0); +} + +void ChilitagsModule::unsubscribeCamera() +{ + ET.unsubscribeCamera(); + qiLogInfo("module.example") << "Unsubscribed camera." << std::endl; +} + +void ChilitagsModule::setDefaultTagSize(float tagSize) +{ + ET.setDefaultTagSize(tagSize); +} + +void ChilitagsModule::readTagConfiguration(std::string configFilename) +{ + ET.readTagConfiguration(configFilename); +} + +void ChilitagsModule::resetTagSettings() +{ + ET.resetTagSettings(); +} + +std::vector< std::vector > ChilitagsModule::estimatePosAllTags() +{ + tagsVec.clear(); + ET.estimateTagsNao(false, "", tagsVec); + qiLogInfo("module.example") << "Estimated position of all visible tags." << std::endl; + return tagsVec; +} + +std::vector< std::vector > ChilitagsModule::estimatePosGivenTag(std::string givenTagName) +{ + tagsVec.clear(); + ET.estimateTagsNao(true, givenTagName, tagsVec); + qiLogInfo("module.example") << "Estimated position of tag " << givenTagName << std::endl; + return tagsVec; +} diff --git a/naoModule/chilitagsmodule/chilitagsmodule.hpp b/naoModule/chilitagsmodule/chilitagsmodule.hpp new file mode 100644 index 0000000..24d1a9f --- /dev/null +++ b/naoModule/chilitagsmodule/chilitagsmodule.hpp @@ -0,0 +1,91 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This file contains the class for ChilitagsModule (Chilitags for NAO Robot).* +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ + +#ifndef CHILITAGSMODULE_H +#define CHILITAGSMODULE_H + +#include +#include +#include "../tagEstimation/estimate3d_nao.hpp" + +namespace AL +{ +// This is a forward declaration of AL:ALBroker which +// avoids including in this header +class ALBroker; +} + +/** + * A simple example module that says "Hello world" using + * text to speech, or prints to the log if we can't find TTS + * + * This class inherits AL::ALModule. This allows it to bind methods + * and be run as a remote executable or as a plugin within NAOqi + */ +class ChilitagsModule : public AL::ALModule +{ +private: +EstimateTag ET; +std::vector< std::vector > tagsVec; +public: +ChilitagsModule(boost::shared_ptr pBroker, const std::string& pName); + +virtual ~ChilitagsModule(); + +/** Overloading ALModule::init(). + * This is called right after the module has been loaded + */ +virtual void init(); + +void subscribeCameraRemote(std::string robotIp, int robotPort, int cameraIndex); + +void subscribeCameraLocal(int cameraIndex); + +void subscribeCamera(); + +void unsubscribeCamera(); + +void setCameraResolution640x480(); + +void setCameraResolution320x240(); + +void setDefaultTagSize(float tagSize); + +void readTagConfiguration(std::string configFilename); + +void resetTagSettings(); + +std::vector< std::vector > estimatePosAllTags(); + +std::vector< std::vector > estimatePosGivenTag(std::string givenTagName); + +}; +#endif // CHILITAGSMODULE_H + diff --git a/naoModule/chilitagsmodule/main.cpp b/naoModule/chilitagsmodule/main.cpp new file mode 100644 index 0000000..dcbea18 --- /dev/null +++ b/naoModule/chilitagsmodule/main.cpp @@ -0,0 +1,80 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This is the main file for ChilitagsModule (Chilitags for NAO Robot). * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ + +#ifndef _WIN32 +# include +#endif + +#include +#include +#include +#include "chilitagsmodule.hpp" + +#ifdef CHILITAGSMODULE_IS_REMOTE +# define ALCALL +#else +// when not remote, we're in a dll, so export the entry point +# ifdef _WIN32 +# define ALCALL __declspec(dllexport) +# else +# define ALCALL +# endif +#endif + +extern "C" +{ +ALCALL int _createModule(boost::shared_ptr pBroker) +{ + // init broker with the main broker instance + // from the parent executable + AL::ALBrokerManager::setInstance(pBroker->fBrokerManager.lock()); + AL::ALBrokerManager::getInstance()->addBroker(pBroker); + // create module instances + AL::ALModule::createModule(pBroker, "ChilitagsModule"); + return 0; +} + +ALCALL int _closeModule( ) +{ + return 0; +} +} // extern "C" + + +#ifdef CHILITAGSMODULE_IS_REMOTE +int main(int argc, char *argv[]) +{ + // pointer to createModule + TMainType sig; + sig = &_createModule; + // call main + return ALTools::mainFunction("ChilitagsModule", argc, argv, sig); +} +#endif diff --git a/naoModule/chilitagsmodule/testchilitagsmodule.cpp b/naoModule/chilitagsmodule/testchilitagsmodule.cpp new file mode 100644 index 0000000..8905e69 --- /dev/null +++ b/naoModule/chilitagsmodule/testchilitagsmodule.cpp @@ -0,0 +1,101 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* \file testchilitagsmodule.cpp * +* \brief Test how to call a module from the outside. * +* * +* An example on how to call the example ChilitagsModule module from the * +* outside. * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ + +#include +#include +#include +#include +#include +#include + +int main(int argc, char* argv[]) { + if(argc != 2) + { + std::cerr << "Wrong number of arguments!" << std::endl; + std::cerr << "Usage: testchilitagsmodule NAO_IP" << std::endl; + exit(2); + } + + const std::string robotIP = argv[1]; + int port = 9559; + int camIndex = 0; + float tagSize = 20.f; + std::string configFilename = "tag_configuration_sample.yml"; + + std::vector > givenTag; + + try { + /** Create a generic proxy to "ChilitagsModule" module. + * Arguments for the constructor are + * - name of the module + * - string containing the IP adress of the robot + * - port (default is 9559) + */ + boost::shared_ptr broker = + AL::ALBroker::createBroker("MyBroker", "0.0.0.0", 54500, robotIP, port); + + boost::shared_ptr testProxy + = boost::shared_ptr(new AL::ALProxy(broker, "ChilitagsModule")); + + // testProxy->callVoid("setCameraResolution640x480"); //optional + + // testProxy->callVoid("setCameraResolution320x240"); //default but needed to reset again, if the resolution has changed + + //testProxy->callVoid("subscribeCameraLocal", camIndex); + + testProxy->callVoid("subscribeCameraRemote", robotIP, port, camIndex); + + // testProxy->callVoid("readTagConfiguration", configFilename); + + // testProxy->callVoid("setDefaultTagSize", tagSize); + + // testProxy->callVoid("resetTagSettings"); + + // std::vector> allTags = testProxy->call< std::vector< std::vector > >("estimatePosAllTags"); + + givenTag = testProxy->call< std::vector< std::vector > >("estimatePosGivenTag", std::string("8")); + + testProxy->callVoid("unsubscribeCamera"); + + for (std::vector >::const_iterator i = givenTag.begin(); i != givenTag.end(); ++i) + std::cout << *i << std::endl; + + // for (std::vector>::const_iterator i = allTags.begin(); i != allTags.end(); ++i) + // std::cout << *i << std::endl; + + } + catch (const AL::ALError& e) { + std::cerr << e.what() << std::endl; + } +} diff --git a/naoModule/chilitagsmodule/testchilitagsmodule.py b/naoModule/chilitagsmodule/testchilitagsmodule.py new file mode 100755 index 0000000..cf9393d --- /dev/null +++ b/naoModule/chilitagsmodule/testchilitagsmodule.py @@ -0,0 +1,90 @@ +#!/usr/local/bin/python +""" +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* A sample test file for accessing the ChilitagsModule through Python. * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ +""" + +__version__ = '0.0.1' + +__copyright__ = 'Copyright (c) 2016-present, Bahar Irfan. All rights reserved.' +__author__ = 'Bahar Irfan' +__email__ = 'bahar.irfan@plymouth.ac.uk' + + +import qi + +robotIP = "127.0.0.1" +#robotIP = "192.168.1.115" #IP address of the robot if connecting remotely +port = 9559 +camIndex = 0 # 0: top camera, 1: bottom camera +tagNumber = 8 # tag number to detect +configFilename = "tag_configuration_sample.yml"; + +connectAddress = "tcp://" + robotIP + ":" + str(port) + +qiapp = qi.Application(url=connectAddress) +qiapp.start() +session = qi.Session() +session.connect(connectAddress) +chilitags = session.service("ChilitagsModule") + +#chilitags.setCameraResolution640x480() # comment this line to set the camera resolution to default (320x240) + +#chilitags.setCameraResolution320x240() # default but needed to reset again, if the resolution has changed + +#chilitags.subscribeCameraDefault() # subscribes and starts the bottom camera (camIndex = 1) + +#chilitags.subscribeCameraLocal(camIndex) # comment the line above and uncomment this line to use the top camera instead (camIndex = 0) + +chilitags.subscribeCameraRemote(robotIP, port, camIndex) # comment the line above and uncomment this line to connect to the robot remotely + +chilitags.setDefaultTagSize(20) + +#chilitags.readTagConfiguration(configFilename) + +#chilitags.resetTagSettings() + +givenTag = chilitags.estimatePosGivenTag(str(tagNumber)) # estimate the position of a given tag + +allTags = chilitags.estimatePosAllTags() # estimate the position of all tags + +print("Transformation matrix from given tag " + str(tagNumber)) +for i in range(0, len(givenTag)): + for j in range(0, len(givenTag[i])): + print(givenTag[i][j]) + +print("Transformation matrices for all visible tags") +for i in range(0, len(allTags)): + for j in range(0, len(allTags[i])): + print(allTags[i][j]) + +chilitags.unsubscribeCamera() # unsubscribes the camera (necessary before subscribing again) + +qiapp.stop() diff --git a/naoModule/compiled_files/libchilitags.so b/naoModule/compiled_files/libchilitags.so new file mode 100755 index 0000000..0a351b1 Binary files /dev/null and b/naoModule/compiled_files/libchilitags.so differ diff --git a/naoModule/compiled_files/libchilitags_static.a b/naoModule/compiled_files/libchilitags_static.a new file mode 100755 index 0000000..95d9784 Binary files /dev/null and b/naoModule/compiled_files/libchilitags_static.a differ diff --git a/naoModule/compiled_files/libchilitagsmodule.so b/naoModule/compiled_files/libchilitagsmodule.so new file mode 100755 index 0000000..6655dd0 Binary files /dev/null and b/naoModule/compiled_files/libchilitagsmodule.so differ diff --git a/naoModule/compiled_files/libstdc++.so b/naoModule/compiled_files/libstdc++.so new file mode 100755 index 0000000..ccbebc6 Binary files /dev/null and b/naoModule/compiled_files/libstdc++.so differ diff --git a/naoModule/compiled_files/libstdc++.so.6 b/naoModule/compiled_files/libstdc++.so.6 new file mode 100755 index 0000000..ccbebc6 Binary files /dev/null and b/naoModule/compiled_files/libstdc++.so.6 differ diff --git a/naoModule/compiled_files/libstdc++.so.6.0.21 b/naoModule/compiled_files/libstdc++.so.6.0.21 new file mode 100755 index 0000000..ccbebc6 Binary files /dev/null and b/naoModule/compiled_files/libstdc++.so.6.0.21 differ diff --git a/naoModule/compiled_files/libstdc++.so.6.0.21-gdb.py b/naoModule/compiled_files/libstdc++.so.6.0.21-gdb.py new file mode 100755 index 0000000..6b0cffe --- /dev/null +++ b/naoModule/compiled_files/libstdc++.so.6.0.21-gdb.py @@ -0,0 +1,61 @@ +# -*- python -*- +# Copyright (C) 2009-2015 Free Software Foundation, Inc. + +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +import sys +import gdb +import os +import os.path + +pythondir = '/usr/local/share/gcc-5.3.0/python' +libdir = '/usr/local/lib' + +# This file might be loaded when there is no current objfile. This +# can happen if the user loads it manually. In this case we don't +# update sys.path; instead we just hope the user managed to do that +# beforehand. +if gdb.current_objfile () is not None: + # Update module path. We want to find the relative path from libdir + # to pythondir, and then we want to apply that relative path to the + # directory holding the objfile with which this file is associated. + # This preserves relocatability of the gcc tree. + + # Do a simple normalization that removes duplicate separators. + pythondir = os.path.normpath (pythondir) + libdir = os.path.normpath (libdir) + + prefix = os.path.commonprefix ([libdir, pythondir]) + # In some bizarre configuration we might have found a match in the + # middle of a directory name. + if prefix[-1] != '/': + prefix = os.path.dirname (prefix) + '/' + + # Strip off the prefix. + pythondir = pythondir[len (prefix):] + libdir = libdir[len (prefix):] + + # Compute the ".."s needed to get from libdir to the prefix. + dotdots = ('..' + os.sep) * len (libdir.split (os.sep)) + + objfile = gdb.current_objfile ().filename + dir_ = os.path.join (os.path.dirname (objfile), dotdots, pythondir) + + if not dir_ in sys.path: + sys.path.insert(0, dir_) + +# Call a function as a plain import would not execute body of the included file +# on repeated reloads of this object file. +from libstdcxx.v6 import register_libstdcxx_printers +register_libstdcxx_printers(gdb.current_objfile()) diff --git a/naoModule/compiled_files/testchilitagsmodule b/naoModule/compiled_files/testchilitagsmodule new file mode 100755 index 0000000..a3678a5 Binary files /dev/null and b/naoModule/compiled_files/testchilitagsmodule differ diff --git a/naoModule/compiled_files/testchilitagsmodule.py b/naoModule/compiled_files/testchilitagsmodule.py new file mode 100755 index 0000000..c821283 --- /dev/null +++ b/naoModule/compiled_files/testchilitagsmodule.py @@ -0,0 +1,90 @@ +#!/usr/local/bin/python +""" +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* A sample test file for accessing the ChilitagsModule through Python. * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ +""" + +__version__ = '0.0.1' + +__copyright__ = 'Copyright (c) 2016-present, Bahar Irfan. All rights reserved.' +__author__ = 'Bahar Irfan' +__email__ = 'bahar.irfan@plymouth.ac.uk' + + +import qi + +#robotIP = "127.0.0.1" +robotIP = "192.168.1.115" #IP address of the robot if connecting remotely +port = 9559 +camIndex = 0 # 0: top camera, 1: bottom camera +tagNumber = 8 # tag number to detect +configFilename = "tag_configuration_sample.yml"; + +connectAddress = "tcp://" + robotIP + ":" + str(port) + +qiapp = qi.Application(url=connectAddress) +qiapp.start() +session = qi.Session() +session.connect(connectAddress) +chilitags = session.service("ChilitagsModule") + +#chilitags.setCameraResolution640x480() # comment this line to set the camera resolution to default (320x240) + +#chilitags.setCameraResolution320x240() # default but needed to reset again, if the resolution has changed + +#chilitags.subscribeCameraDefault() # subscribes and starts the bottom camera (camIndex = 1) + +#chilitags.subscribeCameraLocal(camIndex) # comment the line above and uncomment this line to use the top camera instead (camIndex = 0) + +chilitags.subscribeCameraRemote(robotIP, port, camIndex) # comment the line above and uncomment this line to connect to the robot remotely + +chilitags.setDefaultTagSize(20) + +#chilitags.readTagConfiguration(configFilename) + +#chilitags.resetTagSettings() + +givenTag = chilitags.estimatePosGivenTag(str(tagNumber)) # estimate the position of a given tag + +allTags = chilitags.estimatePosAllTags() # estimate the position of all tags + +print("Transformation matrix from given tag " + str(tagNumber)) +for i in range(0, len(givenTag)): + for j in range(0, len(givenTag[i])): + print(givenTag[i][j]) + +print("Transformation matrices for all visible tags") +for i in range(0, len(allTags)): + for j in range(0, len(allTags[i])): + print(allTags[i][j]) + +chilitags.unsubscribeCamera() # unsubscribes the camera (necessary before subscribing again) + +qiapp.stop() diff --git a/naoModule/libnaoqi_files/include/alaudio/alsoundextractor.h b/naoModule/libnaoqi_files/include/alaudio/alsoundextractor.h new file mode 100755 index 0000000..5c36db2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alaudio/alsoundextractor.h @@ -0,0 +1,137 @@ +/** + * @author Alexandre Mazel + * + */ + + +#pragma once +#ifndef _LIBALAUDIO_ALAUDIO_ALSOUNDEXTRACTOR_H_ +#define _LIBALAUDIO_ALAUDIO_ALSOUNDEXTRACTOR_H_ + +#include +#include +#include +#include +#include +#include +#include + +typedef signed short AL_SOUND_FORMAT; // ASSUME: sound data are in 16 bits + +// deprecated +// usable and practical logging system + +#define DESACTIVATE_ALL_DEV_INFO // define me to desactivate all debug or trace info (should be defined on public release version) + +#ifndef DESACTIVATE_ALL_DEV_INFO +# define AL_SOUND_EXTRACTOR_DEBUG_PRINTF(...) if ( getDebugMode() ) { printf(__VA_ARGS__); } +# define AL_SOUND_EXTRACTOR_DEBUG_LOG(onestr) if ( getDebugMode() ) { fLoggerProxy->debug( getName(), std::string( onestr ) ); } +# define AL_SOUND_EXTRACTOR_INFO_LOG(onestr) if ( getDebugMode() ) { fLoggerProxy->info( getName(), std::string( onestr ) ); } +# define AL_SOUND_EXTRACTOR_ERROR_LOG(onestr) if ( getDebugMode() ) { fLoggerProxy->error( getName(), std::string( onestr ) ); } +#else +# define AL_SOUND_EXTRACTOR_DEBUG_PRINTF(...) /* onestr */ +# define AL_SOUND_EXTRACTOR_DEBUG_LOG(onestr) /* onestr */ +# define AL_SOUND_EXTRACTOR_INFO_LOG(onestr) /* onestr */ +# define AL_SOUND_EXTRACTOR_ERROR_LOG(onestr) /* onestr */ +#endif + +namespace AL +{ +class ALProxy; +class ALBroker; + +enum AUDIOCHANNELTYPE +{ + ALLCHANNELS = 0, + LEFTCHANNEL = 1, + RIGHTCHANNEL = 2, + FRONTCHANNEL = 3, + REARCHANNEL = 4, + FIRSTCHANNEL = LEFTCHANNEL, + SECONDCHANNEL= RIGHTCHANNEL, + THIRDCHANNEL = FRONTCHANNEL, + FOURTHCHANNEL= REARCHANNEL +}; + +class ALSoundExtractor: public ALExtractor +{ +public: + ALSoundExtractor( boost::shared_ptr pBroker, std::string pName ); + + virtual ~ALSoundExtractor(); + + virtual std::string version(void) {return "";} + virtual void startDetection(void); + virtual void stopDetection(void); + + /** + * setDebugMode. enable/disable the printing of some debug information + * @param pbSetOrUnset enable the functionality when true + * @deprecated This functionnality is now handled by qi/log + */ + QI_API_DEPRECATED void setDebugMode(const bool &pbSetOrUnset = true) + { + qiLogWarning("audio.alsoundextractor", "The call to setDebugMode() is " + "now deprectated. This functionnality is now handled by qi/log"); + fbDebugMode = pbSetOrUnset; + } + + /** + * getDebugMode. get the status about the printing of some debug information + * @deprecated This functionnality is now handled by qi/log + */ + QI_API_DEPRECATED inline bool getDebugMode(void) + { + qiLogWarning("audio.alsoundextractor", "The call to getDebugMode() is " + "now deprectated. This functionnality is now handled by qi/log"); + return fbDebugMode; + } + + + virtual void process(const int & nbOfChannels, + const int & nbrOfSamplesByChannel, + const AL_SOUND_FORMAT * buffer, + const ALValue & timestamp); + + + QI_API_DEPRECATED virtual void processSound(const int nbOfChannels, + const int nbrOfSamplesByChannel, + const AL_SOUND_FORMAT* buffer); + + QI_API_DEPRECATED virtual void processSoundRemote(const int & nbOfChannels, + const int & nbrOfSamplesByChannel, + const ALValue & buffer); + +private: + void processRemote(const int & nbOfChannels, + const int & nbrOfSamplesByChannel, + const ALValue & timestamp, + const ALValue & buffer); + + void xStartDetection(const int pPeriod, + const float pPrecision) + { + startDetection(); + } + + virtual void xUpdateParameters(const int pPeriod, + const float pPrecision){} + + void xStopDetection(void) + { + stopDetection(); + } + + virtual std::vector getOutputNames(); + +protected: + + bool fIsRunning; + bool fbDebugMode; + boost::shared_ptr audioDevice; + ALValue fNullTimestamp; +}; + +} + +#endif diff --git a/naoModule/libnaoqi_files/include/albehavior/albehavior.h b/naoModule/libnaoqi_files/include/albehavior/albehavior.h new file mode 100755 index 0000000..53f76e8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/albehavior/albehavior.h @@ -0,0 +1,339 @@ +/** +* @author Aldebaran Robotics +* Aldebaran Robotics (c) 2007 All Rights Reserved +*/ + +/** +* The class that implements a Choregraphe box. +* A behavior is an entity that have inputs and outputs. +* So he can be enabled and produce events. +*/ + + +#pragma once + +#ifndef _LIB_ALBEHAVIOR_ALBEHAVIOR_ALBEHAVIOR_H_ +#define _LIB_ALBEHAVIOR_ALBEHAVIOR_ALBEHAVIOR_H_ + +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALMemoryProxy; + class ALResourceManagerProxy; + class ALProxy; + class ALMutexRW; + class ALOwner; + class ALTimeline; + + struct Parameter + { + ::AL::ALValue value; + bool inheritFromParent; + + Parameter() : inheritFromParent(false) {} + Parameter(const ::AL::ALValue& pValue, bool pInheritFromParent): value(pValue), + inheritFromParent(pInheritFromParent) {} + }; + + class ALBehavior: public ALModuleCore + { + protected: + + // + // ALBehavior type definition + // + + struct IO + { + // a link/input/output class. + // It stores the name of the IO, and the type. + + IO(const std::string & pName, bool pIsBang) : fName(pName), + fIsBang(pIsBang) + { + // NOTHING + } + + bool operator<(const ::AL::ALBehavior::IO& io) const {return fName < io.fName;} + + const std::string fName; + const bool fIsBang; // always false for inputs ! + }; + + typedef ::AL::ALBehavior::IO TInput; + typedef ::AL::ALBehavior::IO TOutput; + + /** + * for each input, keep a list of ALMemory's value to which + * the input is subscribed. + */ + typedef std::list TListValues; + typedef TListValues::iterator ITListValues; + typedef TListValues::const_iterator CITListValues; + + typedef std::map TInputMap; + typedef TInputMap::iterator ITInputMap; + typedef TInputMap::const_iterator CITInputMap; + + typedef std::map TOutputMap; + typedef TOutputMap::iterator ITOutputMap; + typedef TOutputMap::const_iterator CITOutputMap; + + typedef std::map TParameterMap; + typedef TParameterMap::iterator ITParameterMap; + typedef TParameterMap::const_iterator CITParameterMap; + + typedef std::vector TParameterVec; + typedef TParameterVec::const_iterator CITParameterVec; + + // do something a little different, as parameters are a lot less often subscribed to anything ! + // and it's easier to manipulate std::string for parameters, in order to use ALBehavior API. + typedef std::map TParameterSubscriptionMap; + typedef TParameterSubscriptionMap::iterator ITParameterSubscriptionMap; + typedef TParameterSubscriptionMap::const_iterator CITParameterSubscriptionMap; + + // + // ALBehavior method definition + // + + public : + + /* + * Creates an ALModule. An ALModule has a name. + * @param pName the behavior name + */ + ALBehavior(boost::shared_ptr pBroker, const std::string& pName); + + virtual ~ALBehavior(); + + + /** + * Wait a resource + * @param pList: resource name list + * @param pCallback: callback if loose resource + * @param pTimeout: timeout if wait resource + * @param pOwnerType (unused) + */ + void waitFor(const std::vector& pList , const char *pCallback , int pTimeout, int pOwnerType); + + /** + * Wait a resource + * @param pCallback: callback if loose resource + */ + void acquireResources(); + + /** + * Wait his resource but never take resource to someone else + */ + void waitResourceFree(); + + /** + * setResources + * @param pList: resource name list to store + */ + void setResources(const std::vector& pList, const int &pTimeout); + + /** + * isResourceFree + * @param pList: resource name list + * @return true if box resources free + */ + bool isResourceFree(const std::vector& pList); + + /** + * releaseResource Release box resources + + */ + void releaseResource(); + + virtual void init(); + + /** + * Will enable or disable a behavior. DEPRECATED since 1.14 + * When switching from one state to another, all the subscription will be done/undone. + */ + void setEnabled(const bool& pEnabled); + + /** + * return true if state is ENABLED, false otherwise. DEPRECATED since 1.14 + */ + bool isEnabled(); + + /** + * DEPRECATED since 1.14 + */ + void setParameters(const ALValue& pValue); + void addOutputLink( const std::string & pOutputName, const std::string & pALMemoryValueName ); + void removeOutputLink(const std::string & pOutputName, const std::string & pALMemoryValueName); + + /** + * A behavior can have a parent (hierarchy in Choregraphe !) + * Using a string (name) instead of a pointer as we can come from Python ! + */ + void setParentFromName(const std::string& p); + + /** + * Returns the input/ouput names ! + */ + std::vector getInputNames(); + std::vector getOutputNames(); + + /** + * addInput. Add a new input to this behavior + * @param pInputName input name ! + * @return true if input added (false if an in put with the same name already exists + */ + bool addInput(const std::string & pInputName); + + /** + * addOutput. Add a new output to this behavior + * @param pOutputName output name ! + * @param pbIsBang is it a bang type ? + * @return true if input added (false if an in put with the same name already exists + */ + bool addOutput(const std::string & pOutputName, bool pIsBang); + + /** + * addParameter. Add a new parameter to this behavior + * @param pParameterName parameter name ! + * @param pValue value of parameter + * @param pInheritFromParent do we want to inherit from parent + */ + void addParameter(const std::string & pParameterName, const ::AL::ALValue& pValue, const bool& pInheritFromParent); + + /** + * Returns current value of a given parameter. + * Throw an exception if parameter does not exist. + * Method is bound, and thus cannot be const :-( + */ + ALValue getParameter(const std::string& pParameterName); + + /** + * Returns the list of parameters. + */ + std::vector getParametersList(); + + /** + * Returns true if box has a parameter of this name, false otherwise. + */ + bool hasParameter(const std::string& pParameterName); + + /** + * Set a given parameter to a new value. + * Throw an exception if parameter does not exist. + */ + void setParameter(const std::string& pParameterName, const ::AL::ALValue& pValue); + + /** + * connectInput. Add a connection between an ALMemory value and one input, it's a kind of trigger for this behavior: when a value in ALMemory change, the value is send to an input of this behavior. + * @param pInputName name of an input + * @param pALMemoryValueName name of the ALMemory that will + * throw an exception if something goes wrong + */ + void _connectInput(const std::string & pInputName, + const std::string & pALMemoryValueName, const bool& enabled); + + /** + * connectParameter. Add a connection between an ALMemory value and one parameter. + * Any change to given value will update parameter accordingly. + * @param pParameterName name of a parameter + * @param pALMemoryValueName name of the ALMemory that will + * throw an exception if something goes wrong + */ + void _connectParameter(const std::string & pParameterName, + const std::string & pALMemoryValueName, const bool& enabled); + + /** + * connectOutput. Add a link between an inner value and an output. + * Whenever the value changed, the matching output is stimulated. + * @param pOutputName name of an output + * @param pALMemoryValueName name of the ALMemory that will be removed + * throw an exception if something goes wrong + */ + void _connectOutput(const std::string & pOutputName, + const std::string & pALMemoryValueName, const bool& enabled); + + /** + * stimulateIP. stimulate the output of a box or the input of the diagram + * @param ioName + * @param p data + * throw an exception if something goes wrong + */ + void stimulateIO(const std::string& ioName, const AL::ALValue& p); + + /** + * dataChanged. Called by stm when subcription + * has been modified. + * @param pDataName Name of the modified data + * @param pValue Name of the modified data + * @param pMessage Name of the modified data + */ + virtual void dataChanged(const std::string& pDataName, + const ::AL::ALValue& pValue, + const std::string& pMessage); + + virtual std::string httpGet(); + + virtual void httpPut(const std::string& pValue); + + void setTimeline(const boost::shared_ptr timeline); + boost::shared_ptr getTimeline(); + void setParentTimeline(const boost::shared_ptr timeline); + boost::shared_ptr getParentTimeline(); + + // + // ALBehavior attribut definition + // + + private: + boost::weak_ptr fParent; + std::string fParentName; + boost::weak_ptr fOwner; + + protected: + boost::shared_ptr fStm; + boost::shared_ptr fResourceMnger; + boost::shared_ptr fToMe; + boost::shared_ptr fTimeline; + boost::weak_ptr fParentTimeline; + + // list of inputs & mutex + TInputMap fInputList; + boost::shared_ptr fInputListMutex; + // same for outputs + TOutputMap fOutputList; + boost::shared_ptr fOutputListMutex; + // params + TParameterMap fParametersMap; + boost::shared_ptr fParametersMapMutex; + TParameterVec fParametersInStm; + + // params subscription, separately + TParameterSubscriptionMap fParametersSubsMap; + boost::shared_ptr fParametersSubsMapMutex; + + // true if someone asked to release resources + //bool fReleaseAsked; + + // box resource list + std::vector fResourceNameList; + // box resource timeout + int fTimeoutResource; + + // a string that can hold any data and that will be served on the behavior web page + std::string fHttpData; + + bool fIsEnabled; + + public: + static bool fDeprecationWarning; + }; + +} // namespace AL + +#endif // _LIB_ALBEHAVIOR_ALBEHAVIOR_ALBEHAVIOR_H_ + diff --git a/naoModule/libnaoqi_files/include/albehavior/altimeline.h b/naoModule/libnaoqi_files/include/albehavior/altimeline.h new file mode 100755 index 0000000..3626292 --- /dev/null +++ b/naoModule/libnaoqi_files/include/albehavior/altimeline.h @@ -0,0 +1,55 @@ +/** +* @author Aldebaran Robotics +* Aldebaran Robotics (c) 2012 All Rights Reserved +*/ + +#pragma once + +#ifndef _LIB_ALBEHAVIOR_ALTIMELINE_ALBOX_H_ +#define _LIB_ALBEHAVIOR_ALTIMELINE_ALBOX_H_ + +namespace AL +{ + + class ALTimeline + { + public : + + ALTimeline(){} + virtual ~ALTimeline(){} + + /** + * play.\n + * Read a timeline from the current buffer till the end.\n + */ + virtual void play(void) = 0; + + /** + * pause.\n + * Pause the reading a timeline at the current frame.\n + */ + virtual void pause(void) = 0; + + + /** + * stop.\n + * Stop reading a timeline.\n + */ + virtual void stop(void) = 0; + + /** + * goTo.\n + * goTo moving time cursor.\n + */ + virtual void goTo(const int &pFrame) = 0; + virtual void goTo(const std::string &pFrameName) = 0; + + virtual int getSize() const = 0; + virtual int getFPS() const = 0; + virtual void setFPS(const int fps) = 0; + }; + +} // namespace AL + +#endif // _LIB_ALBEHAVIOR_ALTIMELINE_ALBOX_H_ + diff --git a/naoModule/libnaoqi_files/include/alcommon/albroker.h b/naoModule/libnaoqi_files/include/alcommon/albroker.h new file mode 100755 index 0000000..9ccbb70 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/albroker.h @@ -0,0 +1,325 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2011, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALBROKER_H_ +#define _LIBALCOMMON_ALCOMMON_ALBROKER_H_ + +# include +# include + +# include +# include +# include + +# include +# include +# include + +//needed because templated code initialize an ALProxy in this file +# include + +# include +# include + +# define BROKERMASK_KEEPALIVE 1 /**< No exit() if connection lost. */ +# define BROKERMASK_LIGHT 2 /**< No thread pool. */ +# define BROKERMASK_NOSERVER 4 /**< No server. */ +# define BROKERMASK_NOHEARTBEAT 8 /**< No nohearbeat. */ +# define BROKERMASK_WITHALNETWORK 16 /**< With ALNetwork. */ + +namespace AL +{ + class ALTask; + class ALModuleCore; + class ALBrokerManager; + class ALBrokerInfo; + + /** + * \class ALBroker albroker.h "alcommon/albroker.h" + * \brief ALBroker serves methods advertised by connected modules + * to clients participating in the network. All executables create at least + * one broker in main.cpp. A broker will wait for http request, remote C++ + * request from PC application... + * + * Brokers can be connected to each other to form a tree where each + * broker has parent broker until the base of the tree. Typically + * there is one broker for each process and any number of attached + * modules, each with any number of advertised methods. + * + * Brokers transparently handle directory services so that clients + * need not know if the module that provides a service is in the + * same process, on the same machine, or on the same tcp network. + * + * Within the same process, direct method calls are used to + * provide optimal speed without having to change your method + * signatures. + * + * Remote communication is currently handled by SOAP + * + * In most practical usage, you will never need to explicitly + * create a broker. The main NAOqi process has one, and module + * that is compiled as 'remote' and that uses ALToolsMain, will + * create a broker for you if required. + * \ingroup Broker + */ + + class ALBrokerPrivate; + class ALBroker : public ::boost::enable_shared_from_this, public ::boost::noncopyable + { + public: + /** + * \typedef Ptr + * \brief Shared pointer to ALBroker + * \deprecated Use boost::shared_ptr instead + */ + typedef boost::shared_ptr Ptr; + /** + * \typedef WeakPtr + * \brief Weak pointer to ALBroker + * \deprecated Use boost::weak_ptr instead + */ + typedef boost::weak_ptr WeakPtr; + + /** + * \brief Getter to this. + * \return A pointer to this + */ + boost::shared_ptr getThis(); + /** + * \brief Getter to this. + * \return A const pointer to this + */ + boost::shared_ptr getThis() const; + + /** + * \brief Default Constructor. + */ + ALBroker(); + + /** + * \brief Destructor. + */ + virtual ~ALBroker(void); + + /** + * \brief Sets the brokerManager instance. + * \param pBrokerManager A pointer to the broker manager. + */ + void setBrokerManagerInstance(boost::shared_ptr pBrokerManager); + + /** + * \brief Another way to get module by name. + * \param pModuleName name of the module + * \return A pointer to the module. + */ + boost::shared_ptr getModuleByName(const std::string &pModuleName); + + /** + * \brief Called when a module, belonging to this broker, quits. + * + * References to the module (proxies, subscriptions to ALMemory, ...) + * will be deleted + * \param pModuleName name of the module exiting + * \return 0 on success + */ + int unregisterModule(const std::string &pModuleName); + + /** + * \brief Call to know if a module is present. + * @param pModuleName name of the module to search + * @return true if the module is local or + * if the module is present in a broker connected. + */ + bool isModulePresent(const std::string &pModuleName); + + /** + * \brief Return the registered module list. + * \param pModuleList list of module information + * \return 0 on success + */ + int getModuleList(boost::shared_ptr > pModuleList); + + /** + * \brief Return the list of registered Brokers. + * \param pBrokerList [out] list of Broker information + * \return 0 on success + */ + int getBrokerList(std::vector &pBrokerList); + + /** + * \brief Return the registered module list in every broker (global). + * \param pModuleList list of module information + * \return 0 on success + */ + int getGlobalModuleList(boost::shared_ptr > pModuleList); + + + /** + * \brief Check if the application is existing. + * \return true if application is exiting, false otherwise. + */ + bool isExiting() const; + + /** + * \brief Return whether the broker is connected or not + * \return true if connected + */ + bool isConnected(); + + /** + * \brief shutdown, close all modules and send exit command to child broker. + * \return 0 on succes + */ + int shutdown(); + + /** + * \brief Get the name of the broker + * \return A string containing the module name. + */ + std::string getName() const; + + /** + * \brief Get the IP address of the broker + * \return A string containing the broker IP. + */ + std::string getIP() const; + + /** + * \brief fBorkerPort getter. + * \return A integer contain broker port. + */ + int getPort() const; + + /** + * \brief Return the parent IP if any + */ + std::string getParentIP() const; + + /** + * \brief Return the parent Port if any + */ + int getParentPort() const; + + /** + * \brief Get an existing proxy if it exists, create a proxy with option otherwise. + * \param pProxyName proxy's name + * \param[in] deprecated deprecated option for the new proxy. + * \return ALProxy. + */ + boost::shared_ptr getProxy(const std::string &pProxyName, int deprecated = 0); + + /** + * \brief Call for http get request on server. + * \param pPath The path requested by the sender + * \return http address. + */ + std::string httpGet(const std::string &pPath); + + + template + boost::shared_ptr getSpecialisedProxy(const std::string &name = std::string()) { + //if (name.empty()) + //return boost::shared_ptr(new T(getThis())); + //else + return boost::shared_ptr(new T(getProxy(name))); + } + + /** + * \brief deprecated + * + * Get pointer to memory. + * \return Memory Proxy + * \deprecated + */ + #define getMemoryProxy() getSpecialisedProxy("ALMemory") + + /** + * \brief deprecated + * + * Get pointer to leds. + * \return Leds Proxy + * \deprecated + */ + #define getLedsProxy() getSpecialisedProxy("ALLeds") + + /** + * \brief deprecated + * + * Get pointer to logger. + * \return Logger Proxy + * \deprecated + */ + #define getLoggerProxy() getSpecialisedProxy("ALLogger") + + /** + * \brief deprecated + * + * Get pointer to motion. + * \return Motion Proxy + * \deprecated + */ + #define getMotionProxy() getSpecialisedProxy("ALMotion") + + /** + * \brief deprecated + * + * Get pointer to preferences. + * \return Preferences Proxy + * \deprecated + */ + #define getPreferencesProxy() getSpecialisedProxy("ALPreferences") + + /** + * \brief deprecated + * + * Get pointer to DCM. + * \return Dcm Proxy + * \deprecated + */ + #define getDcmProxy() getSpecialisedProxy("DCM") + + + /** + * \brief CreateBroker helps to broker creation + * \param pName broker name + * \param pIP broker IP + * \param pPort broker port + * \param pParentIP parent broker IP + * \param pParentPort parent broker port + * \param pKeepAlive true => broker will not be destroyed if parent broker is destroyed + * \param pPath deprecated, do not use, will have no effect + * \param pLoadLib boolean to know if the module is loaded + * \return pointer on broker + */ + static boost::shared_ptr createBroker(const std::string &pName, + const std::string &pIP, + int pPort, + const std::string &pParentIP, + int pParentPort, + int pKeepAlive = 0, + std::string pPath = "", + bool pLoadLib = true); + + qi::SessionPtr session(); + public: + /** for compat only, useless */ + boost::weak_ptr fBrokerManager; + + /** Private implementation of ALBroker. */ + ALBrokerPrivate *_p; + + }; + + typedef boost::shared_ptr ALBrokerPtr; + +} // !namespace AL + + +#endif // _LIBALCOMMON_ALCOMMON_ALBROKER_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/albrokermanager.h b/naoModule/libnaoqi_files/include/alcommon/albrokermanager.h new file mode 100755 index 0000000..393be4d --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/albrokermanager.h @@ -0,0 +1,154 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALBROKERMANAGER_H_ +#define _LIBALCOMMON_ALCOMMON_ALBROKERMANAGER_H_ + +# include +# include +# include + +# define MAXBROKER 10 /**< Broker's max number */ + +namespace AL +{ + class ALBroker; + class ALBrokerManagerPrivate; + + /** + * \class ALBrokerManager albrokermanager.h "alcommon/albrokermanager.h" + * \brief ALBrokerManager is a class to manage brokers. + * + * It should be only singleton with various main pointer. + * \ingroup Broker + */ + class ALBrokerManager + { + protected: + /** \brief Constructor. */ + ALBrokerManager(); + ALBrokerManager(const ALBrokerManager &); + ALBrokerManager &operator=(const ALBrokerManager &); + public: + /** \brief Destructor. */ + virtual ~ALBrokerManager(); + + /** + * \brief Add a Broker in the map of broker. + * + * Add a broker to the map if it do not already exist. + * \param pBroker pointer to a broker + */ + void addBroker(boost::shared_ptr pBroker); + + /** + * \brief Remove a broker from the map of broker. + * \warning It will also shutdown the broker. + * \param pBroker pointer to a broker + */ + void removeBroker(boost::shared_ptr pBroker); + + /** + * \brief Remove a broker from the map of broker. + * + * It won't shutdown of the broker + * \param pBroker pointer to a broker + */ + void removeFromList(boost::shared_ptr pBroker); + + /** + * \brief Get the suitable broker. + * + * \param brokerName name of wanted broker + */ + boost::shared_ptr getBrokerByName(const std::string &brokerName); + + /** + * \brief Get the first broker in the list. + * \return A pointer to a broker, throw if broker's list is empty + * \throw ALERROR + */ + boost::shared_ptr getRandomBroker(void); + + /** + * \brief Get a broker from index. + * \param i index to the broker + * \return A pointer to the broker. + */ + boost::shared_ptr getBroker(int i); + + /** + * \brief Get a broker from IP and port address. + * \param strEndPoint broker's address, format "127.0.0.1:5559/" + * \return A pointer to the broker if we find it, + * a pointer to the first borker in the list otherwise. + */ + boost::shared_ptr getBrokerByIPPort(const std::string &strEndPoint); + + + /** + * \brief Get a broker by port address. + * \param strIP broker's IP (unused) + * \param pPort broker's port + * \return A pointer to the broker if we find it, + * a pointer to the first borker in the list otherwise. + */ + boost::shared_ptr getBrokerByIPPort(const std::string &strIP, + int pPort); + + /** + * \brief Get a broker by parent's broker port. + * \param strIP broker's IP (unused) + * \param pPort parent's port the broker + * \return A pointer to the broker, boost::shared_ptr() otherwise + */ + boost::shared_ptr getBrokerByParentIPPort(const std::string &strIP, int pPort); + + /** + * \brief Remove and shutdown all brokers. + * \warning Program should not work any more after that. + */ + void killAllBroker(void); + + /** + * \brief Create a empty broker. + * \return A pointer to a Broker + */ + boost::shared_ptr getReservedBroker(void); + + /** + * \brief Get the ALBrokerManager singleton. + * \return A poitner to the instance of the ALBrokerManager + */ + static boost::shared_ptr getInstance(); + + /** + * \brief Set the ALBrokerManager singleton. + * \warning It will kill the old singleton to replace it by the new one + * \param pSingleton A pointer to a new ALBrokerManager + * \return A poitner to the new instance of the ALBrokerManager + */ + static boost::shared_ptr setInstance(boost::shared_ptr pSingleton); + + /** + * \brief Reset the ALBrokerManager singleton + */ + static void kill(); + + private: + /** ALBrokerManager singleton. */ + static boost::shared_ptr *_singleton; + + public: + /** A pointer to the private implementation of ALBrokerManager. */ + ALBrokerManagerPrivate *_p; + }; +} // !namespace AL +#endif // _LIBALCOMMON_ALCOMMON_ALBROKERMANAGER_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/alfunctor.h b/naoModule/libnaoqi_files/include/alcommon/alfunctor.h new file mode 100755 index 0000000..2e15cbc --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/alfunctor.h @@ -0,0 +1,131 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALFUNCTOR_H_ +#define _LIBALCOMMON_ALCOMMON_ALFUNCTOR_H_ + +# include +# include +# include +# include +# include + +/// \ingroup Functor +namespace AL +{ + /** + * \typedef ALVoid + * \brief Type def to void. + * \ingroup Functor + */ + typedef void ALVoid; + + /** + * \class ALFunctorBase alfunctor.h "alcommon/alfunctor.h" + * \brief ALFunctorBase is a generic functor class for pointer management. + * \ingroup Functor + */ + class ALFunctorBase + { + public: + ALFunctorBase() + { + } + + ALFunctorBase(qi::AnyFunction metaFun) + : _functor(metaFun) + { + } + + void reset(){ + _functor = qi::AnyFunction(); + } + + qi::AnyFunction genericFunction() { + return _functor; + } + + qi::Signature signature() const + { + //drop the first arg + return _functor.parametersSignature(true); + } + + qi::Signature sigreturn() const + { + return _functor.returnSignature(); + } + + /** + * \brief Generic call to a bound module's method. + * \param pParams input parameter + * \param pResult output result + */ + virtual void call(const ALValue& pParams, ALValue& pResult) { + qiLogError("alcommon.ALFunctor") << "ALFunctor::call not implemented"; + //TODO: NOT IMPLEMENTED + }; + + /** \brief Destructor. */ + virtual ~ALFunctorBase() { + //delete _functor; + } + + qi::AnyFunction _functor; + }; + +} + +namespace AL { + + template + boost::shared_ptr createFunctor(C* obj, F fun) + { + return boost::shared_ptr(new ALFunctorBase( + qi::AnyFunction::from(fun, obj).dropFirstArgument())); + } + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) ()) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &, const P2 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &, const P2 &, const P3 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &, const P2 &, const P3 &, const P4 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &, const P2 &, const P3 &, const P4 &, const P5 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + + template + boost::shared_ptr createFunctor(C *obj, R (C::*f) (const P1 &, const P2 &, const P3 &, const P4 &, const P5 &, const P6 &)) { + return boost::shared_ptr(new ALFunctorBase(qi::AnyFunction::from(f, obj).dropFirstArgument())); + } + +} + +#endif // _LIBALCOMMON_ALCOMMON_ALFUNCTOR_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/almethodinfo.h b/naoModule/libnaoqi_files/include/alcommon/almethodinfo.h new file mode 100755 index 0000000..3207630 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/almethodinfo.h @@ -0,0 +1,200 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALMETHODINFO_H_ +#define _LIBALCOMMON_ALCOMMON_ALMETHODINFO_H_ + +# include +# include + + +# define BLOCKINGFUNCTION 0 /**< Functions are synchronous */ +# define ASYNCHRONOUSFUNCTION 1 /**< Functions are asynchronous */ + +namespace AL +{ + class ALFunctorBase; + + /** + * \class ALMethodInfo almethodinfo.h "alcommon/almethodinfo.h" + * \brief ALMethodInfo is the introspection container. + * + * We store method description, return type, argument list, examples... + * \ingroup Proxy + * \ingroup Module + */ + class ALMethodInfo + { + public: + /** \brief Default constructor. */ + ALMethodInfo() { + mask = 0; + } + + /** \brief Default destructor. */ + virtual ~ALMethodInfo() {} + + /** + * \enum methodOption + * \brief methodOption is differents option for the method. + */ + enum methodOption { + CPPMethod = 1, /**< C++ method. */ + AsynchronousMethod = 2, /**< Asynchronous method. */ + localMethod = 4 /**< Local method. */ + }; + + /** + * \class ALParameterInfo almethodinfo.h "alcommon/almethodinfo.h" + * \brief ALParameterInfo is the introspection container. + */ + class ALParameterInfo + { + public: + std::string paramError; /**< */ + std::string name; /**< Parameter's name. */ + std::string description; /**< Parameter's description. */ + std::string strType; /**< Parameter's type name. */ + bool optional; /**< True if it is an optional parameter. */ + }; + + /** + * \class ALParameterInfoOptional almethodinfo.h "alcommon/almethodinfo.h" + * \brief ALParameterInfoOptional is the option container. + */ + template + class ALParameterInfoOptional: public ALParameterInfo { + public: + /** + * \brief Default contructor. + * \param defaultValue new optional paramater + */ + ALParameterInfoOptional(T defaultValue) { + m_defaultValue = defaultValue; + } + T m_defaultValue; /**< Optional parameter. */ + }; + + /** + * \class ALExample almethodinfo.h "alcommon/almethodinfo.h" + * \brief ALExample is container for example. + */ + class ALExample { + public: + std::string language; /**< Example's language. */ + std::string strExample; /**< Example. */ + }; + + std::string moduleName; /**< Module name. */ + std::string methodName; /**< Method name. */ + std::string methodDescription; /**< Method description. */ + std::vector parameters; /**< Method parameters. */ + std::string returnValue; /**< Method return value. */ + std::vector examples; /**< Method example. */ + boost::shared_ptr ptrOnMethod; /**< Pointer on the mehotd. */ + ALParameterInfo returnInfo; /**< Info about the return */ + short mask; /**< Method options. */ + + + /** + * \brief Check is the method is used for C++. + * \return true if it's a C++ the method, flase otherwise + */ + bool isCpp(void) { + return ((mask & CPPMethod) == CPPMethod); + } + + /** + * \brief Check is the method is used as asynchronous one. + * \return true if it's a asynchronous method, flase otherwise + */ + bool isAsynchronous(void) { + return (mask & AsynchronousMethod) > 0 ? true: false; + } + + /** + * \brief Check is the method is a local one. + * \return true if it's a local method, flase otherwise + */ + bool isLocalMethod(void) { + return ((mask & localMethod) == localMethod); + } + + /** + * \brief Add method option. + * \param pOption new option + */ + void addOption(int pOption) + { + mask = mask | (short)pOption; + } + + /** + * \brief Get a pointer to the method. + * \return a pointer to the method + */ + ALFunctorBase* getFunction() { + return ptrOnMethod.get(); + } + + /** + * \brief Clear parameters and examples. + */ + void clear(void) { + parameters.clear(); + examples.clear(); + } + }; + + template + void completeAndCheck(R(C::*) (), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1, P2), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1, P2, P3), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1, P2, P3, P4), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1, P2, P3, P4, P5), ALMethodInfo & pDesc) + { + //useless + } + + template + void completeAndCheck(R(C::*) (P1, P2, P3, P4, P5, P6), ALMethodInfo & pDesc) + { + //useless + } + +} +#endif // _LIBALCOMMON_ALCOMMON_ALMETHODINFO_H_ + diff --git a/naoModule/libnaoqi_files/include/alcommon/almodule.h b/naoModule/libnaoqi_files/include/alcommon/almodule.h new file mode 100755 index 0000000..ff3da9e --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/almodule.h @@ -0,0 +1,258 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALMODULE_H_ +#define _LIBALCOMMON_ALCOMMON_ALMODULE_H_ + +# include +# include +# include +# include + +/// \brief NAOqi +namespace AL +{ + class ALBroker; + class ALProxy; + class ALValue; + + + namespace detail + { + class ALProcessSignals + { + public: + ALProcessSignals() {} + virtual ~ALProcessSignals() {} + + typedef boost::signal ProcessSignal; + typedef boost::signal::slot_function_type ProcessSignalSlot; + typedef boost::signals::connect_position ProcessSignalPosition; + typedef boost::signals::connection ProcessSignalConnection; + + /** + * Connect to the preProcess signal + */ + inline ProcessSignalConnection atPreProcess( + ProcessSignalSlot subscriber, + ProcessSignalPosition pos = boost::signals::at_back) + { + return fPreProcess.connect(subscriber, pos); + } + + /// Connect to the postProcess signal + inline ProcessSignalConnection atPostProcess( + ProcessSignalSlot subscriber, + ProcessSignalPosition pos = boost::signals::at_back) + { + return fPostProcess.connect(subscriber, pos); + } + + inline void removeAllPreProcess(void) { + fPreProcess.disconnect_all_slots(); + } + + inline void removeAllPostProcess(void) { + fPostProcess.disconnect_all_slots(); + } + + /// Trigger methods attached to preProcess + inline void preProcess(void) { + fPreProcess(); + } + + /// Trigger methods attached to postProcess + inline void postProcess(void) { + fPostProcess(); + } + + protected: + ProcessSignal fPreProcess; + ProcessSignal fPostProcess; + }; + } + + + /** + * \class ALModule almodule.h "alcommon/almodule.h" + * \brief ALModule can be used as a base class for user modules to + * help serve and advertise their methods. + * + * Each module advertises the methods that it wishes to make available + * to clients participating in the network to a broker within the + * same process. + * + * The broker then transparently handles directory services so that clients + * need not know if the module that provides a service is in the + * same process, on the same machine, or on the same tcp network. + * + * Within the same process, direct method calls are used to + * provide optimal speed without having to change your method + * signatures. + * + * Clients exist in a growing number of languages including c++, + * Python, .Net, Java and Matlab. + * + * \ingroup Module + */ + class ALModule: public ALModuleCore, public detail::ALProcessSignals + { + friend class baseModule; + + public: + /** + * \brief Create a module and link it to a broker. + * \param pBroker Pointer to the broker + * \return A pointer to the module + * \throw ALError + */ + template + static boost::shared_ptr createModule(boost::shared_ptr pBroker) + { + boost::shared_ptr module(new T(pBroker)); + module->initModule(); + try + { + // we call init on a ALModule::Ptr as init may be protected + // init is a virtual method that can be reimplemented + (boost::static_pointer_cast(module))->init(); + } + catch(const ALError& e) + { + module->exit(); + throw(e); + } + return module; + } + + /** + * \brief Create a module and link it to a broker. + * \param pBroker Pointer to the broker + * \param p1 first parameter after pBroker for the module's constructor + * \return A pointer to the module + * \throw ALError + */ + template + static boost::shared_ptr createModule(boost::shared_ptr pBroker, P1 p1) + { + boost::shared_ptr module(new T(pBroker, p1)); + module->initModule(); + try + { + // we call init on a ALModule::Ptr as init may be protected + // init is a virtual method that can be reimplemented + (boost::static_pointer_cast(module))->init(); + } + catch(const ALError& e) + { + module->exit(); + throw(e); + } + return module; + } + + /** + * \brief Creates an ALModule. + * + * An ALModule has a name, and is registered in a broker, + * so that its methods can be called by other modules, + * via a proxy constructed with module's name. + * \param pBroker Pointer to a broker + * \param pName The name for the new module. This is used as the + * prefix for all method calls e.g. MyModule.myMethod() + */ + ALModule(boost::shared_ptr pBroker, const std::string& pName); + + /** \brief Destructor */ + virtual ~ALModule(); + + /** + * \brief Called by the broker webpage to detail the module. + * This can be overriden to provide information specific to + * your module. The default is an empty page. + * \return "" + */ + virtual std::string httpGet(); + + /** + * \brief Stops a module's method using the ID given returned + * by a 'post' call. Module authors are encouraged to implement + * this if they have long running methods that they wish to + * allow users to interrupt. + * + * \warning Module has to overload stop method + * or an exception will be raised. + * \param taskId The id of the method that was returned by 'post' + */ + virtual void stop(const int &taskId); + + /** + * \brief Check if the user call stop. + * \param taskId The id of the method that was returned by 'post' + * \return true if used call stop, false otherwise + */ + bool isStopRequired(const int &taskId = -1); + + /** + * \brief Waits until the end of a long running method using the ID that was + returned from a method started with 'post' + * \param taskId The id of the method that was returned by 'post' + * \param timeout The wait timeout period in ms. If 0 wait indefinately. + * \return true if the timeout period expired, false otherwise + */ + bool wait(const int &taskId, const int &timeout); + + /** + * \brief Determines if the method created with a 'post' is still running. + * \param taskId The id of the method that was returned by 'post' + * \return true if the method is still running, false otherwise + */ + bool isRunning(const int &taskId); + + /** + * \brief Return unique ID if method call. + * + * Useful to check for instance if user asked your method to stop. + * First get ID with getMethodID, then call isRequireStop + * \return Method's ID + */ + int getMethodID(void); + + /** + * \brief Check if the module is pcalled. + * \return true if pcalled, false otherwise + */ + bool isPCalled(); + + + /** + * \brief Exit the module and unregister it. + */ + virtual void exit(); + + /** + * \brief deprecated + * + * Find the the right module corresponding to the task + * and call the stop method. + * Use ProxyModule.stop(...) for remote/local compatibility + * \param pIDTask task's ID + * \deprecated + */ + QI_API_DEPRECATED void functionStop(int pIDTask); + + /** + * \brief It will be called at every module creation, user can overload it. + */ + virtual void init(void) {} + }; +} + +#endif // _LIBALCOMMON_ALCOMMON_ALMODULE_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/almodulecore.h b/naoModule/libnaoqi_files/include/alcommon/almodulecore.h new file mode 100755 index 0000000..a4ca195 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/almodulecore.h @@ -0,0 +1,561 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALMODULECORE_H_ +#define _LIBALCOMMON_ALCOMMON_ALMODULECORE_H_ + +# include +# include +# include +# include + +# include +# include +# include + +# include +# include +# include + +#include +#include +#include +#include +#include + +//legacy hell, LEGACY HELL +#define BIND_OBJ_METHOD(objptr, meth) _builder.advertiseMethod(_mBuilder, objptr, &meth) +#define BIND_METHOD(meth) _builder.advertiseMethod(_mBuilder, this, &meth) + +#define BIND_OBJ_METHOD_PTR(objptr, methptr) _builder.advertiseMethod(_mBuilder, objptr, methptr) +#define BIND_METHOD_PTR(methptr) _builder.advertiseMethod(_mBuilder, this, methptr) + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALValue; + class ALModuleCorePrivate; + + /** + * \class ALModuleCore almodulecore.h "alcommon/almodulecore.h" + * \brief ALModuleCore is the superclass of user modules. + * + * It implements basic functions that enables communication with naoqi + * brokers, so that the distributed approach is painless for users + * who just want to come up with a simple module quickly, + * compile it and have it work, without having to deal with + * interprocess communication. + * \ingroup Module + */ + class ALModuleCore: public ::boost::enable_shared_from_this, public ::boost::noncopyable, public qi::DynamicObject + { + public: + /** + * \typedef Ptr + * \brief Shared pointer to ALModuleCore + * \deprecated Use boost::shared_ptr instead + */ + typedef boost::shared_ptr Ptr; + /** + * \typedef WeakPtr + * \brief Weak pointer to ALModuleCore + * \deprecated Use boost::weak_ptr instead + */ + typedef boost::weak_ptr WeakPtr; + + /** + * \enum ModuleType + * \brief Module type (Ruby, lua, and matlab are not currently used) + * \deprecated not used anywhere + */ + enum ModuleType + { + CPP = 0, /**< C++ type */ + PYTHON = 1, /**< python type */ + RUBY = 2, /**< ruby type (unused) */ + LUA = 3, /**< lua type (unused) */ + MATLAB = 4, /**< matlab type (unused) */ + URBI /**< urbi type */ + }; + + /** + * \brief Constructor. + * + * An ALModule has a name, and is registered in a broker, + * so that its methods can be called by other modules, + * via a proxy constructed with module's name + * \param pBroker a pointer to the broker + * \param pName name of the module + */ + ALModuleCore(boost::shared_ptr pBroker, + const std::string &pName); + + /** \brief Destructor. */ + virtual ~ALModuleCore(); + + /** + * \brief Get a reference to a temporary object used to construct + * method help + * \return a reference to a temporary ALMethodInfo + */ + ALMethodInfo& getCurrentMethodDescription(); + + /** + * \brief Getter to the class. + * \return a pointer to this + */ + boost::shared_ptr getThis(); + /** + * \brief Getter to class. + * \return a const pointer to this + */ + boost::shared_ptr getThis() const; + + /** + * \brief Check if someone want to exit the module. + * \return true if someone ask to exit the module, false othewise + */ + bool isClosing(); + + /** + * \brief Register a module to a broker. + * + * Automatically called when loading a module from autoload.ini + */ + void initModule(void); + + /** + * \brief Get access to a module. + * + * ex: getProxy("ALMotion") + * \param pModuleName module name + * \return a pointer to ALProxy + */ + boost::shared_ptr getProxy(const std::string &pModuleName); + + /** + * \brief Get the name of the registered broker. + * \return name of the broker + */ + std::string getBrokerName(); + + /** + * \brief Get the type of the module. + * \return type of the module + */ + ModuleType getModuleType(void); + + /** + * \brief Set the type of the module. + * \param pType type of the module + */ + void setModuleType(ModuleType pType); + + /** + * \brief Execute a method with some arguments and store the result. + * \param pMethod method to execute + * \param pParams set of arguments for the method + * \param pResult result of the method execution + * \return a pointer to the method executed, + * so it can be used to get information about the method + */ + virtual ALMethodInfo* execute(const std::string &pMethod, + const AL::ALValue &pParams, + AL::ALValue &pResult); + + /** + * \brief Get the module method list. + * \return vector of string module name + */ + std::vector getMethodList(); + + /** + * \brief Get a method's description string. + * \param pMethodName method's name. + * \return a structured method's description following the format : + * [ + * std::string methodName, + * std::string methodDescription, + * [parameter, ...], + * std::string returnName, + * std::string returnDescription + * ] + * Where parameter is : + * [ + * std::string parameterName, + * std::string parameterDescription + * ] + * \warning Will return only one version of a method, therefore the method + * doesn't handle overloading. + */ + AL::ALValue getMethodHelp(const std::string &pMethodName); + + /** + * \brief Get a method's description string. + * \param pMethodName method's name. + * \return a structured method's description + */ + ALMethodInfo getMethodHelpObject(const std::string &pMethodName); + + /** + * \brief Get the module's description. + * \return a string describing the module + */ + AL::ALValue moduleHelp(); + + /** + * \brief Just a ping. Used to test connectivity to a module. + * \return always returns true + */ + bool ping(void); + + /** + * \brief Get module's version + * \return The version as a string + */ + virtual std::string version(); + + /** + * \brief Exit the module and unregister it. + */ + virtual void exit(); + + /** + * \brief Get the name of the module given when constructing + * \return The name of the module + */ + const std::string& getName() const; + + /** + * \brief Get information about the module. + * \return a pointer to ALModuleInfo + */ + boost::shared_ptr getModuleInfo(); + + /** + * \brief Called by the broker webpage to detail the module. + * \return an optional extra description of the module + */ + virtual std::string httpGet(); + + /** + * \brief Find method information by name and argument type + * not only by map key. + * \param pName method name + * \param paramType list of parameters + * \param softCompare true mean ALValue can be anyType + * (use it for all type compare except local call) + * \return a poitner to methodInfo + */ + ALMethodInfo* getMethodInfoByNameMember(const std::string &pName, + const std::vector ¶mType, + bool softCompare = true); + + /** + * \brief Call by a proxy to check function's parameter. + * \param pName function Name + * \return a poitner to methodInfo + */ + ALMethodInfo* getMethodInfo(const std::string &pName); + + /** + * \brief Call by a proxy to check function's parameter. + * \param pName function Name + * \param pParamsType parameters type + * \return a poitner to methodInfo + */ + ALMethodInfo* getMethodInfo(const std::string &pName, + std::vector pParamsType); + + /** + * \brief Call by a proxy to check function's parameter. + * \param pName function Name + * \param pParams method parameters + * \return a poitner to methodInfo + */ + ALMethodInfo* getMethodInfo(const std::string &pName, + const AL::ALValue &pParams); + + /** + * \brief deprecated + * \deprecated + */ + ALMethodInfo* getFunctionDesc(const std::string &pName); + + /** + * \brief deprecated + * \deprecated + */ + ALMethodInfo* getFunctionDesc(const std::string &pName, + std::vector pParamsType); + + /** + * \brief deprecated + * \deprecated + */ + ALMethodInfo* getFunctionDesc(const std::string &pName, + const AL::ALValue &pParams); + + /** + * \brief deprecated + * \deprecated + */ + ALMethodInfo* getFunctionDescByNameMember(const std::string &pName, + const std::vector ¶mType, + bool softCompare = true); + + /** + * \brief Get a pointer to the broker context. + * \return a shared pointer to the broker context + */ + boost::shared_ptr getParentBroker() const; + + /** + * \brief Local stop. Use stop(id) for remote/local compatibility + * \param pTaskID the ID of the task you want to stop + */ + void functionStop(int pTaskID); + + + /** + * \brief Set the description of the module. + * \param pDesc a description of the module + */ + void setModuleDescription(const std::string &pDesc); + + /** + * \brief Get the usage of a method as a string. + * \param methodName the name of the method + * \return the usage as a string + */ + std::string getUsage(const std::string &methodName); + + /** + * \brief Create a module core link to a broker. + * \param pBroker to pointer the a broker + * \return a pointer to the module + * \throw ALError + */ + template + static boost::shared_ptr createModuleCore(boost::shared_ptr pBroker) + { + boost::shared_ptr module = boost::shared_ptr(new T(pBroker)); + module->initModule(); // register module in broker + try + { + // we call init on a ALModule::Ptr as init may be protected + // init is a virtual method that can be reimplemented + (boost::static_pointer_cast(module))->init(); + } + catch(const ALError& e) + { + module->exit(); + throw(e); + } + return module; + } + + /** + * \brief Create a module core, do not register on the broker + * \param pBroker to pointer the a broker + * @param[in] name Name of the module core. + * \return a pointer to the module + * \throw ALError + */ + template + static boost::shared_ptr createModuleCoreNoRegister(boost::shared_ptr pBroker, const std::string &name) + { + boost::shared_ptr module = boost::shared_ptr(new T(pBroker, name)); + //module->initModule(); // register module in broker + try + { + // we call init on a ALModule::Ptr as init may be protected + // init is a virtual method that can be reimplemented + (boost::static_pointer_cast(module))->init(); + } + catch(const ALError& e) + { + module->exit(); + throw(e); + } + return module; + } + + /** + * \brief Create a module core link to a broker. + * \param pBroker pointer to the a broker + * \param name module's name + * \return a pointer to the module + * \throw ALError + */ + template + static boost::shared_ptr createModuleCore(boost::shared_ptr pBroker, + const std::string &name) + { + boost::shared_ptr module = boost::shared_ptr(new T(pBroker, name)); + module->initModule(); + try + { + // init if you redefined it + (boost::static_pointer_cast(module))->init(); + } + catch(const ALError& e) + { + module->exit(); + throw(e); + } + return module; + } + + /** + * \brief Create a URBI module core link to a broker. + * \param pBroker pointer to the a broker + * \param name module's name + * \return a pointer to the module + */ + template + static boost::shared_ptr createUrbiModule(boost::shared_ptr pBroker, + const std::string &name) + { + boost::shared_ptr module = createModuleCore(pBroker, name); + module->setModuleType(AL::ALModuleCore::URBI); + return module; + } + + /** + * \brief Know if program or module termination is asked. + * \return true if module termination is asked, false otherwise + */ + bool isModuleStopped(); + + /** + * \brief Set the id of the module used to determine the shutdown order. + * \param id the id given to it by the broker + */ + void setModuleID(int id); + + /** + * \brief Get the module id given to it be the broker. + * \return an int module id + */ + int getModuleID(); + + /** + * \brief Bind a method. + * \param pFunctor pointer to a generic functor + */ + void bindMethod(boost::shared_ptr pFunctor); + + /** + * \brief Bind a method. + * \param pFunctor pointer to a generic functor + * \param pName the name of the method + * \param pClass the name of your class + * \param pFunctionDescription the description of the method + * \param pMethodDescription the description method. + */ + void bindMethod(boost::shared_ptr pFunctor, + const std::string &pName, + const std::string &pClass, + const std::string &pFunctionDescription, + const ALMethodInfo &pMethodDescription); + + /** + * \brief Use to define a bound method. + * \param pFunctor pointer to a generic functor + */ + void bindMethodOverload(boost::shared_ptr pFunctor); + + /** + * \brief Define the name of a bound method. + * \param pName the name of the method + * \param pClass the name of your class + * \param pFunctionDescription the description of the method + * \param pMask optional Mask, default 0. + * see almethodinfo.h for more information + */ + void functionName(const std::string &pName, + const std::string &pClass, + const std::string &pFunctionDescription, + int pMask = 0); + + /** + * \brief Add a documented parameter to a method. + * + * \param pName the name of the parameter + * \param pDesc the description of the parmeter + */ + void addParam(const std::string &pName, + const std::string &pDesc); + + /** + * \brief Add a module example. + * \param pLanguage the language of the example (c++, python, .net, etc) + * \param pExample the example + */ + void addModuleExample(const std::string &pLanguage, + const std::string &pExample); + + /** + * \brief Add a method example. + * \param pLanguage the language of the example (c++, python, .net, etc) + * \param pExample the example + */ + void addMethodExample(const std::string &pLanguage, + const std::string &pExample); + + /** + * \brief Sets the description of the return value. + * \param pName the name of the return item (used in autogeneration) + * \param pDesc the description of the return item + */ + void setReturn(const std::string &pName, const std::string &pDesc); + + virtual qi::Future metaCall(qi::AnyObject context, unsigned int method, const qi::GenericFunctionParameters &in, qi::MetaCallType callType, qi::Signature returnSignature); + + + qi::AnyObject asObject(); + + /** + * Used only for naoqi1/naoqi2 compatibility layers. Do not use unless you + * know what you are doing + */ + qi::DynamicObjectBuilder& getBuilder() {return _builder;}; + + + /** + * Used for simulating old naoqi1 post behavior that return an id + */ + int pCall(const qi::AnyArguments& args); + + protected: + /** + * \brief Call at every module creation. + * + * User can overload it + */ + virtual void init(void) {} + + private: + int _pCall(const unsigned int &methodId, const std::vector &args); + + protected: + qi::DynamicObjectBuilder _builder; + friend class baseModule; // for inaoqi that needs to advertise methods + public: + qi::GenericObject _go; + ALModuleCorePrivate *_p; + qi::MetaMethodBuilder _mBuilder; + + }; // !ALModuleCore +} + +#endif // _LIBALCOMMON_ALCOMMON_ALMODULECORE_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/almoduleinfo.h b/naoModule/libnaoqi_files/include/alcommon/almoduleinfo.h new file mode 100755 index 0000000..ad4435a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/almoduleinfo.h @@ -0,0 +1,43 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALMODULEINFO_H_ +#define _LIBALCOMMON_ALCOMMON_ALMODULEINFO_H_ + +# include +# include +# include + +namespace AL +{ + /** + * \class ALModuleInfo almoduleinfo.h "alcommon/almoduleinfo.h" + * \brief ALModuleInfo is the class of information about user modules. + * \ingroup Module + * \ingroup Proxy + * \ingroup Broker + */ + class ALModuleInfo + { + public: + std::string name; /**< Module name */ + int architecture; /**< linux/win32/macOSX */ + std::string ip; /**< Broker IP */ + int port; /**< Broker port*/ + int processId; /**< Module unique ID*/ + bool isABroker; /**< true if the module is link to a broker */ + bool keepAlive; /**< if false, automatically destroys broker when parent broker dies*/ + }; + +} + +#endif // _LIBALCOMMON_ALCOMMON_ALMODULEINFO_H_ + + diff --git a/naoModule/libnaoqi_files/include/alcommon/alproxy.h b/naoModule/libnaoqi_files/include/alcommon/alproxy.h new file mode 100755 index 0000000..f2cf3b9 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/alproxy.h @@ -0,0 +1,401 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2010, 2011, 2012 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALPROXY_H_ +#define _LIBALCOMMON_ALCOMMON_ALPROXY_H_ + +# include +# include +# include +# include +# include + +# include +# include +# include + +#ifdef _WIN32 +# pragma warning(disable:4996) +# pragma warning(disable:4800) +#endif + +namespace AL +{ + + + + class ALProxyPrivate; + + /** + * \class ALProxy alproxy.h "alcommon/alproxy.h" + * \brief ALProxy is a client to the served methods of a module. + * + * It gives access to the methods of a module without needing to + * know if the module that provides a service is in the + * same process, on the same machine, or on the same tcp network. + * + * ALProxy is a generic client in that it can be constructed + * using just the name of the module that you wish to connect to. + * Once connected, methods are availble via templated calls. While + * generic and flexible, these provide no checking on the availabilty + * or signature of a method until runtime. + * + * All Aldebaran provided modules have classes called 'specific' + * proxies built around this generic proxy. When using a specific + * proxy, explicit method signatures are provided which allows + * correctness to be validated at runtime. In addition, specific + * proxies include optimisations for local calls that are easily + * available in the generic proxy. + * e.g. + * \#include + * ... + * AL::ALTextToSpeechProxy tts; + * tts.say("hello world"); + * + * Lifetime: The broker own a private qi::object, proxies own a weak + * pointer on the object. If the object is destroyed (because the module do not + * exist anymore, the weak_ptr wont work anymore). + * once there is no weak_ptr on the object the object could be deleted from + * broker. + * + * \ingroup Proxy + */ + class ALProxy : public ::boost::enable_shared_from_this + { + public: + /** + * \typedef Ptr + * \brief Shared pointer to ALProxy. + * \deprecated Use boost::shared_ptr instead. + */ + typedef boost::shared_ptr Ptr; + /** + * \typedef WeakPtr + * \brief Weak pointer to ALProxy. + * \deprecated Use boost::weak_ptr instead. + */ + typedef boost::weak_ptr WeakPtr; + + typedef int (*onFinishedCallback)(const char*, int, const AL::ALValue &); + + /** + * \brief Get a pointer to this ALProxy. + * \return A pointer to this + */ + boost::shared_ptr getThis(); + /** + * \brief Get a pointer to this ALProxy. + * \return A const pointer to this + */ + boost::shared_ptr getThis() const; + + /** + * \enum pProxyOption + * \brief Different options for the ALProxy. + */ + enum pProxyOption + { + NO_OPTION = 0, /**< no options */ + FORCED_LOCAL = 1, /**< only local proxy */ + NO_LOAD_DEPENDS = 2, /**< don't load dependency */ + MAIN_PROXY = 4 /**< only main broker proxy */ + }; + + ALProxy(const ALProxy &rhs); + private: + const ALProxy &operator=(const ALProxy &rhs); + + public: + /** + * \brief Constructor. + * \param pBroker pointer to a broker + * \param pModuleName module's name + * \param pProxyMask + * \param timeout + */ + ALProxy(boost::shared_ptr pBroker, + const std::string &pModuleName, + int pProxyMask = 0, + int timeout = 0); + + + /** + * \brief Constructor + * \param pObject pointer to a service object be careful this pointer wont be owned by ALProxy + * \param pModuleName module's name + */ + ALProxy(qi::AnyObject pObject, const std::string &pModuleName); + + /** + * \brief Constructor allowing to use proxy without instancing a broker. + * \param pModuleName module's name + * \param pIp + * \param pPort + * \param pProxyMask + * \param timeout + */ + ALProxy(const std::string &pModuleName, + const std::string &pIp, + int pPort, + int pProxyMask = 0, + int timeout = 0); + /** + * \brief Constructor. + * \param pModuleName module's name + * \param pIp + * \param pPort + * \param pBroker + * \param pProxyMask + * \param timeout + */ + ALProxy(const std::string &pModuleName, + const std::string &pIp, + int pPort, + boost::shared_ptr pBroker, + int pProxyMask = 0, + int timeout = 0); + /** + * \brief Constructor. + * \param pModuleName module's name + * \param pProxyOption + * \param pTimeout + */ + ALProxy(const std::string &pModuleName, + int pProxyOption, + int pTimeout); + + public: + /** \brief Destructor. */ + virtual ~ALProxy(void); + + + /** \brief return the name of the remote broker + * \return name of the remote broker, "" is it's a local broker + */ + std::string remoteBrokerName(); + + /** + * \brief A generic call, without type optimisation, + * using AL::ALValue for each call... (local or not). + * + * Used from a C++ code not knowing the signature of the called method + * + * \param strMethodName the name of the method to call + * \param listParams the list of parameters (possibly no params) + * + * \return an alvalue, possibly invalid if function returns nothing + */ + AL::ALValue genericCall(const std::string &strMethodName, + const AL::ALValue &listParams); + + + /** + * \brief A generic post-call, without type optimisation, + * using AL::ALValue for each call... (local or not). + * + * Used from a C++ code not knowing the signature of the called method + * \warning the callback will still be called if the proxy is destroyed. + * + * \param strMethodName the name of the method to call + * \param listParams the list of parameters (possibly no params) + * \param pCallbackToCallOnFinished a callback to call when task is + * finished (NULL if no callback) + * DEPRECATED + * \param pszCallerName the name of the caller (proxy name or module name, + * dependings on langage, script, caller...) + * DEPRECATED + * \return nID: ID of the new created task (0 if error) + */ + int genericPCall(const std::string &strMethodName, + const AL::ALValue &listParams, + onFinishedCallback pCallbackToCallOnFinished = NULL, + const char *pszCallerName = NULL); + + /** + * \brief Get the version. + * \return the revision number as a string + */ + std::string version(); + + /** + * \brief Get the module. + * \return a pointer to the module + */ + boost::shared_ptr getModule() const; + /** + * \brief Get the moduleCore. + * \return a pointer to the moduleCore + */ + boost::shared_ptr getModuleCore() const; + + /** + * \brief Get information about the module stored into \a pModuleInfo + * \param pModuleInfo reference to the module information found + * \return 0 if module info find, -1 otherwise + */ + int getInfo(ALModuleInfo &pModuleInfo); + + /** + * \brief Check if the module is in the same process than the proxy. + * \return true if the module is in the same process, false otherwise + */ + bool isLocal(); + + /** + * \brief Make sure that we notice that someone has invalidated our module. + * + * This check is done before each specialized proxy's use of a method ptr. + * \return true if the module is valide, false otherwise + */ + bool isValid(); + + /** + * \brief Get a pointer to a method form its name and its parameters. + * \param pName name of the method + * \param pParamTypes parameters' list + * \return a pointer to the method + */ + boost::shared_ptr getFunctor(const std::string &pName, + const std::vector &pParamTypes); + + /** + * \brief Get the parent broker. + * \return a pointer to the parent broker + */ + boost::shared_ptr getParentBroker(void) const; + + /** + * \brief Destroy a proxy to clean each shared_ptr of the class. + */ + void destroyConnection(void); + + template + R call(const std::string &pName); + + template + R call(const std::string &pName, const P1 &p1); + + template + R call(const std::string &pName, const P1 &p1, const P2 &p2); + + template + R call(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3); + + template + R call(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4); + + template + R call(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5); + + template + R call(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5, const P6 &p6); + + inline void callVoid(const std::string &pName); + + template + void callVoid(const std::string &pName, const P1 &p1); + + template + void callVoid(const std::string &pName, const P1 &p1, const P2 &p2); + + template + void callVoid(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3); + + template + void callVoid(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4); + + template + void callVoid(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5); + + template + void callVoid(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5, const P6 &p6); + + inline int pCall(const std::string &pName); + + template + int pCall(const std::string &pName, const P1 &p1); + + template + int pCall(const std::string &pName, const P1 &p1, const P2 &p2); + + template + int pCall(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3); + + template + int pCall(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4); + + template + int pCall(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5); + + template + int pCall(const std::string &pName, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5, const P6 &p6); + + /** + * \brief Wait for the end of a long running method + * that was called using 'post' + * \param id the ID of the method that was returned + * when calling the method using 'post' + * \param timeoutPeriod the timeout period in ms. To wait indefinately, + * use a timeoutPeriod of zero + * \return true if the timeout period terminated. + * false if the method returned. + */ + bool wait(const int &id, const int &timeoutPeriod); + + /** + * \brief Stop a long running method that was called using 'post' + * \param id the ID of the method that was returned + * when calling the method using 'post' + */ + void stop(const int &id); + + /** + * \brief Check if the method is running. + * \param id the ID of the method that was returned + * when calling the method using 'post' + * \return true if the method is currently running. + */ + bool isRunning(const int &id); + + /** \cond PRIVATE */ + /** + * \brief Notification for ALMemory. + * + * Should not be used by clients. + */ + int pCallNotify(const std::string &name, + const std::string &key, + const ALValue &value, + const ALValue &message = std::string(), + std::pair* cache = 0); + + std::string moduleName() const; + + /** + * \brief Return the locked underlying qi::AnyObject, or throw on lock failure. + */ + qi::AnyObject asObject(); + + ALProxyPrivate *_p; + qi::AnyWeakObject _object; + protected: + int xMetaPCall(const std::string &signature, const qi::GenericFunctionParameters &in); + + friend class AL::ALModuleCore; + //! @endcond + }; // ALProxy + + typedef boost::shared_ptr ALProxyPtr; +} // namespace AL + +#include + +#endif // _LIBALCOMMON_ALCOMMON_ALPROXY_H_ + diff --git a/naoModule/libnaoqi_files/include/alcommon/alproxy.hxx b/naoModule/libnaoqi_files/include/alcommon/alproxy.hxx new file mode 100755 index 0000000..799a27b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/alproxy.hxx @@ -0,0 +1,155 @@ +/** + * AUTOGENERATED CODE, DO NOT EDIT + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2010, 2011, 2012 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALPROXY_HXX_ +#define _LIBALCOMMON_ALCOMMON_ALPROXY_HXX_ + +#include + +namespace AL +{ + + #define pushi(z, n,_) args.push_back(::qi::AnyReference::from(p ## n)); + #define consti(z, n,_) , const P ## n & p ## n + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + R ALProxy::call(const std::string& pName BOOST_PP_REPEAT(n, consti, _) ) \ +{ \ + qi::AnyObject object = _object.lock(); \ + if (!object) \ + throw ALERROR(moduleName(), pName, "module destroyed"); \ + ::qi::GenericFunctionParameters args; \ + args.reserve(n); \ + BOOST_PP_REPEAT(n, pushi, _) \ + try \ + { \ + qi::AnyValue res(object.metaCall(pName, args).value(), false, true); \ + qi::Promise prom(qi::FutureCallbackType_Sync); \ + if (qi::detail::handleFuture(res.asReference(), prom)) \ + { \ + res.release(); /* handleFuture will free it */ \ + prom.future().wait(); \ + qiLogDebug("alproxy.call") << prom.future().hasError(); \ + return (R)prom.future().value(); \ + } \ + else \ + return res.to(); \ + /*return qi::AnyValue(object.metaCall(pName, args).value(), false, true).to();*/ \ + } \ + catch(const std::exception& e) \ + { \ + throw ALERROR(moduleName(), pName, e.what()); \ + } \ + } + QI_GEN_RANGE(genCall, 7) +#undef pushi +#undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + QI_GEN_MAYBE_TEMPLATE_OPEN(comma) ATYPEDECL QI_GEN_MAYBE_TEMPLATE_CLOSE(comma) \ + inline void ALProxy::callVoid(const std::string& pName BOOST_PP_REPEAT(n, consti, _)) \ + { \ + call(pName comma AUSE); \ + } + +QI_GEN_RANGE(genCall, 7) +#undef genCall +#undef consti + + inline + int ALProxy::pCall(const std::string& pName) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0, const P1 &p1) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + params.push_back(qi::AnyReference::from(p1)); + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0, const P1 &p1, const P2 &p2) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + params.push_back(qi::AnyReference::from(p1)); + params.push_back(qi::AnyReference::from(p2)); + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0, const P1 &p1, const P2 &p2, const P3 &p3) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + params.push_back(qi::AnyReference::from(p1)); + params.push_back(qi::AnyReference::from(p2)); + params.push_back(qi::AnyReference::from(p3)); + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + params.push_back(qi::AnyReference::from(p1)); + params.push_back(qi::AnyReference::from(p2)); + params.push_back(qi::AnyReference::from(p3)); + params.push_back(qi::AnyReference::from(p4)); + return xMetaPCall(pName, params); + } + + template + int ALProxy::pCall(const std::string& pName, const P0 &p0, const P1 &p1, const P2 &p2, const P3 &p3, const P4 &p4, const P5 &p5) + { + qi::AnyObject object = _object.lock(); + if (!object) + throw ALERROR(moduleName(), pName, "module destroyed"); + qi::GenericFunctionParameters params; + params.push_back(qi::AnyReference::from(p0)); + params.push_back(qi::AnyReference::from(p1)); + params.push_back(qi::AnyReference::from(p2)); + params.push_back(qi::AnyReference::from(p3)); + params.push_back(qi::AnyReference::from(p4)); + params.push_back(qi::AnyReference::from(p5)); + return xMetaPCall(pName, params); + } + +} +#endif // _LIBALCOMMON_ALCOMMON_ALPROXY_HXX_ diff --git a/naoModule/libnaoqi_files/include/alcommon/altoolsmain.h b/naoModule/libnaoqi_files/include/alcommon/altoolsmain.h new file mode 100755 index 0000000..199359a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/altoolsmain.h @@ -0,0 +1,39 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011, 2012 All Rights Reserved +*/ + + +#pragma once +#ifndef _LIBALCOMMON_ALCOMMON_ALTOOLSMAIN_H_ +#define _LIBALCOMMON_ALCOMMON_ALTOOLSMAIN_H_ + +#include +#include +#include + +/// \brief NAOqi +namespace AL +{ + class ALBroker; +} + +/** \brief main entry point function pointer. + * \ingroup MainFunc + */ +typedef boost::function1< int, boost::shared_ptr > TMainType; + +/// \brief tools +namespace ALTools +{ + /** \brief main function for remote modules + * \param pBrokerName name used for the main broker, should be the module name + * \param argc main argc + * \param argv main argv + * \param callback a function pointer to _createModule + * \ingroup MainFunc + */ + int mainFunction(const std::string &pBrokerName, int argc, char *argv[], const TMainType &callback); +} + +#endif // _LIBALCOMMON_ALCOMMON_ALTOOLSMAIN_H_ diff --git a/naoModule/libnaoqi_files/include/alcommon/api.h b/naoModule/libnaoqi_files/include/alcommon/api.h new file mode 100755 index 0000000..b168745 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/api.h @@ -0,0 +1,20 @@ +/* + * Copyright (C) 2011, 2012 Aldebaran Robotics + */ + +#pragma once +#ifndef _ALCOMMON_API_HPP_ +#define _ALCOMMON_API_HPP_ + +#include + +#ifdef alcommon_EXPORTS +# define ALCOMMON_API QI_EXPORT_API +#else +# define ALCOMMON_API QI_IMPORT_API +#endif + +#define ALCOMMON_API_LEVEL 1 + +#endif // _ALCOMMON_API_HPP_ + diff --git a/naoModule/libnaoqi_files/include/alcommon/version.h b/naoModule/libnaoqi_files/include/alcommon/version.h new file mode 100755 index 0000000..3984eac --- /dev/null +++ b/naoModule/libnaoqi_files/include/alcommon/version.h @@ -0,0 +1,11 @@ +/** + * Aldebaran Robotics (c) 2010-2013 All Rights Reserved + */ + +#ifndef ALCOMMON_REVISION_H +#define ALCOMMON_REVISION_H + +#define NAOQI_VERSION "2.1.4" + + +#endif // !ALCOMMON_REVISION_H diff --git a/naoModule/libnaoqi_files/include/alerror/alerror.h b/naoModule/libnaoqi_files/include/alerror/alerror.h new file mode 100755 index 0000000..79c3260 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alerror/alerror.h @@ -0,0 +1,109 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALERROR_ALERROR_ALERROR_H_ +#define _LIBALERROR_ALERROR_ALERROR_H_ + +# include + +# include +# include + +/** + * \def ALERROR(module, method, description) + * Create an ALError for the \a method from this \a module + * using that \a description + * (It will automaticly add file and line context) + */ +#define ALERROR(module, method, description) \ + AL::ALError(module, method, description, __FILE__, __LINE__) + +namespace AL +{ + /** + * \class ALError alerror.h "alerror/alerror.h" + * \brief ALError is used to send exception. All NAOqi errors are based on exception. All user commands should be encapsulated in a try catch block. + * \warning If you want to rethrow the exception you've just been catched + * (std::exception or ALError), you need to do: + +\verbatim try +{ + throw ALERROR("moduleTest", "methodeTest", "Should be working."); +} +catch (const std::exception& e) // or catch (const ALError& e) +{ + std::cout << e.what() << std::endl; + throw; // and not throw e; +} +\endverbatim + \ingroup libalerror + */ + class ALERROR_API ALError : public std::runtime_error + { + public: + /** + * \brief Constructor. + * \param pModuleName module's name that create error + * \param pMethod method's name where error occured + * \param pDescription error's descripton + * \param pszFilename source code file name + * \param pnNumLine source code line number + */ + ALError(const std::string& pModuleName, + const std::string& pMethod, + const std::string& pDescription, + const char* pszFilename = 0, + const unsigned int pnNumLine = 0); + + /** \brief Constructor. */ + ALError(); + + /** \brief Copy Constructor. */ + ALError(const ALError &e); + + /** + * \brief Destructor. + */ + virtual ~ALError() throw(); + + /** + * \brief deprecated + * \deprecated use what() + */ + QI_API_DEPRECATED const std::string toString() const; + /** + * \brief deprecated + * \deprecated + */ + QI_API_DEPRECATED const std::string& getModuleName() const; + /** + * \brief deprecated + * \deprecated + */ + QI_API_DEPRECATED const std::string& getMethodName() const; + /** + * \brief deprecated + * \deprecated + */ + QI_API_DEPRECATED const std::string& getFileName() const; + /** + * \brief deprecated + * \deprecated + */ + QI_API_DEPRECATED int getLine() const; + /** + * \brief deprecated + * \deprecated use what() + */ + QI_API_DEPRECATED const std::string getDescription() const; + }; +} + +#endif // _LIBALERROR_ALERROR_ALERROR_H_ diff --git a/naoModule/libnaoqi_files/include/alerror/alnetworkerror.h b/naoModule/libnaoqi_files/include/alerror/alnetworkerror.h new file mode 100755 index 0000000..5dacb98 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alerror/alnetworkerror.h @@ -0,0 +1,56 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALERROR_ALERROR_ALNETWORKERROR_H_ +#define _LIBALERROR_ALERROR_ALNETWORKERROR_H_ + +# include +# include + +# include + +/** + * \def ALNETWORKERROR(module, method, description) + * Create an ALNetworkError for the \a method from this \a module + * using that \a description + * (It will automaticly add file and line context) + */ +# define ALNETWORKERROR(module, method, description) \ + AL::ALNetworkError(module, method, description, __FILE__, __LINE__) + +namespace AL +{ + + /** + * \class ALNetworkError alnetworkerror.h "alerror/alnetworkerror.h" + * \brief ALNetworkError is an exception raised + * when a network error occur in alcommon. + * \ingroup libalerror + */ + class ALERROR_API ALNetworkError : public ALError + { + public: + /** + * \brief Constructor. + * \param pModuleName module's name that create error + * \param pMethod method's name where error occured + * \param pDescription error's descripton + * \param pszFilename source code file name + * \param pnNumLine source code line number + */ + ALNetworkError(std::string pModuleName, + std::string pMethod, + std::string pDescription, + const char* pszFilename = NULL, + const unsigned int pnNumLine = 0); + }; +} + +#endif // _LIBALERROR_ALERROR_ALNETWORKERROR_H_ diff --git a/naoModule/libnaoqi_files/include/alerror/config.h b/naoModule/libnaoqi_files/include/alerror/config.h new file mode 100755 index 0000000..4dfd419 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alerror/config.h @@ -0,0 +1,23 @@ +/** + * Author(s): + * - Cedric GESTES + * + * Copyright (C) 2011 Aldebaran Robotics + */ + +/** @file + * @brief dll import/export + */ + +#pragma once +#ifndef _LIBALERROR_ALERROR_CONFIG_H_ +#define _LIBALERROR_ALERROR_CONFIG_H_ + +#include + +/* #undef alerror_STATIC_BUILD */ + +#define ALERROR_API QI_LIB_API(alerror) + +#endif // _LIBALERROR_ALERROR_CONFIG_H_ + diff --git a/naoModule/libnaoqi_files/include/alextractor/alextractor.h b/naoModule/libnaoqi_files/include/alextractor/alextractor.h new file mode 100755 index 0000000..0a0ebcf --- /dev/null +++ b/naoModule/libnaoqi_files/include/alextractor/alextractor.h @@ -0,0 +1,247 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALEXTRACTOR_ALEXTRACTOR_ALEXTRACTOR_H_ +#define _LIBALEXTRACTOR_ALEXTRACTOR_ALEXTRACTOR_H_ + +#include +#include + +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALExtractorPrivate; + + /** + * \class ALExtractor alextractor.h "alextractor/alextractor.h" + * \brief ALExtractor class implements an extractor. + * + * An extractor is a module which extracts some information + * about the world. It can be activated to produce information. + * \ingroup libalextractor + */ + class ALEXTRACTOR_API ALExtractor: public ALModule + { + public: + /** + * \brief Constructor. + * + * Create a extractor link to a broker. + * \param pBroker pointer to the broker + * \param pName name of the extractor + */ + ALExtractor(boost::shared_ptr pBroker, + const std::string& pName); + + /** \brief Destructor. */ + virtual ~ALExtractor(); + + /** + * \brief Called by the "client" to tell that + * it is interested in the output values. + * \param pSubscribedName Name of the client module + * \param pPeriod period of the extractor + * \param pPrecision precision of the extractor + */ + virtual void subscribe(const std::string &pSubscribedName, + const int &pPeriod, + const float &pPrecision); + + /** + * \brief Called by the "client" to tell that + * it is interested in the output values. + * Period and Precision specified by getDefaultPrecision() + * and getDefaultPeriod() will be used by default. + * \param pSubscribedName Name of the client module + */ + virtual void subscribe(const std::string &pSubscribedName); + + + /** + * \brief Called by the "client" to update the periode. + * \param pSubscribedName Name of the client module + * \param pPeriod period of the extractor + */ + virtual void updatePeriod(const std::string &pSubscribedName, + const int &pPeriod); + + /** + * \brief Called by the "client" to update the precision. + * \param pSubscribedName Name of the client module + * \param pPrecision precision of the extractor + */ + virtual void updatePrecision(const std::string &pSubscribedName, + const float &pPrecision); + + /** + * \brief Called by the "client" to tell that + * it is not interested anymore in the output values. + * \param pSubscribedName Name of the client module + */ + virtual void unsubscribe(const std::string &pSubscribedName); + + /** + * \brief Called by the "client" to get the + * current period chosen by the Extractor. + * \return current period + */ + virtual int getCurrentPeriod(); + + /** + * \brief Called by the "client" to get the + * current precision chosen by the Extractor. + * \return current precision + */ + virtual float getCurrentPrecision(); + + /** + * \brief Called by the "client" to get the period. + * \param pSubscribedName Name of the client module + * \return period I required + */ + virtual int getMyPeriod(const std::string &pSubscribedName); + + /** + * \brief Called by the "client" to get the precision. + * \param pSubscribedName Name of the client module + * \return precision I required + */ + virtual float getMyPrecision(const std::string &pSubscribedName); + + /** + * \brief Called by the "client" to get the + * information of all the current subscribers. + * \return info, names and parameters of all subscribers + */ + ALValue getSubscribersInfo(); + + /** + * \brief Called by the broker webpage to detail the module. + * \return an optional extra description of the module + */ + virtual std::string httpGet(); + + protected: + + /** + * \brief What the extractor shall do to start detection. + * + * + * This method is called only once: when the first module subscribes. + * \param pPeriod period of the extractor + * \param pPrecision precision of the extractor + */ + virtual void xStartDetection(const int pPeriod, + const float pPrecision) = 0; + + /** + * \brief Enables to do some custom updates when the period and/or + * the precision have been updated + * + * This empty method can be overrided to do some custom updates + * when the period and/or the precision have been updated. + * \param pPeriod period of the extractor + * \param pPrecision precision of the extractor + */ + virtual void xUpdateParameters(const int pPeriod, const float pPrecision) {} + + /** + * \brief What the extractor shall do to stop detection. + * + * this method is called only once: when the last module unsubscribes. + */ + virtual void xStopDetection() = 0; + + + /** + * \brief Specifies the advertised period that should be chosen + * by default when subscribe(std::string name) is used + * + * Implementing this method is optional. If not implemented, 30 ms will + * be chosen. + */ + virtual int getDefaultPeriod(); + + /** + * \brief Specifies the advertised precision that should be chosen + * by default when subscribe(std::string name) is used + * + * Implementing this method is optional. If not implemented, 0 will + * be chosen. + */ + virtual float getDefaultPrecision(); + + + /** + * \brief Specifies the minimum period (in ms) that can be set + * for the extractor. + * + * Implementing this method is optional. If not implemented, 1 ms + * will be chosen. + */ + virtual int getMinimumPeriod(); + + /** + * \brief Specifies the maximum period (in ms) that can be set + * for the extractor. + * + * Implementing this method is optional. If not implemented, no + * maximum period will be set and the function will return -1. + */ + virtual int getMaximumPeriod(); + + /** + * \brief Which values this extractor updates in ALMemory. + * \return vector of modified value + */ + virtual std::vector getOutputNames(void); + + /** + * \brief Retrieves the list of events updated by the extractor. + * \return vector of events + */ + std::vector getEventList(void); + + /** + * \brief Retrieves the list of memory keys updated by the extractor. + * \return vector of memory keys + */ + std::vector getMemoryKeyList(void); + + /** + * \brief Declares an event in ALMemory. + */ + void declareEvent(const std::string& event); + + /** + * \brief Initializes a memory key in ALMemory (with an empty ALValue). + */ + void declareMemoryKey(const std::string& key); + + private: + /** Pointer to ALExtractor private implementation */ + boost::scoped_ptr _private; + /** + * \brief updates fCurrentParameters from fSubscribedList. + */ + void xUpdateParameters(); + + + boost::mutex fSubscriptionMutex; + }; +} // namespace AL + +#endif // _LIBALEXTRACTOR_ALEXTRACTOR_ALEXTRACTOR_H_ + diff --git a/naoModule/libnaoqi_files/include/alextractor/config.h b/naoModule/libnaoqi_files/include/alextractor/config.h new file mode 100755 index 0000000..cb470c6 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alextractor/config.h @@ -0,0 +1,27 @@ +/** + * Author(s): + * - Cedric GESTES + * + * Copyright (C) 2011 Aldebaran Robotics + */ + +/** @file + * @brief dll import/export + */ + +#pragma once +#ifndef _LIBALEXTRACTOR_ALEXTRACTOR_CONFIG_H_ +#define _LIBALEXTRACTOR_ALEXTRACTOR_CONFIG_H_ + +#include + +#ifdef alextractor_EXPORTS +# define ALEXTRACTOR_API QI_EXPORT_API +#elif defined(alextractor_IMPORTS) +# define ALEXTRACTOR_API QI_IMPORT_API +#else +# define ALEXTRACTOR_API +#endif + +#endif // _LIBALEXTRACTOR_ALEXTRACTOR_CONFIG_H_ + diff --git a/naoModule/libnaoqi_files/include/allauncher/launcher.h b/naoModule/libnaoqi_files/include/allauncher/launcher.h new file mode 100755 index 0000000..9642bfe --- /dev/null +++ b/naoModule/libnaoqi_files/include/allauncher/launcher.h @@ -0,0 +1,96 @@ +#pragma once +/* -*- Mode: C++; -*- */ +/* +** Author(s): +** - Cedric GESTES +** +** Copyright (C) 2011, 2013 Cedric GESTES +*/ + + +#ifndef _LIB_ALLAUNCHER_ALLAUNCHER_LAUNCHER_H_ +#define _LIB_ALLAUNCHER_ALLAUNCHER_LAUNCHER_H_ + +#include +#include +#include + +#include + +namespace AL +{ + class ALSharedLibrary; + class ALBroker; + + + class LauncherStat { + public: + LauncherStat() + : loadlib(0) + , createmodule(0) + {} + + int loadlib; + int createmodule; + }; + + /** + * A class to use to launch/remove module at demand + * + * FIXME: add a unloadLibrary() function? + */ + class Launcher + { + public: + Launcher(const boost::shared_ptr pBroker); + + typedef std::pair ModuleInfo; + typedef std::vector ModuleInfoVector; + typedef std::map AutoLoadMap; + + + /** + * Parse the user autoload.ini (/home/nao/naoqi/preferences/autoload.ini) + * file and try to launch everything. + * Errors are caught and printed: does not throw on error. + */ + void loadUserAutoload(const std::vector &blacklist = std::vector()); + + /** + * Parse the autoload.ini file and try to launch everything. + * Errors are caught and printed: does not throw on error. + */ + void loadAutoload(const std::vector &blacklist = std::vector()); + + /** + * Parse the iniPath file and try to launch everything. + * Errors are caught and printed: does not throw on error. + */ + void loadIni(const std::string &iniPath, const std::vector &blacklist, bool coreNeeded=false); + + /** + * Load a library inside the broker. + * Throw on error. + */ + void loadLibrary(const std::string &moduleName, const std::string launcherName=""); + int loadProgram(const std::string &programPath); + int loadPython(const std::string &scriptPath); + + void dumpStat(); + + bool moduleInAutoload(const std::string& module, + const std::string& section); + private: + AutoLoadMap parseIni(const std::string &filename); + bool loadSection(AutoLoadMap amap, const std::string &name, const std::vector &blacklist); + void printAutoLoadMap(const AutoLoadMap &amap); + + private: + boost::shared_ptr _broker; + std::vector _sdkPrefix; + std::map _stats; + }; + +} // namespace AL + +#endif // _LIB_ALLAUNCHER_ALLAUNCHER_LAUNCHER_H_ diff --git a/naoModule/libnaoqi_files/include/almath.i b/naoModule/libnaoqi_files/include/almath.i new file mode 100755 index 0000000..5c6113e --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath.i @@ -0,0 +1,382 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/* + * Workaround a swig problem regarding std::vector __getitem__ + * Without this macro, constructs like x = myVectorPosition2D[i] return + * elements by reference and not by value, which causes problems + * when myVectorPosition2D gets garbage-collected: the C++ vector is freed + * and x holds a dandling pointer. + * With this macro, myVectorPosition2D[i] return a copy of the element. + * + * See bug 3497770 + * https://sourceforge.net/tracker/?func=browse&group_id=1645&atid=101645 + */ +%define RETURN_COPY_FROM_VECTOR(TYPE) +%typemap(out) TYPE & front { + $result = SWIG_NewPointerObj(%new_copy(*$1, $*ltype), $descriptor, + SWIG_POINTER_OWN | %newpointer_flags); + } +%typemap(out) TYPE & back { + $result = SWIG_NewPointerObj(%new_copy(*$1, $*ltype), $descriptor, + SWIG_POINTER_OWN | %newpointer_flags); + } +%typemap(out) TYPE & __getitem__ { + $result = SWIG_NewPointerObj(%new_copy(*$1, $*ltype), $descriptor, + SWIG_POINTER_OWN | %newpointer_flags); + } +%enddef +%module almathswig + +%feature("autodoc", "1"); + +%{ +#include +#include "almath/dsp/digitalfilter.h" +#include "almath/dsp/pidcontroller.h" + +#include "almath/types/alaxismask.h" + +#include "almath/types/alpose2d.h" +#include "almath/types/alposition2d.h" +#include "almath/types/alposition3d.h" +#include "almath/types/alposition6d.h" +#include "almath/types/alpositionandvelocity.h" +#include "almath/types/alquaternion.h" +#include "almath/types/aldisplacement.h" + +#include "almath/types/alrotation.h" +#include "almath/types/alrotation3d.h" + +#include "almath/types/altransform.h" + +#include "almath/types/alvelocity3d.h" +#include "almath/types/alvelocity6d.h" + +#include "almath/types/altransformandvelocity6d.h" + +#include "almath/tools/aldubinscurve.h" +#include "almath/tools/altrigonometry.h" +#include "almath/tools/avoidfootcollision.h" +#include "almath/tools/altransformhelpers.h" +#include "almath/tools/almath.h" + +// forward-declare function that swig will create (thanks to the %extend +// below) and that we use to print some std::vector +static char * AL_Math_Position2D___repr__(AL::Math::Position2D *); +static char * AL_Math_Pose2D___repr__(AL::Math::Pose2D *); +static char * AL_Math_Position6D___repr__(AL::Math::Position6D *); +%} + +RETURN_COPY_FROM_VECTOR(AL::Math::Position2D) +RETURN_COPY_FROM_VECTOR(AL::Math::Pose2D) +RETURN_COPY_FROM_VECTOR(AL::Math::Position6D) + +%include "std_vector.i" +%include "std_string.i" + +namespace std { + %template(vectorFloat) vector; + %template(vectorPosition2D) vector; + %template(vectorPose2D) vector; + %template(vectorPosition6D) vector; + + + %extend vector { + std::string __repr__() { + std::ostringstream out; + out << "vectorFloat(["; + if ($self->size() > 0) { + std::vector::iterator it = $self->begin(); + // print all but the last element + for ( ; it<$self->end()-1; ++it) + out << *it << ", "; + // print the last element, without the trailing ", " + out << *it; + } + out << "])" << std::endl; + return out.str(); + } + } + + %extend vector { + std::string __repr__() { + std::ostringstream out; + out << "vectorPosition2D(["; + if ($self->size() > 0) { + std::vector::iterator it = $self->begin(); + // print all but the last element + for ( ; it<$self->end()-1; ++it) + out << AL_Math_Position2D___repr__(&(*it)) << ", "; + // print the last element, without the trailing ", " + out << AL_Math_Position2D___repr__(&(*it)); + } + out << "])" << std::endl; + return out.str(); + } + } + + %extend vector { + std::string __repr__() { + std::ostringstream out; + out << "vectorPose2D(["; + if ($self->size() > 0) { + std::vector::iterator it = $self->begin(); + // print all but the last element + for ( ; it<$self->end()-1; ++it) + out << AL_Math_Pose2D___repr__(&(*it)) << ", "; + // print the last element, without the trailing ", " + out << AL_Math_Pose2D___repr__(&(*it)); + } + out << "])" << std::endl; + return out.str(); + } + } + + %extend vector { + std::string __repr__() { + std::ostringstream out; + out << "vectorPosition6D(["; + if ($self->size() > 0) { + std::vector::iterator it = $self->begin(); + // print all but the last element + for ( ; it<$self->end()-1; ++it) + out << AL_Math_Position6D___repr__(&(*it)) << ", "; + // print the last element, without the trailing ", " + out << AL_Math_Position6D___repr__(&(*it)); + } + out << "])" << std::endl; + return out.str(); + } + } +} + +%include "almath/dsp/digitalfilter.h" +%include "almath/dsp/pidcontroller.h" + +%include "almath/types/alaxismask.h" + +%include "almath/types/alpose2d.h" +%include "almath/types/alposition2d.h" +%include "almath/types/alposition3d.h" +%include "almath/types/alposition6d.h" +%include "almath/types/alpositionandvelocity.h" +%include "almath/types/alquaternion.h" +%include "almath/types/aldisplacement.h" + +%include "almath/types/alrotation.h" +%include "almath/types/alrotation3d.h" + +%include "almath/types/altransform.h" + +%include "almath/types/alvelocity3d.h" +%include "almath/types/alvelocity6d.h" + +%include "almath/types/altransformandvelocity6d.h" + +%include "almath/tools/aldubinscurve.h" +%include "almath/tools/altrigonometry.h" +%include "almath/tools/avoidfootcollision.h" +%include "almath/tools/altransformhelpers.h" +%include "almath/tools/almath.h" + + +%extend AL::Math::Pose2D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Pose2D(x=%g, y=%g, theta=%g)", + $self->x, $self->y, $self->theta); + return tmp; + } + + AL::Math::Pose2D __rmul__(const float lhs) { + return (*$self) * lhs; + } +}; + +%extend AL::Math::Position2D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Position2D(x=%g, y=%g)", + $self->x, $self->y); + return tmp; + } + + AL::Math::Position2D __rmul__(const float lhs) { + return (*$self) * lhs; + } +}; + + +%extend AL::Math::Position3D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Position3D(x=%g, y=%g, z=%g)", + $self->x, $self->y, $self->z); + return tmp; + } + + AL::Math::Position3D __rmul__(const float lhs) { + return (*$self) * lhs; + } +}; + + +%extend AL::Math::Quaternion { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Quaternion(w=%g, x=%g, y=%g, z=%g)", + $self->w, $self->x, $self->y, $self->z); + return tmp; + } +}; + +%extend AL::Math::Position6D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Position6D(x=%g, y=%g, z=%g, wx=%g, wy=%g, wz=%g)", + $self->x, $self->y, $self->z, + $self->wx, $self->wy, $self->wz); + return tmp; + } + + AL::Math::Position6D __rmul__(const float lhs) { + return (*$self) * lhs; + } +}; + +%extend AL::Math::PositionAndVelocity { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "PositionAndVelocity(q=%g, dq=%g)", + $self->q, $self->dq); + return tmp; + } +}; + + +%extend AL::Math::Rotation { + char *__str__() { + static char tmp[1024]; + sprintf(tmp, "[[%g, %g, %g]\n" + " [%g, %g, %g]\n" + " [%g, %g, %g]]", + $self->r1_c1, $self->r1_c2, $self->r1_c3, + $self->r2_c1, $self->r2_c2, $self->r2_c3, + $self->r3_c1, $self->r3_c2, $self->r3_c3); + return tmp; + } + + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Rotation([%g, %g, %g\n" + " %g, %g, %g\n" + " %g, %g, %g])", + $self->r1_c1, $self->r1_c2, $self->r1_c3, + $self->r2_c1, $self->r2_c2, $self->r2_c3, + $self->r3_c1, $self->r3_c2, $self->r3_c3); + return tmp; + } + + AL::Math::Position3D __mul__(AL::Math::Position3D rhs) const { + return (*$self) * rhs; + } +}; + + +%extend AL::Math::Rotation3D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Rotation3D(wx=%g, wy=%g, wz=%g)", + $self->wx, $self->wy, $self->wz); + return tmp; + } +}; + + +%extend AL::Math::Transform { + char *__str__() { + static char tmp[1024]; + sprintf(tmp, "[[%g, %g, %g, %g]\n" + " [%g, %g, %g, %g]\n" + " [%g, %g, %g, %g]]", + $self->r1_c1, $self->r1_c2, $self->r1_c3, $self->r1_c4, + $self->r2_c1, $self->r2_c2, $self->r2_c3, $self->r2_c4, + $self->r3_c1, $self->r3_c2, $self->r3_c3, $self->r3_c4); + return tmp; + } + + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Transform([%g, %g, %g, %g\n" + " %g, %g, %g, %g\n" + " %g, %g, %g, %g])", + $self->r1_c1, $self->r1_c2, $self->r1_c3, $self->r1_c4, + $self->r2_c1, $self->r2_c2, $self->r2_c3, $self->r2_c4, + $self->r3_c1, $self->r3_c2, $self->r3_c3, $self->r3_c4); + return tmp; + } + + AL::Math::Position3D __mul__(AL::Math::Position3D rhs) const { + return (*$self) * rhs; + } +}; + + +%extend AL::Math::TransformAndVelocity6D { + // TODO: fix these 2 methods + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "TransformAndVelocity6D(T=Transform([%g, %g, %g, %g\n" + " %g, %g, %g, %g\n" + " %g, %g, %g, %g]),\n" + " V=Velocity6D(xd=%g, yd=%g, zd=%g, wxd=%g, wyd=%g, wzd=%g))", + $self->T.r1_c1, $self->T.r1_c2, $self->T.r1_c3, $self->T.r1_c4, + $self->T.r2_c1, $self->T.r2_c2, $self->T.r2_c3, $self->T.r2_c4, + $self->T.r3_c1, $self->T.r3_c2, $self->T.r3_c3, $self->T.r3_c4, + $self->V.xd, $self->V.yd, $self->V.zd, + $self->V.wxd, $self->V.wyd, $self->V.wzd); + return tmp; + } +}; + +%extend AL::Math::Displacement { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Displacement(P=Position3D(x=%g, y=%g, z=%g)\n" + " Q=Quaternion(w=%g, x=%g, y=%g, z=%g))\n", + $self->P.x, $self->P.y, $self->P.z, + $self->Q.w, $self->Q.x, $self->Q.y, $self->Q.z); + return tmp; + } +}; + +%extend AL::Math::Velocity3D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Velocity3D(xd=%g, yd=%g, zd=%g)", + $self->xd, $self->yd, $self->zd); + return tmp; + } + + AL::Math::Velocity3D __rmul__(const float lhs) { + return (*$self) * lhs; + } +}; + +%extend AL::Math::Velocity6D { + char *__repr__() { + static char tmp[1024]; + sprintf(tmp, "Velocity6D(xd=%g, yd=%g, zd=%g, wxd=%g, wyd=%g, wzd=%g", + $self->xd, $self->yd, $self->zd, + $self->wxd, $self->wyd, $self->wzd); + return tmp; + } + + AL::Math::Velocity6D __rmul__(const float lhs) const { + return lhs * (*$self); + } +}; diff --git a/naoModule/libnaoqi_files/include/almath/dsp/digitalfilter.h b/naoModule/libnaoqi_files/include/almath/dsp/digitalfilter.h new file mode 100755 index 0000000..66389ec --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/dsp/digitalfilter.h @@ -0,0 +1,74 @@ +/* + * Copyright (c) 2012-2014 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#pragma once + +#ifndef _LIB_ALMATH_ALMATH_DSP_DIGITALFILTER_H_ +#define _LIB_ALMATH_ALMATH_DSP_DIGITALFILTER_H_ + +#include +#include + +namespace AL +{ +namespace Math +{ +namespace DSP +{ + +class DigitalFilter +{ +public: + DigitalFilter(void); + ~DigitalFilter(void); + + /*! \fn AL::Math::DSP::DigitalFilter::configureFilter( + const int order, + const std::vector & weightsIn, + const std::vector & weightsOut, + const float dcGain) + \brief Configure the digital filter + \param order The order of the filter + \param weightsIn A vector of float describing weights applied on input vector + \param weightsOut A vector of float describing weights applied on output vector + \param dcGain Static gain of the filter + */ + void configureFilter(unsigned int pOrder, + const std::vector & pWeightsIn, + const std::vector & pWeightsOut, + float pDcGain); + + /*! \fn void AL::Math::DSP::DigitalFilter::resetFilter() + \brief Reset the processing of the filter + */ + void resetFilter(); + + /*! \fn float AL::Math::DSP::DigitalFilter::processFilter(const float inputData) + \brief Process a step of the filter + \param in Signal input + */ + float processFilter(float pInputData); + +private: + std::deque fFilterBufferIn; + std::deque fFilterBufferOut; + + unsigned int fFilterOrder; + float fFilterDcGain; + + std::vector fFilterWeightsIn; + std::vector fFilterWeightsOut; + +}; +} +} +} + + + + + +#endif // _LIB_ALMATH_ALMATH_DSP_DIGITALFILTER_H_ diff --git a/naoModule/libnaoqi_files/include/almath/dsp/pidcontroller.h b/naoModule/libnaoqi_files/include/almath/dsp/pidcontroller.h new file mode 100755 index 0000000..32afe80 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/dsp/pidcontroller.h @@ -0,0 +1,70 @@ +/* + * Copyright (c) 2012-2014 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _LIB_ALMATH_ALMATH_DSP_PIDCONTROLLER_H_ +#define _LIB_ALMATH_ALMATH_DSP_PIDCONTROLLER_H_ + + +namespace AL { +namespace Math { + +namespace DSP { +class PIDController +{ + +public : + PIDController(void); + + PIDController(float pKp, + float pKv, + float pKi, + float pThreshold, + float pStaticOffset, + float pPeriod); + + ~PIDController(); + + void initialize(); + + void initialize(float pKp, + float pKv, + float pKi, + float pThreshold, + float pStaticOffset, + float pPeriod); + + float computeFeedback(float pCommand, + float pSensor, + float pPeriod = -1.0f); + float computeFeedbackAbsolute(float pAbsoluteErr); + + +private: + float fKp; + float fKv; + float fKi; + + float fPeriod; + + float fThreshold; + float fStaticOffset; + + float fErr; + float fPreviousErr; + float fdErr; + float fiErr; + + bool fFirstIteration; + + void xResetParameters(void); + void xCheckData(void) const; + void xCheckPositif(float pVal) const; + void xCheckStriclyPositif(float pVal) const; +}; +} +} +} +#endif // _LIB_ALMATH_ALMATH_DSP_PIDCONTROLLER_H_ diff --git a/naoModule/libnaoqi_files/include/almath/tools/aldubinscurve.h b/naoModule/libnaoqi_files/include/almath/tools/aldubinscurve.h new file mode 100755 index 0000000..d67685b --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/tools/aldubinscurve.h @@ -0,0 +1,29 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TOOLS_ALDUBINSCURVE_H_ +#define _LIBALMATH_ALMATH_TOOLS_ALDUBINSCURVE_H_ + +#include +#include + +namespace AL { + namespace Math { + + /// Get the dubins solutions. + /// the target pose + /// the circle radius + /// The dubins solution. + /// \ingroup Tools + std::vector getDubinsSolutions( + const Pose2D& pTargetPose, + const float pCircleRadius); + + } +} +#endif // _LIBALMATH_ALMATH_TOOLS_ALDUBINSCURVE_H_ diff --git a/naoModule/libnaoqi_files/include/almath/tools/almath.h b/naoModule/libnaoqi_files/include/almath/tools/almath.h new file mode 100755 index 0000000..996e4d3 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/tools/almath.h @@ -0,0 +1,438 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TOOLS_ALMATH_H_ +#define _LIBALMATH_ALMATH_TOOLS_ALMATH_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace AL { + namespace Math { + + /// + /// Set an angle between ]-PI, PI]. + /// + /// + /// the input/output angle + /// \ingroup Tools + void modulo2PIInPlace(float& pAngle); + + /// + /// Return an angle between ]-PI, PI]. + /// + /// + /// the input angle + /// + /// Return an angle between ]-PI, PI]. + /// + /// \ingroup Tools + float modulo2PI(float pAngle); + + /// + /// Clip an input data inside min and max limit. + /// + /// \f$ pMin \leq pData \leq pMax \f$ + /// + /// + /// the min limit + /// the max limit + /// the clipped data + /// + /// Return true if the input pData is clipped. + /// + /// \ingroup Tools + bool clipData( + const float& pMin, + const float& pMax, + float& pData); + + bool clipData( + const float& pMin, + const float& pMax, + std::vector& pData); + + bool clipData( + const float& pMin, + const float& pMax, + std::vector >& pData); + + /// + /** \f$ \left[\begin{array}{c} + * pPosOut.x \\ + * pPosOut.y \\ + * pPosOut.theta \\ + * \end{array}\right] + * = + * \left[\begin{array}{cccccc} + * cos(pTheta) & -sin(pTheta) & 0 \\ + * sin(pTheta) & cos(pTheta) & 0 \\ + * 0 & 0 & 1 \\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pPosIn.x \\ + * pPosIn.y \\ + * pPosIn.theta \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given angle in radian + /// a input Pose2D + /// the output Pose2D + /// \ingroup Tools + void changeReferencePose2D( + const float& pTheta, + const Pose2D& pPosIn, + Pose2D& pPosOut); + + /// + /// Change orientation of a Pose2D in place. + /// + /// the given angle in radian + /// the input output Pose2D + /// \ingroup Tools + void changeReferencePose2DInPlace( + const float& pTheta, + Pose2D& pPosOut); + + /// + /// Create a Position6D from a Velocity6D + /// + /** \f$\begin{array}{ccc} + * result.x & = & pVel.xd \\ + * result.y & = & pVel.yd \\ + * result.z & = & pVel.zd \\ + * result.wx & = & pVel.wxd \\ + * result.wy & = & pVel.wyd \\ + * result.wz & = & pVel.wzd + * \end{array} \f$ + */ + /// + /// + /// the given Velocity6D + /// + /// the Position6D result. + /// + /// \ingroup Tools + Position6D position6DFromVelocity6D(const Velocity6D& pVel); + + /// + /// Compute a Position2D from a Pose2D. + /// The theta member of the Pose2D is not taken into account. + /// + /// the Pose2D to extract + /// the result Position2D + /// \ingroup Tools + void position2DFromPose2DInPlace( + const Pose2D& pPose2D, + Position2D& pPosition2D); + + /// + /// Create a Position2D from a Pose2D + /// + /** \f$\begin{array}{ccc} + * result.x & = & pPose2d.x \\ + * result.y & = & pPose2d.y \\ + * \end{array} \f$ + */ + /// + /// + /// the given Pose2D + /// + /// the Position2D result. + /// + /// \ingroup Tools + Position2D position2DFromPose2D(const Pose2D& pPose2D); + + /// + /// Create a Position3D from a Position6D + /// + /** \f$\begin{array}{ccc} + * result.x & = & pPose6d.x \\ + * result.y & = & pPose6d.y \\ + * result.z & = & pPose6d.z \\ + * \end{array} \f$ + */ + /// + /// + /// the given Position6D + /// + /// the Position3D result. + /// + /// \ingroup Tools + Position3D position3DFromPosition6D(const Position6D& pPosition6D); + + /// + /// Overloading of operator * between Rotation and Position3D: + /// + /** \f$\left[\begin{array}{c} + * result.x \\ + * result.y \\ + * result.z + * \end{array}\right] = + * \left[\begin{array}{ccc} + * pRot.r_1c_1 & pRot.r_1c_2 & pRot.r_1c_3 \\ + * pRot.r_2c_1 & pRot.r_2c_2 & pRot.r_2c_3 \\ + * pRot.r_3c_1 & pRot.r_3c_2 & pRot.r_3c_3 + * \end{array}\right] * + * \left[\begin{array}{c} + * pPos.x \\ + * pPos.y \\ + * pPos.z + * \end{array}\right] \f$ + */ + /// + /// + /// the given Rotation + /// the given Position3D + /// + /// the Position3D result. + /// + /// \ingroup Tools + Position3D operator*( + const Rotation& pRot, + const Position3D& pPos); + + /// + /// Overloading of operator * between Quaternion and Position3D + /// + /// the given Quaternion + /// the given Position3D + /// + /// the Position3D result. + /// + /// \ingroup Tools + Position3D operator*( + const Quaternion& pQuat, + const Position3D& pPos); + + + /// + /// Overloading of operator * for float to Position6D, give a Velocity6D: + /// + /** \f$\begin{array}{ccc} + * pVel.xd & = & pVal*pPos.x \\ + * pVel.yd & = & pVal*pPos.y \\ + * pVel.zd & = & pVal*pPos.z \\ + * pVel.wxd & = & pVal*pPos.wx \\ + * pVel.wyd & = & pVal*pPos.wy \\ + * pVel.wzd & = & pVal*pPos.wz + * \end{array} \f$ + */ + /// + /// + /// the given float + /// the given Position6D + /// + /// the Velocity6D + /// + /// \ingroup Tools + Velocity6D operator*( + const float pVal, + const Position6D& pPos); + + /// + /// Overloading of operator * for float to Position3D, give a Velocity3D: + /// + /** \f$\begin{array}{ccc} + * pVel.xd & = & pVal*pPos.x \\ + * pVel.yd & = & pVal*pPos.y \\ + * pVel.zd & = & pVal*pPos.z \\ + * \end{array} \f$ + */ + /// + /// + /// the given float + /// the given Position3D + /// + /// the Velocity3D + /// + /// \ingroup Tools + Velocity3D operator*( + const float pVal, + const Position3D& pPos); + + + /// + /// Creates a 3*3 Rotation Matrix from a an angle and a normalized Position3D. + /// + /// the float value of angle in radian + /// the Position3D direction of the vector of the rotation, normalized + /// + /// the Rotation matrix + /// + /// \ingroup Tools + Rotation rotationFromAngleDirection( + const float& pTheta, + const Position3D& pPos); + + + /// + /// Compute a Position6D from a Pose2D. + /// + /// the Pose2D to extract + /// the result Position6D + /// \ingroup Tools + void position6DFromPose2DInPlace( + const Pose2D& pPose2D, + Position6D& pPosition6D); + + /// + /// Create a Position6D from a Pose2D. + /// + /// the pose2D you want to extract + /// the result Position6D + /// \ingroup Tools + Position6D position6DFromPose2D(const Pose2D& pPose2D); + + /// + /// Compute a Position6D from a Position3D. + /// + /// the Position3D to extract + /// the result Position6D + /// \ingroup Tools + void position6DFromPosition3DInPlace( + const Position3D& pPosition3D, + Position6D& pPosition6D); + + /// + /// Create a Position6D from a Position3D. + /// + /// the position3D you want to extract + /// the result Position6D + /// \ingroup Tools + Position6D position6DFromPosition3D(const Position3D& pPosition3D); + + /// + /// Compute a Pose2D from a Position6D. + /// + /// the Position6D you want to extract + /// the result Pose2D + /// \ingroup Tools + void pose2DFromPosition6DInPlace( + const Position6D& pPosition6D, + Pose2D& pPose2D); + + /// + /// Create a Pose2D from a Position6D. + /// + /// the position6d you want to extract + /// the Pose2D extracted from the Position6D + /// \ingroup Tools + Pose2D pose2DFromPosition6D(const Position6D& pPosition6D); + + /// + /// Compute a Pose2D from a Position2D. + /// pPose2D.x = pPosition2D.x + /// pPose2D.y = pPosition2D.y + /// pPose2D.theta = pAngle + /// + /// the Position2D you want to extract + /// the angle in radians to set pPose2d to + /// the result Pose2D + /// \ingroup Tools + void pose2DFromPosition2DInPlace( + const Position2D& pPosition2D, + const float pAngle, + Pose2D& pPose2D); + + /// + /// Create a Pose2D from a Position2D. + /// + /// the Position2D you want to extract + /// the angle in radians to set the new Pose2D to + /// the Pose2D extracted from the Position2D + /// \ingroup Tools + Pose2D pose2DFromPosition2D(const Position2D& pPosition2D, + const float pAngle=0.0f); + + /// + /// Overloading of operator * for Pose2D to Position2D, give a Position2D: + /// + /** \f$\begin{array}{ccc} + * pRes.x & = & pVal.x + cos(pVal.theta)*pPos.x - sin(pVal.theta)*pPos.y \\ + * pRes.y & = & pVal.y + sin(pVal.theta)*pPos.x + cos(pVal.theta)*pPos.y \\ + * \end{array} \f$ + */ + /// + /// + /// the given Pose2D + /// the given Position2D + /// + /// the Position2D + /// + /// \ingroup Tools + Position2D operator*( + const Pose2D& pVal, + const Position2D& pPos); + + /// + /// Create a Quaternion from a Rotation3D when composed + /// in the following order: Rz(wz) * Ry(wy) * Rx(wx) + /// + /// the rotation3d you want to extract + /// the Quaternion extracted from the Rotation3D + /// \ingroup Tools + void quaternionFromRotation3D( + const Rotation3D& pRot3D, + Quaternion& pQuaternion); + + Quaternion quaternionFromRotation3D( + const Rotation3D& pRot3D); + + /// + /// Create a Rotation Matrix from a Quaternion + /// + /// the quaternion you want to extract + /// the Rotation matrix extracted from the Quaternion + /// \ingroup Tools + void rotationFromQuaternion( + const Quaternion& pQua, + Rotation& pRot); + + Rotation rotationFromQuaternion( + const Quaternion& pQua); + + /// + /// Create a Rotation3D from a Quaternion when composed + /// in the following order: Rz(wz) * Ry(wy) * Rx(wx) + /// + /// the quaternion you want to extract + /// the Rotation3D extracted from the Quaternion + /// \ingroup Tools + void rotation3DFromQuaternion( + const Quaternion& pQuaterion, + Rotation3D& pRot3D); + + Rotation3D rotation3DFromQuaternion( + const Quaternion& pQuaternion); + + /// + /// Convert a Position6D to Quaternion and Position3D + /// + /// the input Position6D you want to extract + /// the Quaternion extracted from Position6D + /// the Position3D extracted from Position6D + /// \ingroup Tools + void quaternionPosition3DFromPosition6D( + const Position6D& pPos6D, + Quaternion& pQua, + Position3D& pPos3D); + + } // namespace Math +} // namespace AL +#endif // _LIBALMATH_ALMATH_TOOLS_ALMATH_H_ diff --git a/naoModule/libnaoqi_files/include/almath/tools/almathio.h b/naoModule/libnaoqi_files/include/almath/tools/almathio.h new file mode 100755 index 0000000..fb30e40 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/tools/almathio.h @@ -0,0 +1,245 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TOOLS_ALMATHIO_H_ +#define _LIBALMATH_ALMATH_TOOLS_ALMATHIO_H_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/// The purpose of grouping ostream operations in one place, is to speed +/// compilation times when not requiring output. +namespace AL { +namespace Math { + +/// +/// Overloading of operator << for Pose2D. +/// +/// +/// the given ostream +/// the given Pose2D +/// +/// the Pose2D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Pose2D& pPos); + +/// +/// Overloading of operator << for Position2D. +/// +/// +/// the given ostream +/// the given Position2D +/// +/// the Position2D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Position2D& pPos); + +/// +/// Overloading of operator << for Position3D. +/// +/// +/// the given ostream +/// the given Position3D +/// +/// the Position3D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Position3D& pPos); + +/// +/// Overloading of operator << for Position6D. +/// +/// +/// the given ostream +/// the given Position6D +/// +/// the Position6D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Position6D& pPos); + +/// +/// Overloading of operator << for PositionAndVelocity. +/// +/// +/// the given ostream +/// the given PositionAndVelocity +/// +/// the PositionAndVelocity print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const PositionAndVelocity& pPosVel); + +/// +/// Overloading of operator << for Rotation. +/// +/// +/// the given ostream +/// the given Rotation +/// +/// the Rotation print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Rotation& pRot); + +/// +/// Overloading of operator << for Rotation3D. +/// +/// +/// the given ostream +/// the given Rotation3D +/// +/// the Rotation3D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Rotation3D& pRot); + +/// +/// Overloading of operator << for Transform. +/// +/// +/// the given ostream +/// the given Transform +/// +/// the Transform print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Transform& pT); + +/// +/// Overloading of operator << for TransformAndVelocity6D. +/// +/// +/// the given ostream +/// the given TransformAndVelocity6D +/// +/// the TransformAndVelocity6D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const TransformAndVelocity6D& pTV); + +/// +/// Overloading of operator << for Velocity3D. +/// +/// +/// the given ostream +/// the given Velocity3D +/// +/// the Velocity3D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Velocity3D& pVel); + +/// +/// Overloading of operator << for Quaternion. +/// +/// +/// the given ostream +/// the given Quaternion +/// +/// the Quaternion print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Quaternion& pQua); + +/// +/// Overloading of operator << for Velocity6D. +/// +/// +/// the given ostream +/// the given Velocity6D +/// +/// the Velocity6D print +/// +/// \ingroup Types +std::ostream& operator<< (std::ostream& pStream, const Velocity6D& pVel); + +/// +/// Create a string of Position3D. +/// +/// +/// the given Position3D +/// +/// the Position3D string +/// +/// \ingroup Types +std::string toSpaceSeparated(const Position3D& pPos); + +/// +/// Create a string of Rotation3D. +/// +/// +/// the given Rotation3D +/// +/// the Rotation3D string +/// +/// \ingroup Types +std::string toSpaceSeparated(const Rotation3D& pPos); + +/// +/// Create a string of Velocity6D. +/// +/// +/// the given Velocity6D +/// +/// the Velocity6D string +/// +/// \ingroup Types +std::string toSpaceSeparated(const Velocity6D& pVel); + +/// +/// Create a string of Transform. +/// +/// +/// the given Transform +/// +/// the Transform string +/// +/// \ingroup Types +std::string toSpaceSeparated(const Transform& pT); + +/// +/// Create a string of Position6D. +/// +/// +/// the given Position6D +/// +/// the Position6D string +/// +/// \ingroup Types +std::string toSpaceSeparated(const Position6D& pPos); + +/// +/// Create a string of Quaternion. +/// +/// +/// the given Transform + /// the given Transform + /// + /// the Velocity6D logarithme: kinematic screw in se3 + /// + /// \ingroup Tools + void transformLogarithmInPlace( + const Transform& pT, + Velocity6D& pVel); + + + /// + /// Compute the logarithme of a transform. + /// Angle must be between \f$\left[-\pi+0.001, \pi-0.001\right] \f$ + /** + * Cette fonction calcule le + * logarithme associe a une matrice de type Deplacement - + * matrice homogene 4x4 (SE3) + * La sortie est un torseur cinematique de se3. + * Le resultat n'est garanti que pour des angles dans [-pi+0.001,pi-0.001]. + * cette fonction calcule la differentielle du logarithme associe + * a une matrice de type Deplacement - matrice homogene 4x4 (SE3). + */ + /// + /// the given Transform + /// + /// the Velocity6D logarithme: kinematic screw in se3 + /// + /// \ingroup Tools + Velocity6D transformLogarithm(const Transform& pT); + + + /// + /// Compute the logarithme of a transform. + /// Angle must be between \f$\left[-\pi+0.001, \pi-0.001\right] \f$ + /** + * Function Velocity Exponential: compute homogenous matrix + * displacement from a dt * 6D velocity vector. + */ + /// + /// the given Velocity6D + /// + /// the Velocity6D logarithme: kinematic screw in se3 + /// + /// \ingroup Tools + Transform velocityExponential(const Velocity6D& pVel); + + // TODO: Add to doc or set private. + void velocityExponentialInPlace( + const Velocity6D& pVel, + Transform& pT); + + /// + /** \f$ \left[\begin{array}{c} + * pVOut.xd \\ + * pVOut.yd \\ + * pVOut.zd \\ + * pVOut.wxd \\ + * pVOut.wyd \\ + * pVOut.wzd \\ + * \end{array}\right] + * = + * \left[\begin{array}{cccccc} + * r_1c_1 & r_1c_2 & r_1c_3 & 0 & 0 & 0 \\ + * r_2c_1 & r_2c_2 & r_2c_3 & 0 & 0 & 0 \\ + * r_3c_1 & r_3c_2 & r_3c_3 & 0 & 0 & 0 \\ + * 0 & 0 & 0 & r_1c_1 & r_1c_2 & r_1c_3 \\ + * 0 & 0 & 0 & r_2c_1 & r_2c_2 & r_2c_3 \\ + * 0 & 0 & 0 & r_3c_1 & r_3c_2 & r_3c_3 \\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pVIn.xd \\ + * pVIn.yd \\ + * pVIn.zd \\ + * pVIn.wxd \\ + * pVIn.wyd \\ + * pVIn.wzd \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// a Velocity6D containing the velocity + /// to change + /// + /// a Velocity6D containing the changed velocity + /// + /// \ingroup Tools + void changeReferenceVelocity6D( + const Transform& pT, + const Velocity6D& pVelIn, + Velocity6D& pVelOut); + + /// + /** \f$ \left[\begin{array}{c} + * pPOut.x \\ + * pPOut.y \\ + * pPOut.z \\ + * pPOut.wx \\ + * pPOut.wy \\ + * pPOut.wz \\ + * \end{array}\right] + * = + * \left[\begin{array}{cccccc} + * r_1c_1 & r_1c_2 & r_1c_3 & 0 & 0 & 0 \\ + * r_2c_1 & r_2c_2 & r_2c_3 & 0 & 0 & 0 \\ + * r_3c_1 & r_3c_2 & r_3c_3 & 0 & 0 & 0 \\ + * 0 & 0 & 0 & r_1c_1 & r_1c_2 & r_1c_3 \\ + * 0 & 0 & 0 & r_2c_1 & r_2c_2 & r_2c_3 \\ + * 0 & 0 & 0 & r_3c_1 & r_3c_2 & r_3c_3 \\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pPIn.x \\ + * pPIn.y \\ + * pPIn.z \\ + * pPIn.wx \\ + * pPIn.wy \\ + * pPIn.wz \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// a Position6D containing the position + /// to change + /// + /// a Position6D containing the changed position + /// + /// \ingroup Tools + void changeReferencePosition6D( + const Transform& pT, + const Position6D& pPosIn, + Position6D& pPosOut); + + // TODO: rename argument. + void changeReferencePosition3DInPlace( + const Transform& pT, + Position3D& pPosOut); + + // TODO: rename argument. + void changeReferenceTransposePosition3DInPlace( + const Transform& pT, + Position3D& pPosOut); + + /// + /** \f$ \left[\begin{array}{c} + * pPosOut.x \\ + * pPosOut.y \\ + * pPosOut.z \\ + * \end{array}\right] + * = + * \left[\begin{array}{ccc} + * r_1c_1 & r_1c_2 & r_1c_3\\ + * r_2c_1 & r_2c_2 & r_2c_3\\ + * r_3c_1 & r_3c_2 & r_3c_3\\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pPosIn.x \\ + * pPosIn.y \\ + * pPosIn.z \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// a Position3D containing the position + /// to change + /// + /// a Position3D containing the changed position + /// + /// \ingroup Tools + void changeReferencePosition3D( + const Transform& pT, + const Position3D& pPosIn, + Position3D& pPosOut); + + /// + /** \f$ \left[\begin{array}{c} + * pTOut \\ + * \end{array}\right] + * = + * \left[\begin{array}{c} + * pT + * \end{array}\right] + * \left[\begin{array}{c} + * pTIn \\ + * \end{array}\right]^T + * \f$ + */ + /// + /// the given Transform + /// a Position3D containing the position to change + /// + /// a Position3D containing the changed position + /// + /// \ingroup Tools + void changeReferenceTransposePosition3D( + const Transform& pT, + const Position3D& pPosIn, + Position3D& pPosOut); + + /// + /** \f$ \left[\begin{array}{c} + * pTOut \\ + * \end{array}\right] + * = + * \left[\begin{array}{c} + * pT + * \end{array}\right] + * \left[\begin{array}{c} + * pTIn \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// the Transform to change + /// + /// the changed Transform + /// + /// \ingroup Tools + void changeReferenceTransform( + const Transform& pT, + const Transform& pTIn, + Transform& pTOut); + + /// + /** \f$ \left[\begin{array}{c} + * pTOut \\ + * \end{array}\right] + * = + * \left[\begin{array}{c} + * pT + * \end{array}\right] + * \left[\begin{array}{c} + * pTIn \\ + * \end{array}\right]^T + * \f$ + */ + /// + /// the given Transform + /// the Transform to change + /// + /// the changed Transform + /// + /// \ingroup Tools + void changeReferenceTransposeTransform( + const Transform& pT, + const Transform& pTIn, + Transform& pTOut); + + + /// + /** \f$ \left[\begin{array}{c} + * pVOut.xd \\ + * pVOut.yd \\ + * pVOut.zd \\ + * pVOut.wxd \\ + * pVOut.wyd \\ + * pVOut.wzd \\ + * \end{array}\right] + * = + * \left[\begin{array}{cccccc} + * r_1c_1 & r_2c_1 & r_3c_1 & 0 & 0 & 0 \\ + * r_1c_2 & r_2c_2 & r_3c_2 & 0 & 0 & 0 \\ + * r_1c_3 & r_2c_3 & r_3c_3 & 0 & 0 & 0 \\ + * 0 & 0 & 0 & r_1c_1 & r_2c_1 & r_3c_1 \\ + * 0 & 0 & 0 & r_1c_2 & r_2c_2 & r_3c_2 \\ + * 0 & 0 & 0 & r_1c_3 & r_2c_3 & r_3c_3 \\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pVIn.xd \\ + * pVIn.yd \\ + * pVIn.zd \\ + * pVIn.wxd \\ + * pVIn.wyd \\ + * pVIn.wzd \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// a Velocity6D containing the velocity + /// to change + /// + /// a Velocity6D containing the changed velocity + /// + /// \ingroup Tools + void changeReferenceTransposeVelocity6D( + const Transform& pT, + const Velocity6D& pVelIn, + Velocity6D& pVelOut); + + /// + /** \f$ \left[\begin{array}{c} + * pPOut.x \\ + * pPOut.y \\ + * pPOut.z \\ + * pPOut.wx \\ + * pPOut.wy \\ + * pPOut.wz \\ + * \end{array}\right] + * = + * \left[\begin{array}{cccccc} + * r_1c_1 & r_2c_1 & r_3c_1 & 0 & 0 & 0 \\ + * r_1c_2 & r_2c_2 & r_3c_2 & 0 & 0 & 0 \\ + * r_1c_3 & r_2c_3 & r_3c_3 & 0 & 0 & 0 \\ + * 0 & 0 & 0 & r_1c_1 & r_2c_1 & r_3c_1 \\ + * 0 & 0 & 0 & r_1c_2 & r_2c_2 & r_3c_2 \\ + * 0 & 0 & 0 & r_1c_3 & r_2c_3 & r_3c_3 \\ + * \end{array}\right] + * + * \left[\begin{array}{c} + * pPIn.x \\ + * pPIn.y \\ + * pPIn.z \\ + * pPIn.wx \\ + * pPIn.wy \\ + * pPIn.wz \\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Transform + /// a Position6D containing the position + /// to change + /// + /// a Position6D containing the changed position + /// + /// \ingroup Tools + void changeReferenceTransposePosition6D( + const Transform& pT, + const Position6D& pPosIn, + Position6D& pPosOut); + + /// + /// Preform a logarithmic mean of pTIn1 and pTIn2 and put it in pTout. + /// + /// the first given Transform + /// the second given Transform + /// the value between 0 and 1 used in the logarithmic + /// mean + /// the output Transform. + /// + /// \ingroup Tools + void transformMeanInPlace( + const Transform& pTIn1, + const Transform& pTIn2, + const float& pVal, + Transform& pTOut); + + /// + /// Preform a logarithmic mean of pTIn1 and pTIn2. + /// + /// cartesian coordinates + /// the given Transform + /// the value between 0 and 1 used in the logarithmic + /// mean, 0.5 by default + /// + /// a Transform with the mean of pTIn1 and pTIn2 + /// + /// \ingroup Tools + Transform transformMean( + const Transform& pTIn1, + const Transform& pTIn2, + const float& pVal = 0.5f); + + /// + /// Create a Transform from 3D cartesian coordiantes and a Rotation. + /** + * \f$ T = \left[\begin{array}{cccc} + * pRot.r_1c_1 & pRot.r_1c_2 & pRot.r_1c_3 & pX \\ + * pRot.r_2c_1 & pRot.r_2c_2 & pRot.r_2c_3 & pY \\ + * pRot.r_3c_1 & pRot.r_3c_2 & pRot.r_3c_3 & pZ \\ + * 0.0 & 0.0 & 0.0 & 1.0 \end{array}\right] \f$ + */ + /// + /// the given Rotation + /// the translation along x axis + /// the translation along y axis + /// the translation along z axis + /// + /// the Transform result. + /// + /// \ingroup Tools + Transform transformFromRotationPosition3D( + const Rotation& pRot, + const float& pX, + const float& pY, + const float& pZ); + + /// + /// Create a Transform from a Position3D and a Rotation. + /** \f$ T = \left[\begin{array}{cccc} + * pRot.r_1c_1 & pRot.r_1c_2 & pRot.r_1c_3 & pPos.x \\ + * pRot.r_2c_1 & pRot.r_2c_2 & pRot.r_2c_3 & pPos.y \\ + * pRot.r_3c_1 & pRot.r_3c_2 & pRot.r_3c_3 & pPos.z \\ + * 0.0 & 0.0 & 0.0 & 1.0 \end{array}\right] \f$ + */ + /// + /// the given Position3D + /// the given Rotation + /// + /// the Transform result. + /// + /// \ingroup Tools + Transform transformFromRotationPosition3D( + const Rotation& pRot, + const Position3D& pPos); + + /// + /// Modify pTransform to set the translation part to pPosition. + /** \f$ + * \left[\begin{array}{c} + * Transform \\ + * \end{array}\right] + * = + * \left[\begin{array}{cc} + * pRotation& *_{3,1}\\ + * 0_{1,3} & 1\\ + * \end{array}\right] + * \f$ + */ + /// + /// a Position3D cartesian coordinates + /// the given Transform + /// \ingroup Tools + void transformFromPosition3DInPlace( + const Position3D& pPosition, + Transform& pTransform); + + /// + /// Create a 4*4 transform matrix from cartesian coordinates + /// given in pPosition. + /** \f$ + * \left[\begin{array}{c} + * Transform \\ + * \end{array}\right] + * = + * \left[\begin{array}{cc} + * pRotation& *_{3,1}\\ + * 0_{1,3} & 1\\ + * \end{array}\right] + * \f$ + */ + /// + /// position in cartesian coordinates + /// + /// a Transform with the translation part initialized to pPosition, rotation + /// part is set to identity + /// + /// \ingroup Tools + Transform transformFromPosition3D(const Position3D& pPosition); + + /// + /// Modify the rotation part of the transform. + /// The translation part of the transform is not modified. + /** \f$ + * \left[\begin{array}{c} + * Transform \\ + * \end{array}\right] + * = + * \left[\begin{array}{cc} + * pRotation& *_{3,1}\\ + * 0_{1,3} & 1\\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Rotation + /// the Transform to modify + /// \ingroup Tools + void transformFromRotationInPlace( + const Rotation& pRotation, + Transform& pTransform); + + /// + /** \f$ + * \left[\begin{array}{c} + * Transform \\ + * \end{array}\right] + * = + * \left[\begin{array}{cc} + * pRotation& 0_{3,1}\\ + * 0_{1,3} & 1\\ + * \end{array}\right] + * \f$ + */ + /// + /// the given Rotation + /// + /// a Transform with the rotation part initialized to pRotation + /// + /// \ingroup Tools + Transform transformFromRotation(const Rotation& pRotation); + + /// + /// Extract the position coordinates from a Transform. + /// + /// the given transform + /// a Rotation to be set with the reslut + /// \ingroup Tools + void rotationFromTransformInPlace( + const Transform& pTransform, + Rotation& pRotation); + + /// + /// + /// + /// position in cartesian coordinates + /// + /// the Rotation extracted from the Transform + /// + /// \ingroup Tools + Rotation rotationFromTransform(const Transform& pTransform); + + /// + /// return 3 angles which result in the equivalent rotation when composed + /// in the following order: Rz(wz) * Ry(wy) * Rx(wx) = R + /// + /// the Rotation to extract + /// + /// the Rotation3D extracted from pRotation + /// + /// \ingroup Tools + Rotation3D rotation3DFromRotation(const Rotation& pRotation); + + /// + /// Compute Position6D corresponding to the Transform. + /// + /// the transform you want to extract + /// the transform you want to extract + /// \ingroup Tools + void position6DFromTransformInPlace( + const Transform& pT, + Position6D& pPos); + + /// + /// Compute Position6D corresponding to 4*4 Homogenous Transform. + /// + /// the transform you want to extract + /// the extracted Position6D + /// \ingroup Tools + Position6D position6DFromTransform(const Transform& pT); + + /// + /// Compute a Transform from a Pose2D. + /// + /// the Pose2D to extract + /// the result Transform + /// \ingroup Tools + void transformFromPose2DInPlace( + const Pose2D& pPose, + Transform& pT); + + /// + /// Create a Transform from a Pose2D. + /// + /// the pose2D you want to extract + /// the result Transform + /// \ingroup Tools + Transform transformFromPose2D(const Pose2D& pPose); + + /// + /// Compute a Pose2D from a Transform. + /// + /// the Transform you want to extract + /// the result Pose2D + /// \ingroup Tools + void pose2DFromTransformInPlace( + const Transform& pT, + Pose2D& pPos); + + /// + /// Create a Pose2D from a Transform. + /// + /// the transform you want to extract + /// the Pose2D extracted from the Transform + /// \ingroup Tools + Pose2D pose2DFromTransform(const Transform& pT); + + /// + /// Compute a Position2D from a Transform. + /// + /// the Transform you want to extract + /// the result Position2D + /// \ingroup Tools + void position2DFromTransformInPlace( + const Transform& pT, + Position2D& pPos); + + /// + /// Create a Position2D from a Transform. + /// + /// the transform you want to extract + /// the Position2D extracted from the Transform + /// \ingroup Tools + Position2D position2DFromTransform(const Transform& pT); + + /// + /// Create a Transform from the 3 angles stored in a Rotation3D. + /// The angles are composed in the following order: + /// Rz(wz) * Ry(wy) * Rx(wx) = R + /// + /// the Rotation you want to extract + /// the result Transform + /// \ingroup Tools + Transform transformFromRotation3D(const Rotation3D& pRotation); + + /// + /// Create a Transform from a Position6D. + /// + /// the Position6D you want to extract + /// the result Transform + /// \ingroup Tools + Transform transformFromPosition6D(const Position6D& pPosition6D); + + /// + /// Computes a 6 differential motion require to move + /// from a 4*4 Homogenous transform matrix Current to + /// a 4*4 Homogenous transform matrix target. + /// + /// For instance, one would do + /// + /// Position6D P_a; + /// position6DFromTransformDiffInPlace(H_ab, H_ac, P) + /// + /// Now P contains (an approximation of) the dispacement from the frame b + /// to the frame c, expressed at the origin of frame b, and in the basis + /// of frame a + /// + /// the Position6D you want to extract + /// the Position6D you want to extract + /// the result Position6D + /// \ingroup Tools + void position6DFromTransformDiffInPlace( + const Transform& pCurrent, + const Transform& pTarget, + Position6D& result); + + /// + /// Computes a 6 differential motion require to move + /// from a 4*4 Homogenous transform matrix Current to + /// a 4*4 Homogenous transform matrix target. + /// + /// the Position6D you want to extract + /// the Position6D you want to extract + /// the result Position6D + /// \ingroup Tools + Position6D position6DFromTransformDiff( + const Transform& pCurrent, + const Transform& pTarget); + + /// + /// Compute a Position3D from a Transform. + /// + /** \f$ + * \left[\begin{array}{c} + * pPos.x \\ + * pPos.y \\ + * pPos.z \\ + * \end{array}\right] + * = + * \left[\begin{array}{c} + * pT.r_1c_4 \\ + * pT.r_2c_4 \\ + * pT.r_3c_4 \\ + * \end{array}\right] + * \f$ + */ + /// + /// the Transform you want to extract + /// the result Position3D + /// \ingroup Tools + void position3DFromTransformInPlace( + const Transform& pT, + Position3D& pPos); + + /// + /// Create a Position3D from a Transform. + /// + /** \f$ + * \left[\begin{array}{c} + * return.x \\ + * return.y \\ + * return.z \\ + * \end{array}\right] + * = + * \left[\begin{array}{c} + * pT.r_1c_4 \\ + * pT.r_2c_4 \\ + * pT.r_3c_4 \\ + * \end{array}\right] + * \f$ + */ + /// + /// the Transform you want to extract + /// the result Position6D + /// \ingroup Tools + Position3D position3DFromTransform(const Transform& pT); + + + /// + /// Create a Rotation3D (Roll, Pitch, Yaw) corresponding to the rotational + /// part of the Transform. + /// R = Rz(wz) * Ry(wy) * Rx(wx) + /// + /// the Transform you want to extract + /// the result Rotation3D + /// \ingroup Tools + Rotation3D rotation3DFromTransform(const Transform& pT); + + /// + /// Compute a Transform from + /// + /// the Rotation you want to extract + /// the rotation you want to extract + /// the Position3D you want to extract + /// the Rotation you want to extract + /// \ingroup Tools + void transformFromRotVecInPlace( + const int pAxis, + const float pTheta, + const Position3D& pPos, + Transform& pT); + + /// + /// + /// the Rotation you want to extract + /// the Rotation you want to extract + /// the Rotation you want to extract + /// the result Transform + /// \ingroup Tools + Transform transformFromRotVec( + const int pAxis, + const float pTheta, + const Position3D& pPos); + + + /// + /// + /// the Rotation you want to extract + /// the Rotation you want to extract + /// \ingroup Tools + void transformFromRotVecInPlace( + const Position3D& pPos, + Transform& pT); + + /// + /// + /// the Rotation you want to extract + /// the result Transform + /// \ingroup Tools + Transform transformFromRotVec(const Position3D& pPos); + + /// + /// + /// the Rotation you want to extract + /// the Rotation you want to extract + + /// the result Transform + /// \ingroup Tools + Transform transformFromRotVec( + const int& pAxis, + const float& pTheta); + + Position3D operator*( + const Transform& pT, + const Position2D& pPos); + + Position3D operator*( + const Transform& pT, + const Position3D& pPos); + + /** + * Function axisRotationProjection: + * finding the closest rotation Rw of R around an axis (Position3D) + * @param pAxis: axis of rotation + * @param pT: a transform + * @return Transform + **/ + Transform axisRotationProjection( + const Position3D& pAxis, + const Transform& pT); + + /** + * Function axisRotationProjection: + * finding the closest rotation Rw of R around an axis (Position3D) + * @param pAxis: axis of rotation + * @param pRot: a rotation + * @return Rotation + **/ + Rotation axisRotationProjection( + const Position3D& pAxis, + const Rotation& pRot); + + + /** + * Function axisRotationProjectionInPlace: + * finding the closest rotation Rw of R around an axis (Position3D) + * @param pAxis: axis of rotation + * @param pT: a transform + **/ + void axisRotationProjectionInPlace( + const Position3D& pAxis, + Transform& pT); + + /** + * Function axisRotationProjectionInPlace: + * finding the closest rotation Rw of R around an axis (Position3D) + * @param pAxis: axis of rotation + * @param pRot: a rotation + **/ + void axisRotationProjectionInPlace( + const Position3D& pAxis, + Rotation& pRot); + + /** + * Function orthogonalSpace: + * create an orthonormal direct base from a vector (Position3D) + * @param pPos: a vector of direction + * @param pTf: the result transform + **/ + void orthogonalSpace( + const Position3D& pPos, + Transform& pTf); + + Transform orthogonalSpace(const Position3D& pPos); + + Transform transformFromQuaternion( + const Quaternion& pQua); + + Quaternion quaternionFromTransform( + const Transform& pT); + + /** + * Function transformFromDisplacement: + * computing the transform equivalent to the displacement + * @param pDisp: a displacement + * @return computed Transform + **/ + Transform transformFromDisplacement(const Displacement& pDisp); + + /** + * Function displacementFromTransform: + * computing the displacement equivalent to the transform + * @param pTrans: a transform + * @return computed Displacement + **/ + Displacement displacementFromTransform(const Transform& pTrans); + + } // namespace Math +} // namespace AL +#endif // _LIBALMATH_ALMATH_TOOLS_ALTRANSFORMHELPERS_H_ diff --git a/naoModule/libnaoqi_files/include/almath/tools/altrigonometry.h b/naoModule/libnaoqi_files/include/almath/tools/altrigonometry.h new file mode 100755 index 0000000..d433466 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/tools/altrigonometry.h @@ -0,0 +1,24 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TOOLS_ALTRIGONOMETRY_H_ +#define _LIBALMATH_ALMATH_TOOLS_ALTRIGONOMETRY_H_ + +namespace AL { + namespace Math { + + static const float _4_PI_ = 12.56637056f; + static const float _2_PI_ = 6.28318528f; + static const float PI = 3.14159265358979323846f; + static const float PI_2 = 1.57079632679489661923f; + static const float PI_4 = 0.785398163397448309616f; + static const float TO_RAD = 0.017453292f; + static const float TO_DEG = 57.295779579f; + } +} +#endif // _LIBALMATH_ALMATH_TOOLS_ALTRIGONOMETRY_H_ diff --git a/naoModule/libnaoqi_files/include/almath/tools/avoidfootcollision.h b/naoModule/libnaoqi_files/include/almath/tools/avoidfootcollision.h new file mode 100755 index 0000000..aa3c885 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/tools/avoidfootcollision.h @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TOOLS_AVOIDFOOTCOLLISION_H_ +#define _LIBALMATH_ALMATH_TOOLS_AVOIDFOOTCOLLISION_H_ + +#include +#include +#include + +namespace AL +{ + namespace Math + { + /// + /// Compute the best position(orientation) of the foot to avoid collision. + /// + /// vector of the left footBoundingBox. + /// vector of the right footBoundingBox. + /// Bool true if left is the support leg. + /// the desired and return Pose2D. + /// + /// true if pMove is clamped. + /// + /// \ingroup Tools + const bool avoidFootCollision( + const std::vector& pLFootBoundingBox, + const std::vector& pRFootBoundingBox, + const bool& pIsLeftSupport, + Pose2D& pMove); + + + /// + /// Clip foot move with ellipsoid function + /// + /// float of the max step along x axis. + /// float of the max step along y axis. + /// the desired and return Pose2D. + /// + /// true if pMove is clamped. + /// + /// \ingroup Tools + const bool clipFootWithEllipse( + const float& pMaxFootX, + const float& pMaxFootY, + Pose2D& pMove); + + // Query if the box A and the box B are in collision. + // vector of the box A. + // vector of the box B. + // true if box A and the box B are in collision. + const bool areTwoBoxesInCollision( + const std::vector& pBoxA, + const std::vector& pBoxB); + + // Compute the box point due to a move. + // vector of the fixed box. + // Pose2D the initial move. + // vector the new box. + void computeBox( + const std::vector& pInitBox, + const Pose2D& pMove, + std::vector& pMovedBox); + + // Compute the best orientation of the moving box without + // collsion with fixed box. + // vector of the fixed box. + // vector of the moving box. + // Pose2D of moving box respect to fix box. + // Pose2D, the best position. + const void dichotomie( + const std::vector& pFixedBox, + const std::vector& pMovingBox, + Pose2D& pMove); + + // Checks if segment A intersects segment B. + // first point of segment A. + // second point of segment A. + // first point of segment B. + // second point of segment B. + // computed intersection point. + // true if the segments intersect in a single point (pC). + bool intersectionSegment2D( + const Position2D &pA1, + const Position2D &pA2, + const Position2D &pB1, + const Position2D &pB2, + Position2D &pC); + + } // namespace Math +} // namespace AL + +#endif // _LIBALMATH_ALMATH_TOOLS_AVOIDFOOTCOLLISION_H_ + diff --git a/naoModule/libnaoqi_files/include/almath/types/alaxismask.h b/naoModule/libnaoqi_files/include/almath/types/alaxismask.h new file mode 100755 index 0000000..86e190e --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alaxismask.h @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALAXISMASK_H_ +#define _LIBALMATH_ALMATH_TYPES_ALAXISMASK_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Definition of an AXIS_MASK as a bit set. + /// + /// static const int AXIS_MASK_X = 1 \n + /// static const int AXIS_MASK_Y = 2 \n + /// static const int AXIS_MASK_XY = 3 \n + /// static const int AXIS_MASK_Z = 4 \n + /// static const int AXIS_MASK_WX = 8 \n + /// static const int AXIS_MASK_WY = 16 \n + /// static const int AXIS_MASK_WZ = 32 \n + /// static const int AXIS_MASK_WYWZ = 48 \n + /// static const int AXIS_MASK_ALL = 63 \n + /// static const int AXIS_MASK_VEL = 7 \n + /// static const int AXIS_MASK_ROT = 56 \n + /// static const int AXIS_MASK_NONE = 0 \n + /// + /// \ingroup Types + typedef std::bitset<6> AXIS_MASK; + + static const int AXIS_MASK_X = 1; + static const int AXIS_MASK_Y = 2; + static const int AXIS_MASK_XY = 3; + static const int AXIS_MASK_Z = 4; + static const int AXIS_MASK_WX = 8; + static const int AXIS_MASK_WY = 16; + static const int AXIS_MASK_WZ = 32; + static const int AXIS_MASK_WYWZ = 48; + static const int AXIS_MASK_ALL = 63; + static const int AXIS_MASK_VEL = 7; + static const int AXIS_MASK_ROT = 56; + static const int AXIS_MASK_NONE = 0; + + /// Validates an AxisMask. + /// An Axis Mask. + /// true if it succeeds, false if it fails. + bool isAxisMask(const int pAxisMask); + + } +} +#endif // _LIBALMATH_ALMATH_TYPES_ALAXISMASK_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/aldisplacement.h b/naoModule/libnaoqi_files/include/almath/types/aldisplacement.h new file mode 100755 index 0000000..908f05d --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/aldisplacement.h @@ -0,0 +1,81 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef ALDISPLACEMENT_H +#define ALDISPLACEMENT_H + +#include +#include + +namespace AL { + namespace Math { + + /// + /// Struct composed of a Position3D and a Quaternion + /// + struct Displacement + { + /// Translation of the Displacement + Position3D P; + /// Rotation of the Displacement + Quaternion Q; + + /// + /// Create a Displacement initialized with default values + /// + explicit Displacement(); + + /// + /// Create a Displacement with the given Position3D and Quaternion + /// + /// the pose of the created Displacement + /// + /// the rotation of the created Displacement - default: identity + /// + Displacement( + const Position3D& pos3d, + const Quaternion& quat = Quaternion()); + + /// + /// Defining composition of Displacement with * sign + /// + /// the displacement that is composed with the + /// current displacement + /// + /// The composed Displacement + /// + Displacement& operator*=(const Displacement& pDisp); + + /// + /// Define the binary operation of a composition of Displacements. + /// + /// second operand of the composition + /// + /// The resulting Displacement + /// + Displacement operator*(const Displacement& pDisp); + + /// + /// Check if the current Displacement is Near the one + /// given in argument. + /// + /// the second Displacement + /// an optional epsilon distance + /// + /// true if the distance between the two Displacement is less than pEpsilon + /// + bool isNear( + const Displacement& pDisp2, + const float pEpsilon=0.0001f) const; + + }; + + } +} + +#endif // ALDISPLACEMENT_H diff --git a/naoModule/libnaoqi_files/include/almath/types/alpose2d.h b/naoModule/libnaoqi_files/include/almath/types/alpose2d.h new file mode 100755 index 0000000..3a0a097 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alpose2d.h @@ -0,0 +1,407 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALPOSE2D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALPOSE2D_H_ + +#include +#include + +namespace AL { + namespace Math { + + /// + /// A pose in a 2-dimentional space. + /// + /// On a plane a position is totally defined + /// by the postions x,y and the rotation theta. + /// + /// \ingroup Types + struct Pose2D { + /// + float x; + /// + float y; + /// + float theta; + + /// + /// Create a Pose2D initialized with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * theta + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Pose2D(); + + /// + /// Create a Pose2D initialize with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * theta + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// the float value for each member + /// + explicit Pose2D(float pInit); + + /// + /// Create a Pose2D initialized with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * theta + * \end{array}\right] = + * \left[\begin{array}{c} + * pX \\ + * pY \\ + * pTheta + * \end{array}\right]\f$ + */ + /// + /// the float value for x + /// the float value for y + /// the float value for theta + explicit Pose2D( + float pX, + float pY, + float pTheta); + + /// + /// Create a Pose2D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * theta + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 3 for respectively: + /// + /// x, y and theta + /// + Pose2D(const std::vector& pFloats); + + /// + /// Create a Pose2D from polar coordinates. + /// + /// the polar radius + /// the polar angle in radians + /// the Pose2D extracted from the polar coordinates + /// \ingroup Tools + static Pose2D fromPolarCoordinates(const float pRadius, const float pAngle); + + /// + /// Overloading of operator + for Pose2D. + /// + /// the second Pose2D + inline Pose2D operator+ (const Pose2D& pPos2) const + { + return Pose2D(x + pPos2.x, y + pPos2.y, theta + pPos2.theta); + } + + /// + /// Overloading of operator - for Pose2D. + /// + /// the second Pose2D + inline Pose2D operator- (const Pose2D& pPos2) const + { + return Pose2D(x - pPos2.x, y - pPos2.y, theta - pPos2.theta); + } + + /// + /// Overloading of operator + for Pose2D. + /// + inline Pose2D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Pose2D. + /// + inline Pose2D operator- () const + { + return Pose2D(-x, -y, -theta); + } + + /// + /// Overloading of operator += for Pose2D. + /// + /// the second Pose2D + Pose2D& operator+= (const Pose2D& pPos2); + + /// + /// Overloading of operator -= for Pose2D. + /// + /// the second Pose2D + Pose2D& operator-= (const Pose2D& pPos2); + + /// + /// Overloading of operator *= for Pose2D. + /// + /// the second Pose2D + Pose2D& operator*= (const Pose2D& pPos2); + + /// + /// Overloading of operator * for Pose2D. + /// + /// the second Pose2D + inline Pose2D operator* (const Pose2D& pPos2) const + { + return Pose2D( + x + std::cos(theta) * pPos2.x - std::sin(theta) * pPos2.y, + y + std::sin(theta) * pPos2.x + std::cos(theta) * pPos2.y, + theta + pPos2.theta); + } + + /// + /// Overloading of operator == for Pose2D. + /// + /// the second Pose2D + bool operator==(const Pose2D& pPos2) const; + + /// + /// Overloading of operator != for Pose2D. + /// + /// the second Pose2D + bool operator!=(const Pose2D& pPos2) const; + + /// + /// Overloading of operator * for Pose2D. + /// + /// the float factor + inline Pose2D operator* (float pVal) const + { + return Pose2D(x*pVal, y*pVal, theta*pVal); + } + + /// + /// Overloading of operator / for Pose2D. + /// + /// the float factor + Pose2D operator/ (float pVal) const; + + /// + /// Overloading of operator *= for Pose2D. + /// + /// the float factor + Pose2D& operator*= (float pVal); + + /// + /// Overloading of operator /= for Pose2D. + /// + /// the float factor + Pose2D& operator/= (float pVal); + + /// + /// Compute the squared distance between the actual + /// Pose2D and the one give in argument. + /// + /// This avoids doing the sqrt needed for a true distance. + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2\f$ + /// + /// the second Pose2D + /// + /// the float squared distance between the two Pose2D + /// + float distanceSquared(const Pose2D& pPos2) const; + + /// + /// Compute the distance between the actual + /// Pose2D and the one give in argument. + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2}\f$ + /// + /// the second Pose2D + /// + /// the float distance between the two Pose2D + /// + float distance(const Pose2D& pPos2) const; + + /// + /// Return the inverse of the Pose2D + /// + Pose2D inverse() const; + + /// + /// Compute the Pose2D between the actual + /// Pose2D and the one given in argument: + /// + /// result: inverse(pPos1)*pPos2 + /// + /// + /// the second Pose2D + Pose2D diff(const Pose2D& pPos2) const; + + /// + /// Check if the actual Pose2D is near the one + /// given in argument. + /// + /// + /// the second Pose2D + /// an optionnal epsilon distance - default: 0.0001 + /// + /// true if the distance between the two Pose2D is less than pEpsilon + /// + bool isNear(const Pose2D& pPos2, + const float& pEpsilon=0.0001f) const; + + /// + /// Return the Pose2D as a vector of float [x, y, theta]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + + /// + /// Compute the norm of the current Pose2D. + /// + /// result: $$/sqrt(pose.x^{2} + pose.y^{2})$$ + /// + /// + inline float norm() const + { + return std::sqrt(x * x + y * y); + } + + /// + /// Normalize the current Pose2D position. + /// + /// \f$pRes = \frac{pPos}{norm(pPos)}\f$ + /// + /// + /// the Pose2D normalized + /// + Pose2D normalize() const; + + /// + /// Returns the angle of the current Pose2D. + /// + /// result: $$/atan2(pose.y, pose.x)$$ + /// + /// + inline float getAngle(void) const + { + return std::atan2(y, x); + } + }; // end struct + + + /// + /// Compute the squared distance between two Pose2D. + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2\f$ + /// + /// the first Pose2D + /// the second Pose2D + /// + /// the float squared distance between the two Pose2D + /// + /// \ingroup Types + float distanceSquared( + const Pose2D& pPos1, + const Pose2D& pPos2); + + /// + /// Compute the distance between two Pose2D. + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2}\f$ + /// + /// the first Pose2D + /// the second Pose2D + /// + /// the float distance between the two Pose2D + /// + /// \ingroup Types + float distance( + const Pose2D& pPos1, + const Pose2D& pPos2); + + /// + /// Inverse the given Pose2D in place: + /// + /// + /// the given Pose2D + /// \ingroup Types + void pose2dInvertInPlace(Pose2D& pPos); + + /// + /// Alternative name for inverse: return the pose2d inverse of the given Pose2D. + /// + /// + /// the given Pose2D + /// \ingroup Types + Pose2D pinv(const Pose2D& pPos); + + + /// + /// Compute the Pose2D between the actual Pose2D and the one give in argument result: + /// + /// inverse(pPos1)*pPos2 + /// + /// + /// the first Pose2D + /// the second Pose2D + /// + /// the Pose2D + /// + /// \ingroup Types + Pose2D pose2dDiff( + const Pose2D& pPos1, + const Pose2D& pPos2); + + /// + /// Compute the inverse of a Pose2D. + /// + /// the initial Pose2D + /// the inverse Pose2D + /// \ingroup Types + Pose2D pose2DInverse(const Pose2D& pPos); + + /// + /// Compute the inverse of a Pose2D. + /// + /// the initial Pose2D + /// the inverse Pose2D + /// \ingroup Types + void pose2DInverse( + const Pose2D& pPos, + Pose2D& pRes); + + + } // end namespace math +} // end namespace AL +#endif // _LIBALMATH_ALMATH_TYPES_ALPOSE2D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alposition2d.h b/naoModule/libnaoqi_files/include/almath/types/alposition2d.h new file mode 100755 index 0000000..a2c7148 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alposition2d.h @@ -0,0 +1,403 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALPOSITION2D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALPOSITION2D_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a Position2D. + /// + /// A Position2D is just defined by x and y. + /// + /// \ingroup Types + struct Position2D + { + /// + float x; + /// + float y; + + /// + /// Create a Position2D initialized with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Position2D(); + + /// + /// Create a Position2D initialize with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + /// the float value for each member + /// + explicit Position2D(float pInit); + + /// + /// Create a Position2D initialized with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y + * \end{array}\right] = + * \left[\begin{array}{c} + * pX \\ + * pY + * \end{array}\right]\f$ + */ + /// + /// the float value for x + /// the float value for y + Position2D(float pX, float pY); + + /// + /// Create a Position2D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 2 for respectively: + /// x and y + /// + Position2D(const std::vector& pFloats); + + /// + /// Build a Position2D from polar coordinates. + /// + /// + /// polar radius + /// polar angle in radians + static Position2D fromPolarCoordinates(const float pRadius, + const float pAngle); + + /// + /// Overloading of operator + for Position2D. + /// + /// the second Position2D + inline Position2D operator+ (const Position2D& pPos2) const + { + return Position2D(x + pPos2.x, y + pPos2.y); + } + + /// + /// Overloading of operator - for Position2D. + /// + /// the second Position2D + inline Position2D operator- (const Position2D& pPos2) const + { + return Position2D(x - pPos2.x, y - pPos2.y); + } + + /// + /// Overloading of operator + for Position2D. + /// + inline Position2D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Position2D. + /// + inline Position2D operator- () const + { + return Position2D(-x, -y); + } + + /// + /// Overloading of operator += for Position2D. + /// + /// the second Position2D + Position2D& operator+= (const Position2D& pPos2); + + /// + /// Overloading of operator -= for Position2D. + /// + /// the second Position2D + Position2D& operator-= (const Position2D& pPos2); + + /// + /// Overloading of operator == for Position2D. + /// + /// the second Position2D + /// + /// true if each float of the two Position2D are equal + /// + bool operator==(const Position2D& pPos2) const; + + /// + /// Overloading of operator != for Position2D. + /// + /// the second Position2D + /// + /// true if one of each float of the two Position2D are not equal + /// + bool operator!=(const Position2D& pPos2) const; + + /// + /// Overloading of operator * for Position2D. + /// + /// the float factor + inline Position2D operator* (float pVal) const + { + return Position2D(x*pVal, y*pVal); + } + + /// + /// Overloading of operator / for Position2D. + /// + /// the float factor + Position2D operator/ (float pVal) const; + + /// + /// Overloading of operator *= for Position2D. + /// + /// the float factor + Position2D& operator*= (float pVal); + + /// + /// Overloading of operator /= for Position2D. + /// + /// the float factor + Position2D& operator/= (float pVal); + + /// + /// Compute the squared distance between the actual + /// Position2D and the one give in argument. + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2\f$ + /// + /// the second Position2D + /// + /// the float squared distance between the two Position2D + /// + float distanceSquared(const Position2D& pPos2) const; + + /// + /// Compute the distance between the actual + /// Position2D and the one give in argument. + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2}\f$ + /// + /// the second Position2D + /// + /// the float distance between the two Position2D + /// + float distance(const Position2D& pPos2) const; + + /// + /// Check if the actual Position2D is near the one + /// give in argument. + /// + /// the second Position2D + /// an optionnal epsilon distance + /// + /// true if the distance between the two Position2D is less than pEpsilon + /// + bool isNear( + const Position2D& pPos2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the norm of the actual Position2D. + /// + /// \f$\sqrt{pPos.x^2+pPos.y^2}\f$ + /// + /// + /// the float norm of the Position2D + /// + float norm() const; + + /// + /// Normalize the actual Position2D. + /// + /// \f$pRes = \frac{pPos}{norm(pPos)}\f$ + /// + /// + /// the Position2D normalized + /// + Position2D normalize() const; + + /// + /// Compute the dot Product between the actual + /// Position2D and the one give in argument. + /// + /// \f$result = (pPos1.x*pPos2.x + pPos1.y*pPos2.y)\f$ + /// + /// the second Position2D + /// + /// the float dot product between the two Position2D + /// + float dotProduct(const Position2D& pPos2) const; + + /// + /// Compute the cross Product between the actual + /// Position2D and the one give in argument. + /// + /// \f$pRes = (pPos1.x*pPos2.y - pPos1.y*pPos2.x)\f$ + /// + /// the second Position2D + /// + /// the float cross product between the two Position2D + /// + float crossProduct(const Position2D& pPos2) const; + + /// + /// Return the Position2D as a vector of float [x, y]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + + + /// + /// Return the angular direction of a Position2D. + /// + /// \f$pRes = atan2(y, x)\f$ + /// + float getAngle() const; + }; + + // TODO : Need this ? + Position2D operator* ( + const float pM, + const Position2D& pPos1); + + /// + /// Compute the squared distance between two Position2D. + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2\f$ + /// + /// the first Position2D + /// the second Position2D + /// + /// the float squared distance between the two Position2D + /// + /// \ingroup Types + float distanceSquared( + const Position2D& pPos1, + const Position2D& pPos2); + + /// + /// Compute the distance between two Position2D \f$(pPos1,pPos2)\f$: + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2}\f$ + /// + /// the first Position2D + /// the second Position2D + /// + /// the float distance between the two Position2D + /// + /// \ingroup Types + float distance( + const Position2D& pPos1, + const Position2D& pPos2); + + /// + /// Compute the norm of a Position2D. + /// + /// \f$\sqrt{(pPos.x)^2+(pPos.y)^2}\f$ + /// + /// the given Position2D + /// + /// the float norm of the given Position2D + /// + /// \ingroup Types + float norm(const Position2D& pPos); + + /// + /// Normalize a Position2D. + /// + /// \f$pRes = \frac{pPos}{norm(pPos)}\f$ + /// + /// the given Position2D + /// + /// the given Position2D normalized + /// + /// \ingroup Types + Position2D normalize(const Position2D& pPos); + + /// + /// Compute the dot Product between two Position2D: + /// + /// \f$pRes = (pPos1.x*pPos2.x + pPos1.y*pPos2.y)\f$ + /// + /// the first Position2D + /// the second Position2D + /// + /// the float dot product between the two Position2D + /// + float dotProduct( + const Position2D& pPos1, + const Position2D& pPos2); + + /// + /// Compute the cross Product of two Position2D. + /// + /// \f$pRes = (pPos1.x*pPos2.y - pPos1.y*pPos2.x)\f$ + /// + /// the first Position2D + /// the second Position2D + /// + /// the float cross product between the two Position2D + /// + /// \ingroup Types + float crossProduct( + const Position2D& pPos1, + const Position2D& pPos2); + + /// + /// Compute the cross Product of two Position2D. + /// + /// \f$pRes = (pPos1.x*pPos2.y - pPos1.y*pPos2.x)\f$ + /// + /// the first Position2D + /// the second Position2D + /// + /// the float cross product between the two Position2D + /// \ingroup Types + void crossProduct( + const Position2D& pPos1, + const Position2D& pPos2, + float& pRes); + + } // end namespace math +} // end namespace al +#endif // _LIBALMATH_ALMATH_TYPES_ALPOSITION2D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alposition3d.h b/naoModule/libnaoqi_files/include/almath/types/alposition3d.h new file mode 100755 index 0000000..90a655f --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alposition3d.h @@ -0,0 +1,389 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALPOSITION3D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALPOSITION3D_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a Position3D. + /// + /// A Position3D is just defined by x, y and z. + /// + /// \ingroup Types + struct Position3D { + /// + float x; + /// + float y; + /// + float z; + + /// + /// Create a Position3D initialize with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Position3D(); + + /// + /// Create a Position3D initialize with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + /// the float value for each member + /// + explicit Position3D(float pInit); + + /// + /// Create a Position3D initialize with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * pX \\ + * pY \\ + * pZ + * \end{array}\right]\f$ + */ + /// + /// the float value for x + /// the float value for y + /// the float value for z + Position3D( + float pX, + float pY, + float pZ); + + /// + /// Create a Position3D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 3 for respectively: + /// x, y and z + /// + Position3D (const std::vector& pFloats); + + /// + /// Overloading of operator + for Position3D. + /// + /// the second Position3D + inline Position3D operator+ (const Position3D& pPos2) const + { + return Position3D(x + pPos2.x, y + pPos2.y, z + pPos2.z); + } + + /// + /// Overloading of operator - for Position3D. + /// + /// the second Position3D + inline Position3D operator- (const Position3D& pPos2) const + { + return Position3D(x - pPos2.x, y - pPos2.y, z - pPos2.z); + } + + /// + /// Overloading of operator + for Position3D. + /// + inline Position3D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Position3D. + /// + inline Position3D operator- () const + { + return Position3D(-x, -y, -z); + } + + /// + /// Overloading of operator += for Position3D. + /// + /// the second Position3D + Position3D& operator+= (const Position3D& pPos2); + + /// + /// Overloading of operator -= for Position3D. + /// + /// the second Position3D + Position3D& operator-= (const Position3D& pPos2); + + /// + /// Overloading of operator == for Position3D. + /// + /// the second Position3D + bool operator== (const Position3D& pPos2) const; + + /// + /// Overloading of operator != for Position3D. + /// + /// the second Position3D + bool operator!= (const Position3D& pPos2) const; + + /// + /// Overloading of operator * for Position3D. + /// + /// the float factor + Position3D operator* (float pVal) const; + + /// + /// Overloading of operator / for Position3D. + /// + /// the float factor + Position3D operator/ (float pVal) const; + + /// + /// Overloading of operator *= for Position3D. + /// + /// the float factor + Position3D& operator*= (float pVal); + + /// + /// Overloading of operator /= for Position3D. + /// + /// the float factor + Position3D& operator/= (float pVal); + + /// + /// Compute the squared distance between the actual + /// Position3D and the one given in argument. + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2\f$ + /// + /// the second Position3D + /// + /// the float squared distance between the two Position3D + /// + float distanceSquared(const Position3D& pPos2) const; + + /// + /// Compute the distance between the actual + /// Position3D and the one given in argument. + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2}\f$ + /// + /// the second Position3D + /// + /// the float distance between the two Position3D + /// + float distance(const Position3D& pPos2) const; + + /// + /// Check if the actual Position3D is near the one + /// give in argument. + /// + /// + /// the second Position3D + /// an optionnal epsilon distance + /// + /// true if the distance between the two Position3D is less than pEpsilon + /// + bool isNear( + const Position3D& pPos2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the norm of the actual Position3D. + /// + /// \f$\sqrt{pPos.x^2+pPos.y^2+pPos.z^2}\f$ + /// + /// + /// the float norm of the Position3D + /// + float norm() const; + + /// + /// Normalize the actual Position3D. + /// + /// \f$result = \frac{pPos}{norm(pPos)}\f$ + /// + /// + /// the Position3D normalized + /// + Position3D normalize() const; + + /// + /// Compute the dot Product between the actual + /// Position3D and the one give in argument. + /// + /// \f$result = (pPos1.x*pPos2.x + pPos1.y*pPos2.y + pPos1.z*pPos2.z)\f$ + /// + /// the second Position3D + /// + /// the float dot product between the two Position3D + /// + float dotProduct(const Position3D& pPos2) const; + + /// + /// Compute the cross Product between the actual + /// Position3D and the one give in argument. + /// + /// \f$pRes.x = pPos1.y*pPos2.z - pPos1.z*pPos2.y\f$\n + /// \f$pRes.y = pPos1.z*pPos2.x - pPos1.x*pPos2.z\f$\n + /// \f$pRes.z = pPos1.x*pPos2.y - pPos1.y*pPos2.x\f$\n + /// + /// the second Position3D + /// + /// the Position3D cross product between the two Position3D + /// + Position3D crossProduct(const Position3D& pPos2) const; + + /// + /// Return the Position3D as a vector of float [x, y, z]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + }; + + /// + /// Compute the squared distance between two Position3D: + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2\f$ + /// + /// the first Position3D + /// the second Position3D + /// + /// the float squared distance between the two Position3D + /// + /// \ingroup Types + float distanceSquared( + const Position3D& pPos1, + const Position3D& pPos2); + + /// + /// Compute the distance between two Position3D: + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2}\f$ + /// + /// the first Position3D + /// the second Position3D + /// + /// the float distance between the two Position3D + /// + /// \ingroup Types + float distance( + const Position3D& pPos1, + const Position3D& pPos2); + + /// + /// Compute the norm of a Position3D: + /// + /// \f$\sqrt{pPos.x^2+pPos.y^2+pPos.z^2}\f$ + /// + /// the given Position3D + /// + /// the float norm of the given Position3D + /// + /// \ingroup Types + float norm(const Position3D& pPos); + + /// + /// Normalize a Position3D: + /// + /// \f$pRes = \frac{pPos}{norm(pPos)}\f$ + /// + /// the given Position3D + /// + /// the given Position3D normalized + /// + /// \ingroup Types + Position3D normalize(const Position3D& pPos); + + /// + /// Compute the dot Product between two Position3D: + /// + /// \f$pRes = (pPos1.x*pPos2.x + pPos1.y*pPos2.y + pPos1.z*pPos2.z)\f$ + /// + /// the first Position3D + /// the second Position3D + /// + /// the float dot product between the two Position3D + /// + float dotProduct( + const Position3D& pPos1, + const Position3D& pPos2); + + /// + /// Compute the cross Product between two Position3D: + /// + /// \f$pRes.x = pPos1.y*pPos2.z - pPos1.z*pPos2.y\f$\n + /// \f$pRes.y = pPos1.z*pPos2.x - pPos1.x*pPos2.z\f$\n + /// \f$pRes.z = pPos1.x*pPos2.y - pPos1.y*pPos2.x\f$\n + /// + /// the first Position3D + /// the second Position3D + /// + /// the Position3D cross product between the two Position3D + /// + Position3D crossProduct( + const Position3D& pPos1, + const Position3D& pPos2); + + /// + /// Compute the cross Product between two Position3D: + /// + /// \f$pRes.x = pPos1.y*pPos2.z - pPos1.z*pPos2.y\f$\n + /// \f$pRes.y = pPos1.z*pPos2.x - pPos1.x*pPos2.z\f$\n + /// \f$pRes.z = pPos1.x*pPos2.y - pPos1.y*pPos2.x\f$\n + /// + /// the first Position3D + /// the second Position3D + /// the Position3D cross product between the two Position3D + void crossProduct( + const Position3D& pPos1, + const Position3D& pPos2, + Position3D& pRes); + + } // end namespace math +} // end namespace al +#endif // _LIBALMATH_ALMATH_TYPES_ALPOSITION3D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alposition6d.h b/naoModule/libnaoqi_files/include/almath/types/alposition6d.h new file mode 100755 index 0000000..664bdaa --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alposition6d.h @@ -0,0 +1,370 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALPOSITION6D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALPOSITION6D_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a Position6D. + /// + /// A Position6D is just defined by x, y, z, wx, wy and wz. + /// + /// \ingroup Types + struct Position6D { + /// + float x; + /// + float y; + /// + float z; + /// + float wx; + /// + float wy; + /// + float wz; + + /// + /// Create a Position6D initialized with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z \\ + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Position6D(); + + /// + /// Create a Position6D initialized with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z \\ + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit \\ + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + /// the float value for each member + /// + explicit Position6D(float pInit); + + /// + /// Create a Position6D initialized with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z \\ + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pX \\ + * pY \\ + * pZ \\ + * pWx \\ + * pWy \\ + * pWz + * \end{array}\right]\f$ + */ + /// + /// the float value for x + /// the float value for y + /// the float value for z + /// the float value for wx + /// the float value for wy + /// the float value for wz + Position6D( + float pX, + float pY, + float pZ, + float pWx, + float pWy, + float pWz); + + /// + /// Create a Position6D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * x \\ + * y \\ + * z \\ + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] \\ + * pFloats[3] \\ + * pFloats[4] \\ + * pFloats[5] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 6 for respectively: + /// x, y, z, wx, wy and wz + /// + Position6D(const std::vector& pFloats); + + /// + /// Overloading of operator + for Position6D. + /// + /// the second Position6D + inline Position6D operator+ (const Position6D& pPos2) const + { + return Position6D( + x + pPos2.x, + y + pPos2.y, + z + pPos2.z, + wx + pPos2.wx, + wy + pPos2.wy, + wz + pPos2.wz); + } + + /// + /// Overloading of operator - for Position6D. + /// + /// the second Position6D + inline Position6D operator- (const Position6D& pPos2) const + { + return Position6D( + x - pPos2.x, + y - pPos2.y, + z - pPos2.z, + wx - pPos2.wx, + wy - pPos2.wy, + wz - pPos2.wz); + } + + /// + /// Overloading of operator + for Position6D. + /// + inline Position6D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Position6D. + /// + inline Position6D operator- () const + { + return Position6D(-x, -y, -z, -wx, -wy, -wz); + } + + /// + /// Overloading of operator += for Position6D. + /// + /// the second Position6D + Position6D& operator+= (const Position6D& pPos2); + + /// + /// Overloading of operator -= for Position6D. + /// + /// the second Position6D + Position6D& operator-= (const Position6D& pPos2); + + /// + /// Overloading of operator == for Position6D. + /// + /// the second Position6D + bool operator== (const Position6D& pPos2) const; + + /// + /// Overloading of operator != for Position6D. + /// + /// the second Position6D + bool operator!= (const Position6D& pPos2) const; + + /// + /// Overloading of operator * for Position6D. + /// + /// the float factor + inline Position6D operator* (float pVal) const + { + return Position6D( + x * pVal, + y * pVal, + z * pVal, + wx * pVal, + wy * pVal, + wz * pVal); + } + + /// + /// Overloading of operator / for Position6D. + /// + /// the float factor + Position6D operator/ (float pVal) const; + + /// + /// Overloading of operator *= for Position6D. + /// + /// the float factor + Position6D& operator*= (float pVal); + + /// + /// Overloading of operator /= for Position6D. + /// + /// the float factor + Position6D& operator/= (float pVal); + + /// + /// Check if the actual Position6D is near the one + /// given in argument. + /// + /// + /// the second Position6D + /// an optional epsilon distance + /// + /// true if the difference of each float of the two Position6D is less + /// than pEpsilon + /// + bool isNear( + const Position6D& pPos2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the squared distance of translation part (x, y and z) + /// between the actual Position6D and the one give in argument: + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2\f$ + /// + /// the second Position6D + /// + /// the float squared distance between the two Position6D + /// + float distanceSquared(const Position6D& pPos2) const; + + /// + /// Compute the distance of translation part (x, y and z) between the actual + /// Position6D and the one give in argument: + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2}\f$ + /// + /// the second Position6D + /// + /// the float distance between the two Position6D + /// + float distance(const Position6D& pPos2) const; + + /// + /// Compute the norm of the actual Position6D: + /// + /// \f$\sqrt{pPos.x^2 + pPos.y^2 + pPos.z^2 + pPos.wx^2 + pPos.wy^2 + pPos.wz^2}\f$ + /// + /// + /// the float norm of the Position6D + /// + float norm() const; + + /// + /// Return the Position6D as a vector of float [x, y, z, wx, wy, wz]. + /// + void toVector (std::vector& pReturnVector) const; + std::vector toVector (void) const; + }; // end struct + + + /// + /// Compute the squared distance of translation part (x, y and z) + /// between two Position6D: + /// + /// \f$(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2\f$ + /// + /// the first Position6D + /// the second Position6D + /// + /// the float squared distance between the two Position6D + /// + /// \ingroup Types + float distanceSquared( + const Position6D& pPos1, + const Position6D& pPos2); + + + /// + /// Compute the distance of translation part (x, y and z) between two Position6D: + /// + /// \f$\sqrt{(pPos1.x-pPos2.x)^2+(pPos1.y-pPos2.y)^2+(pPos1.z-pPos2.z)^2}\f$ + /// + /// the first Position6D + /// the second Position6D + /// + /// the float distance between the two Position6D + /// + /// \ingroup Types + float distance( + const Position6D& pPos1, + const Position6D& pPos2); + + /// + /// Compute the norm of a Position6D: + /// + /// \f$\sqrt{pPos.x^2 + pPos.y^2 + pPos.z^2 + pPos.wx^2 + pPos.wy^2 + pPos.wz^2}\f$ + /// + /// the given Position6D + /// + /// the float norm of the given Position6D + /// + /// \ingroup Types + float norm(const Position6D& pPos); + + /// + /// Normalize a Position6D: + /// + /// \f$pRes = \frac{pPos}{norm(pPos)} \f$ + /// + /// the given Position6D + /// + /// the given Position6D normalized + /// + /// \ingroup Types + Position6D normalize(const Position6D& pPos); + + } // end namespace math +} // end namespace al + +#endif // _LIBALMATH_ALMATH_TYPES_ALPOSITION6D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alpositionandvelocity.h b/naoModule/libnaoqi_files/include/almath/types/alpositionandvelocity.h new file mode 100755 index 0000000..72fbc36 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alpositionandvelocity.h @@ -0,0 +1,74 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALPOSITIONANDVELOCITY_H_ +#define _LIBALMATH_ALMATH_TYPES_ALPOSITIONANDVELOCITY_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a PositionAndVelocity. + /// + /// A PositionAndVelocity is just defined by q and dq. + /// + /// \ingroup Types + struct PositionAndVelocity + { + /// + float q; + /// + float dq; + + /// + /// Create a PositionAndVelocity initialize with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * q \\ + * dq + * \end{array}\right] = + * \left[\begin{array}{c} + * pq \\ + * pdq + * \end{array}\right]\f$ + */ + /// + /// the float value for q + /// the float value for dq + PositionAndVelocity( + const float pq = 0.0f, + const float pdq = 0.0f); + + /// + /// Check if the actual PositionAndVelocity is near the one + /// give in argument. + /// + /// + /// the second PositionAndVelocity + /// an optional epsilon distance (default = 0.0001f) + /// + /// true if the difference of each float of the two PositionAndVelocity is less than pEpsilon + /// + bool isNear( + const PositionAndVelocity& pDat2, + const float& pEpsilon=0.0001f) const; + + + /// + /// Return the PositionAndVelocity as a vector of float [q, dq]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + }; + + } +} +#endif // _LIBALMATH_ALMATH_TYPES_ALPOSITIONANDVELOCITY_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alquaternion.h b/naoModule/libnaoqi_files/include/almath/types/alquaternion.h new file mode 100755 index 0000000..bf627e1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alquaternion.h @@ -0,0 +1,327 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALQUATERNION_H_ +#define _LIBALMATH_ALMATH_TYPES_ALQUATERNION_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a Quaternion. + /// + /// A Quaternion is just defined by w, x, y and z. + /// + /// \ingroup Types + struct Quaternion { + /// + float w; + /// + float x; + /// + float y; + /// + float z; + + /// + /// Create a Quaternion initialize with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * w \\ + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Quaternion(); + + /// + /// Create a Quaternion initialize with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * w \\ + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * pW \\ + * pX \\ + * pY \\ + * pZ + * \end{array}\right]\f$ + */ + /// + /// the float value for w + /// the float value for x + /// the float value for y + /// the float value for z + Quaternion( + float pW, + float pX, + float pY, + float pZ); + + /// + /// Create a Quaternion with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * w \\ + * x \\ + * y \\ + * z + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] \\ + * pFloats[3] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 4 for respectively: + /// w, x, y and z + /// + Quaternion(const std::vector& pFloats); + + /// + /// Overloading of operator *= for Quaternion. + /// + /// the second Quaternion + Quaternion& operator*= (const Quaternion& pQua2); + + /// + /// Overloading of operator * for Quaternion. + /// + /// the second Quaternion + inline Quaternion operator* (const Quaternion& pQua2) const + { + return Quaternion( + w*pQua2.w - x*pQua2.x - y*pQua2.y - z*pQua2.z, + w*pQua2.x + pQua2.w*x + y*pQua2.z - z*pQua2.y, + w*pQua2.y + pQua2.w*y + z*pQua2.x - x*pQua2.z, + w*pQua2.z + pQua2.w*z + x*pQua2.y - y*pQua2.x); + } + + /// + /// Overloading of operator == for Quaternion. + /// + /// the second Quaternion + bool operator== (const Quaternion& pQua2) const; + + /// + /// Overloading of operator != for Quaternion. + /// + /// the second Quaternion + bool operator!= (const Quaternion& pQua2) const; + + /// + /// Overloading of operator * for Quaternion. + /// + /// the float factor + inline Quaternion operator* (float pVal) const + { + return Quaternion(w*pVal, x*pVal, y*pVal, z*pVal); + } + + /// + /// Overloading of operator / for Quaternion. + /// + /// the float factor + Quaternion operator/ (float pVal) const; + + /// + /// Overloading of operator *= for Quaternion. + /// + /// the float factor + Quaternion& operator*= (float pVal); + + /// + /// Overloading of operator /= for Quaternion. + /// + /// the float factor + Quaternion& operator/= (float pVal); + + /// + /// Check if the actual Quaternion is near the one + /// give in argument. + /// + /// + /// the second Quaternion + /// an optionnal epsilon distance + /// + /// true if the distance between the two Quaternion is less than pEpsilon + /// Check if |Qua1+Qua2| < epsilon or |Qua1-Qua2| < epsilon + /// + bool isNear( + const Quaternion& pQua2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the norm of the actual Quaternion. + /// + /// \f$\sqrt{pQua.w^2+pQua.x^2+pQua.y^2+pQua.z^2}\f$ + /// + /// + /// the float norm of the Quaternion + /// + float norm() const; + + /// + /// Normalize the actual Quaterion. + /// + /// \f$result = \frac{pQua}{norm(pQua)}\f$ + /// + /// + /// the Quaternion normalized + /// + Quaternion normalize() const; + + /// + /// Compute the quaternion inverse of the actual Quaternion + /// + /// + /// + /// the Quaternion inverse + /// + Quaternion inverse() const; + + /// + /// Create a Quaternion initialized with explicit angle and axis rotation. + /// + /// + /// the float value for angle in radian around axis rotation + /// the float value for x value of axis rotation + /// the float value for y value of axis rotation + /// the float value for z value of axis rotation + static Quaternion fromAngleAndAxisRotation( + const float pAngle, + const float pAxisX, + const float pAxisY, + const float pAxisZ); + + /// + /// Return the Quaternion as a vector of float [w, x, y, z]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + }; + + /// + /// Compute the norm of a Quaternion: + /// + /// \f$\sqrt{pQua.w^2+pQua.x^2+pQua.y^2+pQua.z^2}\f$ + /// + /// the given Quaternion + /// + /// the float norm of the given Quaternion + /// + /// \ingroup Types + float norm(const Quaternion& pQua); + + /// + /// Normalize a Quaternion: + /// + /// \f$pRes = \frac{pQua}{norm(pQua)}\f$ + /// + /// the given Quaternion + /// + /// the given Quaternion normalized + /// + /// \ingroup Types + Quaternion normalize(const Quaternion& pQua); + + + /// + /// Return the quaternion inverse of the given Quaternion: + /// + /// + /// the given Quaternion + /// the inverse of the given Quaternion + /// \ingroup Types + void quaternionInverse( + const Quaternion& pQua, + Quaternion& pQuaOut); + + /// + /// Return the quaternion inverse of the given Quaternion + /// + /// + /// the given Quaternion + /// + /// the Quaternion inverse + /// + /// \ingroup Types + Quaternion quaternionInverse(const Quaternion& pQua); + + + /// + /// Create a Quaternion initialized with explicit angle and axis rotation. + /// + /// + /// the float value for angle in radian around axis rotation + /// the float value for x value of axis rotation + /// the float value for y value of axis rotation + /// the float value for z value of axis rotation + /// + /// the Quaternion + /// + /// \ingroup Types + Quaternion quaternionFromAngleAndAxisRotation( + const float pAngle, + const float pAxisX, + const float pAxisY, + const float pAxisZ); + + + /// + /// Compute angle and axis rotation from a Quaternion. + /// + /// + /// the given quaternion + /// the computed float value for angle in radian around axis rotation + /// the computed float value for x value of axis rotation + /// the computed float value for y value of axis rotation + /// the computed float value for z value of axis rotation + /// \ingroup Types + void angleAndAxisRotationFromQuaternion( + const Quaternion& pQuaternion, + float& pAngle, + float& pAxisX, + float& pAxisY, + float& pAxisZ); + + /// + /// Compute angle and axis rotation from a Quaternion. + /// + /// + /// the given quaternion + /// + /// a vector containing angle, axisX, axisY, axisZ. + /// + /// \ingroup Types + std::vector angleAndAxisRotationFromQuaternion( + const Quaternion& pQuaternion); + + + } // end namespace math +} // end namespace al +#endif // _LIBALMATH_ALMATH_TYPES_ALQUATERNION_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alrotation.h b/naoModule/libnaoqi_files/include/almath/types/alrotation.h new file mode 100755 index 0000000..e604aac --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alrotation.h @@ -0,0 +1,460 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALROTATION_H_ +#define _LIBALMATH_ALMATH_TYPES_ALROTATION_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// A 3*3 rotation matrix. + /** + * + * \f$ \left[\begin{array}{ccc} + * r_1c_1 & r_1c_2 & r_1c_3 \\ + * r_2c_1 & r_2c_2 & r_2c_3 \\ + * r_3c_1 & r_3c_2 & r_3c_3 + * \end{array}\right]\f$ + */ + /// + /// more information + /// \ingroup Types + struct Rotation + { + /// + /// row 1 column 1. + /// + float r1_c1; + /// + /// row 1 column 2. + /// + float r1_c2; + /// + /// row 1 column 3. + /// + float r1_c3; + /// + /// row 2 column 1. + /// + float r2_c1; + /// + /// row 2 column 2. + /// + float r2_c2; + /// + /// row 2 column 3. + /// + float r2_c3; + /// + /// row 3 column 1. + /// + float r3_c1; + /// + /// row 3 column 2. + /// + float r3_c2; + /// + /// row 3 column 3. + /// + float r3_c3; + + /// + /// Create a Rotation initialized to identity. + /** + * + * \f$ \left[\begin{array}{ccc} + * r_1c_1 & r_1c_2 & r_1c_3 \\ + * r_2c_1 & r_2c_2 & r_2c_3 \\ + * r_3c_1 & r_3c_2 & r_3c_3 + * \end{array}\right] = + * \left[\begin{array}{ccc} + * 1.0 & 0.0 & 0.0 \\ + * 0.0 & 1.0 & 0.0 \\ + * 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + Rotation(); + + /// + /// Create a Rotation with an std::vector. + /// + /// + /// An std::vector of size 9, 12 or 16 for respectively: + /// + /// For std::vector of size 9 + /// + /** + * + * \f$ \left[\begin{array}{cccc} + * r_1c_1 & r_1c_2 & r_1c_3 \\ + * r_2c_1 & r_2c_2 & r_2c_3 \\ + * r_3c_1 & r_3c_2 & r_3c_3 + * \end{array}\right] = + * \left[\begin{array}{cccc} + * pFloats[0] & pFloats[1] & pFloats[2] \\ + * pFloats[3] & pFloats[4] & pFloats[5] \\ + * pFloats[6] & pFloats[7] & pFloats[8] + * \end{array}\right]\f$ + * + */ + /// + /// For std::vector of size 12 or 16: + /// + /** \f$ + * + * \left[\begin{array}{cccc} + * r_1c_1 & r_1c_2 & r_1c_3 \\ + * r_2c_1 & r_2c_2 & r_2c_3 \\ + * r_3c_1 & r_3c_2 & r_3c_3 + * \end{array}\right] = + * \left[\begin{array}{cccc} + * pFloats[0] & pFloats[1] & pFloats[2] \\ + * pFloats[4] & pFloats[5] & pFloats[6] \\ + * pFloats[8] & pFloats[9] & pFloats[10] + * \end{array}\right]\f$ + */ + /// + Rotation (const std::vector& pFloats); + + /// + /// Overloading of operator *= for Rotation. + /// + /// the second Rotation + Rotation& operator*= (const Rotation& pRot2); + + /// + /// Overloading of operator * for Rotation. + /// + /// the second Rotation + Rotation operator* (const Rotation& pRot2) const; + + /// + /// Overloading of operator == for Rotation. + /// + /// the second Rotation + bool operator==(const Rotation& pRot2) const; + + /// + /// Overloading of operator != for Rotation. + /// + /// the second Rotation + bool operator!=(const Rotation& pRot2) const; + + /// + /// Check if the actual Rotation is near the one + /// give in argument. + /// + /// + /// the second Rotation + /// an optionnal epsilon distance: default: 0.0001 + /// + /// true if the distance between the two rotations is less than pEpsilon + /// + bool isNear( + const Rotation& pRot2, + const float& pEpsilon=0.0001f) const; + + /// + /// Normalize data, if needed, to have Rotation properties. + /// + /// + void normalizeRotation(void); + + /// + /// Check if the rotation is correct. + /// The condition checks are: + /// \f$R^t * R = I\f$ + /// and + /// determinant(R) = 1.0 + /// + /// + /// an optionnal epsilon distance. Default: 0.0001 + /// + /// true if the Rotation is correct + /// + bool isRotation(const float& pEpsilon=0.0001f) const; + + /// + /// Compute the rotation transpose (inverse) of the actual Rotation: + /// + /// + /// the Rotation transpose + /// + Rotation transpose() const; + + /// + /// Compute the determinant of the Rotation: + /// + /** \f$pRot.r_1c_1*pRot.r_2c_2*pRot.r_3c_3 + + * pRot.r_1c_2*pRot.r_2c_3*pRot.r_3c_1 + + * pRot.r_1c_3*pRot.r_2c_1*pRot.r_3c_2 - + * pRot.r_1c_1*pRot.r_2c_3*pRot.r_3c_2 - + * pRot.r_1c_2*pRot.r_2c_1*pRot.r_3c_3 - + * pRot.r_1c_3*pRot.r_2c_2*pRot.r_3c_1\f$ + */ + /// + /// + /// the float determinant of the Rotation + /// + float determinant() const; + + /// + /// Creates a 3*3 Rotation Matrix from a normalized quaternion ( |a + bi + cj + dk| = 1). + /// + /// Coefficient a of the normalized quaternion + /// Coefficient b of the normalized quaternion + /// Coefficient c of the normalized quaternion + /// Coefficient d of the normalized quaternion + static Rotation fromQuaternion( + const float pA, + const float pB, + const float pC, + const float pD); + + + /// + /// Creates a 3*3 Rotation Matrix from a an angle and a normalized direction( |pX, pY, pZ| = 1). + /// + /// the float value of angle in radian + /// the X direction of the vector of the rotation + /// the Y direction of the vector of the rotation + /// the Z direction of the vector of the rotation + static Rotation fromAngleDirection( + const float pAngle, + const float pX, + const float pY, + const float pZ); + + /// + /// Create a Rotation initialized with explicit rotation around x axis. + /// + /** \f$ pRot = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 \\ + * 0.0 & cos(pRotX) & -sin(pRotX) \\ + * 0.0 & sin(pRotX) & cos(pRotX) + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around x axis + static Rotation fromRotX(const float pRotX); + + /// + /// Create a Rotation initialized with explicit rotation around y axis. + /// + /** \f$ pT = \left[\begin{array}{cccc} + * cos(pRotY) & 0.0 & sin(pRotY) \\ + * 0.0 & 1.0 & 0.0 \\ + * -sin(pRotY) & 0.0 & cos(pRotY) + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around y axis + static Rotation fromRotY(const float pRotY); + + /// + /// Create a Rotation initialized with explicit rotation around z axis. + /// + /** \f$ pT = \left[\begin{array}{cccc} + * cos(pRotZ) & -sin(pRotZ) & 0.0 \\ + * sin(pRotZ) & cos(pRotZ) & 0.0 \\ + * 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around z axis + static Rotation fromRotZ(const float pRotZ); + + /// + /// Create a Rotation initialized with euler angle. + /// + /// Rot = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + static Rotation from3DRotation( + const float& pWX, + const float& pWY, + const float& pWZ); + + /// + /// Return the Rotation as a vector of float: + /// + /** \f$ \begin{array}{cccc} + * [r_1c_1, & r_1c_2, & r_1c_3, \\ + * r_2c_1, & r_2c_2, & r_2c_3, \\ + * r_3c_1, & r_3c_2, & r_3c_3] + * \end{array}\f$ + */ + /// + void toVector(std::vector& pReturnValue) const; + std::vector toVector(void) const; + + }; // end struct + + /// + /// Compute the transpose rotation of + /// the one given in argument: + /// + /// the rotation matrix + /// + /// the rotation transposed + /// + /// \ingroup Types + Rotation transpose(const Rotation& pRot); + + + /// + /// Compute the determinant of the given Rotation: + /// + /** \f$pRot.r_1c_1*pRot.r_2c_2*pRot.r_3c_3 + + * pRot.r_1c_2*pRot.r_2c_3*pRot.r_3c_1 + + * pRot.r_1c_3*pRot.r_2c_1*pRot.r_3c_2 - + * pRot.r_1c_1*pRot.r_2c_3*pRot.r_3c_2 - + * pRot.r_1c_2*pRot.r_2c_1*pRot.r_3c_3 - + * pRot.r_1c_3*pRot.r_2c_2*pRot.r_3c_1\f$ + */ + /// + /// the given Rotation + /// + /// the float determinant of Rotation + /// + /// \ingroup Types + float determinant(const Rotation& pRot); + + /// + /// Normalize data, if needed, to have Rotation properties. + /// + /// + /// the given Rotation + /// \ingroup Types + void normalizeRotation(Rotation& pRot); + + /// + /// Creates a 3*3 Rotation Matrix from a normalized quaternion ( |a + bi + cj + dk| = 1). + /// + /// Coefficient a of the normalized quaternion + /// Coefficient b of the normalized quaternion + /// Coefficient c of the normalized quaternion + /// Coefficient d of the normalized quaternion + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFromQuaternion( + const float pA, + const float pB, + const float pC, + const float pD); + + /// + /// Creates a 3*3 Rotation Matrix from a an angle and a normalized direction( |pX, pY, pZ| = 1). + /// + /// the float value of angle in radian + /// the X direction of the vector of the rotation + /// the Y direction of the vector of the rotation + /// the Z direction of the vector of the rotation + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFromAngleDirection( + const float pAngle, + const float pX, + const float pY, + const float pZ); + + /// + /// Apply Rotation to a 3D point. + /// + /// the given rotation + /// the X position of the 3D point after rotation + /// the Y position of the 3D point after rotation + /// the Z position of the 3D point after rotation + /// \ingroup Types + void applyRotation( + const AL::Math::Rotation& pRot, + float& pX, + float& pY, + float& pZ); + + /// + /// Create a Rotation initialized with explicit rotation around x axis. + /// + /** \f$ pRot = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 \\ + * 0.0 & cos(pRotX) & -sin(pRotX) \\ + * 0.0 & sin(pRotX) & cos(pRotX) + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around x axis + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFromRotX(const float pRotX); + + /// + /// Create a Rotation initialized with explicit rotation around y axis. + /// + /** \f$ pT = \left[\begin{array}{cccc} + * cos(pRotY) & 0.0 & sin(pRotY) \\ + * 0.0 & 1.0 & 0.0 \\ + * -sin(pRotY) & 0.0 & cos(pRotY) + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around y axis + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFromRotY(const float pRotY); + + /// + /// Create a Rotation initialized with explicit rotation around z axis. + /// + /** \f$ pT = \left[\begin{array}{cccc} + * cos(pRotZ) & -sin(pRotZ) & 0.0 \\ + * sin(pRotZ) & cos(pRotZ) & 0.0 \\ + * 0.0 & 0.0 & 1.0 \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around z axis + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFromRotZ(const float pRotZ); + + /// + /// Create a Rotation initialized with euler angle. + /// Rot = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + /// + /// the Rotation matrix + /// + /// \ingroup Types + Rotation rotationFrom3DRotation( + const float& pWX, + const float& pWY, + const float& pWZ); + + } +} +#endif // _LIBALMATH_ALMATH_TYPES_ALROTATION_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alrotation3d.h b/naoModule/libnaoqi_files/include/almath/types/alrotation3d.h new file mode 100755 index 0000000..8ee144a --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alrotation3d.h @@ -0,0 +1,233 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALROTATION3D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALROTATION3D_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// A Rotation3D give 3 composed angles in radians. + /// + /// \ingroup Types + struct Rotation3D { + /// + float wx; + /// + float wy; + /// + float wz; + + /// + /// Create a Rotation3D initialized with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Rotation3D(); + + /// + /// Create a Rotation3D initialized with the same float. + /// + /// the float value for each member + /** + * + * \f$ \left[\begin{array}{c} + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + explicit Rotation3D(float pInit); + + /// + /// Create a Rotation3D initialized with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pWx \\ + * pWy \\ + * pWz + * \end{array}\right]\f$ + */ + /// + /// the float value for wx + /// the float value for wy + /// the float value for wz + Rotation3D( + float pWx, + float pWy, + float pWz); + + /// + /// Create a Rotation3D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * wx \\ + * wy \\ + * wz + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 3 for respectively: + /// wx, wy and wz + /// + Rotation3D (const std::vector& pFloats); + + /// + /// Overloading of operator + for Rotation3D. + /// + /// the second Rotation3D + inline Rotation3D operator+ (const Rotation3D& pRot2) const + { + return Rotation3D( + wx + pRot2.wx, + wy + pRot2.wy, + wz + pRot2.wz); + } + + /// + /// Overloading of operator - for Rotation3D. + /// + /// the second Rotation3D + inline Rotation3D operator- (const Rotation3D& pRot2) const + { + return Rotation3D( + wx - pRot2.wx, + wy - pRot2.wy, + wz - pRot2.wz); + } + + /// + /// Overloading of operator += for Rotation3D. + /// + /// the second Rotation3D + Rotation3D& operator+= (const Rotation3D& pRot2); + + /// + /// Overloading of operator -= for Rotation3D. + /// + /// the second Rotation3D + Rotation3D& operator-= (const Rotation3D& pRot2); + + /// + /// Overloading of operator == for Rotation3D. + /// + /// the second Rotation3D + bool operator== (const Rotation3D& pRot2) const; + + /// + /// Overloading of operator != for Rotation3D. + /// + /// the second Rotation3D + bool operator!= (const Rotation3D& pRot2) const; + + /// + /// Overloading of operator * for Rotation3D. + /// + /// the float factor + inline Rotation3D operator* (const float pVal) const + { + return Rotation3D(wx*pVal, wy*pVal, wz*pVal); + } + + /// + /// Overloading of operator / for Rotation3D. + /// + /// the float factor + Rotation3D operator/ (const float pVal) const; + + /// + /// Overloading of operator *= for Rotation3D. + /// + /// the float factor + Rotation3D& operator*= (const float pVal); + + /// + /// Overloading of operator /= for Rotation3D. + /// + /// the float factor + Rotation3D& operator/= (const float pVal); + + /// + /// Check if the actual Rotation3D is near the one + /// given in argument. + /// + /// + /// the second Rotation3D + /// an optional epsilon distance + /// + /// true if the difference of each float of the two Rotation3D is less than pEpsilon + /// + bool isNear( + const Rotation3D& pRot2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the norm of the actual Position6D: + /// + /// \f$\sqrt{pRot.wx^2 + pRot.wy^2 + pRot.wz^2}\f$ + /// + /// + /// the float norm of the Position6D + /// + float norm() const; + + /// + /// Return the Rotation3D as a vector of float [wx, wy, wz]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + }; + + /// + /// Compute the norm of a Rotation3D: + /// + /// \f$\sqrt{pRot.wx^2 + pRot.wy^2 + pRot.wz^2}\f$ + /// + /// the given Rotation3D + /// + /// the float norm of the given Rotation3D + /// + /// \ingroup Types + float norm(const Rotation3D& pRot); + + } // end namespace Math +} // end namespace AL +#endif // _LIBALMATH_ALMATH_TYPES_ALROTATION3D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/altransform.h b/naoModule/libnaoqi_files/include/almath/types/altransform.h new file mode 100755 index 0000000..bf55395 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/altransform.h @@ -0,0 +1,723 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALTRANSFORM_H_ +#define _LIBALMATH_ALMATH_TYPES_ALTRANSFORM_H_ + +#include + +namespace AL { + namespace Math { + /// + /// A homogenous transformation matrix. + /// + /// + /// more information + /// \ingroup Types + struct Transform { + + /** \cond PRIVATE */ + float r1_c1, r1_c2, r1_c3, r1_c4; + float r2_c1, r2_c2, r2_c3, r2_c4; + float r3_c1, r3_c2, r3_c3, r3_c4; + /** \endcond */ + + /// + /// Create a Transform initialized to identity. + /** + * + * \f$ \left[\begin{array}{cccc} + * r_1c_1 & r_1c_2 & r_1c_3 & r_1c_4 \\ + * r_2c_1 & r_2c_2 & r_2c_3 & r_2c_4 \\ + * r_3c_1 & r_3c_2 & r_3c_3 & r_3c_4 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right] = + * \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & 0.0 \\ + * 0.0 & 1.0 & 0.0 & 0.0 \\ + * 0.0 & 0.0 & 1.0 & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + Transform(); + + /// + /// Create a Transform with an std::vector. + /// + /// + /// An std::vector of size 12 or 16 for respectively: + /// + /** + * + * \f$ \left[\begin{array}{cccc} + * r_1c_1 & r_1c_2 & r_1c_3 & r_1c_4 \\ + * r_2c_1 & r_2c_2 & r_2c_3 & r_2c_4 \\ + * r_3c_1 & r_3c_2 & r_3c_3 & r_3c_4 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right] = + * \left[\begin{array}{cccc} + * pFloats[00] & pFloats[01] & pFloats[02] & pFloats[03] \\ + * pFloats[04] & pFloats[05] & pFloats[06] & pFloats[07] \\ + * pFloats[08] & pFloats[09] & pFloats[10] & pFloats[11] \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + explicit Transform(const std::vector& pFloats); + + /// + /// Create a Transform initialized with explicit value for translation + /// part. Rotation part is set to identity. + /** + * + * \f$ \left[\begin{array}{cccc} + * r_1c_1 & r_1c_2 & r_1c_3 & r_1c_4 \\ + * r_2c_1 & r_2c_2 & r_2c_3 & r_2c_4 \\ + * r_3c_1 & r_3c_2 & r_3c_3 & r_3c_4 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right] = + * \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & pPosX \\ + * 0.0 & 1.0 & 0.0 & pPosY \\ + * 0.0 & 0.0 & 1.0 & pPosZ \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// the float value for translation x + /// the float value for translation y + /// the float value for translation z + Transform( + const float& pPosX, + const float& pPosY, + const float& pPosZ); + + /// + /// Overloading of operator *= for Transform. + /// + /// the second Transform + Transform& operator*= (const Transform& pT2); + + /// + /// Overloading of operator * for Transform. + /// + /// the second Transform + Transform operator* (const Transform& pT2) const; + + /// + /// Overloading of operator == for Transform. + /// + /// the second Transform + bool operator==(const Transform& pT2) const; + + /// + /// Overloading of operator != for Transform. + /// + /// the second Transform + bool operator!=(const Transform& pT2) const; + + /// + /// Check if the actual Transform is near the one + /// given in argument. + /// + /// + /// the second Transform + /// an optionnal epsilon distance: Default: 0.0001 + /// + /// true if the distance between the two Transform is less than pEpsilon + /// + bool isNear( + const Transform& pT2, + const float& pEpsilon=0.0001f) const; + + /// + /// Check if the rotation part is correct. + /// The condition checks are: + /// \f$R^t * R = I\f$ + /// and + /// determinant(R) = 1.0 + /// + /// + /// an optionnal epsilon distance. Default: 0.0001 + /// + /// true if the Transform is correct + /// + bool isTransform( + const float& pEpsilon=0.0001f) const; + + /// + /// Normalize data, if needed, to have transform properties. + /// + /// + void normalizeTransform(void); + + /// + /// Compute the norm translation part of the actual Transform: + /// + /// \f$\sqrt{pT.r_1c_4^2+pT.r_2c_4^2+pT.r_3c_4^2}\f$ + /// + /// + /// the float norm of the Transform + /// + float norm() const; + + /// + /// Compute the determinant of rotation part of the actual Transform: + /// + /** + * \f$pT.r_1c_1*pT.r_2c_2*pT.r_3c_3 + pT.r_1c_2*pT.r_2c_3*pT.r_3c_1 + + * pT.r_1c_3*pT.r_2c_1*pT.r_3c_2 - pT.r_1c_1*pT.r_2c_3*pT.r_3c_2 - + * pT.r_1c_2*pT.r_2c_1*pT.r_3c_3 - pT.r_1c_3*pT.r_2c_2*pT.r_3c_1\f$ + */ + /// + /// + /// the float determinant of rotation Transform part + /// + float determinant() const; + + /// + /// Compute the transform inverse of the actual Transform: + /// + /** + * \f$ pT = \left[\begin{array}{cc}R & r \\ + * 0_{31} & 1 \end{array}\right]\f$ + */ + /// + /** \f$ pTOut = \left[\begin{array}{cc} + * R^t & (-R^t*r) \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /// + /// + /// the Transform inverse + /// + Transform inverse() const; + + /// + /// Create a Transform initialized with explicit rotation around x axis. + /// + /** \f$ pT = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & 0.0 \\ + * 0.0 & cos(pRotX) & -sin(pRotX) & 0.0 \\ + * 0.0 & sin(pRotX) & cos(pRotX) & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around x axis + static Transform fromRotX(const float pRotX); + + /// + /// Create a Transform initialized with explicit rotation around y axis. + /// + /** + * \f$ pT = \left[\begin{array}{cccc} + * cos(pRotY) & 0.0 & sin(pRotY) & 0.0 \\ + * 0.0 & 1.0 & 0.0 & 0.0 \\ + * -sin(pRotY) & 0.0 & cos(pRotY) & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around y axis + static Transform fromRotY(const float pRotY); + + /// + /// Create a Transform initialized with explicit rotation around z axis. + /// + /** + * \f$ pT = \left[\begin{array}{cccc} + * cos(pRotZ) & -sin(pRotZ) & 0.0 & 0.0 \\ + * sin(pRotZ) & cos(pRotZ) & 0.0 & 0.0 \\ + * 0.0 & 0.0 & 1.0 & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// the float value for angle rotation in radian around z axis + static Transform fromRotZ(const float pRotZ); + + + /// + /// Create a Transform initialize with euler angle. + /// + /// H = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + static Transform from3DRotation( + const float& pWX, + const float& pWY, + const float& pWZ); + + + /// + /// Create a Transform initialize with explicit value for translation part. + /// + /** + * \f$ pT = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & pX \\ + * 0.0 & 1.0 & 0.0 & pY \\ + * 0.0 & 0.0 & 1.0 & pZ \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// the float value for translation axis x in meter (r1_c4) + /// the float value for translation axis y in meter (r2_c4) + /// the float value for translation axis z in meter (r3_c4) + static Transform fromPosition( + const float pX, + const float pY, + const float pZ); + + /// + /// Create a Transform initialize with explicit value for translation part and euler angle. + /// + /// H = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// then + /// + /// H.r1_c4 = pX + /// + /// H.r2_c4 = pY + /// + /// H.r3_c4 = pZ + /// + /// + /// the float value for translation axis x in meter (r1_c4) + /// the float value for translation axis y in meter (r2_c4) + /// the float value for translation axis z in meter (r3_c4) + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + static Transform fromPosition( + const float& pX, + const float& pY, + const float& pZ, + const float& pWX, + const float& pWY, + const float& pWZ); + + /// + /// Compute the Transform between the actual + /// Transform and the one given in argument: + /// + /// result: inverse(pT1)*pT2 + /// + /// + /// the second transform + Transform diff(const Transform& pT2) const; + + + /// + /// Compute the squared distance between the actual + /// Transform and the one given in argument (translation part): + /// + /// \f$(pT1.r_1c_4-pT2.r_1c_4)^2+(pT1.r_2c_4-pT2.r_2c_4)^2+(pT1.r_3c_4-pT2.r_3c_4)^2\f$ + /// + /// the second Transform + /// + /// the float squared distance between the two Transform: translation part + /// + float distanceSquared(const Transform& pT2) const; + + + /// + /// Compute the distance between the actual + /// Transform and the one given in argument: + /// + /// \f$\sqrt{(pT1.r_1c_4-pT2.r_1c_4)^2+(pT1.r_2c_4-pT2.r_2c_4)^2+(pT1.r_3c_4-pT2.r_3c_4)^2}\f$ + /// + /// the second Transform + /// + /// the float distance between the two Transform + /// + float distance(const Transform& pT2) const; + + /// + /// Return the Transform as a vector of float: + /// + /** \f$ \begin{array}{cccc} + * [r_1c_1, & r_1c_2, & r_1c_3, & r_1c_4, \\ + * r_2c_1, & r_2c_2, & r_2c_3, & r_2c_4, \\ + * r_3c_1, & r_3c_2, & r_3c_3, & r_3c_4, \\ + * 0.0, & 0.0, & 0.0, & 1.0] + * \end{array}\f$ + */ + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; + }; // end struct + + /// + /// pTOut = pT*pTOut + /// + /// + /// the first constant Transform + /// the second modified Transform + /// \ingroup Types + void transformPreMultiply( + const Transform& pT, + Transform& pTOut); + + /// + /// Compute the norm translation part of the actual Transform: + /// + /// \f$\sqrt{pT.r_1c_4^2+pT.r_2c_4^2+pT.r_3c_4^2}\f$ + /// + /// the given Transform + /// + /// the float norm of the given Transform + /// + /// \ingroup Types + float norm(const Transform& pT); + + /// + /// Normalize data, if needed, to have transform properties. + /// + /// + /// the given Transform + /// \ingroup Types + void normalizeTransform(Transform& pT); + + /// + /// DEPRECATED: Use toVector function. + /// Copy the Transform in a vector of float: + /// + /** \f$ \begin{array}{cccc} + * [r_1c_1, & r_1c_2, & r_1c_3, & r_1c_4, \\ + * r_2c_1, & r_2c_2, & r_2c_3, & r_2c_4, \\ + * r_3c_1, & r_3c_2, & r_3c_3, & r_3c_4, \\ + * 0.0, & 0.0, & 0.0, & 1.0] + * \end{array}\f$ + */ + /// + /// + /// the given Transform + /// the vector of float update to given transform value + /// \ingroup Types + void transformToFloatVector( + const Transform& pT, + std::vector& pTOut); + + /// + /// DEPRECATED: Use toVector function. + /// Return the Transform in a vector of float: + /// + /** + * \f$ \begin{array}{cccc} + * [r_1c_1, & r_1c_2, & r_1c_3, & r_1c_4, \\ + * r_2c_1, & r_2c_2, & r_2c_3, & r_2c_4, \\ + * r_3c_1, & r_3c_2, & r_3c_3, & r_3c_4, \\ + * 0.0, & 0.0, & 0.0, & 1.0] + * \end{array}\f$ + */ + /// + /// + /// the given Transform + /// + /// the vector of float update to given transform value + /// + /// \ingroup Types + std::vector transformToFloatVector( + const Transform& pT); + + + /// + /// Compute the determinant of rotation part of the given Transform: + /// + /** \f$pT.r_1c_1*pT.r_2c_2*pT.r_3c_3 + pT.r_1c_2*pT.r_2c_3*pT.r_3c_1 + + * pT.r_1c_3*pT.r_2c_1 * pT.r_3c_2 - pT.r_1c_1*pT.r_2c_3*pT.r_3c_2 - + * pT.r_1c_2*pT.r_2c_1*pT.r_3c_3 - pT.r_1c_3*pT.r_2c_2*pT.r_3c_1\f$ + */ + /// + /// the given Transform + /// + /// the float determinant of rotation Transform part + /// + /// \ingroup Types + float determinant(const Transform& pT); + + /// + /// Compute the determinant of rotation part of the given vector of floats: + /// + /** \f$pT[0]*pT[5]*pT[10] + pT[1]*pT[6]*pT[8] + + * pT[2]*pT[4]*pT[9] - pT[0]*pT[6]*pT[9] - + * pT[1]*pT[4]*pT[10] - pT[2]*pT[5]*pT[8]\f$ + */ + /// + /// the given vector of floats + /// + /// the float determinant of rotation Transform part + /// + /// \ingroup Types + float determinant(const std::vector& pFloats); + + /// + /// Return the transform inverse of the given Transform: + /// + /** \f$ pT = \left[\begin{array}{cc} + * R & r \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /** \f$ pTOut = \left[\begin{array}{cc} + * R^t & (-R^t*r) \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /// + /// the given Transform + /// the inverse of the given Transform + /// \ingroup Types + void transformInverse( + const Transform& pT, + Transform& pTOut); + + /// + /// Return the transform inverse of the given Transform: + /// + /** \f$ pT = \left[\begin{array}{cc} + * R & r \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /** \f$ pTOut = \left[\begin{array}{cc} + * R^t & (-R^t*r) \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /// + /// the given Transform + /// + /// the Transform inverse + /// + /// \ingroup Types + Transform transformInverse(const Transform& pT); + + + /// + /// Create a Transform initialize with explicit rotation around x axis: + /// + /** \f$ pTOut = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & 0.0 \\ + * 0.0 & cos(pRotX) & -sin(pRotX) & 0.0 \\ + * 0.0 & sin(pRotX) & cos(pRotX) & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// + /// the float value for angle rotation in radian around x axis + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFromRotX(const float pRotX); + + /// + /// Create a Transform initialize with explicit rotation around y axis: + /// + /** \f$ pTOut = \left[\begin{array}{cccc} + * cos(pRotY) & 0.0 & sin(pRotY) & 0.0 \\ + * 0.0 & 1.0 & 0.0 & 0.0 \\ + * -sin(pRotY) & 0.0 & cos(pRotY) & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// + /// the float value for angle rotation in radian around y axis + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFromRotY(const float pRotY); + + /// + /// Create a Transform initialize with explicit rotation around z axis: + /// + /** \f$ pTOut = \left[\begin{array}{cccc} + * cos(pRotZ) & -sin(pRotZ) & 0.0 & 0.0 \\ + * sin(pRotZ) & cos(pRotZ) & 0.0 & 0.0 \\ + * 0.0 & 0.0 & 1.0 & 0.0 \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// + /// the float value for angle rotation in radian around z axis + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFromRotZ(const float pRotZ); + + + /// + /// Create a Transform initialize with euler angle: + /// H = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFrom3DRotation( + const float& pWX, + const float& pWY, + const float& pWZ); + + /// + /// Create a Transform initialize with explicit value for translation part: + /// + /** \f$ pTOut = \left[\begin{array}{cccc} + * 1.0 & 0.0 & 0.0 & pX \\ + * 0.0 & 1.0 & 0.0 & pY \\ + * 0.0 & 0.0 & 1.0 & pZ \\ + * 0.0 & 0.0 & 0.0 & 1.0 + * \end{array}\right]\f$ + */ + /// + /// + /// the float value for translation axis x in meter (r1_c4) + /// the float value for translation axis y in meter (r2_c4) + /// the float value for translation axis z in meter (r3_c4) + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFromPosition( + const float& pX, + const float& pY, + const float& pZ); + + /// + /// Create a Transform initialize with explicit value for translation part and euler angle: + /// + /// H = fromRotZ(pWZ)*fromRotY(pWY)*fromRotX(pWX) + /// + /// H.r1_c4 = pX + /// + /// H.r2_c4 = pY + /// + /// H.r3_c4 = pZ + /// + /// + /// the float value for translation axis x in meter (r1_c4) + /// the float value for translation axis y in meter (r2_c4) + /// the float value for translation axis z in meter (r3_c4) + /// the float value for euler angle x in radian + /// the float value for euler angle y in radian + /// the float value for euler angle z in radian + /// + /// the Transform + /// + /// \ingroup Types + Transform transformFromPosition( + const float& pX, + const float& pY, + const float& pZ, + const float& pWX, + const float& pWY, + const float& pWZ); + + + /// + /// Inverse the given Transform in place: + /// + /// + /// the given Transform + /// \ingroup Types + void transformInvertInPlace(Transform& pT); + + + /// + /// Alternative name for inverse: return the transform inverse of the given Transform: + /// + /** \f$ pT = \left[\begin{array}{cc} + * R & r \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /** \f$ pTOut = \left[\begin{array}{cc} + * R^t & (-R^t*r) \\ + * 0_{31} & 1 + * \end{array}\right]\f$ + */ + /// + /// + /// the given Transform + /// \ingroup Types + Transform pinv(const Transform& pT); + + + /// + /// Compute the Transform between the actual Transform and the one give in argument result: + /// + /// inverse(pT1)*pT2 + /// + /// + /// the first transform + /// the second transform + /// + /// the Transform + /// + /// \ingroup Types + Transform transformDiff( + const Transform& pT1, + const Transform& pT2); + + /// + /// Compute the squared distance between the actual + /// Transform and the one give in argument (translation part): + /// + /// \f$(pT1.r_1c_4-pT2.r_1c_4)^2 +(pT1.r_2c_4-pT2.r_2c_4)^2+(pT1.r_3c_4-pT2.r_3c_4)^2\f$ + /// + /// the first Transform + /// the second Transform + /// + /// the float squared distance between the two Transform: translation part + /// + /// \ingroup Types + float transformDistanceSquared( + const Transform& pT1, + const Transform& pT2); + + + /// + /// Compute the distance between the actual + /// Transform and the one give in argument: + /// + /// \f$\sqrt{(pT1.r_1c_4-pT2.r_1c_4)^2+(pT1.r_2c_4-pT2.r_2c_4)^2+(pT1.r_3c_4-pT2.r_3c_4)^2}\f$ + /// + /// the first Transform + /// the second Transform + /// + /// the float distance between the two Transform + /// + /// \ingroup Types + float transformDistance( + const Transform& pT1, + const Transform& pT2); + + } // end namespace Math +} // end namespace AL +#endif // _LIBALMATH_ALMATH_TYPES_ALTRANSFORM_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/altransformandvelocity6d.h b/naoModule/libnaoqi_files/include/almath/types/altransformandvelocity6d.h new file mode 100755 index 0000000..19f0476 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/altransformandvelocity6d.h @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALTRANSFORMANDVELOCITY6D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALTRANSFORMANDVELOCITY6D_H_ + +#include +#include + +namespace AL { + namespace Math { + + /// + /// Struct composed of a Transform and a Velocity6D + /// + struct TransformAndVelocity6D + { + /// + AL::Math::Transform T; + /// + AL::Math::Velocity6D V; + + TransformAndVelocity6D(); + + /*! @brief Build a transform and velocity object. + * @param[in] pT the given Transform. + * @param[in] pV the given Velocity6D.*/ + TransformAndVelocity6D( + const AL::Math::Transform& pT, + const AL::Math::Velocity6D& pV); + + /// + /// Check if the actual TransformAndVelocity6D is Near the one + /// given in argument. + /// + /// + /// the second TransformAndVelocity6D + /// an optionnal epsilon distance - default: 0.0001 + /// + /// true if the distance between the two TransformAndVelocity6D is less than pEpsilon + /// + bool isNear( + const TransformAndVelocity6D& pTV2, + const float& pEpsilon=0.0001f) const; + + }; + + } +} +#endif // _LIBALMATH_ALMATH_TYPES_ALTRANSFORMANDVELOCITY6D_H_ + diff --git a/naoModule/libnaoqi_files/include/almath/types/alvelocity3d.h b/naoModule/libnaoqi_files/include/almath/types/alvelocity3d.h new file mode 100755 index 0000000..359c96d --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alvelocity3d.h @@ -0,0 +1,275 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALVELOCITY3D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALVELOCITY3D_H_ + +#include + +namespace AL { + namespace Math { + + /// + /// Create and play with a Velocity3D. + /// + /// A Velocity3D is just defined by xd, yd and zd. + /// + /// \ingroup Types + struct Velocity3D { + /// + float xd; + /// + float yd; + /// + float zd; + + /// + /// Create a Velocity3D initialize with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Velocity3D(); + + /// + /// Create a Velocity3D initialize with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + /// the float value for each member + /// + explicit Velocity3D(float pInit); + + /// + /// Create a Velocity3D initialize with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd + * \end{array}\right] = + * \left[\begin{array}{c} + * pXd \\ + * pYd \\ + * pZd + * \end{array}\right]\f$ + */ + /// + /// the float value for xd + /// the float value for yd + /// the float value for zd + Velocity3D( + float pXd, + float pYd, + float pZd); + + /// + /// Create a Velocity3D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 3 for respectively: + /// xd, yd, zd + /// + Velocity3D(const std::vector& pFloats); + + /// + /// Overloading of operator + for Velocity3D. + /// + /// the second Velocity3D + inline Velocity3D operator+ (const Velocity3D& pVel2) const + { + return Velocity3D(xd + pVel2.xd, yd + pVel2.yd, zd + pVel2.zd); + } + + /// + /// Overloading of operator - for Velocity3D. + /// + /// the second Velocity3D + inline Velocity3D operator- (const Velocity3D& pVel2) const + { + return Velocity3D( + xd - pVel2.xd, + yd - pVel2.yd, + zd - pVel2.zd); + } + + /// + /// Overloading of operator + for Velocity3D. + /// + inline Velocity3D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Velocity3D. + /// + inline Velocity3D operator- () const + { + return Velocity3D(-xd, -yd, -zd); + } + + /// + /// Overloading of operator += for Velocity3D. + /// + /// the second Velocity3D + Velocity3D& operator+= (const Velocity3D& pVel2); + + /// + /// Overloading of operator -= for Velocity3D. + /// + /// the second Velocity3D + Velocity3D& operator-= (const Velocity3D& pVel2); + + /// + /// Overloading of operator == for Velocity3D. + /// + /// the second Velocity3D + bool operator== (const Velocity3D& pVel2) const; + + /// + /// Overloading of operator != for Velocity3D. + /// + /// the second Velocity3D + bool operator!= (const Velocity3D& pVel2) const; + + /// + /// Overloading of operator * for Velocity3D. + /// + /// the float factor + inline Velocity3D operator* (const float pVal) const + { + return Velocity3D(xd*pVal, yd*pVal, zd*pVal); + } + + /// + /// Overloading of operator / for Velocity3D. + /// + /// the float factor + Velocity3D operator/ (const float pVal) const; + + /// + /// Overloading of operator *= for Velocity3D. + /// + /// the float factor + Velocity3D& operator*= (const float pVal); + + /// + /// Overloading of operator /= for Velocity3D. + /// + /// the float factor + Velocity3D& operator/= (const float pVal); + + /// + /// Check if the actual Velocity3D is Near the one + /// given in argument. + /// + /// + /// the second Velocity3D + /// an optional epsilon distance + /// + /// true if the difference of each float of the two Velocity3D is less than pEpsilon + /// + bool isNear( + const Velocity3D& pVel2, + const float& pEpsilon=0.0001f) const; + + + /// + /// Compute the norm of the actual Velocity3D: + /// + /// \f$\sqrt{pVel.xd^2 + pVel.yd^2 + pVel.zd^2}\f$ + /// + /// + /// the float norm of the Velocity3D + /// + float norm () const; + + /// + /// Normalize the actual Velocity3D: + /// + /// \f$ result = \frac{pVel}{norm(pVel)} \f$ + /// + /// + /// the Velocity3D normalized + /// + Velocity3D normalize() const; + + /// + /// Return the Velocity3D as a vector of float [xd, yd, zd]. + /// + void toVector(std::vector& pReturnValue) const; + std::vector toVector(void) const; + }; + + Velocity3D operator* ( + const float pM, + const Velocity3D& pVel1); + + /// + /// Compute the norm of a Velocity3D: + /// + /// \f$\sqrt{pVel.xd^2 + pVel.yd^2 + pVel.zd^2}\f$ + /// + /// the given Velocity3D + /// + /// the float norm of the given Velocity3D + /// + /// \ingroup Types + float norm (const Velocity3D& pVel); + + /// + /// Normalize a Velocity3D: + /// + /// \f$ pRes = \frac{pVel}{norm(pVel)} \f$ + /// + /// the given Velocity3D + /// + /// the given Velocity3D normalized + /// + /// \ingroup Types + Velocity3D normalize(const Velocity3D& pVel); + + } // end namespace Math +} // end namespace AL +#endif // _LIBALMATH_ALMATH_TYPES_ALVELOCITY3D_H_ diff --git a/naoModule/libnaoqi_files/include/almath/types/alvelocity6d.h b/naoModule/libnaoqi_files/include/almath/types/alvelocity6d.h new file mode 100755 index 0000000..662846b --- /dev/null +++ b/naoModule/libnaoqi_files/include/almath/types/alvelocity6d.h @@ -0,0 +1,320 @@ +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#pragma once +#ifndef _LIBALMATH_ALMATH_TYPES_ALVELOCITY6D_H_ +#define _LIBALMATH_ALMATH_TYPES_ALVELOCITY6D_H_ + +#include + +namespace AL { +namespace Math { + + +/// +/// Create and play with a Velocity6D. +/// +/// A Velocity6D is just defined by xd, yd, zd, wxd, wyd and wzd. +/// +/// \ingroup Types +struct Velocity6D { + /// + float xd; + /// + float yd; + /// + float zd; + /// + float wxd; + /// + float wyd; + /// + float wzd; + + /// + /// Create a Velocity6D initialize with 0.0f. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd \\ + * wxd \\ + * wyd \\ + * wzd + * \end{array}\right] = + * \left[\begin{array}{c} + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 \\ + * 0.0 + * \end{array}\right]\f$ + */ + /// + Velocity6D(); + + /// + /// Create a Velocity6D initialize with the same float. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd \\ + * wxd \\ + * wyd \\ + * wzd + * \end{array}\right] = + * \left[\begin{array}{c} + * pInit \\ + * pInit \\ + * pInit \\ + * pInit \\ + * pInit \\ + * pInit + * \end{array}\right]\f$ + */ + /// + /// the float value for each member + /// + explicit Velocity6D(float pInit); + + /// + /// Create a Velocity6D initialize with explicit value. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd \\ + * wxd \\ + * wyd \\ + * wzd + * \end{array}\right] = + * \left[\begin{array}{c} + * pXd \\ + * pYd \\ + * pZd \\ + * pWxd \\ + * pWyd \\ + * pWzd + * \end{array}\right]\f$ + */ + /// + /// the float value for xd + /// the float value for yd + /// the float value for zd + /// the float value for wxd + /// the float value for wyd + /// the float value for wzd + Velocity6D( + float pXd, + float pYd, + float pZd, + float pWxd, + float pWyd, + float pWzd); + + /// + /// Create a Velocity6D with an std::vector. + /** + * + * \f$ \left[\begin{array}{c} + * xd \\ + * yd \\ + * zd \\ + * wxd \\ + * wyd \\ + * wzd + * \end{array}\right] = + * \left[\begin{array}{c} + * pFloats[0] \\ + * pFloats[1] \\ + * pFloats[2] \\ + * pFloats[3] \\ + * pFloats[4] \\ + * pFloats[5] + * \end{array}\right]\f$ + */ + /// + /// + /// An std::vector of size 6 for respectively: + /// + /// xd, yd, zd, wxd, wyd and wzd + /// + Velocity6D(const std::vector& pFloats); + + /// + /// Overloading of operator + for Velocity6D. + /// + /// the second Velocity6D + inline Velocity6D operator+ (const Velocity6D& pVel2) const + { + return Velocity6D( + xd + pVel2.xd, + yd + pVel2.yd, + zd + pVel2.zd, + wxd + pVel2.wxd, + wyd + pVel2.wyd, + wzd + pVel2.wzd); + } + + /// + /// Overloading of operator - for Velocity6D. + /// + /// the second Velocity6D + inline Velocity6D operator- (const Velocity6D& pVel2) const + { + return Velocity6D( + xd - pVel2.xd, + yd - pVel2.yd, + zd - pVel2.zd, + wxd - pVel2.wxd, + wyd - pVel2.wyd, + wzd - pVel2.wzd); + } + + /// + /// Overloading of operator + for Velocity6D. + /// + inline Velocity6D operator+ (void) const + { + return *this; + } + + /// + /// Overloading of operator - for Velocity6D. + /// + inline Velocity6D operator- () const + { + return Velocity6D(-xd, -yd, -zd, -wxd, -wyd, -wzd); + } + + /// + /// Overloading of operator * for Velocity6D. + /// + /// the float factor. + inline Velocity6D operator* (const float pVal) const + { + return Velocity6D( + xd*pVal, + yd*pVal, + zd*pVal, + wxd*pVal, + wyd*pVal, + wzd*pVal); + } + + /// + /// Overloading of operator / for Velocity6D. + /// + /// the float factor. + Velocity6D operator/ (const float pVal) const; + + /// + /// Overloading of operator == for Velocity6D. + /// + /// the second Velocity6D. + bool operator== (const Velocity6D& pVel2) const; + + /// + /// Overloading of operator != for Velocity6D. + /// + /// the second Velocity6D. + bool operator!= (const Velocity6D& pVel2) const; + + /// + /// Overloading of operator *= for Velocity6D. + /// + /// the float factor. + Velocity6D& operator*= (const float pVal); + + /// + /// Overloading of operator /= for Velocity6D. + /// + /// the float factor. + Velocity6D& operator/= (const float pVal); + + /// + /// Check if the actual Velocity6D is Near the one + /// given in argument. + /// + /// + /// the second Velocity6D + /// an optional epsilon distance + /// + /// true if the difference of each float of the two Velocity6D is less than pEpsilon + /// + bool isNear( + const Velocity6D& pVel2, + const float& pEpsilon=0.0001f) const; + + /// + /// Compute the norm of the actual Velocity6D: + /// + /// \f$\sqrt{xd^2 + yd^2 + zd^2 + wxd^2 + wyd^2 + wzd^2}\f$ + /// + /// + /// the float norm of the Velocity6D + /// + float norm() const; + + /// + /// Normalize the actual Velocity6D: + /// + /// \f$ result = \frac{pVel}{norm(pVel)} \f$ + /// + /// + /// the Velocity6D normalized + /// + Velocity6D normalize() const; + + /// + /// Return the Velocity6D as a vector of float [xd, yd, zd, wxd, wyd, wzd]. + /// + void toVector(std::vector& pReturnVector) const; + std::vector toVector(void) const; +}; // end struct + +/// +/// Overloading of operator * for left Velocity6D. +/// +/// the float factor. +/// the given Velocity6D. +Velocity6D operator* ( + const float pVal, + const Velocity6D& pVel); + +/// +/// Compute the norm of a Velocity6D: +/// +/// \f$\sqrt{pVel.xd^2 + pVel.yd^2 + pVel.zd^2 + pVel.wxd^2 + pVel.wyd^2 + pVel.wzd^2}\f$ +/// +/// the given Velocity6D +/// +/// the float norm of the given Velocity6D +/// +/// \ingroup Types +float norm(const Velocity6D& pVel); + +/// +/// Normalize a Velocity6D: +/// +/// \f$pRes = \frac{pVel}{norm(pVel)} \f$ +/// +/// the given Velocity6D +/// +/// the given Velocity6D normalized +/// +/// \ingroup Types +Velocity6D normalize(const Velocity6D& pVel); + +} // end namespace Math +} // end namespace AL +#endif // _LIBALMATH_ALMATH_TYPES_ALVELOCITY6D_H_ diff --git a/naoModule/libnaoqi_files/include/almemory/constants.hpp b/naoModule/libnaoqi_files/include/almemory/constants.hpp new file mode 100755 index 0000000..22bda44 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almemory/constants.hpp @@ -0,0 +1,24 @@ +/** + * Copyright (c) Aldebaran Robotics 2012 All Rights Reserved. + */ + +#ifndef _AL_MEMORY_CONSTANTS_H_ +#define _AL_MEMORY_CONSTANTS_H_ + +namespace AL +{ + namespace Memory + { + // ALMemory key names + /// Key for new key event. + extern const char* keyAddedKey; + + /// Key for removed key event. + extern const char* keyRemovedKey; + + /// Key for key nature changed event. + extern const char* keyTypeChanged; + } +} + +#endif // _AL_MEMORY_CONSTANTS_H_ diff --git a/naoModule/libnaoqi_files/include/almemoryfastaccess/almemoryfastaccess.h b/naoModule/libnaoqi_files/include/almemoryfastaccess/almemoryfastaccess.h new file mode 100755 index 0000000..0c1ef76 --- /dev/null +++ b/naoModule/libnaoqi_files/include/almemoryfastaccess/almemoryfastaccess.h @@ -0,0 +1,242 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALMEMORYFASTACCESS_ALMEMORYFASTACCESS_ALMEMORYFASTACCESS_H_ +#define _LIBALMEMORYFASTACCESS_ALMEMORYFASTACCESS_ALMEMORYFASTACCESS_H_ + +#include +#include + +#include + +namespace AL +{ + class ALProxy; + class ALBroker; + + /** + * \class ALMemoryFastAccess almemoryfastaccess/almemoryfastaccess.h + * \brief ALMemoryFastAccess is a fast access in Read/Write to some variables of ALMemory. + * + * ALMemoryFastAccess is a fast access in Read/Write to some variables + * of ALMemory regularily accessed, with a unified interface. + * + * - if ALMemory is in same broker than the caller: + * store directly pointer to data (hack* method) + * - if ALMemory is remote with the caller: + * standard call (not so optimised, but the more optimal possible access) + * + * - ASSUME: variables never disappear. + * - ASSUME: variables are all floats or ints. + * \ingroup libalmemoryfastaccess + */ + class ALMemoryFastAccess + { + /** + * \typedef TVariablePtrArray + * \brief Vector of float pointer + */ + typedef std::vector TVariablePtrArray; + /** + * \typedef TFloatPtrArray + * \brief Vector of float pointer + */ + typedef std::vector TFloatPtrArray; + /** + * \typedef TIntPtrArray + * \brief Vector of int pointer + */ + typedef std::vector TIntPtrArray; + /** + * \typedef ITVariablePtrArray + * \brief Iterator on a vector of float pointer + */ + typedef TVariablePtrArray::iterator ITVariablePtrArray; + /** + * \typedef CITVariablePtrArray + * \brief Iterator on a vector of float pointer + */ + typedef TVariablePtrArray::const_iterator CITVariablePtrArray; + + public: + /** + * \brief Default constructor. + */ + ALMemoryFastAccess(); + + /** + * \brief Default destructor. + */ + ~ALMemoryFastAccess(); + + + /** + * \brief Remove all pointer. + */ + void StopAllAccess(void); + + /** + * \brief Insert a binary ALValue in ALMemory. + * \param pName value + * \param pBuff ALValue + */ + void insertBuffer(const std::string &pName, + const ALValue &pBuff); + + /** + * \brief First time, you must "connect" to variables to access later, + * many times. + * \param pBroker a pointer to the broker + * \param pListVariables list of variable names, + * eg: {"DCM/Sensor1", "DCM/Sensor2"} ... + * \param bAllowNonExistantVariable unused parameter + */ + void ConnectToVariables(const boost::shared_ptr pBroker, + const std::vector &pListVariables, + bool bAllowNonExistantVariable = false); + + /** + * \brief First time, you must "connect" to int variables to access later, + * many times. + * \param pBroker a pointer to the broker + * \param pListVariables list of variable names, + * eg: {"DCM/Sensor1", "DCM/Sensor2"} ... + */ + void ConnectToIntVariables(const boost::shared_ptr pBroker, + const std::vector &pListVariables); + + /** + * \brief Get pointer on 32bit data + * \param pBroker a pointer to the broker + * \param pStrValue value name + * \param bAllowUnexistantVariable unused parameter + */ + static void *getDataPtr(boost::shared_ptr pBroker, + const std::string &pStrValue, + bool bAllowUnexistantVariable); + + /** + * \brief Get pointer on 32bit data + * \param pMemoryProxy a pointer to the memory + * \param pStrValue value name + * \param pValue value to insert if pStrValue is non-existent + */ + template + static T *getSafeDataPtr(boost::shared_ptr pMemoryProxy, + const std::string &pStrValue, + T pValue) + { + bool insertData = false; + + try + { + insertData = !pMemoryProxy->getData(pStrValue).isValid(); + } + catch(const std::exception &) + { + // If the data doesn't exist in memory getData return an invalid ALValue + // or throw. So in this case we try to insert data before getting pointer. + insertData = true; + } + + if(insertData) + { + pMemoryProxy->insertData(pStrValue, pValue); + } + + return static_cast(pMemoryProxy->getDataPtr(pStrValue)); + } + + /** + * \brief FIXME: No implementation. + * \param pBroker a pointer to the broker + * \param pListVariables list of variable names, + * eg: {"DCM/Sensor1", "DCM/Sensor2"} ... + * \param bAllowUnexistantVariable unused parameter + */ + void directConnectToVariables(const boost::shared_ptr pBroker, + const std::vector &pListVariables, + bool bAllowUnexistantVariable = false); + + /** + * \brief Get previous "connected" variables. + * \param pListValue where to put the gathered value of variables + */ + void GetValues(std::vector &pListValue) const; + + /** + * \brief Set previous "connected" variables. + * \param pListValue Value of variables to put into memory. + */ + void SetValues(const std::vector &pListValue); + + /** + * \brief Get previous "connected" variables. + * \param pListValue where to put the gathered value of variables + */ + void GetValues(std::vector &pListValue) const; + + /** + * \brief Set previous "connected" variables. + * \param pListValue Value of variables to put into memory. + */ + void SetValues(const std::vector &pListValue); + +#ifdef DEBUG + /** + * \brief Disable fatal error, if values connecting doesn't exists + * \warning this is a debug functionnality only. + */ + inline void DisableCheckOnNotExistingValueOrThings_Debug(void) { fbDisableCheking_Debug = true; }; +#endif + + /** + * \brief Test function. + * \param pBroker a pointer to the broker + * \return true if test ok, false otherwise + */ + static bool InnerTest(const boost::shared_ptr pBroker); + + private: + /** + * \brief Get data from name's value. + * \param pName name's value you want + */ + static ALValue* getBuffer(const std::string &pName); + + /** A pointer to ALProxy (ALMemory) */ + boost::shared_ptr fMemoryProxy; + + /** true if ALMemory is local to us */ + bool fbIsLocal; + /** local case: direct memory pointer access where the data is stored */ + TVariablePtrArray fListVariablePtr; + /** local case: direct memory pointer access where the data is stored */ + TFloatPtrArray fListFloatPtr; + /** local case: direct memory pointer access where the data is stored */ + TIntPtrArray fListIntPtr; + + + /** remote case: the format of the GetListData Command to send */ + ALValue fCommandToGetData; + /** remote case: the format of the GetListData Command to send */ + ALValue fCommandToSetData; + + /** if true, stop all access (usually ALMemory has been destroyed) */ + bool fStopAllAccess; + +#ifdef DEBUG + /** if true, doesn't complaign if value doesn't exists */ + bool fbDisableCheking_Debug; +#endif + }; + +} // !namespace AL +#endif // _LIBALMEMORYFASTACCESS_ALMEMORYFASTACCESS_ALMEMORYFASTACCESS_H_ diff --git a/naoModule/libnaoqi_files/include/alparammanager/alparammanager.h b/naoModule/libnaoqi_files/include/alparammanager/alparammanager.h new file mode 100755 index 0000000..817876a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alparammanager/alparammanager.h @@ -0,0 +1,414 @@ +#ifndef _PARAMMANAGER_H_ +#define _PARAMMANAGER_H_ + + +#include +#include +#include +#include +#include + + +namespace AL { +namespace Param { + +// Exceptions from this library inherit from this class. +// TODO: +// - create derived exceptions classes, +// - move error classes in a separate header. +class ParamError: public std::runtime_error { +public: + ParamError(const std::string& what); + virtual ~ParamError() throw(); +}; + + +// Checker base class. +// Its main purpose is to tell whether a given value is valid or not. +// Used by Param to know if an affectation is valid. +template +class ParamChecker { +public: + virtual bool isValid(const T&) const = 0; + virtual std::string usage() const = 0; + virtual void throwIfInvalid(const T&) const = 0; + virtual ~ParamChecker() {} +}; + +template +class AlwaysTrueChecker : public ParamChecker { +public: + bool isValid(const T&) const { return true; } + void throwIfInvalid(const T&) const {} + std::string usage() const { return "Is always true"; } +}; + + +template +class RangeChecker : public ParamChecker { +public: + RangeChecker(const T& min, const T& max) + : fMin(min), + fMax(max) {} + + virtual bool isValid(const T& val) const { + return (val >= fMin && val <= fMax); + } + + void throwIfInvalid(const T& val) const { + if (!isValid(val)) + throw ParamError("Invalid range"); + } + + std::string usage() const { return "True when in range ... TODO"; } +private: + T fMin; + T fMax; +}; + + +template +class ListChecker : public ParamChecker { +public: + template + ListChecker(InputIterator begin, InputIterator end) + : fValidValues(begin, end) { + + } + + virtual bool isValid(const T& val) const { + typename std::set::const_iterator it = fValidValues.find(val); + return it != fValidValues.end(); + } + + void throwIfInvalid(const T& val) const { + if (!isValid(val)) + throw ParamError("Not in the valid set"); + } + + std::string usage() const { return "True when in list ... TODO"; } +private: + std::set fValidValues; +}; + + +// Just to have a different Syntax ... +namespace Checker { +// +template +AlwaysTrueChecker* alwaysTrue(const T& min, const T& max) { + return new AlwaysTrueChecker(min, max); +} + +// +template +RangeChecker* range(const T& min, const T& max) { + return new RangeChecker(min, max); +} + +// +template +ListChecker* list(InputIterator begin, InputIterator end) { + return new ListChecker(begin, end); +} + +template +ListChecker* list(const std::vector &container) { + return new ListChecker(container.begin(), container.end()); +} + +} // Checker. + + +/////////////////////////////////////////////////////////////////////////////// + + +// Parameter. +// The value it holds is protected by a checker, it owns a description, +// can be read-only, etc. +template +class Param { +public: + explicit Param() + : fVal(), + fDefaultValue(), + fChecker(NULL), + fDesc(), + fValOwned(false), + fReadOnly(false) { + + fVal = new T(); + fValOwned = true; + } + + Param* setDefaultValue(const T& val) { + fDefaultValue = val; + resetValue(); + return this; + } + + T getDefaultValue() const { + return fDefaultValue; + } + + Param* setChecker(ParamChecker* _checker) { + if (fChecker != _checker) { + delete fChecker; + fChecker = _checker; + } + return this; + } + + // Storage object is set to default. + Param* setStorage(T* storage) { + if (fVal == storage) + return this; + + if (fValOwned) { + delete fVal; + fValOwned = false; + } + fVal = storage; + resetValue(); + return this; + } + + Param* setReadOnly(bool _readOnly) { + fReadOnly = _readOnly; + return this; + } + + + Param* setDescription(const std::string& _desc) { + fDesc = _desc; + return this; + } + + const std::string& description() const { + return fDesc; + } + + void setValue(const T& _val) { + if (fReadOnly) { + throw ParamError("Param is read-only"); + } + if (fChecker) + fChecker->throwIfInvalid(_val); + *fVal = _val; + } + + bool isReadOnly() const { + return fReadOnly; + } + + + T getValue() const { + return *fVal; + } + + void resetValue() { + setValue(fDefaultValue); + } + + ~Param() { + if (fValOwned) { + delete fVal; + } + delete fChecker; + } + +private: + // Actually value. Owned if valOwned = true. + T* fVal; + // Default value set when reset(). + T fDefaultValue; + + // Checker. Owned. + ParamChecker* fChecker; + + std::string fDesc; + + // True if val is owned by this class. + bool fValOwned; + + // set() throws if this is true. + bool fReadOnly; +}; + +// Just to make param instanciation easier. +template +Param* makeParam() { + return new Param(); +} + + +// Template style param manager. +// It handles mappings between a "keyname" and a Param. +// Only handles one type of value. +template +class ParamMap { +public: + + void addParam(const std::string& name, Param* param) { + fMap[name] = param; + } + + const Param* getParam(const std::string& name) const { + MapCIT it = xGetParamThrow(name); + return it->second; + } + + Param* getParam(const std::string& name) { + MapIT it = xGetParamThrow(name); + return it->second; + } + + ~ParamMap() { + for (MapIT it = fMap.begin(); it != fMap.end(); ++it) { + delete it->second; + } + } + +private: + typedef typename std::map< std::string, Param* >::iterator MapIT; + typedef typename std::map< std::string, Param* >::const_iterator MapCIT; + + MapCIT xGetParamThrow(const std::string& name) const { + MapCIT it = fMap.find(name); + if (it == fMap.end()) + throw ParamError(name + " doesn't exist"); + return it; + } + + MapIT xGetParamThrow(const std::string& name) { + MapIT it = fMap.find(name); + if (it == fMap.end()) + throw ParamError(name + " doesn't exist"); + return it; + } + + // Param* are owned by this map. + std::map< std::string, Param* > fMap; +}; + + +enum SupportedType { + kTypeInt = 0, + kTypeFloat, + kTypeBool, + + kTypeNums, + + kTypeUnsupported +}; + +template +struct GetType { + enum { type = kTypeUnsupported }; +}; + +template <> +struct GetType { + enum { type = kTypeInt }; +}; + +template <> +struct GetType { + enum { type = kTypeFloat }; +}; + +template <> +struct GetType { + enum { type = kTypeBool }; +}; + + +// ParamManager. +// Can handle a list of basic types. +class ParamManager { +public: + + template + void addParam(const std::string& name, Param* param) { + SupportedType templateType = static_cast(GetType::type); + ParamMap* mger = xMgerSelect(templateType); + mger->addParam(name, param); + fMap[name] = templateType; + } + + template + const Param* getParam(const std::string& name) const { + MapCIT cit = xGetParamThrow(name); + SupportedType templateType = cit->second; + ParamMap* mger = xMgerSelect(templateType); + return mger->getParam(name); + } + + template + Param* getParam(const std::string& name) { + MapIT it = xGetParamThrow(name); + SupportedType templateType = it->second; + ParamMap* mger = xMgerSelect(templateType); + return mger->getParam(name); + } + +private: + + template + ParamMap* xMgerSelect(SupportedType type) const { + switch (type) { + case kTypeInt: + return (ParamMap*)(&fIntMger); + break; + case kTypeFloat: + return (ParamMap*)(&fFloatMger); + break; + + case kTypeBool: + return (ParamMap*)(&fBoolMger); + break; + + case kTypeUnsupported: + throw ParamError("Unsupported type"); + break; + default: + // Should never happen. + //assert(false); + throw ParamError("Unsupported type"); + } + } + + + typedef std::map< std::string, SupportedType >::iterator MapIT; + typedef std::map< std::string, SupportedType >::const_iterator MapCIT; + + MapCIT xGetParamThrow(const std::string& name) const { + MapCIT it = fMap.find(name); + if (it == fMap.end()) + throw ParamError(name + " doesn't exist"); + return it; + } + + MapIT xGetParamThrow(const std::string& name) { + MapIT it = fMap.find(name); + if (it == fMap.end()) + throw ParamError(name + " doesn't exist"); + return it; + } + + ParamMap fIntMger; + ParamMap fFloatMger; + ParamMap fBoolMger; + + //ParamManager* fMgers[kTypeNums]; + + + std::map< std::string, SupportedType > fMap; + +}; + + +} // Param +} // AL + +#endif // _PARAMMANAGER_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alanimatedspeechproxy.h b/naoModule/libnaoqi_files/include/alproxies/alanimatedspeechproxy.h new file mode 100755 index 0000000..ce172cf --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alanimatedspeechproxy.h @@ -0,0 +1,328 @@ +// Generated for ALAnimatedSpeech version 0 + +#ifndef ALANIMATEDSPEECHPROXY_H_ +#define ALANIMATEDSPEECHPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAnimatedSpeechProxy; + + namespace detail { + class ALAnimatedSpeechProxyPostHandler + { + protected: + ALAnimatedSpeechProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAnimatedSpeechProxy; + + /// + /// Add some new links between tags and words. + /// + /// Map of tags to words. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addTagsToWords(const AL::ALValue& tagsToWords); + + /// + /// Add a new package that contains animations. + /// + /// The new package that contains animations. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int declareAnimationsPackage(const std::string& animationsPackage); + + /// + /// Declare some tags with the associated animations. + /// + /// Map of Tags to Animations. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int declareTagForAnimations(const AL::ALValue& tagsToAnimations); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Say the annotated text given in parameter and animate it with animations inserted in the text. + /// + /// An annotated text (for example: "Hello. ^start(Hey_1) My name is NAO"). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int say(const std::string& text); + + /// + /// Say the annotated text given in parameter and animate it with animations inserted in the text. + /// + /// An annotated text (for example: "Hello. ^start(Hey_1) My name is NAO"). + /// The animated speech configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int say(const std::string& text, const AL::ALValue& configuration); + + /// + /// DEPRECATED since 1.22: use setBodyLanguageMode instead.Enable or disable the automatic body language on the speech.If it is enabled, anywhere you have not annotate your text with animation,the robot will fill the gap with automatically calculated gestures.If it is disabled, the robot will move only where you annotate it withanimations. + /// + /// The boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBodyLanguageEnabled(const bool& enable); + + /// + /// Set the current body language mode. + /// 3 modes exist: BODY_LANGUAGE_MODE_DISABLED,BODY_LANGUAGE_MODE_RANDOM and BODY_LANGUAGE_MODE_CONTEXTUAL + /// (see BodyLanguageMode enum for more details) + /// + /// The choosen body language mode. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBodyLanguageMode(const qi::uint32_t& bodyLanguageMode); + + /// + /// Set the current body language mode. + /// 3 modes exist: "disabled", "random" and "contextual" + /// (see BodyLanguageMode enum for more details) + /// + /// The choosen body language mode. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBodyLanguageModeFromStr(const std::string& stringBodyLanguageMode); + + /// + /// DEPRECATED since 1.18: use setBodyLanguageMode instead.Enable or disable the automatic body talk on the speech.If it is enabled, anywhere you have not annotate your text with animation,the robot will fill the gap with automatically calculated gestures.If it is disabled, the robot will move only where you annotate it withanimations. + /// + /// The boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBodyTalkEnabled(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAnimatedSpeechProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAnimatedSpeechProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAnimatedSpeechProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAnimatedSpeechProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAnimatedSpeechProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Add some new links between tags and words. + /// + /// Map of tags to words. + void addTagsToWords(const AL::ALValue& tagsToWords); + + /// + /// Add a new package that contains animations. + /// + /// The new package that contains animations. + void declareAnimationsPackage(const std::string& animationsPackage); + + /// + /// Declare some tags with the associated animations. + /// + /// Map of Tags to Animations. + void declareTagForAnimations(const AL::ALValue& tagsToAnimations); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Set the current body language mode. + /// 3 modes exist: BODY_LANGUAGE_MODE_DISABLED,BODY_LANGUAGE_MODE_RANDOM and BODY_LANGUAGE_MODE_CONTEXTUAL + /// (see BodyLanguageMode enum for more details) + /// + /// The current body language mode. + qi::uint32_t getBodyLanguageMode(); + + /// + /// Set the current body language mode. + /// 3 modes exist: "disabled", "random" and "contextual" + /// (see BodyLanguageMode enum for more details) + /// + /// The current body language mode. + std::string getBodyLanguageModeToStr(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// DEPRECATED since 1.22: use getBodyLanguageMode instead.Indicate if the body language is enabled or not. + /// + /// The boolean value: true means it is enabled, false means it is disabled. + bool isBodyLanguageEnabled(); + + /// + /// DEPRECATED since 1.18: use getBodyLanguageMode instead.Indicate if the body talk is enabled or not. + /// + /// The boolean value: true means it is enabled, false means it is disabled. + bool isBodyTalkEnabled(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Say the annotated text given in parameter and animate it with animations inserted in the text. + /// + /// An annotated text (for example: "Hello. ^start(Hey_1) My name is NAO"). + void say(const std::string& text); + + /// + /// Say the annotated text given in parameter and animate it with animations inserted in the text. + /// + /// An annotated text (for example: "Hello. ^start(Hey_1) My name is NAO"). + /// The animated speech configuration. + void say(const std::string& text, const AL::ALValue& configuration); + + /// + /// DEPRECATED since 1.22: use setBodyLanguageMode instead.Enable or disable the automatic body language on the speech.If it is enabled, anywhere you have not annotate your text with animation,the robot will fill the gap with automatically calculated gestures.If it is disabled, the robot will move only where you annotate it withanimations. + /// + /// The boolean value: true to enable, false to disable. + void setBodyLanguageEnabled(const bool& enable); + + /// + /// Set the current body language mode. + /// 3 modes exist: BODY_LANGUAGE_MODE_DISABLED,BODY_LANGUAGE_MODE_RANDOM and BODY_LANGUAGE_MODE_CONTEXTUAL + /// (see BodyLanguageMode enum for more details) + /// + /// The choosen body language mode. + void setBodyLanguageMode(const qi::uint32_t& bodyLanguageMode); + + /// + /// Set the current body language mode. + /// 3 modes exist: "disabled", "random" and "contextual" + /// (see BodyLanguageMode enum for more details) + /// + /// The choosen body language mode. + void setBodyLanguageModeFromStr(const std::string& stringBodyLanguageMode); + + /// + /// DEPRECATED since 1.18: use setBodyLanguageMode instead.Enable or disable the automatic body talk on the speech.If it is enabled, anywhere you have not annotate your text with animation,the robot will fill the gap with automatically calculated gestures.If it is disabled, the robot will move only where you annotate it withanimations. + /// + /// The boolean value: true to enable, false to disable. + void setBodyTalkEnabled(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAnimatedSpeechProxyPostHandler post; + }; + +} +#endif // ALANIMATEDSPEECHPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alaudiodeviceproxy.h b/naoModule/libnaoqi_files/include/alproxies/alaudiodeviceproxy.h new file mode 100755 index 0000000..181d552 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alaudiodeviceproxy.h @@ -0,0 +1,490 @@ +// Generated for ALAudioDevice version 0 + +#ifndef ALAUDIODEVICEPROXY_H_ +#define ALAUDIODEVICEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAudioDeviceProxy; + + namespace detail { + class ALAudioDeviceProxyPostHandler + { + protected: + ALAudioDeviceProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAudioDeviceProxy; + + /// + /// Closes the audio device for capture. You can call this method if you want to have access to the alsa input buffers in another program than naoqi while naoqi is running (with arecord for example) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int closeAudioInputs(); + + /// + /// Closes the audio device for playback. close the audio device for capture. You can call this method if you want to send sound to alsa in another program than naoqi while naoqi is running (with aplay for example) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int closeAudioOutputs(); + + /// + /// Disables the computation of the energy of each microphone signal + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int disableEnergyComputation(); + + /// + /// Enables the computation of the energy of each microphone signal + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableEnergyComputation(); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Flush the audio device for playback. close the audio device for capture. You can call this method if you want to send sound to alsa in another program than naoqi while naoqi is running (with aplay for example) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int flushAudioOutputs(); + + /// + /// mute the loudspeakers + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int muteAudioOut(const bool& arg1); + + /// + /// Opens the audio device for capture. If you closed the audio inputs with the closeAudioInputs method, you must call this method to be able to access to the sound data of the nao's microphones. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int openAudioInputs(); + + /// + /// Opens the audio device for playback. If you closed the audio outputs with the closeAudioOutputs method, you must call this method to ear or send sound onto the nao's loudspeakers. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int openAudioOutputs(); + + /// + /// Play a sine wave which specified caracteristics. + /// + /// Frequence in Hertz + /// Volume Gain between 0 and 100 + /// Stereo Pan set to either {-1,0,+1} + /// Duration of the sine wave in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSine(const int& frequence, const int& gain, const int& pan, const float& duration); + + /// + /// Set AudioDevice Client preferences. This function is deprecated, the use of the alternate 4 arguments setClientPreferences() is now prefered. + /// + /// name of the client + /// sample rate of the microphones data sent to the processSound or processSoundRemote functions - must be 16000 or 48000 + /// ALValue containing a vector of int indicating which microphones data will be send to the processSound or processSoundRemote functions + /// indicates if the microphones data sent to the processSound or processSoundRemote functions are interleaved or not - 0 : interleaved - 1 : deinterleaved + /// parameter indicating if audio timestamps are sent to the processSound or processSoundRemote functions - 0 : no - 1 : yes + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setClientPreferences(const std::string& name, const int& sampleRate, const AL::ALValue& channelsVector, const int& deinterleaved, const int& timeStamp); + + /// + /// Set AudioDevice Client preferences + /// + /// name of the client + /// sample rate of the microphones data sent to the process function - must be 16000 or 48000 + /// An int (defined in ALSoundExtractor) indicating which microphones data will be send to the process function. ALLCHANNELS, LEFTCHANNEL, RIGHTCHANNEL, FRONTCHANNEL, REARCHANNEL are the configuration currently supported. + /// indicates if the microphones data sent to the process function are interleaved or not - 0 : interleaved - 1 : deinterleaved + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setClientPreferences(const std::string& name, const int& sampleRate, const int& channelsConfiguration, const int& deinterleaved); + + /// + /// This method allows to send sound samples contained in a sound file at the input of ALAudioDevice, instead of the nao's microphones sound data. The sound file must be a .wav file containing 16bits / 4 channels / interleaved samples. Once the file has been read, microphones sound data will again taken as input + /// + /// Name of the input file. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFileAsInput(const std::string& pFileName); + + /// + /// Sets the output sound level of the system. + /// + /// Volume [0-100]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setOutputVolume(const int& volume); + + /// + /// This method sets the specified internal parameter ('outputSampleRate' or 'inputBufferSize') + /// inputBufferSize can bet set to 8192 or 16384. Warning: when speech recognition is running, a buffer size of 8192 is used. Don't change it during the recognition process. + /// outputSampleRate can bet set to 16000 Hz, 22050 Hz, 44100 Hz or 48000 Hz. Warning: if speech synthesis is running, a sample rate of 16000 Hz or 22050 Hz is used (depending of the language). Don't change it during the synthesis process + /// + /// Name of the parameter to set ('outputSampleRate' or 'inputBufferSize'). + /// The value to which the specified parameter should be set. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& pParamName, const int& pParamValue); + + /// + /// This method allows to record the signal collected on the nao's microphones. You can choose to record only the front microphone in a ogg file, or the 4 microphones in a wav file. In this last case the format of the file is 4 channels, 16 bits little endian, 48 KHz + /// + /// Name of the file where to record the sound. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startMicrophonesRecording(const std::string& pFileName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// This method stops the recording of the sound collected by the microphones. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopMicrophonesRecording(); + + /// + /// This function allows a module to subscribe to the ALAudioDevice module.For more informations see the audio part of the red documentation + /// + /// Name of the module + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& pModule); + + /// + /// This function allows a module to subscribe to the ALAudioDevice module.For more informations see the audio part of the red documentation + /// + /// Name of the module + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& pModule); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAudioDeviceProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAudioDeviceProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAudioDeviceProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAudioDeviceProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAudioDeviceProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Closes the audio device for capture. You can call this method if you want to have access to the alsa input buffers in another program than naoqi while naoqi is running (with arecord for example) + /// + void closeAudioInputs(); + + /// + /// Closes the audio device for playback. close the audio device for capture. You can call this method if you want to send sound to alsa in another program than naoqi while naoqi is running (with aplay for example) + /// + void closeAudioOutputs(); + + /// + /// Disables the computation of the energy of each microphone signal + /// + void disableEnergyComputation(); + + /// + /// Enables the computation of the energy of each microphone signal + /// + void enableEnergyComputation(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Flush the audio device for playback. close the audio device for capture. You can call this method if you want to send sound to alsa in another program than naoqi while naoqi is running (with aplay for example) + /// + void flushAudioOutputs(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns the energy of the front microphone signal + /// + /// energy of the front microphone signal + float getFrontMicEnergy(); + + /// + /// Returns the energy of the left microphone signal + /// + /// energy of the left microphone signal + float getLeftMicEnergy(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the output sound level of the system. + /// + /// outputVolume of the system + int getOutputVolume(); + + /// + /// This method returns the specified internal parameter ('outputSampleRate' or 'inputBufferSize'). The value -1 is returned if the specified parameter is not valid. + /// + /// Name of the parameter to get ('outputSampleRate' or 'inputBufferSize'). + /// value of the specified parameter + int getParameter(const std::string& pParamName); + + /// + /// Returns the energy of the rear microphone signal + /// + /// energy of the rear microphone signal + float getRearMicEnergy(); + + /// + /// Returns the energy of the right microphone signal + /// + /// energy of the right microphone signal + float getRightMicEnergy(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// check if loudspeakers are muted + /// + /// 1 if true / 0 otherwise + bool isAudioOutMuted(); + + /// + /// Allows to know if audio inputs are closed or not + /// + /// True if audio inputs are closed / False otherwise + bool isInputClosed(); + + /// + /// Allows to know if audio ouputs are closed or not + /// + /// True if audio outputs are closed / False otherwise + bool isOutputClosed(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// mute the loudspeakers + /// + /// arg + void muteAudioOut(const bool& arg1); + + /// + /// Opens the audio device for capture. If you closed the audio inputs with the closeAudioInputs method, you must call this method to be able to access to the sound data of the nao's microphones. + /// + void openAudioInputs(); + + /// + /// Opens the audio device for playback. If you closed the audio outputs with the closeAudioOutputs method, you must call this method to ear or send sound onto the nao's loudspeakers. + /// + void openAudioOutputs(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Play a sine wave which specified caracteristics. + /// + /// Frequence in Hertz + /// Volume Gain between 0 and 100 + /// Stereo Pan set to either {-1,0,+1} + /// Duration of the sine wave in seconds + void playSine(const int& frequence, const int& gain, const int& pan, const float& duration); + + /// + /// This function allows a local module to send sound onto the nao's loudpseakers + /// You must pass to this function a pointer to the stereo buffer to send, and the number of frames per channel. The buffer must contain 16bits stereo interleaved samples, and the number of frames does not exceed 16384 + /// + /// Number of 16 bits samples per channel to send. + /// Buffer to send + /// True if the operation is successfull - False otherwise + bool sendLocalBufferToOutput(const int& nbOfFrames, const int& pBuffer); + + /// + /// This function allows a remote module to send sound onto the nao's loudpseakers + /// You must pass to this function the stereo buffer you want to send as an ALValue converted to binary, and the number of frames per channel. The number of frames does not exceed 16384. For more information please see the red documentation + /// + /// Number of 16 bits samples per channel to send. + /// Buffer to send + /// True if the operation is successfull - False otherwise + bool sendRemoteBufferToOutput(const int& nbOfFrames, const AL::ALValue& pBuffer); + + /// + /// Set AudioDevice Client preferences. This function is deprecated, the use of the alternate 4 arguments setClientPreferences() is now prefered. + /// + /// name of the client + /// sample rate of the microphones data sent to the processSound or processSoundRemote functions - must be 16000 or 48000 + /// ALValue containing a vector of int indicating which microphones data will be send to the processSound or processSoundRemote functions + /// indicates if the microphones data sent to the processSound or processSoundRemote functions are interleaved or not - 0 : interleaved - 1 : deinterleaved + /// parameter indicating if audio timestamps are sent to the processSound or processSoundRemote functions - 0 : no - 1 : yes + void setClientPreferences(const std::string& name, const int& sampleRate, const AL::ALValue& channelsVector, const int& deinterleaved, const int& timeStamp); + + /// + /// Set AudioDevice Client preferences + /// + /// name of the client + /// sample rate of the microphones data sent to the process function - must be 16000 or 48000 + /// An int (defined in ALSoundExtractor) indicating which microphones data will be send to the process function. ALLCHANNELS, LEFTCHANNEL, RIGHTCHANNEL, FRONTCHANNEL, REARCHANNEL are the configuration currently supported. + /// indicates if the microphones data sent to the process function are interleaved or not - 0 : interleaved - 1 : deinterleaved + void setClientPreferences(const std::string& name, const int& sampleRate, const int& channelsConfiguration, const int& deinterleaved); + + /// + /// This method allows to send sound samples contained in a sound file at the input of ALAudioDevice, instead of the nao's microphones sound data. The sound file must be a .wav file containing 16bits / 4 channels / interleaved samples. Once the file has been read, microphones sound data will again taken as input + /// + /// Name of the input file. + void setFileAsInput(const std::string& pFileName); + + /// + /// Sets the output sound level of the system. + /// + /// Volume [0-100]. + void setOutputVolume(const int& volume); + + /// + /// This method sets the specified internal parameter ('outputSampleRate' or 'inputBufferSize') + /// inputBufferSize can bet set to 8192 or 16384. Warning: when speech recognition is running, a buffer size of 8192 is used. Don't change it during the recognition process. + /// outputSampleRate can bet set to 16000 Hz, 22050 Hz, 44100 Hz or 48000 Hz. Warning: if speech synthesis is running, a sample rate of 16000 Hz or 22050 Hz is used (depending of the language). Don't change it during the synthesis process + /// + /// Name of the parameter to set ('outputSampleRate' or 'inputBufferSize'). + /// The value to which the specified parameter should be set. + void setParameter(const std::string& pParamName, const int& pParamValue); + + /// + /// This method allows to record the signal collected on the nao's microphones. You can choose to record only the front microphone in a ogg file, or the 4 microphones in a wav file. In this last case the format of the file is 4 channels, 16 bits little endian, 48 KHz + /// + /// Name of the file where to record the sound. + void startMicrophonesRecording(const std::string& pFileName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// This method stops the recording of the sound collected by the microphones. + /// + void stopMicrophonesRecording(); + + /// + /// This function allows a module to subscribe to the ALAudioDevice module.For more informations see the audio part of the red documentation + /// + /// Name of the module + void subscribe(const std::string& pModule); + + /// + /// This function allows a module to subscribe to the ALAudioDevice module.For more informations see the audio part of the red documentation + /// + /// Name of the module + void unsubscribe(const std::string& pModule); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAudioDeviceProxyPostHandler post; + }; + +} +#endif // ALAUDIODEVICEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alaudioplayerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alaudioplayerproxy.h new file mode 100755 index 0000000..da7e44b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alaudioplayerproxy.h @@ -0,0 +1,640 @@ +// Generated for ALAudioPlayer version 0 + +#ifndef ALAUDIOPLAYERPROXY_H_ +#define ALAUDIOPLAYERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAudioPlayerProxy; + + namespace detail { + class ALAudioPlayerProxyPostHandler + { + protected: + ALAudioPlayerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAudioPlayerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Goes to a given position in a file which is playing. + /// + /// Id of the process which is playing the file + /// Position in the file (in second) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int goTo(const int& playId, const float& position); + + /// + /// Load a sound set + /// + /// name of the set + /// brokerTaskID : The ID of the task assigned to it by the broker. + int loadSoundSet(const std::string& setName); + + /// + /// Pause a play back + /// + /// Id of the process that is playing the file you want to put in pause + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const int& id); + + /// + /// Starts the playback of a file preloaded with the loadFile function. + /// + /// Id returned by the loadFile function + /// brokerTaskID : The ID of the task assigned to it by the broker. + int play(const int& id); + + /// + /// Starts the playback of a file preloaded with the loadFile function, with specific volume and audio balance + /// + /// Id returned by the loadFile function + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int play(const int& id, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file + /// + /// Path of the sound file + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFile(const std::string& fileName); + + /// + /// Plays a wav or mp3 file, with specific volume and audio balance + /// + /// Path of the sound file + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right / 0.0 : centered) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFile(const std::string& fileName, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file from a given position in the file. + /// + /// Name of the sound file + /// Position in second where the playing has to begin + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFileFromPosition(const std::string& fileName, const float& position); + + /// + /// Plays a wav or mp3 file from a given position in the file, with specific volume and audio balance + /// + /// Name of the sound file + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFileFromPosition(const std::string& fileName, const float& position, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file in loop + /// + /// Path of the sound file + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFileInLoop(const std::string& fileName); + + /// + /// Plays a wav or mp3 file in loop, with specific volume and audio balance + /// + /// Path of the sound file + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playFileInLoop(const std::string& fileName, const float& volume, const float& pan); + + /// + /// Starts the playback in loop of a file preloaded with the loadFile function + /// + /// Id returned by the loadFile function + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playInLoop(const int& id); + + /// + /// Plays a wav or mp3 file in loop, with specific volume and audio balance + /// + /// Id returned by the loadFile function + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playInLoop(const int& id, const float& volume, const float& pan); + + /// + /// Play a sine wave which specified caracteristics. + /// + /// Frequence in Hertz + /// Volume Gain between 0 and 100 + /// Stereo Pan set to either {-1,0,+1} + /// Duration of the sine wave in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSine(const int& frequence, const int& gain, const int& pan, const float& duration); + + /// + /// Plays a file contained in one of the sound sets loaded + /// + /// Name of the file without extension + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSoundSetFile(const std::string& fileName); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the soundset + /// Name of the file without extension + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSoundSetFile(const std::string& soundSetName, const std::string& fileName); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the soundset + /// Name of the file without extension + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// specify if the file must be played in loop + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSoundSetFile(const std::string& soundSetName, const std::string& fileName, const float& position, const float& volume, const float& pan, const bool& loop); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the file without extension + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// specify if the file must be played in loop + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playSoundSetFile(const std::string& fileName, const float& position, const float& volume, const float& pan, const bool& loop); + + /// + /// Starts the playback of a wab audio stream + /// + /// Path of the web audio stream + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playWebStream(const std::string& streamName, const float& arg2, const float& arg3); + + /// + /// Sets the master volume of the player + /// + /// Volume - range 0.0 to 1.0 + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMasterVolume(const float& volume); + + /// + /// sets the audio panorama : -1 for left speaker / 1 for right speaker + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPanorama(const float& arg1); + + /// + /// Sets the volume of the player + /// + /// Id of the process that is playing the file you want to put louder or less loud + /// Volume - range 0.0 to 1.0 + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVolume(const int& id, const float& volume); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops all the files that are currently playing. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAll(); + + /// + /// unloads all the files already loaded. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unloadAllFiles(); + + /// + /// unloads a file previously loaded with the loadFile function + /// + /// Id returned by the loadFile function + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unloadFile(const int& id); + + /// + /// Unload a sound set + /// + /// name of the set + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unloadSoundSet(const std::string& setName); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAudioPlayerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAudioPlayerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAudioPlayerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAudioPlayerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAudioPlayerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns the position in the file which is currently played + /// + /// Id of the process which is playing the file + /// Position in the file in seconds + float getCurrentPosition(const int& playId); + + /// + /// Returns the length of the file played + /// + /// Id of the process which is playing the file + /// Length of the file in seconds + float getFileLength(const int& playId); + + /// + /// + /// + std::vector getInstalledSoundSetsList(); + + /// + /// returns an array containing the Ids of the currently loaded files + /// + /// Array containing the Ids of the files which has been loaded + std::vector getLoadedFilesIds(); + + /// + /// returns an array containing the names of the currently loaded files + /// + /// Array containing the names of the files which has been loaded + std::vector getLoadedFilesNames(); + + /// + /// + /// + std::vector getLoadedSoundSetsList(); + + /// + /// Returns the master volume of the player + /// + /// Volume of the master - range 0.0 to 1.0. + float getMasterVolume(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Return the list of files contained in a sound set + /// + /// name of the set + std::vector getSoundSetFileNames(const std::string& setName); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns the volume of the player + /// + /// Id of the process which is playing the file + /// Volume of the player - range 0.0 to 1.0. + float getVolume(const int& playId); + + /// + /// Goes to a given position in a file which is playing. + /// + /// Id of the process which is playing the file + /// Position in the file (in second) + void goTo(const int& playId, const float& position); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// name of the set + /// name of the sound + bool isSoundSetFileInstalled(const std::string& setName, const std::string& soundName); + + /// + /// + /// + /// name of the set + bool isSoundSetInstalled(const std::string& setName); + + /// + /// Loads a file for ulterior playback + /// + /// Path of the sound file (either mp3 or wav) + /// Id of the file which has been loaded. This file can then be played with the play function + int loadFile(const std::string& fileName); + + /// + /// Load a sound set + /// + /// name of the set + void loadSoundSet(const std::string& setName); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Pause a play back + /// + /// Id of the process that is playing the file you want to put in pause + void pause(const int& id); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Starts the playback of a file preloaded with the loadFile function. + /// + /// Id returned by the loadFile function + void play(const int& id); + + /// + /// Starts the playback of a file preloaded with the loadFile function, with specific volume and audio balance + /// + /// Id returned by the loadFile function + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + void play(const int& id, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file + /// + /// Path of the sound file + void playFile(const std::string& fileName); + + /// + /// Plays a wav or mp3 file, with specific volume and audio balance + /// + /// Path of the sound file + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right / 0.0 : centered) + void playFile(const std::string& fileName, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file from a given position in the file. + /// + /// Name of the sound file + /// Position in second where the playing has to begin + void playFileFromPosition(const std::string& fileName, const float& position); + + /// + /// Plays a wav or mp3 file from a given position in the file, with specific volume and audio balance + /// + /// Name of the sound file + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + void playFileFromPosition(const std::string& fileName, const float& position, const float& volume, const float& pan); + + /// + /// Plays a wav or mp3 file in loop + /// + /// Path of the sound file + void playFileInLoop(const std::string& fileName); + + /// + /// Plays a wav or mp3 file in loop, with specific volume and audio balance + /// + /// Path of the sound file + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + void playFileInLoop(const std::string& fileName, const float& volume, const float& pan); + + /// + /// Starts the playback in loop of a file preloaded with the loadFile function + /// + /// Id returned by the loadFile function + void playInLoop(const int& id); + + /// + /// Plays a wav or mp3 file in loop, with specific volume and audio balance + /// + /// Id returned by the loadFile function + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + void playInLoop(const int& id, const float& volume, const float& pan); + + /// + /// Play a sine wave which specified caracteristics. + /// + /// Frequence in Hertz + /// Volume Gain between 0 and 100 + /// Stereo Pan set to either {-1,0,+1} + /// Duration of the sine wave in seconds + void playSine(const int& frequence, const int& gain, const int& pan, const float& duration); + + /// + /// Plays a file contained in one of the sound sets loaded + /// + /// Name of the file without extension + void playSoundSetFile(const std::string& fileName); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the soundset + /// Name of the file without extension + void playSoundSetFile(const std::string& soundSetName, const std::string& fileName); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the soundset + /// Name of the file without extension + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// specify if the file must be played in loop + void playSoundSetFile(const std::string& soundSetName, const std::string& fileName, const float& position, const float& volume, const float& pan, const bool& loop); + + /// + /// Plays a file contained in a given sound set + /// + /// Name of the file without extension + /// Position in second where the playing has to begin + /// volume of the sound file (must be between 0.0 and 1.0) + /// audio balance of the sound file (-1.0 : left / 1.0 : right) + /// specify if the file must be played in loop + void playSoundSetFile(const std::string& fileName, const float& position, const float& volume, const float& pan, const bool& loop); + + /// + /// Starts the playback of a wab audio stream + /// + /// Path of the web audio stream + /// arg + /// arg + void playWebStream(const std::string& streamName, const float& arg2, const float& arg3); + + /// + /// Sets the master volume of the player + /// + /// Volume - range 0.0 to 1.0 + void setMasterVolume(const float& volume); + + /// + /// sets the audio panorama : -1 for left speaker / 1 for right speaker + /// + /// arg + void setPanorama(const float& arg1); + + /// + /// Sets the volume of the player + /// + /// Id of the process that is playing the file you want to put louder or less loud + /// Volume - range 0.0 to 1.0 + void setVolume(const int& id, const float& volume); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops all the files that are currently playing. + /// + void stopAll(); + + /// + /// unloads all the files already loaded. + /// + void unloadAllFiles(); + + /// + /// unloads a file previously loaded with the loadFile function + /// + /// Id returned by the loadFile function + void unloadFile(const int& id); + + /// + /// Unload a sound set + /// + /// name of the set + void unloadSoundSet(const std::string& setName); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAudioPlayerProxyPostHandler post; + }; + +} +#endif // ALAUDIOPLAYERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alaudiorecorderproxy.h b/naoModule/libnaoqi_files/include/alproxies/alaudiorecorderproxy.h new file mode 100755 index 0000000..c8ad5e2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alaudiorecorderproxy.h @@ -0,0 +1,203 @@ +// Generated for ALAudioRecorder version 0 + +#ifndef ALAUDIORECORDERPROXY_H_ +#define ALAUDIORECORDERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAudioRecorderProxy; + + namespace detail { + class ALAudioRecorderProxyPostHandler + { + protected: + ALAudioRecorderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAudioRecorderProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// This method allows to record the signal collected on the nao's microphones. You can choose to record only the front microphone in a ogg file, or the 4 microphones in a wav file. + /// + /// Name of the file where to record the sound. + /// wav or ogg. + /// Required sample rate. + /// vector of booleans. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startMicrophonesRecording(const std::string& filename, const std::string& type, const int& samplerate, const AL::ALValue& channels); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// This method stops the recording of the sound collected by the microphones. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopMicrophonesRecording(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAudioRecorderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAudioRecorderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAudioRecorderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAudioRecorderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAudioRecorderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// This method allows to record the signal collected on the nao's microphones. You can choose to record only the front microphone in a ogg file, or the 4 microphones in a wav file. + /// + /// Name of the file where to record the sound. + /// wav or ogg. + /// Required sample rate. + /// vector of booleans. + void startMicrophonesRecording(const std::string& filename, const std::string& type, const int& samplerate, const AL::ALValue& channels); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// This method stops the recording of the sound collected by the microphones. + /// + void stopMicrophonesRecording(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAudioRecorderProxyPostHandler post; + }; + +} +#endif // ALAUDIORECORDERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alaudiosourcelocalizationproxy.h b/naoModule/libnaoqi_files/include/alproxies/alaudiosourcelocalizationproxy.h new file mode 100755 index 0000000..ca7dc03 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alaudiosourcelocalizationproxy.h @@ -0,0 +1,336 @@ +// Generated for ALAudioSourceLocalization version 0 + +#ifndef ALAUDIOSOURCELOCALIZATIONPROXY_H_ +#define ALAUDIOSOURCELOCALIZATIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAudioSourceLocalizationProxy; + + namespace detail { + class ALAudioSourceLocalizationProxyPostHandler + { + protected: + ALAudioSourceLocalizationProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAudioSourceLocalizationProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundLocalization/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAudioSourceLocalizationProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAudioSourceLocalizationProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAudioSourceLocalizationProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAudioSourceLocalizationProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAudioSourceLocalizationProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundLocalization/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + void setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAudioSourceLocalizationProxyPostHandler post; + }; + +} +#endif // ALAUDIOSOURCELOCALIZATIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alautomaticvolumeproxy.h b/naoModule/libnaoqi_files/include/alproxies/alautomaticvolumeproxy.h new file mode 100755 index 0000000..91607d1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alautomaticvolumeproxy.h @@ -0,0 +1,358 @@ +// Generated for ALAutomaticVolume version 0 + +#ifndef ALAUTOMATICVOLUMEPROXY_H_ +#define ALAUTOMATICVOLUMEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAutomaticVolumeProxy; + + namespace detail { + class ALAutomaticVolumeProxyPostHandler + { + protected: + ALAutomaticVolumeProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAutomaticVolumeProxy; + + /// + /// This method will start the adaptation of the speaker volume from the background noise. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableVolumeAdaptation(const bool& arg1); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the timestamp of the buffer. + /// Provides the audio buffer as an ALValue. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int processRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& timestamp, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the audio buffer as an ALValue. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int processSoundRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// enable the functionnality when true. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDebugMode(const bool& bSetOrUnset); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAutomaticVolumeProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAutomaticVolumeProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAutomaticVolumeProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAutomaticVolumeProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAutomaticVolumeProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// This method will start the adaptation of the speaker volume from the background noise. + /// + /// arg + void enableVolumeAdaptation(const bool& arg1); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the timestamp of the buffer. + /// Provides the audio buffer as an ALValue. + void processRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& timestamp, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the audio buffer as an ALValue. + void processSoundRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// enable the functionnality when true. + void setDebugMode(const bool& bSetOrUnset); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAutomaticVolumeProxyPostHandler post; + }; + +} +#endif // ALAUTOMATICVOLUMEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alautonomouslifeproxy.h b/naoModule/libnaoqi_files/include/alproxies/alautonomouslifeproxy.h new file mode 100755 index 0000000..6b66e9f --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alautonomouslifeproxy.h @@ -0,0 +1,396 @@ +// Generated for ALAutonomousLife version 0 + +#ifndef ALAUTONOMOUSLIFEPROXY_H_ +#define ALAUTONOMOUSLIFEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAutonomousLifeProxy; + + namespace detail { + class ALAutonomousLifeProxyPostHandler + { + protected: + ALAutonomousLifeProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAutonomousLifeProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Temporarily enables/disables AutonomousLaunchpad Plugins + /// + /// The name of the plugin to enable/disable + /// Whether or not to enable this plugin + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLaunchpadPluginEnabled(const std::string& plugin_name, const bool& enabled); + + /// + /// Set the vertical offset (in meters) of the base of the robot with respect to the floor + /// + /// The new vertical offset (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setRobotOffsetFromFloor(const float& offset); + + /// + /// Set if a given safeguard will be handled by Autonomous Life or not. + /// + /// Name of the safeguard to consider: RobotPushed, RobotFell,CriticalDiagnosis, CriticalTemperature + /// True if life handles the safeguard. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSafeguardEnabled(const std::string& name, const bool& enabled); + + /// + /// Programatically control the state of Autonomous Life + /// + /// The possible states of AutonomousLife are: interactive, solitary, safeguard, disabled + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setState(const std::string& state); + + /// + /// Start monitoring ALMemory and reporting conditional triggers with AutonomousLaunchpad. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startMonitoringLaunchpadConditions(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops the focused activity and clears stack of activities + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAll(); + + /// + /// Stops the focused activity. If another activity is stacked it will be started. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopFocus(); + + /// + /// Stop monitoring ALMemory and reporting conditional triggers with AutonomousLaunchpad. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopMonitoringLaunchpadConditions(); + + /// + /// Set an activity as running with user focus + /// + /// The package_name/activity_name to run + /// Flags for focus changing. STOP_CURRENT or STOP_AND_STACK_CURRENT + /// brokerTaskID : The ID of the task assigned to it by the broker. + int switchFocus(const std::string& activity_name, const int& flags); + + /// + /// Set an activity as running with user focus + /// + /// The package_name/activity_name to run + /// brokerTaskID : The ID of the task assigned to it by the broker. + int switchFocus(const std::string& activity_name); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAutonomousLifeProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAutonomousLifeProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAutonomousLifeProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAutonomousLifeProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAutonomousLifeProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Returns the currently focused activity + /// + /// The name of the focused activity + std::string focusedActivity(); + + /// + /// Returns the nature of an activity + /// + /// The package_name/activity_name to check + /// Possible values are: solitary, interactive + std::string getActivityNature(const std::string& activity_name); + + /// + /// Get launch count, last completion time, etc for activities. + /// + /// A map of activity names, with a cooresponding map of "prevStartTime", "prevCompletionTime", "startCount", "totalDuration". Times are 0 for unlaunched Activities + std::map > getActivityStatistics(); + + /// + /// Get launch count, last completion time, etc for activities with autonomous launch trigger conditions. + /// + /// A map of activity names, with a cooresponding map of "prevStartTime", "prevCompletionTime", "startCount", "totalDuration". Times are 0 for unlaunched Activities + std::map > getAutonomousActivityStatistics(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get a list of enabled AutonomousLaunchpad Plugins. Enabled plugins will run when AutonomousLaunchpad is started + /// + /// A list of strings of enabled plugins. + std::vector getEnabledLaunchpadPlugins(); + + /// + /// Get a list of the order that activities that have been focused, and their time focused. + /// + /// A list of pairs, each pair is ActivityName/PreviousFocusedTime + std::vector > getFocusHistory(); + + /// + /// Get a list of the order that activities that have been focused, and their time focused. + /// + /// How many items of history to report, starting from most recent. + /// A list of pairs, each pair is ActivityName/PreviousFocusedTime + std::vector > getFocusHistory(const int& depth); + + /// + /// Get a list of AutonomousLaunchpad Plugins that belong to specified group + /// + /// The group to search for the plugins + /// A list of strings of the plugins belonging to the group. + std::vector getLaunchpadPluginsForGroup(const std::string& group); + + /// + /// Get the time in seconds as life sees it. Based on gettimeofday() + /// + /// The int time in seconds as Autonomous Life sees it + int getLifeTime(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the vertical offset (in meters) of the base of the robot with respect to the floor + /// + /// Current vertical offset (in meters) + float getRobotOffsetFromFloor(); + + /// + /// Returns the current state of AutonomousLife + /// + /// Can be: solitary, interactive, safeguard, disabled + std::string getState(); + + /// + /// Get a list of the order that states that have been entered, and their time entered. + /// + /// A list of pairs, each pair is StateName/PreviousEnteredTime + std::vector > getStateHistory(); + + /// + /// Get a list of the order that states that have been entered, and their time entered. + /// + /// How many items of history to report, starting from most recent. + /// A list of pairs, each pair is StateName/PreviousEnteredTime + std::vector > getStateHistory(const int& depth); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets running status of AutonomousLaunchpad + /// + /// True if AutonomousLaunchpad is monitoring ALMemory and reporting conditional triggers. + bool isMonitoringLaunchpadConditions(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Get if a given safeguard will be handled by Autonomous Life or not. + /// + /// Name of the safeguard to consider: RobotPushed, RobotFell,CriticalDiagnosis, CriticalTemperature + /// True if life handles the safeguard. + bool isSafeguardEnabled(const std::string& name); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Temporarily enables/disables AutonomousLaunchpad Plugins + /// + /// The name of the plugin to enable/disable + /// Whether or not to enable this plugin + void setLaunchpadPluginEnabled(const std::string& plugin_name, const bool& enabled); + + /// + /// Set the vertical offset (in meters) of the base of the robot with respect to the floor + /// + /// The new vertical offset (in meters) + void setRobotOffsetFromFloor(const float& offset); + + /// + /// Set if a given safeguard will be handled by Autonomous Life or not. + /// + /// Name of the safeguard to consider: RobotPushed, RobotFell,CriticalDiagnosis, CriticalTemperature + /// True if life handles the safeguard. + void setSafeguardEnabled(const std::string& name, const bool& enabled); + + /// + /// Programatically control the state of Autonomous Life + /// + /// The possible states of AutonomousLife are: interactive, solitary, safeguard, disabled + void setState(const std::string& state); + + /// + /// Start monitoring ALMemory and reporting conditional triggers with AutonomousLaunchpad. + /// + void startMonitoringLaunchpadConditions(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops the focused activity and clears stack of activities + /// + void stopAll(); + + /// + /// Stops the focused activity. If another activity is stacked it will be started. + /// + void stopFocus(); + + /// + /// Stop monitoring ALMemory and reporting conditional triggers with AutonomousLaunchpad. + /// + void stopMonitoringLaunchpadConditions(); + + /// + /// Set an activity as running with user focus + /// + /// The package_name/activity_name to run + /// Flags for focus changing. STOP_CURRENT or STOP_AND_STACK_CURRENT + void switchFocus(const std::string& activity_name, const int& flags); + + /// + /// Set an activity as running with user focus + /// + /// The package_name/activity_name to run + void switchFocus(const std::string& activity_name); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAutonomousLifeProxyPostHandler post; + }; + +} +#endif // ALAUTONOMOUSLIFEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alautonomousmovesproxy.h b/naoModule/libnaoqi_files/include/alproxies/alautonomousmovesproxy.h new file mode 100755 index 0000000..628f122 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alautonomousmovesproxy.h @@ -0,0 +1,233 @@ +// Generated for ALAutonomousMoves version 0 + +#ifndef ALAUTONOMOUSMOVESPROXY_H_ +#define ALAUTONOMOUSMOVESPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALAutonomousMovesProxy; + + namespace detail { + class ALAutonomousMovesProxyPostHandler + { + protected: + ALAutonomousMovesProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALAutonomousMovesProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// The background strategy. + /// + /// The autonomous background posture strategy. ("none" or "backToNeutral") + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBackgroundStrategy(const std::string& strategy); + + /// + /// Enable or disable expressive listening. + /// + /// The boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setExpressiveListeningEnabled(const bool& enable); + + /// + /// DEPRECATED since 2.0: do ALBasicAwareness.setTrackingMode("MoveContextually") instead.Start small base moves. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startSmallDisplacements(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// DEPRECATED since 2.0: do ALBasicAwareness.setTrackingMode instead.Stop small base moves. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopSmallDisplacements(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALAutonomousMovesProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALAutonomousMovesProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALAutonomousMovesProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALAutonomousMovesProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALAutonomousMovesProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the background strategy. + /// + /// The autonomous background posture strategy. ("none" or "backToNeutral") + std::string getBackgroundStrategy(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// If expressive listening is enabled. + /// + /// The boolean value: true means it is enabled, false means it is disabled. + bool getExpressiveListeningEnabled(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// The background strategy. + /// + /// The autonomous background posture strategy. ("none" or "backToNeutral") + void setBackgroundStrategy(const std::string& strategy); + + /// + /// Enable or disable expressive listening. + /// + /// The boolean value: true to enable, false to disable. + void setExpressiveListeningEnabled(const bool& enable); + + /// + /// DEPRECATED since 2.0: do ALBasicAwareness.setTrackingMode("MoveContextually") instead.Start small base moves. + /// + void startSmallDisplacements(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// DEPRECATED since 2.0: do ALBasicAwareness.setTrackingMode instead.Stop small base moves. + /// + void stopSmallDisplacements(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALAutonomousMovesProxyPostHandler post; + }; + +} +#endif // ALAUTONOMOUSMOVESPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albacklightingdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/albacklightingdetectionproxy.h new file mode 100755 index 0000000..bbea764 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albacklightingdetectionproxy.h @@ -0,0 +1,383 @@ +// Generated for ALBacklightingDetection version 0 + +#ifndef ALBACKLIGHTINGDETECTIONPROXY_H_ +#define ALBACKLIGHTINGDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBacklightingDetectionProxy; + + namespace detail { + class ALBacklightingDetectionProxyPostHandler + { + protected: + ALBacklightingDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBacklightingDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBacklightingDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBacklightingDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBacklightingDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBacklightingDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBacklightingDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBacklightingDetectionProxyPostHandler post; + }; + +} +#endif // ALBACKLIGHTINGDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albarcodereaderproxy.h b/naoModule/libnaoqi_files/include/alproxies/albarcodereaderproxy.h new file mode 100755 index 0000000..2fab982 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albarcodereaderproxy.h @@ -0,0 +1,360 @@ +// Generated for ALBarcodeReader version 0 + +#ifndef ALBARCODEREADERPROXY_H_ +#define ALBARCODEREADERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBarcodeReaderProxy; + + namespace detail { + class ALBarcodeReaderProxyPostHandler + { + protected: + ALBarcodeReaderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBarcodeReaderProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBarcodeReaderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBarcodeReaderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBarcodeReaderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBarcodeReaderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBarcodeReaderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets extractor framerate + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBarcodeReaderProxyPostHandler post; + }; + +} +#endif // ALBARCODEREADERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albasicawarenessproxy.h b/naoModule/libnaoqi_files/include/alproxies/albasicawarenessproxy.h new file mode 100755 index 0000000..e167ca0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albasicawarenessproxy.h @@ -0,0 +1,471 @@ +// Generated for ALBasicAwareness version 0 + +#ifndef ALBASICAWARENESSPROXY_H_ +#define ALBASICAWARENESSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBasicAwarenessProxy; + + namespace detail { + class ALBasicAwarenessProxyPostHandler + { + protected: + ALBasicAwarenessProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBasicAwarenessProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Reset all parameters, including enabled/disabled stimulus. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetAllParameters(); + + /// + /// Set engagement mode. + /// + /// Name of the mode + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setEngagementMode(const std::string& modeName); + + /// + /// Set the specified parameter + /// + /// "ServoingSpeed" : Speed of servoing head moves, as fraction of max speed + /// "LookStimulusSpeed" : Speed of head moves when looking at a stimulus, as fraction of max speed + /// "LookBackSpeed" : Speed of head moves when looking back to previous position, as fraction of max speed + /// "LookDownSpeed" : Speed of head moves when looking down to check for children, as fraction of max speed + /// "NobodyFoundTimeOut" : timeout to send HumanLost event when no blob is found, in seconds + /// "MinTimeTracking" : Minimum Time for the robot to be focused on someone, without listening to other stimuli, in seconds + /// "TimeSleepBeforeResumeMS" : Slept time before automatically resuming BasicAwareness when an automatic pause has been made, in milliseconds + /// "TimeOutResetHead" : Timeout to reset the head, in seconds + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// "PeoplePerceptionPeriod" : Period for people perception, in milliseconds + /// "SlowPeoplePerceptionPeriod" : Period for people perception in FullyEngaged mode, in milliseconds + /// "HeadThreshold" : Yaw threshold for tracking, in degrees + /// "BodyRotationThreshold" : Angular threshold for BodyRotation tracking mode, in degrees + /// "BodyRotationThresholdNao" : Angular threshold for BodyRotation tracking mode on Nao, in degrees + /// "MoveDistanceX" : X Distance for the Move tracking mode, in meters + /// "MoveDistanceY" : Y Distance for the Move tracking mode, in meters + /// "MoveAngleTheta" : Angle for the Move tracking mode, in degrees + /// "MoveThresholdX" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdY" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdTheta" : Theta Threshold for the Move tracking mode, in degrees + /// "MaxDistanceFullyEngaged" : Maximum distance for someone to be tracked for FullyEngaged mode, in meters + /// "MaxDistanceNotFullyEngaged" : Maximum distance for someone to be tracked for modes different from FullyEngaged, in meters + /// "MaxHumanSearchTime" : Maximum time to find a human after observing stimulous, in seconds + /// "DeltaPitchComfortZone" : Pitch width of the comfort zone, in degree + /// "CenterPitchComfortZone" : Pitch center of the confort zone, in degree + /// "SoundHeight" : Default Height for sound detection, in meters + /// "MoveSpeed" : Speed of the robot moves + /// "MC_Interactive_MinTime" : Minimum time between 2 contextual moves (when the robot is tracking somebody) + /// "MC_Interactive_MaxOffsetTime" : Maximum time that we can add to MC_Interactive_MinTime (when the robot is tracking somebody) + /// "MC_Interactive_DistanceXY" : Maximum offset distance in X and Y that the robot can apply when he tracks somebody + /// "MC_Interactive_MinTheta" : Minimum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_MaxTheta" : Maximum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_DistanceHumanRobot" : Distance between the human and the robot + /// "MC_Interactive_MaxDistanceHumanRobot" : Maximum distance human robot to allow the robot to move (in MoveContextually mode) + /// + /// "ServoingSpeed" : Float in range [0.01;1] + /// "LookStimulusSpeed" : Float in range [0.01;1] + /// "LookBackSpeed" : Float in range [0.01;1] + /// "LookDownSpeed" : Float in range [0.01;1] + /// "NobodyFoundTimeOut" : Float > 0 + /// "MinTimeTracking" : Float in range [0;20] + /// "TimeSleepBeforeResumeMS" : Int > 0 + /// "TimeOutResetHead" : Float in range [0;30] + /// "AmplitudeYawTracking" : Float in range [10;120] + /// "PeoplePerceptionPeriod" : Int > 1 + /// "SlowPeoplePerceptionPeriod" : Int > 1 + /// "HeadThreshold" : Float in range [0;180] + /// "BodyRotationThreshold" : Float in range [-180;180] + /// "BodyRotationThresholdNao" : Float in range [-180;180] + /// "MoveDistanceX" : Float in range [-5;5] + /// "MoveDistanceY" : Float in range [-5;5] + /// "MoveAngleTheta" : Float in range [-180;180] + /// "MoveThresholdX" : Float in range [0;5] + /// "MoveThresholdY" : Float in range [0;5] + /// "MoveThresholdTheta" : Float in range [-180;180] + /// "MaxDistanceFullyEngaged" : Float in range [0.5;5] + /// "MaxDistanceNotFullyEngaged" : Float in range [0.5;5] + /// "MaxHumanSearchTime" : Float in range [0.1;10] + /// "DeltaPitchComfortZone" : Float in range [0;90] + /// "CenterPitchComfortZone" : Float in range [-90;90] + /// "SoundHeight" : Float in range [0;2] + /// "MoveSpeed" : Float in range [0.1;0.55] + /// "MC_Interactive_MinTime" : Int in range [0;100] + /// "MC_Interactive_MaxOffsetTime" : Int in range [0;100] + /// "MC_Interactive_DistanceXY" : Float in range [0;1] + /// "MC_Interactive_MinTheta" : Float in range [-40;0] + /// "MC_Interactive_MaxTheta" : Float in range [0;40] + /// "MC_Interactive_DistanceHumanRobot" : Float in range [0.1;2] + /// "MC_Interactive_MaxDistanceHumanRobot" : Float in range [0.1;3] + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& newVal); + + /// + /// Enable/Disable Stimulus Detection. + /// + /// Name of the stimulus to enable/disable + /// Boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setStimulusDetectionEnabled(const std::string& stimulusName, const bool& isStimulusDetectionEnabled); + + /// + /// Set tracking mode. + /// + /// Name of the mode + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTrackingMode(const std::string& modeName); + + /// + /// Start Basic Awareness. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startAwareness(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop Basic Awareness. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAwareness(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBasicAwarenessProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBasicAwarenessProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBasicAwarenessProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBasicAwarenessProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBasicAwarenessProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Force Engage Person. + /// + /// ID of the person as found in PeoplePerception. + /// true if the robot succeeded to engage the person, else false. + bool engagePerson(const int& engagePerson); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Set engagement mode. + /// + /// Name of current engagement mode as a string + std::string getEngagementMode(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the specified parameter. + /// + /// "ServoingSpeed" : Speed of servoing head moves, as fraction of max speed + /// "LookStimulusSpeed" : Speed of head moves when looking at a stimulus, as fraction of max speed + /// "LookBackSpeed" : Speed of head moves when looking back to previous position, as fraction of max speed + /// "LookDownSpeed" : Speed of head moves when looking down to check for children, as fraction of max speed + /// "NobodyFoundTimeOut" : timeout to send HumanLost event when no blob is found, in seconds + /// "MinTimeTracking" : Minimum Time for the robot to be focused on someone, without listening to other stimuli, in seconds + /// "TimeSleepBeforeResumeMS" : Slept time before automatically resuming BasicAwareness when an automatic pause has been made, in milliseconds + /// "TimeOutResetHead" : Timeout to reset the head, in seconds + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// "PeoplePerceptionPeriod" : Period for people perception, in milliseconds + /// "SlowPeoplePerceptionPeriod" : Period for people perception in FullyEngaged mode, in milliseconds + /// "HeadThreshold" : Yaw threshold for tracking, in degrees + /// "BodyRotationThreshold" : Angular threshold for BodyRotation tracking mode, in degrees + /// "BodyRotationThresholdNao" : Angular threshold for BodyRotation tracking mode on Nao, in degrees + /// "MoveDistanceX" : X Distance for the Move tracking mode, in meters + /// "MoveDistanceY" : Y Distance for the Move tracking mode, in meters + /// "MoveAngleTheta" : Angle for the Move tracking mode, in degrees + /// "MoveThresholdX" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdY" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdTheta" : Theta Threshold for the Move tracking mode, in degrees + /// "MaxDistanceFullyEngaged" : Maximum distance for someone to be tracked for FullyEngaged mode, in meters + /// "MaxDistanceNotFullyEngaged" : Maximum distance for someone to be tracked for modes different from FullyEngaged, in meters + /// "MaxHumanSearchTime" : Maximum time to find a human after observing stimulous, in seconds + /// "DeltaPitchComfortZone" : Pitch width of the comfort zone, in degree + /// "CenterPitchComfortZone" : Pitch center of the confort zone, in degree + /// "SoundHeight" : Default Height for sound detection, in meters + /// "MoveSpeed" : Speed of the robot moves + /// "MC_Interactive_MinTime" : Minimum time between 2 contextual moves (when the robot is tracking somebody) + /// "MC_Interactive_MaxOffsetTime" : Maximum time that we can add to MC_Interactive_MinTime (when the robot is tracking somebody) + /// "MC_Interactive_DistanceXY" : Maximum offset distance in X and Y that the robot can apply when he tracks somebody + /// "MC_Interactive_MinTheta" : Minimum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_MaxTheta" : Maximum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_DistanceHumanRobot" : Distance between the human and the robot + /// "MC_Interactive_MaxDistanceHumanRobot" : Maximum distance human robot to allow the robot to move (in MoveContextually mode) + /// + /// ALValue format for required parameter + AL::ALValue getParameter(const std::string& paramName); + + /// + /// Set tracking mode. + /// + /// Name of current tracking mode as a string + std::string getTrackingMode(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get the status (started or not) of the module. + /// + /// Boolean value, true if running else false + bool isAwarenessRunning(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Get status enabled/disabled for Stimulus Detection. + /// + /// Name of the stimulus to check + /// Boolean value for status enabled/disabled + bool isStimulusDetectionEnabled(const std::string& stimulusName); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Reset all parameters, including enabled/disabled stimulus. + /// + void resetAllParameters(); + + /// + /// Set engagement mode. + /// + /// Name of the mode + void setEngagementMode(const std::string& modeName); + + /// + /// Set the specified parameter + /// + /// "ServoingSpeed" : Speed of servoing head moves, as fraction of max speed + /// "LookStimulusSpeed" : Speed of head moves when looking at a stimulus, as fraction of max speed + /// "LookBackSpeed" : Speed of head moves when looking back to previous position, as fraction of max speed + /// "LookDownSpeed" : Speed of head moves when looking down to check for children, as fraction of max speed + /// "NobodyFoundTimeOut" : timeout to send HumanLost event when no blob is found, in seconds + /// "MinTimeTracking" : Minimum Time for the robot to be focused on someone, without listening to other stimuli, in seconds + /// "TimeSleepBeforeResumeMS" : Slept time before automatically resuming BasicAwareness when an automatic pause has been made, in milliseconds + /// "TimeOutResetHead" : Timeout to reset the head, in seconds + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// "PeoplePerceptionPeriod" : Period for people perception, in milliseconds + /// "SlowPeoplePerceptionPeriod" : Period for people perception in FullyEngaged mode, in milliseconds + /// "HeadThreshold" : Yaw threshold for tracking, in degrees + /// "BodyRotationThreshold" : Angular threshold for BodyRotation tracking mode, in degrees + /// "BodyRotationThresholdNao" : Angular threshold for BodyRotation tracking mode on Nao, in degrees + /// "MoveDistanceX" : X Distance for the Move tracking mode, in meters + /// "MoveDistanceY" : Y Distance for the Move tracking mode, in meters + /// "MoveAngleTheta" : Angle for the Move tracking mode, in degrees + /// "MoveThresholdX" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdY" : Threshold for the Move tracking mode, in meters + /// "MoveThresholdTheta" : Theta Threshold for the Move tracking mode, in degrees + /// "MaxDistanceFullyEngaged" : Maximum distance for someone to be tracked for FullyEngaged mode, in meters + /// "MaxDistanceNotFullyEngaged" : Maximum distance for someone to be tracked for modes different from FullyEngaged, in meters + /// "MaxHumanSearchTime" : Maximum time to find a human after observing stimulous, in seconds + /// "DeltaPitchComfortZone" : Pitch width of the comfort zone, in degree + /// "CenterPitchComfortZone" : Pitch center of the confort zone, in degree + /// "SoundHeight" : Default Height for sound detection, in meters + /// "MoveSpeed" : Speed of the robot moves + /// "MC_Interactive_MinTime" : Minimum time between 2 contextual moves (when the robot is tracking somebody) + /// "MC_Interactive_MaxOffsetTime" : Maximum time that we can add to MC_Interactive_MinTime (when the robot is tracking somebody) + /// "MC_Interactive_DistanceXY" : Maximum offset distance in X and Y that the robot can apply when he tracks somebody + /// "MC_Interactive_MinTheta" : Minimum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_MaxTheta" : Maximum theta that the robot can apply when he tracks somebody + /// "MC_Interactive_DistanceHumanRobot" : Distance between the human and the robot + /// "MC_Interactive_MaxDistanceHumanRobot" : Maximum distance human robot to allow the robot to move (in MoveContextually mode) + /// + /// "ServoingSpeed" : Float in range [0.01;1] + /// "LookStimulusSpeed" : Float in range [0.01;1] + /// "LookBackSpeed" : Float in range [0.01;1] + /// "LookDownSpeed" : Float in range [0.01;1] + /// "NobodyFoundTimeOut" : Float > 0 + /// "MinTimeTracking" : Float in range [0;20] + /// "TimeSleepBeforeResumeMS" : Int > 0 + /// "TimeOutResetHead" : Float in range [0;30] + /// "AmplitudeYawTracking" : Float in range [10;120] + /// "PeoplePerceptionPeriod" : Int > 1 + /// "SlowPeoplePerceptionPeriod" : Int > 1 + /// "HeadThreshold" : Float in range [0;180] + /// "BodyRotationThreshold" : Float in range [-180;180] + /// "BodyRotationThresholdNao" : Float in range [-180;180] + /// "MoveDistanceX" : Float in range [-5;5] + /// "MoveDistanceY" : Float in range [-5;5] + /// "MoveAngleTheta" : Float in range [-180;180] + /// "MoveThresholdX" : Float in range [0;5] + /// "MoveThresholdY" : Float in range [0;5] + /// "MoveThresholdTheta" : Float in range [-180;180] + /// "MaxDistanceFullyEngaged" : Float in range [0.5;5] + /// "MaxDistanceNotFullyEngaged" : Float in range [0.5;5] + /// "MaxHumanSearchTime" : Float in range [0.1;10] + /// "DeltaPitchComfortZone" : Float in range [0;90] + /// "CenterPitchComfortZone" : Float in range [-90;90] + /// "SoundHeight" : Float in range [0;2] + /// "MoveSpeed" : Float in range [0.1;0.55] + /// "MC_Interactive_MinTime" : Int in range [0;100] + /// "MC_Interactive_MaxOffsetTime" : Int in range [0;100] + /// "MC_Interactive_DistanceXY" : Float in range [0;1] + /// "MC_Interactive_MinTheta" : Float in range [-40;0] + /// "MC_Interactive_MaxTheta" : Float in range [0;40] + /// "MC_Interactive_DistanceHumanRobot" : Float in range [0.1;2] + /// "MC_Interactive_MaxDistanceHumanRobot" : Float in range [0.1;3] + /// + void setParameter(const std::string& paramName, const AL::ALValue& newVal); + + /// + /// Enable/Disable Stimulus Detection. + /// + /// Name of the stimulus to enable/disable + /// Boolean value: true to enable, false to disable. + void setStimulusDetectionEnabled(const std::string& stimulusName, const bool& isStimulusDetectionEnabled); + + /// + /// Set tracking mode. + /// + /// Name of the mode + void setTrackingMode(const std::string& modeName); + + /// + /// Start Basic Awareness. + /// + void startAwareness(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop Basic Awareness. + /// + void stopAwareness(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBasicAwarenessProxyPostHandler post; + }; + +} +#endif // ALBASICAWARENESSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albatteryproxy.h b/naoModule/libnaoqi_files/include/alproxies/albatteryproxy.h new file mode 100755 index 0000000..9cb338c --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albatteryproxy.h @@ -0,0 +1,192 @@ +// Generated for ALBattery version 0 + +#ifndef ALBATTERYPROXY_H_ +#define ALBATTERYPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBatteryProxy; + + namespace detail { + class ALBatteryProxyPostHandler + { + protected: + ALBatteryProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBatteryProxy; + + /// + /// Enable power monitoring + /// + /// True activate power monitoring + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enablePowerMonitoring(const bool& Enable); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBatteryProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBatteryProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBatteryProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBatteryProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBatteryProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Enable power monitoring + /// + /// True activate power monitoring + void enablePowerMonitoring(const bool& Enable); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Get the battery charge in percents + /// + /// the percentage of remaining power + int getBatteryCharge(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBatteryProxyPostHandler post; + }; + +} +#endif // ALBATTERYPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albehaviormanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/albehaviormanagerproxy.h new file mode 100755 index 0000000..fa5f974 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albehaviormanagerproxy.h @@ -0,0 +1,398 @@ +// Generated for ALBehaviorManager version 0 + +#ifndef ALBEHAVIORMANAGERPROXY_H_ +#define ALBEHAVIORMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBehaviorManagerProxy; + + namespace detail { + class ALBehaviorManagerProxyPostHandler + { + protected: + ALBehaviorManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBehaviorManagerProxy; + + /// + /// Set the given behavior as default + /// + /// Behavior name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addDefaultBehavior(const std::string& behavior); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Play default behaviors + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playDefaultProject(); + + /// + /// Remove the given behavior from the default behaviors + /// + /// Behavior name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeDefaultBehavior(const std::string& behavior); + + /// + /// Runs a behavior, returns when finished + /// + /// Behavior name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int runBehavior(const std::string& behavior); + + /// + /// Starts a behavior, returns when started. + /// + /// Behavior name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startBehavior(const std::string& behavior); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop all behaviors + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAllBehaviors(); + + /// + /// Stop a behavior + /// + /// Behavior name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopBehavior(const std::string& behavior); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBehaviorManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBehaviorManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBehaviorManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBehaviorManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBehaviorManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Set the given behavior as default + /// + /// Behavior name + void addDefaultBehavior(const std::string& behavior); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Get behaviors + /// + /// Returns the list of behaviors prefixed by their type (User/ or System/). DEPRECATED in favor of ALBehaviorManager.getInstalledBehaviors. + std::vector getBehaviorNames(); + + /// + /// Get the nature of the given behavior. + /// + /// The local path towards a behavior or a directory. + /// The nature of the behavior. + std::string getBehaviorNature(const std::string& behavior); + + /// + /// Get tags found on the given behavior. + /// + /// The local path towards a behavior or a directory. + /// The list of tags found. + std::vector getBehaviorTags(const std::string& behavior); + + /// + /// Get installed behaviors directories names and filter it by tag. + /// + /// A tag to filter the list with. + /// Returns the behaviors list + std::vector getBehaviorsByTag(const std::string& tag); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get default behaviors + /// + /// Return default behaviors + std::vector getDefaultBehaviors(); + + /// + /// Get installed behaviors directories names + /// + /// Returns the behaviors list + std::vector getInstalledBehaviors(); + + /// + /// Get loaded behaviors + /// + /// Return loaded behaviors + std::vector getLoadedBehaviors(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get running behaviors + /// + /// Return running behaviors + std::vector getRunningBehaviors(); + + /// + /// Get system behaviors + /// + /// Returns the list of system behaviors prefixed by System/. DEPRECATED in favor of ALBehaviorManager.getInstalledBehaviors. + std::vector getSystemBehaviorNames(); + + /// + /// Get tags found on installed behaviors. + /// + /// The list of tags found. + std::vector getTagList(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get user's behaviors + /// + /// Returns the list of user's behaviors prefixed by User/. DEPRECATED in favor of ALBehaviorManager.getInstalledBehaviors. + std::vector getUserBehaviorNames(); + + /// + /// Install a behavior. + /// Check the given local path for a valid behavior or package. + /// On success, behavior added or updated signal is emitted. + /// DEPRECATED in favor of PackageManager.install. + /// + /// the relative destination path. + /// true on success, false on failure. + bool installBehavior(const std::string& localPath); + + /// + /// Install a behavior. + /// Check and take the behavior found at the given absolute path andimport it to the given local path, relative to behaviors path. + /// On success, behavior added signal is emitted before returning.DEPRECATED in favor of PackageManager.install. + /// + /// a behavior on the local file system to install. + /// the relative destination path. + /// whether to replace existing behavior if present. + /// true on success, false on failure. + bool installBehavior(const std::string& absolutePath, const std::string& localPath, const bool& overwrite); + + /// + /// Tell if supplied name corresponds to a behavior that has been installed + /// + /// The behavior directory name + /// Returns true if it is a valid behavior + bool isBehaviorInstalled(const std::string& name); + + /// + /// Tell if supplied name corresponds to a loaded behavior + /// + /// Behavior name + /// Returns true if it is a loaded behavior + bool isBehaviorLoaded(const std::string& behavior); + + /// + /// Tell if the supplied namecorresponds to an existing behavior. + /// + /// Prefixed behavior or just behavior's name (latter usage deprecated, in this case the behavior is searched for amongst user's behaviors, then in system behaviors) DEPRECATED in favor of ALBehaviorManager.isBehaviorInstalled. + /// Returns true if it is an existing behavior + bool isBehaviorPresent(const std::string& prefixedBehavior); + + /// + /// Tell if supplied name corresponds to a running behavior + /// + /// Behavior name + /// Returns true if it is a running behavior + bool isBehaviorRunning(const std::string& behavior); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Play default behaviors + /// + void playDefaultProject(); + + /// + /// Load a behavior + /// + /// Behavior name + /// Returns true if it was successfully loaded. + bool preloadBehavior(const std::string& behavior); + + /// + /// Remove a behavior from the filesystem. DEPRECATED in favor of PackageManager.remove. + /// + /// Behavior name + bool removeBehavior(const std::string& behavior); + + /// + /// Remove the given behavior from the default behaviors + /// + /// Behavior name + void removeDefaultBehavior(const std::string& behavior); + + /// + /// Find out the actual / path behind a behavior name. + /// + /// name of a behavior + /// The actual / path if found, else an empty string. Throws an ALERROR if two behavior names conflicted. + std::string resolveBehaviorName(const std::string& name); + + /// + /// Runs a behavior, returns when finished + /// + /// Behavior name + void runBehavior(const std::string& behavior); + + /// + /// Starts a behavior, returns when started. + /// + /// Behavior name + void startBehavior(const std::string& behavior); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop all behaviors + /// + void stopAllBehaviors(); + + /// + /// Stop a behavior + /// + /// Behavior name + void stopBehavior(const std::string& behavior); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBehaviorManagerProxyPostHandler post; + }; + +} +#endif // ALBEHAVIORMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albodydetection3dproxy.h b/naoModule/libnaoqi_files/include/alproxies/albodydetection3dproxy.h new file mode 100755 index 0000000..b5631c3 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albodydetection3dproxy.h @@ -0,0 +1,275 @@ +// Generated for ALBodyDetection3D version 1.18 + +#ifndef ALBODYDETECTION3DPROXY_H_ +#define ALBODYDETECTION3DPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBodyDetection3DProxy; + + namespace detail { + class ALBodyDetection3DProxyPostHandler + { + protected: + ALBodyDetection3DProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBodyDetection3DProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module contains ... + /// \ingroup ALProxies + class ALPROXIES_API ALBodyDetection3DProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBodyDetection3DProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBodyDetection3DProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBodyDetection3DProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBodyDetection3DProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + ///Exits and unregisters the module. + /// + void exit(); + + /// + ///Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + ///Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + ///Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + ///Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + ///Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + ///Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + ///Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + ///Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + ///Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + ///Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + ///Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + ///Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + ///Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + ///returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + ///Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + ///Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + ///Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + ///Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + ///Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBodyDetection3DProxyPostHandler post; + + }; + +} +#endif // ALBODYDETECTION3DPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albodytemperatureproxy.h b/naoModule/libnaoqi_files/include/alproxies/albodytemperatureproxy.h new file mode 100755 index 0000000..d7f3299 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albodytemperatureproxy.h @@ -0,0 +1,198 @@ +// Generated for ALBodyTemperature version 0 + +#ifndef ALBODYTEMPERATUREPROXY_H_ +#define ALBODYTEMPERATUREPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBodyTemperatureProxy; + + namespace detail { + class ALBodyTemperatureProxyPostHandler + { + protected: + ALBodyTemperatureProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBodyTemperatureProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Enables / Disables temperature notifications. + /// + /// If True enable temperature notifications. If False disable temperature notifications. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setEnableNotifications(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBodyTemperatureProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBodyTemperatureProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBodyTemperatureProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBodyTemperatureProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBodyTemperatureProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Return true if notifications are active. + /// + /// Return True if notifications are active. + bool areNotificationsEnabled(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// The actual state of the temperature diagnosis. + /// + /// Return the current temperature diagnosis. + AL::ALValue getTemperatureDiagnosis(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Enables / Disables temperature notifications. + /// + /// If True enable temperature notifications. If False disable temperature notifications. + void setEnableNotifications(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBodyTemperatureProxyPostHandler post; + }; + +} +#endif // ALBODYTEMPERATUREPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/albonjourproxy.h b/naoModule/libnaoqi_files/include/alproxies/albonjourproxy.h new file mode 100755 index 0000000..b2faa66 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/albonjourproxy.h @@ -0,0 +1,173 @@ +// Generated for ALBonjour version 0 + +#ifndef ALBONJOURPROXY_H_ +#define ALBONJOURPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALBonjourProxy; + + namespace detail { + class ALBonjourProxyPostHandler + { + protected: + ALBonjourProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALBonjourProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALBonjourProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALBonjourProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALBonjourProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALBonjourProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALBonjourProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALBonjourProxyPostHandler post; + }; + +} +#endif // ALBONJOURPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alchestbuttonproxy.h b/naoModule/libnaoqi_files/include/alproxies/alchestbuttonproxy.h new file mode 100755 index 0000000..1dc81b7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alchestbuttonproxy.h @@ -0,0 +1,173 @@ +// Generated for ALChestButton version 0 + +#ifndef ALCHESTBUTTONPROXY_H_ +#define ALCHESTBUTTONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALChestButtonProxy; + + namespace detail { + class ALChestButtonProxyPostHandler + { + protected: + ALChestButtonProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALChestButtonProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALChestButtonProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALChestButtonProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALChestButtonProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALChestButtonProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALChestButtonProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALChestButtonProxyPostHandler post; + }; + +} +#endif // ALCHESTBUTTONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alchoregrapherecorderproxy.h b/naoModule/libnaoqi_files/include/alproxies/alchoregrapherecorderproxy.h new file mode 100755 index 0000000..7136322 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alchoregrapherecorderproxy.h @@ -0,0 +1,206 @@ +// Generated for ALChoregrapheRecorder version 0 + +#ifndef ALCHOREGRAPHERECORDERPROXY_H_ +#define ALCHOREGRAPHERECORDERPROXY_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALChoregrapheRecorderProxy; + + namespace detail { + class ALChoregrapheRecorderProxyPostHandler + { + protected: + ALChoregrapheRecorderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALChoregrapheRecorderProxy; + + /// + /// Called by ALMemory when subcription data is updated. + /// + /// Name of the subscribed data. + /// Value of the the subscribed data + /// The message give when subscribing. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int dataChanged(const std::string& dataName, const AL::ALValue& data, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Triggers recording stop and data importation + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int motionRecorderStopped(); + + /// + /// Send replayed motors to a frame + /// + /// Target frame number + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sendReplayedToStep(const int& frame); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALChoregrapheRecorderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALChoregrapheRecorderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALChoregrapheRecorderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALChoregrapheRecorderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALChoregrapheRecorderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Called by ALMemory when subcription data is updated. + /// + /// Name of the subscribed data. + /// Value of the the subscribed data + /// The message give when subscribing. + void dataChanged(const std::string& dataName, const AL::ALValue& data, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Triggers recording stop and data importation + /// + void motionRecorderStopped(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Send replayed motors to a frame + /// + /// Target frame number + void sendReplayedToStep(const int& frame); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALChoregrapheRecorderProxyPostHandler post; + }; + +} +#endif // ALCHOREGRAPHERECORDERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alcloseobjectdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alcloseobjectdetectionproxy.h new file mode 100755 index 0000000..e124510 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alcloseobjectdetectionproxy.h @@ -0,0 +1,311 @@ +// Generated for ALCloseObjectDetection version 0 + +#ifndef ALCLOSEOBJECTDETECTIONPROXY_H_ +#define ALCLOSEOBJECTDETECTIONPROXY_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALCloseObjectDetectionProxy; + + namespace detail { + class ALCloseObjectDetectionProxyPostHandler + { + protected: + ALCloseObjectDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALCloseObjectDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALCloseObjectDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALCloseObjectDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALCloseObjectDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALCloseObjectDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALCloseObjectDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// + /// + bool isPaused(); + + /// + /// + /// + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALCloseObjectDetectionProxyPostHandler post; + }; + +} +#endif // ALCLOSEOBJECTDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alcolorblobdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alcolorblobdetectionproxy.h new file mode 100755 index 0000000..de1a38a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alcolorblobdetectionproxy.h @@ -0,0 +1,459 @@ +// Generated for ALColorBlobDetection version 0 + +#ifndef ALCOLORBLOBDETECTIONPROXY_H_ +#define ALCOLORBLOBDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALColorBlobDetectionProxy; + + namespace detail { + class ALColorBlobDetectionProxyPostHandler + { + protected: + ALColorBlobDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALColorBlobDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// Set the camera auto exposure to on + /// + /// Whether the exposure is auto or not + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAutoExposure(const bool& mode); + + /// + /// Color parameter setting + /// + /// The R component in RGB of the color to find + /// The G component in RGB of the color to find + /// The B component in RGB of the color to find + /// The color threshold + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setColor(const int& r, const int& g, const int& b, const int& colorThres); + + /// + /// Object parameter setting + /// + /// The minimum size of the cluster to find + /// The span of the object in meters + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setObjectProperties(const int& minSize, const float& span); + + /// + /// Object parameter setting + /// + /// The minimum size of the cluster to find + /// The span of the object in meters + /// The shape of the object + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setObjectProperties(const int& minSize, const float& span, const std::string& shape); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALColorBlobDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALColorBlobDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALColorBlobDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALColorBlobDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALColorBlobDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Get the camera auto exposure mode + /// + /// A flag saying the exposure is auto or not + bool getAutoExposure(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Send back the x,y,radius of the circle if any + /// + /// The circle as x,y,radius in image relative coordinates (x,radius divided by rows and y by cols) + AL::ALValue getCircle(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Set the camera auto exposure to on + /// + /// Whether the exposure is auto or not + void setAutoExposure(const bool& mode); + + /// + /// Color parameter setting + /// + /// The R component in RGB of the color to find + /// The G component in RGB of the color to find + /// The B component in RGB of the color to find + /// The color threshold + void setColor(const int& r, const int& g, const int& b, const int& colorThres); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// Object parameter setting + /// + /// The minimum size of the cluster to find + /// The span of the object in meters + void setObjectProperties(const int& minSize, const float& span); + + /// + /// Object parameter setting + /// + /// The minimum size of the cluster to find + /// The span of the object in meters + /// The shape of the object + void setObjectProperties(const int& minSize, const float& span, const std::string& shape); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALColorBlobDetectionProxyPostHandler post; + }; + +} +#endif // ALCOLORBLOBDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alconnectionmanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alconnectionmanagerproxy.h new file mode 100755 index 0000000..df99f85 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alconnectionmanagerproxy.h @@ -0,0 +1,284 @@ +// Generated for ALConnectionManager version 0 + +#ifndef ALCONNECTIONMANAGERPROXY_H_ +#define ALCONNECTIONMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALConnectionManagerProxy; + + namespace detail { + class ALConnectionManagerProxyPostHandler + { + protected: + ALConnectionManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALConnectionManagerProxy; + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int connect(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int disableTethering(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int disconnect(const std::string& arg1); + + /// + /// + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableTethering(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableTethering(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int forget(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int scan(const std::string& arg1); + + /// + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int scan(); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCountry(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setServiceConfiguration(const AL::ALValue& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setServiceInput(const AL::ALValue& arg1); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALConnectionManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALConnectionManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALConnectionManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALConnectionManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALConnectionManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// arg + void connect(const std::string& arg1); + + /// + /// + /// + std::vector countries(); + + /// + /// + /// + std::string country(); + + /// + /// + /// + /// arg + void disableTethering(const std::string& arg1); + + /// + /// + /// + /// arg + void disconnect(const std::string& arg1); + + /// + /// + /// + /// arg + /// arg + /// arg + void enableTethering(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// + /// + /// arg + void enableTethering(const std::string& arg1); + + /// + /// + /// + /// arg + void forget(const std::string& arg1); + + /// + /// + /// + /// arg + bool getTetheringEnable(const std::string& arg1); + + /// + /// + /// + AL::ALValue interfaces(); + + /// + /// + /// + /// arg + void scan(const std::string& arg1); + + /// + /// + /// + void scan(); + + /// + /// + /// + /// arg + AL::ALValue service(const std::string& arg1); + + /// + /// + /// + AL::ALValue services(); + + /// + /// + /// + /// arg + void setCountry(const std::string& arg1); + + /// + /// + /// + /// arg + void setServiceConfiguration(const AL::ALValue& arg1); + + /// + /// + /// + /// arg + void setServiceInput(const AL::ALValue& arg1); + + /// + /// + /// + std::string state(); + + /// + /// + /// + AL::ALValue technologies(); + + /// + /// + /// + /// arg + std::string tetheringName(const std::string& arg1); + + /// + /// + /// + /// arg + std::string tetheringPassphrase(const std::string& arg1); + + + detail::ALConnectionManagerProxyPostHandler post; + }; + +} +#endif // ALCONNECTIONMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/aldarknessdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/aldarknessdetectionproxy.h new file mode 100755 index 0000000..af74069 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/aldarknessdetectionproxy.h @@ -0,0 +1,402 @@ +// Generated for ALDarknessDetection version 0 + +#ifndef ALDARKNESSDETECTIONPROXY_H_ +#define ALDARKNESSDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALDarknessDetectionProxy; + + namespace detail { + class ALDarknessDetectionProxyPostHandler + { + protected: + ALDarknessDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALDarknessDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// Enables to change the DarknessThreshold for isItDark + /// + /// New darkness threshold (between 0 and 100) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDarknessThreshold(const int& threshold); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALDarknessDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALDarknessDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALDarknessDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALDarknessDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALDarknessDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Returns the current DarknessThreshold for isItDark + /// + /// Current darkness threshold value + int getDarknessThreshold(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Enables to change the DarknessThreshold for isItDark + /// + /// New darkness threshold (between 0 and 100) + void setDarknessThreshold(const int& threshold); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALDarknessDetectionProxyPostHandler post; + }; + +} +#endif // ALDARKNESSDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/aldebugproxy.h b/naoModule/libnaoqi_files/include/alproxies/aldebugproxy.h new file mode 100755 index 0000000..1c332b4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/aldebugproxy.h @@ -0,0 +1,85 @@ +// Generated for ALDebug version 0 + +#ifndef ALDEBUGPROXY_H_ +#define ALDEBUGPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALDebugProxy; + + namespace detail { + class ALDebugProxyPostHandler + { + protected: + ALDebugProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALDebugProxy; + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALDebugProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALDebugProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALDebugProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALDebugProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALDebugProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + + detail::ALDebugProxyPostHandler post; + }; + +} +#endif // ALDEBUGPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/aldiagnosisproxy.h b/naoModule/libnaoqi_files/include/alproxies/aldiagnosisproxy.h new file mode 100755 index 0000000..bedd510 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/aldiagnosisproxy.h @@ -0,0 +1,202 @@ +// Generated for ALDiagnosis version 0 + +#ifndef ALDIAGNOSISPROXY_H_ +#define ALDIAGNOSISPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALDiagnosisProxy; + + namespace detail { + class ALDiagnosisProxyPostHandler + { + protected: + ALDiagnosisProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALDiagnosisProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Enable / Disable diagnosis notification. + /// + /// If True enable diagnosis notification. If False disable diagnosis notification. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setEnableNotification(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALDiagnosisProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALDiagnosisProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALDiagnosisProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALDiagnosisProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALDiagnosisProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// The actual state of the active diagnosis. + /// + AL::ALValue getActiveDiagnosis(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// The actual state of the passive diagnosis. + /// + AL::ALValue getPassiveDiagnosis(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Return true if notification is active. + /// + /// Return True if notifications is active. + bool isNotificationEnabled(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Enable / Disable diagnosis notification. + /// + /// If True enable diagnosis notification. If False disable diagnosis notification. + void setEnableNotification(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALDiagnosisProxyPostHandler post; + }; + +} +#endif // ALDIAGNOSISPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/aldialogproxy.h b/naoModule/libnaoqi_files/include/alproxies/aldialogproxy.h new file mode 100755 index 0000000..5beaf54 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/aldialogproxy.h @@ -0,0 +1,1077 @@ +// Generated for ALDialog version 0 + +#ifndef ALDIALOGPROXY_H_ +#define ALDIALOGPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALDialogProxy; + + namespace detail { + class ALDialogProxyPostHandler + { + protected: + ALDialogProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALDialogProxy; + + /// + /// activate a tag + /// + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int activateTag(const std::string& arg1, const std::string& arg2); + + /// + /// Activate a topic + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int activateTopic(const std::string& arg1); + + /// + /// Callback when speech recognition recognized a word + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addBlockingEvent(const std::string& arg1); + + /// + /// Black list a list of application + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int applicationBlackList(const std::vector& arg1); + + /// + /// clear concepts in DB + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int clearConcepts(); + + /// + /// Close the session + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int closeSession(); + + /// + /// compilationFinished + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int compilationFinished(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// compile all for ASR + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int compileAll(); + + /// + /// Callback when remote connection changes + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int connectionChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// deactivate a tag + /// + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deactivateTag(const std::string& arg1, const std::string& arg2); + + /// + /// Activate a topic + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deactivateTopic(const std::string& arg1); + + /// + /// delete serializations files .ser .ini .bnf .lcf + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deleteSerializationFiles(); + + /// + /// enableCategory + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableCategory(const bool& arg1); + + /// + /// enable sending log audio (recorded conversation) to the cloud + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableLogAudio(const bool& arg1); + + /// + /// let the robot send log the cloud + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableSendingLogToCloud(const bool& arg1); + + /// + /// enableTriggerSentences + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableTriggerSentences(const bool& arg1); + + /// + /// Callback when dialog received a event + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int eventReceived(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Give a sentence to the dialog and get the answer + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int forceInput(const std::string& arg1); + + /// + /// Get a proposal + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int forceOutput(); + + /// + /// Generate sentences + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int generateSentences(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// Callback when ASR status changes + /// + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoTag(const std::string& arg1, const std::string& arg2); + + /// + /// Set the focus to a topic and make a proposal + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoTopic(const std::string& arg1); + + /// + /// insert user data into dialog database + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertUserData(const std::string& arg1, const std::string& arg2, const int& arg3); + + /// + /// noPick + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int noPick(const std::string& arg1); + + /// + /// Open a session + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int openSession(const int& arg1); + + /// + /// packageInstalled + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int packageInstalled(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// releaseEngine + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int releaseEngine(); + + /// + /// remove a user from the database + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeUserData(const int& arg1); + + /// + /// fallback + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetAll(); + + /// + /// run main dialog + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int runDialog(); + + /// + /// Set the minimum confidence required to recognize words + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setASRConfidenceThreshold(const float& arg1); + + /// + /// Set the configuration of animated speech for the current dialog. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAnimatedSpeechConfiguration(const AL::ALValue& arg1); + + /// + /// Set the content of a dynamic concept + /// + /// Name of the concept + /// Language of the concept + /// content of the concept + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setConcept(const std::string& conceptName, const std::string& language, const std::vector& content); + + /// + /// Set the content of a dynamic concept + /// + /// Name of the concept + /// Language of the concept + /// content of the concept + /// determine if the concept will be save in the database + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setConcept(const std::string& conceptName, const std::string& language, const std::vector& content, const bool& store); + + /// + /// set the content of a dynamic concept + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setConceptKeepInCache(const std::string& arg1, const std::string& arg2, const std::vector& arg3); + + /// + /// change event's delay + /// + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDelay(const std::string& arg1, const int& arg2); + + /// + /// Give focus to a dialog + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFocus(const std::string& arg1); + + /// + /// setLanguage + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLanguage(const std::string& arg1); + + /// + /// Set how many scopes remains open + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setNumberOfScopes(const int& arg1); + + /// + /// Set push mode + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPushMode(const int& arg1); + + /// + /// setVariablePath + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVariablePath(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// startUpdate + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startApp(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Start push mode + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startPush(); + + /// + /// startUpdate + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startUpdate(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Callback when ASR status changes + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int statusChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// stop main dialog + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopDialog(); + + /// + /// Stop push mode + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopPush(); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Give a sentence to the dialog and get the answer + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int tell(const std::string& arg1); + + /// + /// unload a dialog + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unloadTopic(const std::string& arg1); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + /// + /// Callback when speech recognition recognized a word + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wordRecognized(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Get loaded dialog list + /// + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wordsRecognizedCallback(const AL::ALValue& arg1, const int& arg2); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALDialogProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALDialogProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALDialogProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALDialogProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALDialogProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// activate a tag + /// + /// arg + /// arg + void activateTag(const std::string& arg1, const std::string& arg2); + + /// + /// Activate a topic + /// + /// arg + void activateTopic(const std::string& arg1); + + /// + /// Callback when speech recognition recognized a word + /// + /// arg + void addBlockingEvent(const std::string& arg1); + + /// + /// Black list a list of application + /// + /// arg + void applicationBlackList(const std::vector& arg1); + + /// + /// clear concepts in DB + /// + void clearConcepts(); + + /// + /// Close the session + /// + void closeSession(); + + /// + /// compilationFinished + /// + /// arg + /// arg + /// arg + void compilationFinished(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// compile all for ASR + /// + void compileAll(); + + /// + /// Callback when remote connection changes + /// + /// arg + /// arg + /// arg + void connectionChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// controlEngine + /// + /// arg + /// arg + std::vector controlEngine(const std::string& arg1, const std::string& arg2); + + /// + /// deactivate a tag + /// + /// arg + /// arg + void deactivateTag(const std::string& arg1, const std::string& arg2); + + /// + /// Activate a topic + /// + /// arg + void deactivateTopic(const std::string& arg1); + + /// + /// delete serializations files .ser .ini .bnf .lcf + /// + void deleteSerializationFiles(); + + /// + /// enableCategory + /// + /// arg + void enableCategory(const bool& arg1); + + /// + /// enable sending log audio (recorded conversation) to the cloud + /// + /// arg + void enableLogAudio(const bool& arg1); + + /// + /// let the robot send log the cloud + /// + /// arg + void enableSendingLogToCloud(const bool& arg1); + + /// + /// enableTriggerSentences + /// + /// arg + void enableTriggerSentences(const bool& arg1); + + /// + /// End of utterance callback + /// + bool endOfUtteranceCallback(); + + /// + /// Callback when dialog received a event + /// + /// arg + /// arg + /// arg + void eventReceived(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Give a sentence to the dialog and get the answer + /// + /// arg + void forceInput(const std::string& arg1); + + /// + /// Get a proposal + /// + void forceOutput(); + + /// + /// Generate sentences + /// + /// arg + /// arg + /// arg + void generateSentences(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// Get the minimum confidence required to recognize words + /// + float getASRConfidenceThreshold(); + + /// + /// Get activated topics + /// + std::vector getActivatedTopics(); + + /// + /// Load precompiled file + /// + std::vector getAllLoadedTopics(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Give focus to a dialog + /// + std::string getFocus(); + + /// + /// Load precompiled file + /// + /// arg + std::vector getLoadedTopics(const std::string& arg1); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// get user data from dialog database + /// + /// arg + /// arg + std::string getUserData(const std::string& arg1, const int& arg2); + + /// + /// get user data list from dialog database + /// + /// arg + std::vector getUserDataList(const int& arg1); + + /// + /// get user list from dialog database + /// + std::vector getUserList(); + + /// + /// Callback when ASR status changes + /// + /// arg + /// arg + void gotoTag(const std::string& arg1, const std::string& arg2); + + /// + /// Set the focus to a topic and make a proposal + /// + /// arg + void gotoTopic(const std::string& arg1); + + /// + /// insert user data into dialog database + /// + /// arg + /// arg + /// arg + void insertUserData(const std::string& arg1, const std::string& arg2, const int& arg3); + + /// + /// True if new content was installed + /// + bool isContentNeedsUpdate(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// check if the robot is sending the log to the cloud + /// + bool isSendingLogToCloud(); + + /// + /// Load a topic + /// + /// arg + std::string loadTopic(const std::string& arg1); + + /// + /// noPick + /// + /// arg + void noPick(const std::string& arg1); + + /// + /// Open a session + /// + /// arg + void openSession(const int& arg1); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// packageInstalled + /// + /// arg + /// arg + /// arg + void packageInstalled(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// releaseEngine + /// + void releaseEngine(); + + /// + /// remove a user from the database + /// + /// arg + void removeUserData(const int& arg1); + + /// + /// fallback + /// + void resetAll(); + + /// + /// run main dialog + /// + void runDialog(); + + /// + /// Set the minimum confidence required to recognize words + /// + /// arg + void setASRConfidenceThreshold(const float& arg1); + + /// + /// Set the configuration of animated speech for the current dialog. + /// + /// arg + void setAnimatedSpeechConfiguration(const AL::ALValue& arg1); + + /// + /// Set the content of a dynamic concept + /// + /// Name of the concept + /// Language of the concept + /// content of the concept + void setConcept(const std::string& conceptName, const std::string& language, const std::vector& content); + + /// + /// Set the content of a dynamic concept + /// + /// Name of the concept + /// Language of the concept + /// content of the concept + /// determine if the concept will be save in the database + void setConcept(const std::string& conceptName, const std::string& language, const std::vector& content, const bool& store); + + /// + /// set the content of a dynamic concept + /// + /// arg + /// arg + /// arg + void setConceptKeepInCache(const std::string& arg1, const std::string& arg2, const std::vector& arg3); + + /// + /// change event's delay + /// + /// arg + /// arg + void setDelay(const std::string& arg1, const int& arg2); + + /// + /// Give focus to a dialog + /// + /// arg + void setFocus(const std::string& arg1); + + /// + /// setLanguage + /// + /// arg + void setLanguage(const std::string& arg1); + + /// + /// Set how many scopes remains open + /// + /// arg + void setNumberOfScopes(const int& arg1); + + /// + /// Set push mode + /// + /// arg + void setPushMode(const int& arg1); + + /// + /// setVariablePath + /// + /// arg + /// arg + /// arg + void setVariablePath(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// startUpdate + /// + /// arg + /// arg + /// arg + void startApp(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Start push mode + /// + void startPush(); + + /// + /// startUpdate + /// + /// arg + /// arg + /// arg + void startUpdate(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Callback when ASR status changes + /// + /// arg + /// arg + /// arg + void statusChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// stop main dialog + /// + void stopDialog(); + + /// + /// Stop push mode + /// + void stopPush(); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Give a sentence to the dialog and get the answer + /// + /// arg + void tell(const std::string& arg1); + + /// + /// unload a dialog + /// + /// arg + void unloadTopic(const std::string& arg1); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Callback when speech recognition recognized a word + /// + /// arg + /// arg + /// arg + void wordRecognized(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Get loaded dialog list + /// + /// arg + /// arg + void wordsRecognizedCallback(const AL::ALValue& arg1, const int& arg2); + + + detail::ALDialogProxyPostHandler post; + }; + +} +#endif // ALDIALOGPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alengagementzonesproxy.h b/naoModule/libnaoqi_files/include/alproxies/alengagementzonesproxy.h new file mode 100755 index 0000000..a43d6d4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alengagementzonesproxy.h @@ -0,0 +1,397 @@ +// Generated for ALEngagementZones version 0 + +#ifndef ALENGAGEMENTZONESPROXY_H_ +#define ALENGAGEMENTZONESPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALEngagementZonesProxy; + + namespace detail { + class ALEngagementZonesProxyPostHandler + { + protected: + ALEngagementZonesProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALEngagementZonesProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Set the first distance used for the delimitation of the engagement zones (nearest limit) + /// + /// New first distance (in meters) for delimitation (nearest limit), it should be positive and smaller than the second distance + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFirstLimitDistance(const float& distance); + + /// + /// Set the angle used for the delimitation of the engagement zones + /// + /// New angle (in degrees) for delimitation, it should be below 180 + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLimitAngle(const float& angle); + + /// + /// Set the second distance used for the delimitation of the engagement zones (furthest limit) + /// + /// New second distance (in meters) for delimitation (furthest limit), it should be positive and bigger than the first distance + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSecondLimitDistance(const float& distance); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALEngagementZonesProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALEngagementZonesProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALEngagementZonesProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALEngagementZonesProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALEngagementZonesProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Computes the engagement zone in which an object is from its position in FRAME_ROBOT + /// + /// X coordinate of the object in FRAME_ROBOT + /// Y coordinate of the object in FRAME_ROBOT + /// Z coordinate of the object in FRAME_ROBOT + /// Engagement zone of the object + int computeEngagementZone(const float& x, const float& y, const float& z); + + /// + /// Computes the engagement zone in which an object is from its anglular position in the camera image, its distance from the robot, and the position of the camera in FRAME_ROBOT + /// + /// X angular coordinate of the object in the image + /// Y angular coordinate of the object in the image + /// distance of the object from the robot + /// camera position in FRAME_ROBOT + /// Engagement zone of the object + int computeEngagementZone(const float& xAngle, const float& yAngle, const float& distance, const AL::ALValue& cameraPositionRobot); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the first distance used for the delimitation of the engagement zones (nearest limit) + /// + /// Current first distance (in meters) used for delimitation (nearest limit) + float getFirstLimitDistance(); + + /// + /// Get the angle used for the delimitation of the engagement zones + /// + /// Current angle used for delimitation + float getLimitAngle(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Get the second distance used for the delimitation of the engagement zones (furthest limit) + /// + /// Current second distance (in meters) used for delimitation (furthest limit) + float getSecondLimitDistance(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set the first distance used for the delimitation of the engagement zones (nearest limit) + /// + /// New first distance (in meters) for delimitation (nearest limit), it should be positive and smaller than the second distance + void setFirstLimitDistance(const float& distance); + + /// + /// Set the angle used for the delimitation of the engagement zones + /// + /// New angle (in degrees) for delimitation, it should be below 180 + void setLimitAngle(const float& angle); + + /// + /// Set the second distance used for the delimitation of the engagement zones (furthest limit) + /// + /// New second distance (in meters) for delimitation (furthest limit), it should be positive and bigger than the first distance + void setSecondLimitDistance(const float& distance); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALEngagementZonesProxyPostHandler post; + }; + +} +#endif // ALENGAGEMENTZONESPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alexpressivelisteningproxy.h b/naoModule/libnaoqi_files/include/alproxies/alexpressivelisteningproxy.h new file mode 100755 index 0000000..175e172 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alexpressivelisteningproxy.h @@ -0,0 +1,337 @@ +// Generated for ALExpressiveListening version 0 + +#ifndef ALEXPRESSIVELISTENINGPROXY_H_ +#define ALEXPRESSIVELISTENINGPROXY_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALExpressiveListeningProxy; + + namespace detail { + class ALExpressiveListeningProxyPostHandler + { + protected: + ALExpressiveListeningProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALExpressiveListeningProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Pause Expressive Listening. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pauseListening(); + + /// + /// Resume Expressive Listening. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resumeListening(); + + /// + /// Enable/Disable nodding. + /// + /// Boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setNoddingEnabled(const bool& enable); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. + /// "MinTimeBeforeFirstNod" : Minimum time (in seconds) before first nod. + /// "MaxTimeBeforeFirstNod" : Maximum time (in seconds) before first nod. + /// "MinTimeBetweenNods" : Minimum time (in seconds) between two nods. + /// "MaxTimeBetweenNods" : Maximum time (in seconds) between two nods. + /// "SpeedNods" : Speed of head moves when nodding + /// "SpeedServoing" : Speed of head moves when servoing. + /// "FrameRateTracking3D" : 3D tracking's framerate. + /// "FrameRateTracking2D" : 2D tracking's framerate. + /// "NobodyFoundTimeOut" : timeout to send peopleLeft event when no blob isfound + /// "AmplitudeNod" : amplitude of the nod (angle made by Up and Down positions), in degree + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// + /// "MinTimeBeforeFirstNod" : Float in range [0;5] + /// "MaxTimeBeforeFirstNod" : Float in range [0;5] + /// "MinTimeBetweenNods" : Float in range [0;5] + /// "MaxTimeBetweenNods" : Float in range [0;5] + /// "SpeedNods" : Float in range [0;1] + /// "SpeedServoing" : Float in range [0;1] + /// "FrameRateTracking3D" : Float in range [0.1;30] + /// "FrameRateTracking2D" : Float in range [0.1;30] + /// "NobodyFoundTimeOut" : Float > 0 + /// "AmplitudeNod" : Float in range [0;45] + /// "AmplitudeYawTracking" : Float in range [10;120] + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// Enable/Disable tracking. + /// + /// Boolean value: true to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTracking3DEnabled(const bool& enable); + + /// + /// Start Expressive Listening. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startListening(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop Expressive Listening. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopListening(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALExpressiveListeningProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALExpressiveListeningProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALExpressiveListeningProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALExpressiveListeningProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALExpressiveListeningProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the specified parameter. + /// + /// Name of the parameter. + /// "MinTimeBeforeFirstNod" : Minimum time (in seconds) before first nod. + /// "MaxTimeBeforeFirstNod" : Maximum time (in seconds) before first nod. + /// "MinTimeBetweenNods" : Minimum time (in seconds) between two nods. + /// "MaxTimeBetweenNods" : Maximum time (in seconds) between two nods. + /// "SpeedNods" : Speed of head moves when nodding + /// "SpeedServoing" : Speed of head moves when servoing. + /// "FrameRateTracking3D" : 3D tracking's framerate. + /// "FrameRateTracking2D" : 2D tracking's framerate. + /// "NobodyFoundTimeOut" : timeout to send peopleLeft event when no blob isfound + /// "AmplitudeNod" : amplitude of the nod (angle made by Up and Down positions), in degree + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// + /// ALValue format for required parameter + AL::ALValue getParameter(const std::string& parameter); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get the status (started or not) of the module. + /// + bool isListening(); + + /// + /// Get status enabled/disabled for Nodding + /// + /// Boolean value for status enabled/disabled + bool isNoddingEnabled(); + + /// + /// Get the pause status of the module. + /// + bool isPaused(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Get status enabled/disabled for tracking. + /// + /// Boolean value for status enabled/disabled + bool isTracking3DEnabled(); + + /// + /// Pause Expressive Listening. + /// + void pauseListening(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Resume Expressive Listening. + /// + void resumeListening(); + + /// + /// Enable/Disable nodding. + /// + /// Boolean value: true to enable, false to disable. + void setNoddingEnabled(const bool& enable); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. + /// "MinTimeBeforeFirstNod" : Minimum time (in seconds) before first nod. + /// "MaxTimeBeforeFirstNod" : Maximum time (in seconds) before first nod. + /// "MinTimeBetweenNods" : Minimum time (in seconds) between two nods. + /// "MaxTimeBetweenNods" : Maximum time (in seconds) between two nods. + /// "SpeedNods" : Speed of head moves when nodding + /// "SpeedServoing" : Speed of head moves when servoing. + /// "FrameRateTracking3D" : 3D tracking's framerate. + /// "FrameRateTracking2D" : 2D tracking's framerate. + /// "NobodyFoundTimeOut" : timeout to send peopleLeft event when no blob isfound + /// "AmplitudeNod" : amplitude of the nod (angle made by Up and Down positions), in degree + /// "AmplitudeYawTracking" : max absolute value for head yaw in tracking, in degrees + /// + /// "MinTimeBeforeFirstNod" : Float in range [0;5] + /// "MaxTimeBeforeFirstNod" : Float in range [0;5] + /// "MinTimeBetweenNods" : Float in range [0;5] + /// "MaxTimeBetweenNods" : Float in range [0;5] + /// "SpeedNods" : Float in range [0;1] + /// "SpeedServoing" : Float in range [0;1] + /// "FrameRateTracking3D" : Float in range [0.1;30] + /// "FrameRateTracking2D" : Float in range [0.1;30] + /// "NobodyFoundTimeOut" : Float > 0 + /// "AmplitudeNod" : Float in range [0;45] + /// "AmplitudeYawTracking" : Float in range [10;120] + /// + void setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// Enable/Disable tracking. + /// + /// Boolean value: true to enable, false to disable. + void setTracking3DEnabled(const bool& enable); + + /// + /// Start Expressive Listening. + /// + void startListening(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop Expressive Listening. + /// + void stopListening(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALExpressiveListeningProxyPostHandler post; + }; + +} +#endif // ALEXPRESSIVELISTENINGPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfacecharacteristicsproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfacecharacteristicsproxy.h new file mode 100755 index 0000000..be8c48a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfacecharacteristicsproxy.h @@ -0,0 +1,347 @@ +// Generated for ALFaceCharacteristics version 0 + +#ifndef ALFACECHARACTERISTICSPROXY_H_ +#define ALFACECHARACTERISTICSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFaceCharacteristicsProxy; + + namespace detail { + class ALFaceCharacteristicsProxyPostHandler + { + protected: + ALFaceCharacteristicsProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFaceCharacteristicsProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Sets the smile degree threshold above which an event is raised. + /// + /// New threshold (must be between 0.0 and 1.0. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSmilingThreshold(const float& threshold); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFaceCharacteristicsProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFaceCharacteristicsProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFaceCharacteristicsProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFaceCharacteristicsProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFaceCharacteristicsProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Runs face analysis for a given person ID. + /// + /// Person ID. + /// True if the face analysis succeeded, false otherwise. + bool analyzeFaceCharacteristics(const int& id); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the smile degree threshold above which an event is raised. + /// + /// Threshold for Smiling event + float getSmilingThreshold(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets the smile degree threshold above which an event is raised. + /// + /// New threshold (must be between 0.0 and 1.0. + void setSmilingThreshold(const float& threshold); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFaceCharacteristicsProxyPostHandler post; + }; + +} +#endif // ALFACECHARACTERISTICSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfacedetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfacedetectionproxy.h new file mode 100755 index 0000000..a84be79 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfacedetectionproxy.h @@ -0,0 +1,491 @@ +// Generated for ALFaceDetection version 0 + +#ifndef ALFACEDETECTIONPROXY_H_ +#define ALFACEDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFaceDetectionProxy; + + namespace detail { + class ALFaceDetectionProxyPostHandler + { + protected: + ALFaceDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFaceDetectionProxy; + + /// + /// deprecated + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableRecognition(const bool& arg1); + + /// + /// deprecated + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableTracking(const bool& arg1); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// enable/disable the recognition stageProcess will be faster when disabled when you don't need to recognize people + /// + /// True/False + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setRecognitionEnabled(const bool& enable); + + /// + /// (BETA) Choose to enable or disable tracking. Enabling tracking usually allows you to follow a face for a longer period of time. However, it can lead to more false detections. + /// + /// True/False + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTrackingEnabled(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFaceDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFaceDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFaceDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFaceDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFaceDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Remove all faces from the database. + /// + /// true if the operation succeeds + bool clearDatabase(); + + /// + /// deprecated + /// + /// arg + void enableRecognition(const bool& arg1); + + /// + /// deprecated + /// + /// arg + void enableTracking(const bool& arg1); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Delete from the database all faces instances of a person. + /// + /// The name of the person to forget + /// true if the operation succeeds + bool forgetPerson(const std::string& pId); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Returns the list of learned faces. + /// + /// List of names + AL::ALValue getLearnedFacesList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Imports the content of an old face reco DB + /// + /// Merging policy if an imported entry has the same name as an existing one. + /// It can be either: + /// "overwrite" to replace the existing entry by the imported one, + /// "merge" to merge data from both entries (if they don't relate to the same person, face recognition may fail), + /// "keep" to keep the existing entry and skip the imported one. + /// True if the import succeeded, false otherwise. + bool importOldDatabase(const std::string& policy); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns if recognition is enabled. + /// + /// True/False + bool isRecognitionEnabled(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// (BETA) Returns if tracking is enabled. + /// + /// True/False + bool isTrackingEnabled(); + + /// + /// Add a new face in the database. + /// + /// The name of the person to save + /// true if the operation succeeds + bool learnFace(const std::string& pId); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// use in a new learning process the latest images where a face has been wrongly recognized + /// + /// The name of the person to save + /// true if the operation succeeds + bool reLearnFace(const std::string& pId); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// enable/disable the recognition stageProcess will be faster when disabled when you don't need to recognize people + /// + /// True/False + void setRecognitionEnabled(const bool& enable); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// (BETA) Choose to enable or disable tracking. Enabling tracking usually allows you to follow a face for a longer period of time. However, it can lead to more false detections. + /// + /// True/False + void setTrackingEnabled(const bool& enable); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFaceDetectionProxyPostHandler post; + }; + +} +#endif // ALFACEDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfacetrackerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfacetrackerproxy.h new file mode 100755 index 0000000..f1741c4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfacetrackerproxy.h @@ -0,0 +1,241 @@ +// Generated for ALFaceTracker version 0 + +#ifndef ALFACETRACKERPROXY_H_ +#define ALFACETRACKERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFaceTrackerProxy; + + namespace detail { + class ALFaceTrackerProxyPostHandler + { + protected: + ALFaceTrackerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFaceTrackerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// if true, the tracking will be through a Whole Body Process. + /// + /// + /// The whole Body state + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWholeBodyOn(const bool& pWholeBodyOn); + + /// + /// Start the tracker by Subscribing to Event FaceDetected from ALFaceDetection module. + /// Then Wait Event FaceDetected from ALFaceDetection module. + /// And finally send information to motion for head tracking. + /// NOTE: Stiffness of Head must be set to 1.0 to move! + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startTracker(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop the tracker by Unsubscribing to Event FaceDetected from ALFaceDetection module. + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopTracker(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFaceTrackerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFaceTrackerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFaceTrackerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFaceTrackerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFaceTrackerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Return the [x, y, z] position of the face in FRAME_TORSO. This is done assuming an average face size, so it might not be very accurate. + /// This invalidates the isNewData field of the tracker. See isNewData()) for more details. + /// + /// An Array containing the face position [x, y, z]. + std::vector getPosition(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Return true if the face Tracker is running. + /// + /// + /// true if the face Tracker is running. + bool isActive(); + + /// + /// Return true if a new face was detected since the last getPosition(). + /// + /// + /// true if a new face was detected since the last getPosition(). + bool isNewData(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// if true, the tracking will be through a Whole Body Process. + /// + /// + /// The whole Body state + void setWholeBodyOn(const bool& pWholeBodyOn); + + /// + /// Start the tracker by Subscribing to Event FaceDetected from ALFaceDetection module. + /// Then Wait Event FaceDetected from ALFaceDetection module. + /// And finally send information to motion for head tracking. + /// NOTE: Stiffness of Head must be set to 1.0 to move! + /// + /// + void startTracker(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop the tracker by Unsubscribing to Event FaceDetected from ALFaceDetection module. + /// + /// + void stopTracker(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFaceTrackerProxyPostHandler post; + }; + +} +#endif // ALFACETRACKERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfastpersontrackingproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfastpersontrackingproxy.h new file mode 100755 index 0000000..0b8afb9 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfastpersontrackingproxy.h @@ -0,0 +1,359 @@ +// Generated for ALFastPersonTracking version 0 + +#ifndef ALFASTPERSONTRACKINGPROXY_H_ +#define ALFASTPERSONTRACKINGPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFastPersonTrackingProxy; + + namespace detail { + class ALFastPersonTrackingProxyPostHandler + { + protected: + ALFastPersonTrackingProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFastPersonTrackingProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Sets the distance (in meters) for the tracking + /// + /// New value (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTrackingDistance(const float& distance); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVerticalOffset(const float& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFastPersonTrackingProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFastPersonTrackingProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFastPersonTrackingProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFastPersonTrackingProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFastPersonTrackingProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the distance (in meters) for the tracking + /// + /// Current tracking distance (in meters) + float getTrackingDistance(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// Current vertical offset of the blob tracker + float getVerticalOffset(); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets the distance (in meters) for the tracking + /// + /// New value (in meters) + void setTrackingDistance(const float& distance); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + void setVerticalOffset(const float& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFastPersonTrackingProxyPostHandler post; + }; + +} +#endif // ALFASTPERSONTRACKINGPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfilemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfilemanagerproxy.h new file mode 100755 index 0000000..e9bc7de --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfilemanagerproxy.h @@ -0,0 +1,226 @@ +// Generated for ALFileManager version 0 + +#ifndef ALFILEMANAGERPROXY_H_ +#define ALFILEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFileManagerProxy; + + namespace detail { + class ALFileManagerProxyPostHandler + { + protected: + ALFileManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFileManagerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Set a new value of the user shared folder path. + /// + /// Name of the module associate to the preference. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setUserSharedFolderPath(const std::string& fileName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFileManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFileManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFileManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFileManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFileManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Try to find if this file does exist on robot or not. + /// + /// Name of the module associate to the preference. + /// True upon success + bool dataFileExists(const std::string& fileName); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Try to find if this file does exist on robot or not. + /// + /// Name of the module associate to the preference. + /// True upon success + bool fileExists(const std::string& fileName); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns the complete path of the file if it does exist. Starts by looking in user's shared folder, then in system folder. + /// + /// array reprenting the whole file. + /// True upon success + std::string getFileCompletePath(const std::string& prefs); + + /// + /// Returns the complete path of the file if it does exist. Starts by looking in user's shared folder, then in system folder. + /// + /// array reprenting the whole file. + /// True upon success + AL::ALValue getFileContents(const std::string& prefs); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the current system shared folder path. + /// + /// System shared folder path string. + std::string getSystemSharedFolderPath(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get the current user shared folder path. + /// + /// User shared folder path string. + std::string getUserSharedFolderPath(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set a new value of the user shared folder path. + /// + /// Name of the module associate to the preference. + void setUserSharedFolderPath(const std::string& fileName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFileManagerProxyPostHandler post; + }; + +} +#endif // ALFILEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfindpersonheadproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfindpersonheadproxy.h new file mode 100755 index 0000000..b16ecf7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfindpersonheadproxy.h @@ -0,0 +1,239 @@ +// Generated for ALFindPersonHead version 0 + +#ifndef ALFINDPERSONHEADPROXY_H_ +#define ALFINDPERSONHEADPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFindPersonHeadProxy; + + namespace detail { + class ALFindPersonHeadProxyPostHandler + { + protected: + ALFindPersonHeadProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFindPersonHeadProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Sets the distance (in meters) for the tracking + /// + /// New value (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTrackingDistance(const float& distance); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVerticalOffset(const float& value); + + /// + /// Starts the module's process, the events are then raised. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startSearch(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops the module's process, the events are not raised anymore. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopSearch(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFindPersonHeadProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFindPersonHeadProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFindPersonHeadProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFindPersonHeadProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFindPersonHeadProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the distance (in meters) for the tracking + /// + /// Current tracking distance (in meters) + float getTrackingDistance(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// Current vertical offset of the blob tracker + float getVerticalOffset(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Tells if the module is running or not. + /// + /// True if the module is running, False if not. + bool isSearching(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets the distance (in meters) for the tracking + /// + /// New value (in meters) + void setTrackingDistance(const float& distance); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + void setVerticalOffset(const float& value); + + /// + /// Starts the module's process, the events are then raised. + /// + void startSearch(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops the module's process, the events are not raised anymore. + /// + void stopSearch(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFindPersonHeadProxyPostHandler post; + }; + +} +#endif // ALFINDPERSONHEADPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alframemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alframemanagerproxy.h new file mode 100755 index 0000000..ab80ac4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alframemanagerproxy.h @@ -0,0 +1,400 @@ +// Generated for ALFrameManager version 0 + +#ifndef ALFRAMEMANAGERPROXY_H_ +#define ALFRAMEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFrameManagerProxy; + + namespace detail { + class ALFrameManagerProxyPostHandler + { + protected: + ALFrameManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFrameManagerProxy; + + /// + /// Stop playing any behavior in FrameManager, and delete all of them. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int cleanBehaviors(); + + /// + /// It will play a behavior and block until the behavior is finished. Note that it can block forever if the behavior output is never called. + /// + /// The id of the box. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int completeBehavior(const std::string& id); + + /// + /// Deletes a behavior (meaning a box). Stop the whole behavior contained in this box first. + /// + /// The id of the box to delete. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deleteBehavior(const std::string& id); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Exit the reading of a timeline contained in a given box + /// + /// The id of the box. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exitBehavior(const std::string& id); + + /// + /// Goes to a certain frame and continue playing. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The behavior frame name we want the timeline to go to. If will jump to the starting index of the name given. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoAndPlay(const std::string& id, const std::string& frame); + + /// + /// Goes to a certain frame and continue playing. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The frame we want the timeline to go to. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoAndPlay(const std::string& id, const int& frame); + + /// + /// Goes to a certain frame and pause. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The behavior frame name we want the timeline to go to. If will jump to the starting index of the name given. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoAndStop(const std::string& id, const std::string& frame); + + /// + /// Goes to a certain frame and pause. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The frame we want the timeline to go to. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int gotoAndStop(const std::string& id, const int& frame); + + /// + /// Starts a behavior + /// + /// The id of the box. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playBehavior(const std::string& id); + + /// + /// Starts playing a timeline contained in a given box. If the box is a flow diagram, it will look for the first onStart input of type Bang, and stimulate it ! DEPRECATED since 1.14 + /// + /// The id of the box. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int playTimeline(const std::string& id); + + /// + /// Sets the FPS of a given timeline. DEPRECATED since 1.14 + /// + /// The id of the timeline. + /// The FPS to set. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTimelineFps(const std::string& id, const int& fps); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops playing a timeline contained in a given box, at the current frame. DEPRECATED since 1.14 + /// + /// The id of the box. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopTimeline(const std::string& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFrameManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFrameManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFrameManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFrameManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFrameManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// List all behaviors currently handled by the frame manager. + /// + /// a set listing all behavior ids + std::vector behaviors(); + + /// + /// Stop playing any behavior in FrameManager, and delete all of them. + /// + void cleanBehaviors(); + + /// + /// It will play a behavior and block until the behavior is finished. Note that it can block forever if the behavior output is never called. + /// + /// The id of the box. + void completeBehavior(const std::string& id); + + /// + /// Creates a timeline. + /// + /// The timeline content (in XML format). + /// return a unique identifier for the created box that contains the timeline. You must call deleteBehavior on it at some point. DEPRECATED since 1.14 + std::string createTimeline(const std::string& timelineContent); + + /// + /// Deletes a behavior (meaning a box). Stop the whole behavior contained in this box first. + /// + /// The id of the box to delete. + void deleteBehavior(const std::string& id); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Exit the reading of a timeline contained in a given box + /// + /// The id of the box. + void exitBehavior(const std::string& id); + + /// + /// Returns a playing behavior absolute path. + /// + /// The id of the behavior. + /// Returns the absolute path of given behavior. + std::string getBehaviorPath(const std::string& id); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Returns in seconds, the duration of a given movement stored in a box. Returns 0 if the behavior has no motion layers. DEPRECATED since 1.14 + /// + /// The id of the box. + /// Returns the time in seconds. + float getMotionLength(const std::string& id); + + /// + /// Gets the FPS of a given timeline. DEPRECATED since 1.14 + /// + /// The id of the timeline. + /// Returns the timeline's FPS. + int getTimelineFps(const std::string& id); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Goes to a certain frame and continue playing. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The behavior frame name we want the timeline to go to. If will jump to the starting index of the name given. + void gotoAndPlay(const std::string& id, const std::string& frame); + + /// + /// Goes to a certain frame and continue playing. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The frame we want the timeline to go to. + void gotoAndPlay(const std::string& id, const int& frame); + + /// + /// Goes to a certain frame and pause. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The behavior frame name we want the timeline to go to. If will jump to the starting index of the name given. + void gotoAndStop(const std::string& id, const std::string& frame); + + /// + /// Goes to a certain frame and pause. DEPRECATED since 1.14 + /// + /// The id of the box containing the box. + /// The frame we want the timeline to go to. + void gotoAndStop(const std::string& id, const int& frame); + + /// + /// Tells whether the behavior is running + /// + /// The id of the behavior to check + /// True if the behavior is running, false otherwise + bool isBehaviorRunning(const std::string& id); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Creates a new behavior, from a box found in an xml file. Note that you have to give the xml file contents, so this method is not very user friendly. You have to open the file, and send the string that matches the file contents if you are working from a file. You probably want to use newBehaviorFromFile instead. DEPRECATED since 1.14 + /// + /// The path to reach the box to instantiate in the project ("" if root). + /// The choregraphe project (in plain text for the moment). + /// return a unique identifier for the created box. + std::string newBehavior(const std::string& path, const std::string& xmlFile); + + /// + /// Creates a new behavior, from the current Choregraphe behavior 0(uploaded to /tmp/currentChoregrapheBehavior/behavior.xar). DEPRECATED since 1.14 + /// + /// return a unique identifier for the created behavior + std::string newBehaviorFromChoregraphe(); + + /// + /// Creates a new behavior, from a box found in an xml file stored in the robot. + /// + /// Path to Xml file, ex : "/home/youhou/mybehavior.xar". + /// + /// return a unique identifier for the created box, that can be used by playBehavior + std::string newBehaviorFromFile(const std::string& xmlFilePath, const std::string& behName); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Starts a behavior + /// + /// The id of the box. + void playBehavior(const std::string& id); + + /// + /// Starts playing a timeline contained in a given box. If the box is a flow diagram, it will look for the first onStart input of type Bang, and stimulate it ! DEPRECATED since 1.14 + /// + /// The id of the box. + void playTimeline(const std::string& id); + + /// + /// Sets the FPS of a given timeline. DEPRECATED since 1.14 + /// + /// The id of the timeline. + /// The FPS to set. + void setTimelineFps(const std::string& id, const int& fps); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops playing a timeline contained in a given box, at the current frame. DEPRECATED since 1.14 + /// + /// The id of the box. + void stopTimeline(const std::string& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFrameManagerProxyPostHandler post; + }; + +} +#endif // ALFRAMEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alfsrproxy.h b/naoModule/libnaoqi_files/include/alproxies/alfsrproxy.h new file mode 100755 index 0000000..e263842 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alfsrproxy.h @@ -0,0 +1,173 @@ +// Generated for ALFsr version 0 + +#ifndef ALFSRPROXY_H_ +#define ALFSRPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALFsrProxy; + + namespace detail { + class ALFsrProxyPostHandler + { + protected: + ALFsrProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALFsrProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALFsrProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALFsrProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALFsrProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALFsrProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALFsrProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALFsrProxyPostHandler post; + }; + +} +#endif // ALFSRPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/algazeanalysisproxy.h b/naoModule/libnaoqi_files/include/alproxies/algazeanalysisproxy.h new file mode 100755 index 0000000..f976518 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/algazeanalysisproxy.h @@ -0,0 +1,359 @@ +// Generated for ALGazeAnalysis version 0 + +#ifndef ALGAZEANALYSISPROXY_H_ +#define ALGAZEANALYSISPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALGazeAnalysisProxy; + + namespace detail { + class ALGazeAnalysisProxyPostHandler + { + protected: + ALGazeAnalysisProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALGazeAnalysisProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Turns face analysis on or off. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFaceAnalysisEnabled(const bool& status); + + /// + /// Sets the tolerance (between 0 and 1) for deciding whether or not a person is looking at the robot after face analysis. This tolerance is used only when face analysis is enabled. + /// + /// New value of the tolerance (between 0 and 1). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTolerance(const float& tolerance); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALGazeAnalysisProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALGazeAnalysisProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALGazeAnalysisProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALGazeAnalysisProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALGazeAnalysisProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the tolerance used to decide whether or not a person is looking at the robot after face analysis. + /// + /// Current value of the tolerance. + float getTolerance(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets the current status of face analysis. + /// + /// True if face analysis is enabled, False otherwise. + bool isFaceAnalysisEnabled(); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Turns face analysis on or off. + /// + /// True to turn it on, False to turn it off. + void setFaceAnalysisEnabled(const bool& status); + + /// + /// Sets the tolerance (between 0 and 1) for deciding whether or not a person is looking at the robot after face analysis. This tolerance is used only when face analysis is enabled. + /// + /// New value of the tolerance (between 0 and 1). + void setTolerance(const float& tolerance); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALGazeAnalysisProxyPostHandler post; + }; + +} +#endif // ALGAZEANALYSISPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alheadposeanalysisproxy.h b/naoModule/libnaoqi_files/include/alproxies/alheadposeanalysisproxy.h new file mode 100755 index 0000000..9b6b263 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alheadposeanalysisproxy.h @@ -0,0 +1,275 @@ +// Generated for ALHeadPoseAnalysis version 1.17 + +#ifndef ALHEADPOSEANALYSISPROXY_H_ +#define ALHEADPOSEANALYSISPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALHeadPoseAnalysisProxy; + + namespace detail { + class ALHeadPoseAnalysisProxyPostHandler + { + protected: + ALHeadPoseAnalysisProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALHeadPoseAnalysisProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module computes the head pose of a personfrom the analysis of the image of his/her face + /// \ingroup ALProxies + class ALPROXIES_API ALHeadPoseAnalysisProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALHeadPoseAnalysisProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALHeadPoseAnalysisProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALHeadPoseAnalysisProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALHeadPoseAnalysisProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + ///Exits and unregisters the module. + /// + void exit(); + + /// + ///Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + ///Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + ///Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + ///Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + ///Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + ///Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + ///Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + ///Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + ///Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + ///Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + ///Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + ///Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + ///Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + ///returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + ///Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + ///Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + ///Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + ///Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + ///Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALHeadPoseAnalysisProxyPostHandler post; + + }; + +} +#endif // ALHEADPOSEANALYSISPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alinfraredproxy.h b/naoModule/libnaoqi_files/include/alproxies/alinfraredproxy.h new file mode 100755 index 0000000..f61faec --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alinfraredproxy.h @@ -0,0 +1,287 @@ +// Generated for ALInfrared version 0 + +#ifndef ALINFRAREDPROXY_H_ +#define ALINFRAREDPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALInfraredProxy; + + namespace detail { + class ALInfraredProxyPostHandler + { + protected: + ALInfraredProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALInfraredProxy; + + /// + /// Rewrite the LIRC daemon configuration file (lircd.conf) with everyremotes configuration concatenated, and reload it in LIRC daemons + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int confRemoteRecordSave(); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Init IR reception (connect as a client to the LIRC daemon). + /// + /// Give the keep-pressing threshold after which the repetition of a key is taken into consideration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int initReception(const int& RepeatThreshold); + + /// + /// Send 4 octets by IR. + /// + /// 4 octets to send through IR. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int send32(const std::string& Data_IR); + + /// + /// Send 4 octets by IR. + /// + /// Octet 1 to send through IR. + /// Octet 2 to send through IR. + /// Octet 3 to send through IR. + /// Octet 4 to send through IR. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int send32(const int& Octet1, const int& Octet2, const int& Octet3, const int& Octet4); + + /// + /// Send 1 octet by IR. + /// + /// octet to send through IR. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int send8(const int& Octet); + + /// + /// Send an IP by IR. + /// + /// IP adress to send through IR. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sendIpAddress(const std::string& IP); + + /// + /// Simulate a remote control (Nao as a remote control). + /// + /// IR remote control name. + /// IR remote control key name. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sendRemoteKey(const std::string& Remote, const std::string& Key); + + /// + /// Simulate a remote control (Nao as a remote control). + /// + /// IR remote control name. + /// IR remote control key name. + /// The time in ms when the remote key must be send. 0 deals like sendRemoteKey + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sendRemoteKeyWithTime(const std::string& Remote, const std::string& Key, const int& pTimeMs); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALInfraredProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALInfraredProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALInfraredProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALInfraredProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALInfraredProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Rewrite the LIRC daemon configuration file (lircd.conf) with everyremotes configuration concatenated, and reload it in LIRC daemons + /// + void confRemoteRecordSave(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Init IR reception (connect as a client to the LIRC daemon). + /// + /// Give the keep-pressing threshold after which the repetition of a key is taken into consideration. + void initReception(const int& RepeatThreshold); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Send 4 octets by IR. + /// + /// 4 octets to send through IR. + void send32(const std::string& Data_IR); + + /// + /// Send 4 octets by IR. + /// + /// Octet 1 to send through IR. + /// Octet 2 to send through IR. + /// Octet 3 to send through IR. + /// Octet 4 to send through IR. + void send32(const int& Octet1, const int& Octet2, const int& Octet3, const int& Octet4); + + /// + /// Send 1 octet by IR. + /// + /// octet to send through IR. + void send8(const int& Octet); + + /// + /// Send an IP by IR. + /// + /// IP adress to send through IR. + void sendIpAddress(const std::string& IP); + + /// + /// Simulate a remote control (Nao as a remote control). + /// + /// IR remote control name. + /// IR remote control key name. + void sendRemoteKey(const std::string& Remote, const std::string& Key); + + /// + /// Simulate a remote control (Nao as a remote control). + /// + /// IR remote control name. + /// IR remote control key name. + /// The time in ms when the remote key must be send. 0 deals like sendRemoteKey + void sendRemoteKeyWithTime(const std::string& Remote, const std::string& Key, const int& pTimeMs); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALInfraredProxyPostHandler post; + }; + +} +#endif // ALINFRAREDPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/allandmarkdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/allandmarkdetectionproxy.h new file mode 100755 index 0000000..5221b70 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/allandmarkdetectionproxy.h @@ -0,0 +1,383 @@ +// Generated for ALLandMarkDetection version 0 + +#ifndef ALLANDMARKDETECTIONPROXY_H_ +#define ALLANDMARKDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLandMarkDetectionProxy; + + namespace detail { + class ALLandMarkDetectionProxyPostHandler + { + protected: + ALLandMarkDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLandMarkDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLandMarkDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLandMarkDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLandMarkDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLandMarkDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLandMarkDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALLandMarkDetectionProxyPostHandler post; + }; + +} +#endif // ALLANDMARKDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/allaserproxy.h b/naoModule/libnaoqi_files/include/alproxies/allaserproxy.h new file mode 100755 index 0000000..3d842ea --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/allaserproxy.h @@ -0,0 +1,225 @@ +// Generated for ALLaser version 0 + +#ifndef ALLASERPROXY_H_ +#define ALLASERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLaserProxy; + + namespace detail { + class ALLaserProxyPostHandler + { + protected: + ALLaserProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLaserProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Disable laser light + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int laserOFF(); + + /// + /// Enable laser light and sampling + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int laserON(); + + /// + /// Set detection threshold of the laser + /// + /// int containing the min length that the laser will detect(mm), this value must be upper than 20 mm + /// int containing the max length that the laser will detect(mm), this value must be lower than 5600 mm + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDetectingLength(const int& length_min_l, const int& length_max_l); + + /// + /// Set openning angle of the laser + /// + /// float containing the min value in rad, this value must be upper than -2.35619449 + /// float containing the max value in rad, this value must be lower than 2.092349795 + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setOpeningAngle(const float& angle_min_f, const float& angle_max_f); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLaserProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLaserProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLaserProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLaserProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLaserProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Disable laser light + /// + void laserOFF(); + + /// + /// Enable laser light and sampling + /// + void laserON(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set detection threshold of the laser + /// + /// int containing the min length that the laser will detect(mm), this value must be upper than 20 mm + /// int containing the max length that the laser will detect(mm), this value must be lower than 5600 mm + void setDetectingLength(const int& length_min_l, const int& length_max_l); + + /// + /// Set openning angle of the laser + /// + /// float containing the min value in rad, this value must be upper than -2.35619449 + /// float containing the max value in rad, this value must be lower than 2.092349795 + void setOpeningAngle(const float& angle_min_f, const float& angle_max_f); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALLaserProxyPostHandler post; + }; + +} +#endif // ALLASERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/allauncherproxy.h b/naoModule/libnaoqi_files/include/alproxies/allauncherproxy.h new file mode 100755 index 0000000..0a5ec03 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/allauncherproxy.h @@ -0,0 +1,214 @@ +// Generated for ALLauncher version 0 + +#ifndef ALLAUNCHERPROXY_H_ +#define ALLAUNCHERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLauncherProxy; + + namespace detail { + class ALLauncherProxyPostHandler + { + protected: + ALLauncherProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLauncherProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLauncherProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLauncherProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLauncherProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLauncherProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLauncherProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// get the list of modules loaded on the robot and connected on the robot + /// + /// array of present modules + std::vector getGlobalModuleList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Tests the existence of an active module in the global system (in same executable or in another executable of the distributed system) + /// + /// a part of the name of the module to test existence + /// the returned value is true if this module is present + bool isModulePresent(const std::string& strPartOfModuleName); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// runs an executable and connect it to current broker (executable) + /// + /// the name of the module to launch or the name of the script file to execute + /// true if ok + bool launchExecutable(const std::string& moduleName); + + /// + /// Loads dynamicaly a module + /// + /// the name of the module to launch or the name of the python script to evaluate + /// list of modules loaded + std::vector launchLocal(const std::string& moduleName); + + /// + /// Import a python module + /// + /// the name of the module to launch + /// true if ok + bool launchPythonModule(const std::string& moduleName); + + /// + /// runs a script connected the current broker + /// + /// the name of the script to launch (python) + /// true if ok + bool launchScript(const std::string& moduleName); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALLauncherProxyPostHandler post; + }; + +} +#endif // ALLAUNCHERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alledsproxy.h b/naoModule/libnaoqi_files/include/alproxies/alledsproxy.h new file mode 100755 index 0000000..3a8d1b8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alledsproxy.h @@ -0,0 +1,424 @@ +// Generated for ALLeds version 0 + +#ifndef ALLEDSPROXY_H_ +#define ALLEDSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLedsProxy; + + namespace detail { + class ALLedsProxyPostHandler + { + protected: + ALLedsProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLedsProxy; + + /// + /// Makes a group name for ease of setting multiple LEDs. + /// + /// The name of the group. + /// A vector of the names of the LEDs in the group. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int createGroup(const std::string& groupName, const std::vector& ledNames); + + /// + /// An animation to show a direction with the ears. + /// + /// The angle you want to show in degrees (int). 0 is up, 90 is forwards, 180 is down and 270 is back. + /// The duration in seconds of the animation. + /// If true the last led is left on at the end of the animation. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int earLedsSetAngle(const int& degrees, const float& duration, const bool& leaveOnAtEnd); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Sets the intensity of a LED or Group of LEDs within a given time. + /// + /// The name of the LED or Group. + /// The intensity of the LED or Group (a value between 0 and 1). + /// The duration of the fade in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fade(const std::string& name, const float& intensity, const float& duration); + + /// + /// Chain a list of color for a device, as the motion.doMove command. + /// + /// The name of the LED or Group. + /// List of RGB led value, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// List of time to go to given intensity. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fadeListRGB(const std::string& name, const AL::ALValue& rgbList, const AL::ALValue& timeList); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// the intensity of red channel (0-1). + /// the intensity of green channel (0-1). + /// the intensity of blue channel (0-1). + /// Time used to fade in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fadeRGB(const std::string& name, const float& red, const float& green, const float& blue, const float& duration); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// the name of the color (supported colors: "white", "red", "green", "blue", "yellow", "magenta", "cyan") + /// Time used to fade in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fadeRGB(const std::string& name, const std::string& colorName, const float& duration); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// The RGB value led, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// Time used to fade in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fadeRGB(const std::string& name, const int& rgb, const float& duration); + + /// + /// Switch to a minimum intensity a LED or Group of LEDs. + /// + /// The name of the LED or Group. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int off(const std::string& name); + + /// + /// Switch to a maximum intensity a LED or Group of LEDs. + /// + /// The name of the LED or Group. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int on(const std::string& name); + + /// + /// Launch a random animation in eyes + /// + /// Approximate duration of the animation in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int randomEyes(const float& duration); + + /// + /// Launch a green/yellow/red rasta animation on all body. + /// + /// Approximate duration of the animation in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int rasta(const float& duration); + + /// + /// Resets the state of the leds to default (for ex, eye LEDs are white and fully on by default). + /// + /// The name of the LED or Group (for now, only "AllLeds" are implemented). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int reset(const std::string& name); + + /// + /// Launch a rotation using the leds of the eyes. + /// + /// the RGB value led, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// Approximate time to make one turn. + /// Approximate duration of the animation in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int rotateEyes(const int& rgb, const float& timeForRotation, const float& totalDuration); + + /// + /// Sets the intensity of a LED or Group of LEDs. + /// + /// The name of the LED or Group. + /// The intensity of the LED or Group (a value between 0 and 1). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setIntensity(const std::string& name, const float& intensity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLedsProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLedsProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLedsProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLedsProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLedsProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Makes a group name for ease of setting multiple LEDs. + /// + /// The name of the group. + /// A vector of the names of the LEDs in the group. + void createGroup(const std::string& groupName, const std::vector& ledNames); + + /// + /// An animation to show a direction with the ears. + /// + /// The angle you want to show in degrees (int). 0 is up, 90 is forwards, 180 is down and 270 is back. + /// The duration in seconds of the animation. + /// If true the last led is left on at the end of the animation. + void earLedsSetAngle(const int& degrees, const float& duration, const bool& leaveOnAtEnd); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Sets the intensity of a LED or Group of LEDs within a given time. + /// + /// The name of the LED or Group. + /// The intensity of the LED or Group (a value between 0 and 1). + /// The duration of the fade in seconds + void fade(const std::string& name, const float& intensity, const float& duration); + + /// + /// Chain a list of color for a device, as the motion.doMove command. + /// + /// The name of the LED or Group. + /// List of RGB led value, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// List of time to go to given intensity. + void fadeListRGB(const std::string& name, const AL::ALValue& rgbList, const AL::ALValue& timeList); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// the intensity of red channel (0-1). + /// the intensity of green channel (0-1). + /// the intensity of blue channel (0-1). + /// Time used to fade in seconds. + void fadeRGB(const std::string& name, const float& red, const float& green, const float& blue, const float& duration); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// the name of the color (supported colors: "white", "red", "green", "blue", "yellow", "magenta", "cyan") + /// Time used to fade in seconds. + void fadeRGB(const std::string& name, const std::string& colorName, const float& duration); + + /// + /// Sets the color of an RGB led. + /// + /// The name of the LED or Group. + /// The RGB value led, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// Time used to fade in seconds. + void fadeRGB(const std::string& name, const int& rgb, const float& duration); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the intensity of a LED or device + /// + /// The name of the LED or Group. + /// The intensity of the LED or Group. + AL::ALValue getIntensity(const std::string& name); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Lists the devices in the group. + /// + /// The name of the Group. + /// A vector of string device names. + std::vector listGroup(const std::string& groupName); + + /// + /// Lists available group names. + /// + /// A vector of group names. + std::vector listGroups(); + + /// + /// Lists the devices aliased by a short LED name. + /// + /// The name of the LED to list + /// A vector of device names. + std::vector listLED(const std::string& name); + + /// + /// Lists the short LED names. + /// + /// A vector of LED names. + std::vector listLEDs(); + + /// + /// Switch to a minimum intensity a LED or Group of LEDs. + /// + /// The name of the LED or Group. + void off(const std::string& name); + + /// + /// Switch to a maximum intensity a LED or Group of LEDs. + /// + /// The name of the LED or Group. + void on(const std::string& name); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Launch a random animation in eyes + /// + /// Approximate duration of the animation in seconds. + void randomEyes(const float& duration); + + /// + /// Launch a green/yellow/red rasta animation on all body. + /// + /// Approximate duration of the animation in seconds. + void rasta(const float& duration); + + /// + /// Resets the state of the leds to default (for ex, eye LEDs are white and fully on by default). + /// + /// The name of the LED or Group (for now, only "AllLeds" are implemented). + void reset(const std::string& name); + + /// + /// Launch a rotation using the leds of the eyes. + /// + /// the RGB value led, RGB as seen in hexa-decimal: 0x00RRGGBB. + /// Approximate time to make one turn. + /// Approximate duration of the animation in seconds. + void rotateEyes(const int& rgb, const float& timeForRotation, const float& totalDuration); + + /// + /// Sets the intensity of a LED or Group of LEDs. + /// + /// The name of the LED or Group. + /// The intensity of the LED or Group (a value between 0 and 1). + void setIntensity(const std::string& name, const float& intensity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALLedsProxyPostHandler post; + }; + +} +#endif // ALLEDSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/allocalizationproxy.h b/naoModule/libnaoqi_files/include/alproxies/allocalizationproxy.h new file mode 100755 index 0000000..ae9743b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/allocalizationproxy.h @@ -0,0 +1,282 @@ +// Generated for ALLocalization version 0 + +#ifndef ALLOCALIZATIONPROXY_H_ +#define ALLOCALIZATIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLocalizationProxy; + + namespace detail { + class ALLocalizationProxyPostHandler + { + protected: + ALLocalizationProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLocalizationProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop all robot movements. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAll(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLocalizationProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLocalizationProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLocalizationProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLocalizationProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLocalizationProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Delete all panoramas in a directory. + /// + /// Name of the directory + int clear(const std::string& pDirectory); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get some information about the current panorama. + /// + AL::ALValue getCurrentPanoramaDescriptor(); + + /// + /// Get a frame buffer. + /// + /// arg + /// arg + AL::ALValue getFrame(const int& arg1, const std::string& arg2); + + /// + /// + /// + /// arg + std::string getMessageFromErrorCode(const int& arg1); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the robot orientation. + /// + AL::ALValue getRobotOrientation(); + + /// + /// Get the robot orientation. + /// + /// arg + AL::ALValue getRobotOrientation(const bool& arg1); + + /// + /// Get the robot position in world navigation. + /// + std::vector getRobotPosition(); + + /// + /// Get the robot position in world navigation. + /// + /// arg + std::vector getRobotPosition(const bool& arg1); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Go to the robot home. + /// + int goToHome(); + + /// + /// Go to a given position. + /// + /// arg + int goToPosition(const std::vector& arg1); + + /// + /// + /// + bool isDataAvailable(); + + /// + /// Is the robot in its home? + /// + bool isInCurrentHome(); + + /// + /// + /// + /// arg + /// arg + /// arg + /// arg + AL::ALValue isInGivenZone(const float& arg1, const float& arg2, const float& arg3, const float& arg4); + + /// + /// + /// + bool isRelocalizationRequired(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Learn the robot home. + /// + int learnHome(); + + /// + /// Loads panoramas from a directory in the default one. + /// + /// Name of the directory + int load(const std::string& pDirectory); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Save the temporary panoramas in a directory from the default one. + /// + /// Name of the directory + int save(const std::string& pDirectory); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop all robot movements. + /// + void stopAll(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALLocalizationProxyPostHandler post; + }; + +} +#endif // ALLOCALIZATIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alloggerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alloggerproxy.h new file mode 100755 index 0000000..ee3d224 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alloggerproxy.h @@ -0,0 +1,313 @@ +// Generated for ALLogger version 0 + +#ifndef ALLOGGERPROXY_H_ +#define ALLOGGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALLoggerProxy; + + namespace detail { + class ALLoggerProxyPostHandler + { + protected: + ALLoggerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALLoggerProxy; + + /// + /// DEPRECATED. Use qiLogDebug instead. + /// Log a debug message. + /// + /// Name of the module. + /// Log Message. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int debug(const std::string& moduleName, const std::string& message); + + /// + /// DEPRECATED. Use qiLogError instead. + /// Log an error. + /// + /// Name of the module. + /// Log Message. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int error(const std::string& moduleName, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// DEPRECATED. Use qiLogFatal instead. + /// Log a fatal error. + /// + /// Name of the module. + /// Log Message. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int fatal(const std::string& moduleName, const std::string& message); + + /// + /// DEPRECATED. Use qiLogInfo instead. + /// Log a info message. + /// + /// Name of the module. + /// Log Message. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int info(const std::string& moduleName, const std::string& message); + + /// + /// Removed: not implemented anymore. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int logInFile(const std::string& arg1); + + /// + /// Removed: not implemented anymore. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int logInForwarder(const std::string& arg1); + + /// + /// Removed: not implemented anymore. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeHandler(const std::string& arg1); + + /// + /// Removed: not implemented anymore. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVerbosity(const std::string& arg1); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// DEPRECATED: use qiLogWarning instead. Log a warning. + /// + /// Name of the module. + /// Log Message. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int warn(const std::string& moduleName, const std::string& message); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALLoggerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALLoggerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALLoggerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALLoggerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALLoggerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// DEPRECATED. Use qiLogDebug instead. + /// Log a debug message. + /// + /// Name of the module. + /// Log Message. + void debug(const std::string& moduleName, const std::string& message); + + /// + /// DEPRECATED. Use qiLogError instead. + /// Log an error. + /// + /// Name of the module. + /// Log Message. + void error(const std::string& moduleName, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// DEPRECATED. Use qiLogFatal instead. + /// Log a fatal error. + /// + /// Name of the module. + /// Log Message. + void fatal(const std::string& moduleName, const std::string& message); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// DEPRECATED. Use qiLogInfo instead. + /// Log a info message. + /// + /// Name of the module. + /// Log Message. + void info(const std::string& moduleName, const std::string& message); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Removed: not implemented anymore. + /// + /// arg + void logInFile(const std::string& arg1); + + /// + /// Removed: not implemented anymore. + /// + /// arg + void logInForwarder(const std::string& arg1); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Removed: not implemented anymore. + /// + /// arg + void removeHandler(const std::string& arg1); + + /// + /// Removed: not implemented anymore. + /// + /// arg + void setVerbosity(const std::string& arg1); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Removed: not implemented anymore. + /// + int verbosity(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// DEPRECATED: use qiLogWarning instead. Log a warning. + /// + /// Name of the module. + /// Log Message. + void warn(const std::string& moduleName, const std::string& message); + + + detail::ALLoggerProxyPostHandler post; + }; + +} +#endif // ALLOGGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almecaloggerproxy.h b/naoModule/libnaoqi_files/include/alproxies/almecaloggerproxy.h new file mode 100755 index 0000000..e34e681 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almecaloggerproxy.h @@ -0,0 +1,201 @@ +// Generated for ALMecaLogger version 0 + +#ifndef ALMECALOGGERPROXY_H_ +#define ALMECALOGGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMecaLoggerProxy; + + namespace detail { + class ALMecaLoggerProxyPostHandler + { + protected: + ALMecaLoggerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMecaLoggerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Increment the number of falls + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int toDoWhenRobotHasFallen(const std::string& arg1, const AL::ALValue& arg2, const AL::ALValue& arg3); + + /// + /// Write results on disk + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int writeFiles(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMecaLoggerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMecaLoggerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMecaLoggerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMecaLoggerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMecaLoggerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Increment the number of falls + /// + /// arg + /// arg + /// arg + void toDoWhenRobotHasFallen(const std::string& arg1, const AL::ALValue& arg2, const AL::ALValue& arg3); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Write results on disk + /// + void writeFiles(); + + + detail::ALMecaLoggerProxyPostHandler post; + }; + +} +#endif // ALMECALOGGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almemoryproxy.h b/naoModule/libnaoqi_files/include/alproxies/almemoryproxy.h new file mode 100755 index 0000000..1d2d515 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almemoryproxy.h @@ -0,0 +1,599 @@ +// Generated for ALMemory version 0 + +#ifndef ALMEMORYPROXY_H_ +#define ALMEMORYPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMemoryProxy; + + namespace detail { + class ALMemoryProxyPostHandler + { + protected: + ALMemoryProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMemoryProxy; + + /// + /// Add a mapping between signal and event + /// + /// Name of the service + /// Name of the signal + /// Name of the event + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addMapping(const std::string& service, const std::string& signal, const std::string& event); + + /// + /// Add a mapping between signal and event + /// + /// Name of the service + /// A map of signal corresponding to event + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addMapping(const std::string& service, const std::map& signalEvent); + + /// + /// Declares an event to allow future subscriptions to the event + /// + /// The name of the event + /// brokerTaskID : The ID of the task assigned to it by the broker. + int declareEvent(const std::string& eventName); + + /// + /// Declares an event to allow future subscriptions to the event + /// + /// The name of the event + /// The name of the extractor capable of creating the event + /// brokerTaskID : The ID of the task assigned to it by the broker. + int declareEvent(const std::string& eventName, const std::string& extractorName); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Inserts a key-value pair into memory, where value is a string + /// + /// Name of the value to be inserted. + /// The string to be inserted + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertData(const std::string& key, const std::string& value); + + /// + /// Inserts a key-value pair into memory, where value is an int + /// + /// Name of the value to be inserted. + /// The int to be inserted + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertData(const std::string& key, const int& value); + + /// + /// Inserts a key-value pair into memory, where value is a float + /// + /// Name of the value to be inserted. + /// The float to be inserted + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertData(const std::string& key, const float& value); + + /// + /// Inserts a key-value pair into memory, where value is an ALValue + /// + /// Name of the value to be inserted. + /// The ALValue to be inserted. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertData(const std::string& key, const AL::ALValue& data); + + /// + /// Inserts a list of key-value pairs into memory. + /// + /// An ALValue list of the form [[Key, Value],...]. Each item will be inserted. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int insertListData(const AL::ALValue& list); + + /// + /// Publishes the given data to all subscribers. + /// + /// Name of the event to raise. + /// The data associated with the event. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int raiseEvent(const std::string& name, const AL::ALValue& value); + + /// + /// Publishes the given data to all subscribers. + /// + /// Name of the event to raise. + /// The data associated with the event. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int raiseMicroEvent(const std::string& name, const AL::ALValue& value); + + /// + /// Removes a key-value pair from memory + /// + /// Name of the data to be removed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeData(const std::string& key); + + /// + /// Removes a event from memory and unsubscribes any exiting subscribers. + /// + /// Name of the event to remove. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeEvent(const std::string& name); + + /// + /// Removes a micro event from memory and unsubscribes any exiting subscribers. + /// + /// Name of the event to remove. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeMicroEvent(const std::string& name); + + /// + /// Describe a key + /// + /// Name of the key. + /// The description of the event (text format). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDescription(const std::string& name, const std::string& description); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to an event and automaticaly launches the module that declared itself as the generator of the event if required. + /// + /// The name of the event to subscribe to + /// Name of the module to call with notifications + /// Name of the module's method to call when a data is changed + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribeToEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMethod); + + /// + /// DEPRECATED Subscribes to event and automaticaly launches the module capable of generating the event if it is not already running. Please use the version without the callbackMessage parameter. + /// + /// The name of the event to subscribe to + /// Name of the module to call with notifications + /// DEPRECATED Message included in the notification. + /// Name of the module's method to call when a data is changed + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribeToEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMessage, const std::string& callbacMethod); + + /// + /// Subscribes to a microEvent. Subscribed modules are notified on theircallback method whenever the data is updated, even if the new value is the same as the old value. + /// + /// Name of the data. + /// Name of the module to call with notifications + /// Message included in the notification. This can be used to disambiguate multiple subscriptions. + /// Name of the module's method to call when a data is changed + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribeToMicroEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMessage, const std::string& callbackMethod); + + /// + /// Informs ALMemory that a module doesn't exist anymore. + /// + /// Name of the departing module. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unregisterModuleReference(const std::string& moduleName); + + /// + /// Unsubscribes a module from the given event. No further notifications will be received. + /// + /// The name of the event + /// The name of the module that was given when subscribing. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribeToEvent(const std::string& name, const std::string& callbackModule); + + /// + /// Unsubscribes from the given event. No further notifications will be received. + /// + /// Name of the event. + /// The name of the module that was given when subscribing. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribeToMicroEvent(const std::string& name, const std::string& callbackModule); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMemoryProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMemoryProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMemoryProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMemoryProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMemoryProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Add a mapping between signal and event + /// + /// Name of the service + /// Name of the signal + /// Name of the event + void addMapping(const std::string& service, const std::string& signal, const std::string& event); + + /// + /// Add a mapping between signal and event + /// + /// Name of the service + /// A map of signal corresponding to event + void addMapping(const std::string& service, const std::map& signalEvent); + + /// + /// Declares an event to allow future subscriptions to the event + /// + /// The name of the event + void declareEvent(const std::string& eventName); + + /// + /// Declares an event to allow future subscriptions to the event + /// + /// The name of the event + /// The name of the extractor capable of creating the event + void declareEvent(const std::string& eventName, const std::string& extractorName); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the value of a key-value pair stored in memory + /// + /// Name of the value. + /// The data as an ALValue. This can often be cast transparently into the original type. + AL::ALValue getData(const std::string& key); + + /// + /// DEPRECATED - Gets the value of a key-value pair stored in memory. Please use the version of this method with no second parameter. + /// + /// Name of the value. + /// DEPRECATED - This parameter has no effect, but is left for compatibility reason. + /// The data as an ALValue + AL::ALValue getData(const std::string& key, const int& deprecatedParameter); + + /// + /// Gets a list of all key names that contain a given string + /// + /// A string used as the search term + /// A list of all the data key names that contain the given string. + std::vector getDataList(const std::string& filter); + + /// + /// Gets the key names for all the key-value pairs in memory + /// + /// A list containing the keys in memory + std::vector getDataListName(); + + /// + /// DEPRECATED - Blocks the caller until the value of a key changes + /// + /// Name of the data. + /// DEPRECATED - this parameter has no effect + /// an array containing all the retrieved data + AL::ALValue getDataOnChange(const std::string& key, const int& deprecatedParameter); + + /// + /// Gets a pointer to 32 a bit data item. Beware, the pointer will only be valid during the lifetime of the ALMemory object. Use with care, at initialization, not every loop. + /// + /// Name of the data. + /// A pointer converted to int + void* getDataPtr(const std::string& key); + + /// + /// Descriptions of all given keys + /// + /// List of keys. (empty to get all descriptions) + /// an array of tuple (name, type, description) describing all keys. + AL::ALValue getDescriptionList(const std::vector& keylist); + + /// + /// Get data value and timestamp + /// + /// Name of the variable + /// A list of all the data key names that contain the given string. + AL::ALValue getEventHistory(const std::string& key); + + /// + /// Gets a list containing the names of all the declared events + /// + /// A list containing the names of all events + std::vector getEventList(); + + /// + /// Gets the list of all events generated by a given extractor + /// + /// The name of the extractor + /// A list containing the names of the events associated with the given extractor + std::vector getExtractorEvent(const std::string& extractorName); + + /// + /// Gets the values associated with the given list of keys. This is more efficient than calling getData many times, especially over the network. + /// + /// An array containing the key names. + /// An array containing all the values corresponding to the given keys. + AL::ALValue getListData(const AL::ALValue& keyList); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Gets a list containing the names of all the declared micro events + /// + /// A list containing the names of all the microEvents + std::vector getMicroEventList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets a list containing the names of subscribers to an event. + /// + /// Name of the event or micro-event + /// List of subscriber names + std::vector getSubscribers(const std::string& name); + + /// + /// Get data value and timestamp + /// + /// Name of the variable + /// A list of all the data key names that contain the given string. + AL::ALValue getTimestamp(const std::string& key); + + /// + /// Gets the storage class of the stored data. This is not the underlying POD type. + /// + /// Name of the variable + /// String type: Data, Event, MicroEvent + std::string getType(const std::string& key); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Inserts a key-value pair into memory, where value is a string + /// + /// Name of the value to be inserted. + /// The string to be inserted + void insertData(const std::string& key, const std::string& value); + + /// + /// Inserts a key-value pair into memory, where value is an int + /// + /// Name of the value to be inserted. + /// The int to be inserted + void insertData(const std::string& key, const int& value); + + /// + /// Inserts a key-value pair into memory, where value is a float + /// + /// Name of the value to be inserted. + /// The float to be inserted + void insertData(const std::string& key, const float& value); + + /// + /// Inserts a key-value pair into memory, where value is an ALValue + /// + /// Name of the value to be inserted. + /// The ALValue to be inserted. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + void insertData(const std::string& key, const AL::ALValue& data); + + /// + /// Inserts a list of key-value pairs into memory. + /// + /// An ALValue list of the form [[Key, Value],...]. Each item will be inserted. + void insertListData(const AL::ALValue& list); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Publishes the given data to all subscribers. + /// + /// Name of the event to raise. + /// The data associated with the event. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + void raiseEvent(const std::string& name, const AL::ALValue& value); + + /// + /// Publishes the given data to all subscribers. + /// + /// Name of the event to raise. + /// The data associated with the event. This could contain a basic type, or a more complex array. See the ALValue documentation for more information. + void raiseMicroEvent(const std::string& name, const AL::ALValue& value); + + /// + /// Removes a key-value pair from memory + /// + /// Name of the data to be removed. + void removeData(const std::string& key); + + /// + /// Removes a event from memory and unsubscribes any exiting subscribers. + /// + /// Name of the event to remove. + void removeEvent(const std::string& name); + + /// + /// Removes a micro event from memory and unsubscribes any exiting subscribers. + /// + /// Name of the event to remove. + void removeMicroEvent(const std::string& name); + + /// + /// Describe a key + /// + /// Name of the key. + /// The description of the event (text format). + void setDescription(const std::string& name, const std::string& description); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to an event and automaticaly launches the module that declared itself as the generator of the event if required. + /// + /// The name of the event to subscribe to + /// Name of the module to call with notifications + /// Name of the module's method to call when a data is changed + void subscribeToEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMethod); + + /// + /// DEPRECATED Subscribes to event and automaticaly launches the module capable of generating the event if it is not already running. Please use the version without the callbackMessage parameter. + /// + /// The name of the event to subscribe to + /// Name of the module to call with notifications + /// DEPRECATED Message included in the notification. + /// Name of the module's method to call when a data is changed + void subscribeToEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMessage, const std::string& callbacMethod); + + /// + /// Subscribes to a microEvent. Subscribed modules are notified on theircallback method whenever the data is updated, even if the new value is the same as the old value. + /// + /// Name of the data. + /// Name of the module to call with notifications + /// Message included in the notification. This can be used to disambiguate multiple subscriptions. + /// Name of the module's method to call when a data is changed + void subscribeToMicroEvent(const std::string& name, const std::string& callbackModule, const std::string& callbackMessage, const std::string& callbackMethod); + + /// + /// Get an object wrapping a signal bound to the given ALMemory event. Throw if the event does not exist or if it is invalid. + /// + /// Name of the ALMemory event + /// An AnyObject with a signal named "signal" + qi::AnyObject subscriber(const std::string& eventName); + + /// + /// Informs ALMemory that a module doesn't exist anymore. + /// + /// Name of the departing module. + void unregisterModuleReference(const std::string& moduleName); + + /// + /// Unsubscribes a module from the given event. No further notifications will be received. + /// + /// The name of the event + /// The name of the module that was given when subscribing. + void unsubscribeToEvent(const std::string& name, const std::string& callbackModule); + + /// + /// Unsubscribes from the given event. No further notifications will be received. + /// + /// Name of the event. + /// The name of the module that was given when subscribing. + void unsubscribeToMicroEvent(const std::string& name, const std::string& callbackModule); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALMemoryProxyPostHandler post; + }; + +} +#endif // ALMEMORYPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almemorywatcherproxy.h b/naoModule/libnaoqi_files/include/alproxies/almemorywatcherproxy.h new file mode 100755 index 0000000..ba63365 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almemorywatcherproxy.h @@ -0,0 +1,332 @@ +// Generated for ALMemoryWatcher version 0 + +#ifndef ALMEMORYWATCHERPROXY_H_ +#define ALMEMORYWATCHERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMemoryWatcherProxy; + + namespace detail { + class ALMemoryWatcherProxyPostHandler + { + protected: + ALMemoryWatcherProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMemoryWatcherProxy; + + /// + /// add an ALMemory key to the list of keys to listen to + /// + /// the complete name of the ALMemory key + /// interval of time the system should wait before retrieving this key value again + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addListener(const std::string& name, const int& interval); + + /// + /// add an ALMemory key to the list of keys to listen to + /// + /// the complete name of the ALMemory key + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addListener(const std::string& name); + + /// + /// add a list of ALMemory keys to the list of keys to listen + /// + /// the vector of complete names of ALMemory keys + /// interval of time the system should wait before retrieving this key value again + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addListeners(const std::vector& listNames, const int& interval); + + /// + /// add a list of ALMemory keys to the list of keys to listen + /// + /// the vector of complete names of ALMemory keys + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addListeners(const std::vector& listNames); + + /// + /// remove all buffered data. The list of keys listened to keeps unchanged. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int clearBuffer(); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// remove all keys listened to + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeAllListeners(); + + /// + /// remove a key from the list to listen to + /// + /// the name of the key to stop to listen + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeListener(const std::string& name); + + /// + /// remove a list of key from the list to listen + /// + /// the vector of names of key to stop to listen + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeListeners(const std::vector& listNames); + + /// + /// edit "period" value between two buffering. + /// + /// the new period (in ms) to apply. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPeriodMs(const int& period); + + /// + /// start listening to selected keys from ALMemory + /// + /// the time between two listen of ALMemory keys, in milliseconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startWatching(const int& period); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// stop listening selected keys from ALMemory. List of listened keys and associated buffers keep unchanged. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopWatching(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMemoryWatcherProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMemoryWatcherProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMemoryWatcherProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMemoryWatcherProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMemoryWatcherProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// add an ALMemory key to the list of keys to listen to + /// + /// the complete name of the ALMemory key + /// interval of time the system should wait before retrieving this key value again + void addListener(const std::string& name, const int& interval); + + /// + /// add an ALMemory key to the list of keys to listen to + /// + /// the complete name of the ALMemory key + void addListener(const std::string& name); + + /// + /// add a list of ALMemory keys to the list of keys to listen + /// + /// the vector of complete names of ALMemory keys + /// interval of time the system should wait before retrieving this key value again + void addListeners(const std::vector& listNames, const int& interval); + + /// + /// add a list of ALMemory keys to the list of keys to listen + /// + /// the vector of complete names of ALMemory keys + void addListeners(const std::vector& listNames); + + /// + /// remove all buffered data. The list of keys listened to keeps unchanged. + /// + void clearBuffer(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// return an ALValue containing all buffered data since the last call of getData(). + /// + /// The complete array of all buffered data + AL::ALValue getData(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// tells whether keys are watched and data being gathered. + /// + /// true if keys are being watched. + bool isWatching(); + + /// + /// get the list of listened ALMemory keys + /// + /// a list of ALMemory keys + std::vector listeners(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// remove all keys listened to + /// + void removeAllListeners(); + + /// + /// remove a key from the list to listen to + /// + /// the name of the key to stop to listen + void removeListener(const std::string& name); + + /// + /// remove a list of key from the list to listen + /// + /// the vector of names of key to stop to listen + void removeListeners(const std::vector& listNames); + + /// + /// edit "period" value between two buffering. + /// + /// the new period (in ms) to apply. + void setPeriodMs(const int& period); + + /// + /// start listening to selected keys from ALMemory + /// + /// the time between two listen of ALMemory keys, in milliseconds. + void startWatching(const int& period); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// stop listening selected keys from ALMemory. List of listened keys and associated buffers keep unchanged. + /// + void stopWatching(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALMemoryWatcherProxyPostHandler post; + }; + +} +#endif // ALMEMORYWATCHERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almodularityproxy.h b/naoModule/libnaoqi_files/include/alproxies/almodularityproxy.h new file mode 100755 index 0000000..4638f01 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almodularityproxy.h @@ -0,0 +1,401 @@ +// Generated for ALModularity version 0 + +#ifndef ALMODULARITYPROXY_H_ +#define ALMODULARITYPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALModularityProxy; + + namespace detail { + class ALModularityProxyPostHandler + { + protected: + ALModularityProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALModularityProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALModularityProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALModularityProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALModularityProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALModularityProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALModularityProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// The name of the filter. + bool deleteFilter(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool deleteProcess(const std::string& name); + + /// + /// + /// + /// The name of the source. + bool deleteSource(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool disableProcess(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool enableProcess(const std::string& name); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// + /// + /// The name of the sink from where data must be extracted. + AL::ALValue getData(const std::string& sink); + + /// + /// + /// + /// The name of the filter to dump. + /// Maximum depth (-1 for unlimited depth) + AL::ALValue getDotGraph(const std::string& filter, const int& level); + + /// + /// + /// + /// The name of the filter. + std::string getFilterDescription(const std::string& name); + + /// + /// + /// + /// The name of the filter. + AL::ALValue getFilterInputs(const std::string& name); + + /// + /// + /// + /// The name of the filter. + AL::ALValue getFilterOutputs(const std::string& name); + + /// + /// + /// + AL::ALValue getFilters(); + + /// + /// + /// + /// The name of the sink from where data must be extracted. + void* getImageLocal(const std::string& sink); + + /// + /// + /// + /// The name of the sink from where data must be extracted. + AL::ALValue getImageRemote(const std::string& sink); + + /// + /// + /// + std::string getInstrumentationResult(); + + /// + /// + /// + /// The name of the sink from where data must be extracted. + AL::ALValue getLastData(const std::string& sink); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// + /// + void* getModularity(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// + /// + /// The name of the process. + std::vector getProcessAggregatedSinks(const std::string& name); + + /// + /// + /// + /// The name of the process. + std::string getProcessDescription(const std::string& name); + + /// + /// + /// + /// The name of the process. + float getProcessFrequency(const std::string& name); + + /// + /// + /// + /// The name of the process. + int getProcessPriority(const std::string& name); + + /// + /// + /// + /// The name of the process. + std::vector getProcessSinks(const std::string& name); + + /// + /// + /// + /// The name of the process. + std::vector getProcessSources(const std::string& name); + + /// + /// + /// + std::vector getProcesses(); + + /// + /// + /// + float getRobotHeightOffset(); + + /// + /// + /// + std::vector getScheduledJobs(); + + /// + /// + /// + /// The name of the source. + float getSourceFrequency(const std::string& name); + + /// + /// + /// + std::vector getSources(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool isProcessEnable(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool isProcessZombie(const std::string& name); + + /// + /// + /// + /// The name of the process. + bool isProcesses(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// The name of the source. + bool isSourceBinded(const std::string& name); + + /// + /// + /// + /// The code that will be used by Modularity to generate a part of the graph. + bool loadProgram(const std::string& program); + + /// + /// + /// + /// arg + bool loadProgramFromFile(const std::string& arg1); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// + /// + /// The name of the process to reset. + bool resetProcess(const std::string& name); + + /// + /// + /// + /// The name of the process. + /// The new frequency of the process. + bool setProcessFrequency(const std::string& name, const float& priority); + + /// + /// + /// + /// The name of the process. + /// The new priority of the process. + bool setProcessPriority(const std::string& name, const qi::uint32_t& priority); + + /// + /// + /// + /// Height Offset of the robot from the ground. + bool setRobotHeightOffset(const float& heightOffset); + + /// + /// + /// + bool startScheduler(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// + /// + bool stopScheduler(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALModularityProxyPostHandler post; + }; + +} +#endif // ALMODULARITYPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almotionproxy.h b/naoModule/libnaoqi_files/include/alproxies/almotionproxy.h new file mode 100755 index 0000000..66a34dd --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almotionproxy.h @@ -0,0 +1,1708 @@ +// Generated for ALMotion version 0 + +#ifndef ALMOTIONPROXY_H_ +#define ALMOTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMotionProxy; + + namespace detail { + class ALMotionProxyPostHandler + { + protected: + ALMotionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMotionProxy; + + /// + /// Interpolates one or multiple joints to a target angle or along timed trajectories. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An angle, list of angles or list of list of angles in radians + /// A time, list of times or list of list of times in seconds + /// If true, the movement is described in absolute angles, else the angles are relative to the current angle. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int angleInterpolation(const AL::ALValue& names, const AL::ALValue& angleLists, const AL::ALValue& timeLists, const bool& isAbsolute); + + /// + /// Interpolates a sequence of timed angles for several motors using bezier control points. This is a blocking call. + /// + /// A vector of joint names + /// An ragged ALValue matrix of floats. Each line corresponding to a motor, and column element to a control point. + /// An ALValue array of arrays each containing [float angle, Handle1, Handle2], where Handle is [int InterpolationType, float dAngle, float dTime] descibing the handle offsets relative to the angle and time of the point. The first bezier param describes the handle that controls the curve preceeding the point, the second describes the curve following the point. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int angleInterpolationBezier(const std::vector& jointNames, const AL::ALValue& times, const AL::ALValue& controlPoints); + + /// + /// Interpolates one or multiple joints to a target angle, using a fraction of max speed. Only one target angle is allowed for each joint. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An angle, or list of angles in radians + /// A fraction. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int angleInterpolationWithSpeed(const AL::ALValue& names, const AL::ALValue& targetAngles, const float& maxSpeedFraction); + + /// + /// Changes Angles. This is a non-blocking call. + /// + /// The name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more changes in radians + /// The fraction of maximum speed to use + /// brokerTaskID : The ID of the task assigned to it by the broker. + int changeAngles(const AL::ALValue& names, const AL::ALValue& changes, const float& fractionMaxSpeed); + + /// + /// DEPRECATED. Use setPositions function instead. + /// + /// Name of the effector. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// 6D position change array (xd, yd, zd, wxd, wyd, wzd) in meters and radians + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int changePosition(const std::string& effectorName, const int& space, const std::vector& positionChange, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// DEPRECATED. Use setTransforms function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int changeTransform(const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// NAO stiffens the motors of desired hand. Then, he closes the hand, then cuts motor current to conserve energy. This is a blocking call. + /// + /// The name of the hand. Could be: "RHand" or "LHand" + /// brokerTaskID : The ID of the task assigned to it by the broker. + int closeHand(const std::string& handName); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Kills all tasks. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int killAll(); + + /// + /// Emergency Stop on Move task: This method will end the move task brutally, without attempting to return to a balanced state. The robot could easily fall. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int killMove(); + + /// + /// Kills all tasks that use any of the resources given. Only motion API's' blocking call takes resources and can be killed. Use getBodyNames("Body") to have the list of the available joint for your robot. + /// + /// A vector of resource joint names + /// brokerTaskID : The ID of the task assigned to it by the broker. + int killTasksUsingResources(const std::vector& resourceNames); + + /// + /// DEPRECATED. Use killMove function instead. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int killWalk(); + + /// + /// Makes the robot move at the given velocity. This is a non-blocking call. + /// + /// The velocity along x axis [m.s-1]. + /// The velocity along y axis [m.s-1]. + /// The velocity around z axis [rd.s-1]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int move(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given velocity. This is a non-blocking call. + /// + /// The velocity along x axis [m.s-1]. + /// The velocity along y axis [m.s-1]. + /// The velocity around z axis [rd.s-1]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int move(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Initialize the move process. Check the robot pose and take a right posture. This is blocking called. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveInit(); + + /// + /// Makes the robot move at the given position. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given position in fixed time. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// The time to reach the target position [s]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta, const float& time); + + /// + /// Makes the robot move at the given position. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given position in fixed time. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// The time to reach the target position [s]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta, const float& time, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move to the given relative positions. This is a blocking call. + /// + /// An ALValue with the control points in FRAME_ROBOT. + /// Each control point is relative to the previous one. [[x1, y1, theta1], ..., [xN, yN, thetaN] + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const AL::ALValue& controlPoint); + + /// + /// Makes the robot move to the given relative positions. This is a blocking call. + /// + /// An ALValue with all the control points in FRAME_ROBOT. + /// Each control point is relative to the previous one. [[x1, y1, theta1], ..., [xN, yN, thetaN] + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const AL::ALValue& controlPoint, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given normalized velocity. This is a non-blocking call. + /// + /// The normalized velocity along x axis (between -1 and 1). + /// The normalized velocity along y axis (between -1 and 1). + /// The normalized velocity around z axis (between -1 and 1). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveToward(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given normalized velocity. This is a non-blocking call. + /// + /// The normalized velocity along x axis (between -1 and 1). + /// The normalized velocity along y axis (between -1 and 1). + /// The normalized velocity around z axis (between -1 and 1). + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveToward(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// NAO stiffens the motors of desired hand. Then, he opens the hand, then cuts motor current to conserve energy. This is a blocking call. + /// + /// The name of the hand. Could be: "RHand or "LHand" + /// brokerTaskID : The ID of the task assigned to it by the broker. + int openHand(const std::string& handName); + + /// + /// DEPRECATED. Use positionInterpolations function instead. + /// + /// Name of the chain. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int positionInterpolation(const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& durations, const bool& isAbsolute); + + /// + /// DEPRECATED. Use the other positionInterpolations function instead. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int positionInterpolations(const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute); + + /// + /// Moves end-effectors to the given positions and orientations over time. This is a blocking call. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// brokerTaskID : The ID of the task assigned to it by the broker. + int positionInterpolations(const AL::ALValue& effectorNames, const AL::ALValue& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes); + + /// + /// The robot will rest: go to a relax and safe position and set Motor OFF + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int rest(); + + /// + /// The robot will rest: go to a relax and safe position on the chain and set Motor OFF + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int rest(const std::string& arg1); + + /// + /// Sets angles. This is a non-blocking call. + /// + /// The name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more angles in radians + /// The fraction of maximum speed to use + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAngles(const AL::ALValue& names, const AL::ALValue& angles, const float& fractionMaxSpeed); + + /// + /// This function configures the breathing animation. + /// + /// Breath configuration. + /// An ALValue of the form [["Bpm", pBpm], ["Amplitude", pAmplitude]]. + /// pBpm is a float between 10 and 50 setting the breathing frequency in beats per minute. + /// pAmplitude is a float between 0 and 1 setting the amplitude of the breathing animation. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBreathConfig(const AL::ALValue& pConfig); + + /// + /// This function starts or stops breathing animation on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// Head breathing animation will work only if Leg animation is active. + /// + /// Chain name. + /// Enables / disables the chain. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBreathEnabled(const std::string& pChain, const bool& pIsEnabled); + + /// + /// Enable or disable the diagnosis effect into ALMotion + /// + /// Enable or disable the diagnosis effect. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDiagnosisEffectEnabled(const bool& pEnable); + + /// + /// Enable / Disable notifications. + /// + /// If True enable notifications. If False disable notifications. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setEnableNotifications(const bool& enable); + + /// + /// Enable Anticollision protection of the arms and base move of the robot with external environment. + /// + /// The name {"All", "Move", "Arms", "LArm" or "RArm"}. + /// Activate or disactivate the anticollision of the desired name. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setExternalCollisionProtectionEnabled(const std::string& pName, const bool& pEnable); + + /// + /// Enable The fall manager protection for the robot. When a fall is detected the robot adopt a joint configuration to protect himself and cut the stiffness. + /// . An memory event called "robotHasFallen" is generated when the fallManager have been activated. + /// + /// Activate or disactivate the smart stiffness. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFallManagerEnabled(const bool& pEnable); + + /// + /// Makes Nao do foot step planner. This is a non-blocking call. + /// + /// name of the leg to move('LLeg'or 'RLeg') + /// [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta] + /// time list of each foot step + /// Clear existing foot steps. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFootSteps(const std::vector& legName, const AL::ALValue& footSteps, const std::vector& timeList, const bool& clearExisting); + + /// + /// Makes Nao do foot step planner with speed. This is a blocking call. + /// + /// name of the leg to move('LLeg'or 'RLeg') + /// [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta] + /// speed of each foot step. Must be between 0 and 1. + /// Clear existing foot steps. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFootStepsWithSpeed(const std::vector& legName, const AL::ALValue& footSteps, const std::vector& fractionMaxSpeed, const bool& clearExisting); + + /// + /// Starts or stops idle posture management on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// + /// Chain name. + /// Enables / disables the chain. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setIdlePostureEnabled(const std::string& pChain, const bool& pIsEnabled); + + /// + /// Internal Use. + /// + /// Internal: An array of ALValues [i][0]: name, [i][1]: value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMotionConfig(const AL::ALValue& config); + + /// + /// Sets if Arms Motions are enabled during the Move Process. + /// + /// if true Left Arm motions are controlled by the Move Task + /// if true Right Arm mMotions are controlled by the Move Task + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMoveArmsEnabled(const bool& leftArmEnabled, const bool& rightArmEnabled); + + /// + /// Defines the orthogonal security distance used with external collision protection "Move". + /// + /// The orthogonal security distance. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setOrthogonalSecurityDistance(const float& securityDistance); + + /// + /// Moves an end-effector to DEPRECATED. Use setPositions function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// 6D position array (x,y,z,wx,wy,wz) in meters and radians + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPosition(const std::string& chainName, const int& space, const std::vector& position, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// Moves multiple end-effectors to the given position and orientation position6d. This is a non-blocking call. + /// + /// The name or names of effector. + /// The task frame or task frames {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Position6D arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPositions(const AL::ALValue& names, const AL::ALValue& spaces, const AL::ALValue& positions, const float& fractionMaxSpeed, const AL::ALValue& axisMask); + + /// + /// Enable The push recovery protection for the robot. + /// + /// Enable the push recovery. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPushRecoveryEnabled(const bool& pEnable); + + /// + /// Enable Smart Stiffness for all the joints (True by default), the update take one motion cycle for updating. The smart Stiffness is a gestion of joint maximum torque. More description is available on the red documentation of ALMotion module. + /// + /// Activate or disactivate the smart stiffness. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSmartStiffnessEnabled(const bool& pEnable); + + /// + /// Sets the stiffness of one or more joints. This is a non-blocking call. + /// + /// Names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more stiffnesses between zero and one. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setStiffnesses(const AL::ALValue& names, const AL::ALValue& stiffnesses); + + /// + /// Defines the tangential security distance used with external collision protection "Move". + /// + /// The tangential security distance. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTangentialSecurityDistance(const float& securityDistance); + + /// + /// Moves an end-effector to DEPRECATED. Use setTransforms function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTransform(const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// Moves multiple end-effectors to the given position and orientation transforms. This is a non-blocking call. + /// + /// The name or names of effector. + /// The task frame or task frames {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTransforms(const AL::ALValue& names, const AL::ALValue& spaces, const AL::ALValue& transforms, const float& fractionMaxSpeed, const AL::ALValue& axisMask); + + /// + /// DEPRECATED. Sets if Arms Motions are enabled during the Walk Process. + /// + /// if true Left Arm motions are controlled by the Walk Task + /// if true Right Arm mMotions are controlled by the Walk Task + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWalkArmsEnabled(const bool& leftArmEnabled, const bool& rightArmEnabled); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + /// An ALValue with the custom gait configuration for both feet + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& feetGaitConfig); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + /// An ALValue with custom move configuration for the left foot + /// An ALValue with custom move configuration for the right foot + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& leftFootMoveConfig, const AL::ALValue& rightFootMoveConfig); + + /// + /// Interpolates one or multiple joints to a target stiffness or along timed trajectories of stiffness. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An stiffness, list of stiffnesses or list of list of stiffnesses + /// A time, list of times or list of list of times. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stiffnessInterpolation(const AL::ALValue& names, const AL::ALValue& stiffnessLists, const AL::ALValue& timeLists); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop Move task safely as fast as possible. The move task is ended less brutally than killMove but more quickly than move(0.0, 0.0, 0.0). + /// This is a blocking call. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopMove(); + + /// + /// DEPRECATED. Use stopMove function instead. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopWalk(); + + /// + /// DEPRECATED. Use the other transformInterpolations function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of Transform arrays + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int transformInterpolation(const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& duration, const bool& isAbsolute); + + /// + /// DEPRECATED. Use the other transformInterpolations function instead. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of transforms arrays. + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int transformInterpolations(const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute); + + /// + /// Moves end-effectors to the given positions and orientations over time. This is a blocking call. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// brokerTaskID : The ID of the task assigned to it by the broker. + int transformInterpolations(const AL::ALValue& effectorNames, const AL::ALValue& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes); + + /// + /// Update the target to follow by the head of NAO. + /// DEPRECATED Function. Please use ALTracker::lookAt. + /// + /// + /// The target position wy in FRAME_ROBOT + /// The target position wz in FRAME_ROBOT + /// The time in Ms since the target was detected + /// If true, the target is follow in cartesian space by the Head with whole Body constraints. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updateTrackerTarget(const float& pTargetPositionWy, const float& pTargetPositionWz, const int& pTimeSinceDetectionMs, const bool& pUseOfWholeBody); + + /// + /// Waits until the move process is finished: This method can be used to block your script/code execution until the move task is totally finished. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int waitUntilMoveIsFinished(); + + /// + /// DEPRECATED. Use waitUntilMoveIsFinished function instead. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int waitUntilWalkIsFinished(); + + /// + /// The robot will wake up: set Motor ON and go to initial position if needed + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wakeUp(); + + /// + /// DEPRECATED. Use moveInit function instead. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int walkInit(); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// Distance along the X axis in meters. + /// Distance along the Y axis in meters. + /// Rotation around the Z axis in radians [-3.1415 to 3.1415]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int walkTo(const float& x, const float& y, const float& theta); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// Distance along the X axis in meters. + /// Distance along the Y axis in meters. + /// Rotation around the Z axis in radians [-3.1415 to 3.1415]. + /// An ALValue with the custom gait configuration for both feet. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int walkTo(const float& x, const float& y, const float& theta, const AL::ALValue& feetGaitConfig); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// An ALValue with all the control point in NAO SPACE[[x1,y1,theta1], ..., [xN,yN,thetaN] + /// brokerTaskID : The ID of the task assigned to it by the broker. + int walkTo(const AL::ALValue& controlPoint); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// An ALValue with all the control point in NAO SPACE[[x1,y1,theta1], ..., [xN,yN,thetaN] + /// An ALValue with the custom gait configuration for both feet + /// brokerTaskID : The ID of the task assigned to it by the broker. + int walkTo(const AL::ALValue& controlPoint, const AL::ALValue& feetGaitConfig); + + /// + /// UserFriendly Whole Body API: enable Whole Body Balancer. It's a Generalized Inverse Kinematics which deals with cartesian control, balance, redundancy and task priority. The main goal is to generate and stabilized consistent motions without precomputed trajectories and adapt nao's behaviour to the situation. The generalized inverse kinematic problem takes in account equality constraints (keep foot fix), inequality constraints (joint limits, balance, ...) and quadratic minimization (cartesian / articular desired trajectories). We solve each step a quadratic programming on the robot. + /// + /// Active / Disactive Whole Body Balancer. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbEnable(const bool& isEnabled); + + /// + /// UserFriendly Whole Body API: enable to keep balance in support polygon. + /// + /// Enable Nao to keep balance. + /// Name of the support leg: "Legs", "LLeg", "RLeg". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbEnableBalanceConstraint(const bool& isEnable, const std::string& supportLeg); + + /// + /// UserFriendly Whole Body API: enable whole body cartesian control of an effector. + /// + /// Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position. + /// Active / Disactive Effector Control. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbEnableEffectorControl(const std::string& effectorName, const bool& isEnabled); + + /// + /// Advanced Whole Body API: enable to control an effector as an optimization. + /// + /// Name of the effector : "All", "Arms", "Legs", "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso", "Com". + /// if true, the effector control is taken in acount in the optimization criteria. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbEnableEffectorOptimization(const std::string& effectorName, const bool& isActive); + + /// + /// UserFriendly Whole Body API: set the foot state: fixed foot, constrained in a plane or free. + /// + /// Name of the foot state. "Fixed" set the foot fixed. "Plane" constrained the Foot in the plane. "Free" set the foot free. + /// Name of the foot. "LLeg", "RLeg" or "Legs". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbFootState(const std::string& stateName, const std::string& supportLeg); + + /// + /// Advanced Whole Body API: "Com" go to a desired support polygon. This is a blocking call. + /// + /// Name of the support leg: "Legs", "LLeg", "RLeg". + /// Time in seconds. Must be upper 0.5 s. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbGoToBalance(const std::string& supportLeg, const float& duration); + + /// + /// UserFriendly Whole Body API: set new target for controlled effector. This is a non-blocking call. + /// + /// Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position. + /// "Head" is controlled in rotation (WX, WY, WZ). "LArm" and "RArm" are controlled in position (X, Y, Z). TargetCoordinate must be absolute and expressed in FRAME_ROBOT. If the desired position/orientation is unfeasible, target is resize to the nearest feasible motion. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int wbSetEffectorControl(const std::string& effectorName, const AL::ALValue& targetCoordinate); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMotionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMotionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMotionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMotionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMotionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Interpolates one or multiple joints to a target angle or along timed trajectories. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An angle, list of angles or list of list of angles in radians + /// A time, list of times or list of list of times in seconds + /// If true, the movement is described in absolute angles, else the angles are relative to the current angle. + void angleInterpolation(const AL::ALValue& names, const AL::ALValue& angleLists, const AL::ALValue& timeLists, const bool& isAbsolute); + + /// + /// Interpolates a sequence of timed angles for several motors using bezier control points. This is a blocking call. + /// + /// A vector of joint names + /// An ragged ALValue matrix of floats. Each line corresponding to a motor, and column element to a control point. + /// An ALValue array of arrays each containing [float angle, Handle1, Handle2], where Handle is [int InterpolationType, float dAngle, float dTime] descibing the handle offsets relative to the angle and time of the point. The first bezier param describes the handle that controls the curve preceeding the point, the second describes the curve following the point. + void angleInterpolationBezier(const std::vector& jointNames, const AL::ALValue& times, const AL::ALValue& controlPoints); + + /// + /// Interpolates one or multiple joints to a target angle, using a fraction of max speed. Only one target angle is allowed for each joint. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An angle, or list of angles in radians + /// A fraction. + void angleInterpolationWithSpeed(const AL::ALValue& names, const AL::ALValue& targetAngles, const float& maxSpeedFraction); + + /// + /// Return true if notifications are active. + /// + /// Return True if notifications are active. + bool areNotificationsEnabled(); + + /// + /// Returns true if all the desired resources are available. Only motion API's' blocking call takes resources. + /// + /// A vector of resource names such as joints. Use getBodyNames("Body") to have the list of the available joint for your robot. + /// True if the resources are available + bool areResourcesAvailable(const std::vector& resourceNames); + + /// + /// Changes Angles. This is a non-blocking call. + /// + /// The name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more changes in radians + /// The fraction of maximum speed to use + void changeAngles(const AL::ALValue& names, const AL::ALValue& changes, const float& fractionMaxSpeed); + + /// + /// DEPRECATED. Use setPositions function instead. + /// + /// Name of the effector. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// 6D position change array (xd, yd, zd, wxd, wyd, wzd) in meters and radians + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void changePosition(const std::string& effectorName, const int& space, const std::vector& positionChange, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// DEPRECATED. Use setTransforms function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void changeTransform(const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// NAO stiffens the motors of desired hand. Then, he closes the hand, then cuts motor current to conserve energy. This is a blocking call. + /// + /// The name of the hand. Could be: "RHand" or "LHand" + void closeHand(const std::string& handName); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the angles of the joints + /// + /// Names the joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// If true, sensor angles will be returned + /// Joint angles in radians. + std::vector getAngles(const AL::ALValue& names, const bool& useSensors); + + /// + /// Gets the names of all the joints and actuators in the collection. + /// + /// Name of a chain, "Arms", "Legs", "Body", "Chains", "JointActuators", "Joints" or "Actuators". + /// Vector of strings, one for each joint and actuator in the collection + std::vector getBodyNames(const std::string& name); + + /// + /// This function gets the current breathing configuration. + /// bpm is the breathing frequency in beats per minute. + /// amplitude is the normalized amplitude of the breathing animation, between 0 and 1. + /// + /// An ALValue of the form [["Bpm", bpm], ["Amplitude", amplitude]]. + AL::ALValue getBreathConfig(); + + /// + /// This function gets the status of breathing animation on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// + /// + /// Chain name. + /// True if breathing animation is enabled on the chain. + bool getBreathEnabled(const std::string& pChain); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the COM of a joint, chain, "Body" or "Joints". + /// + /// Name of the body which we want the mass. In chain name case, this function give the com of the chain. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// If true, the sensor values will be used to determine the position. + /// The COM position (meter). + std::vector getCOM(const std::string& pName, const int& pSpace, const bool& pUseSensorValues); + + /// + /// Gets chain closest obstacle Position . + /// + /// The Chain name {"LArm" or "RArm"}. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector containing the Position3D in meters (x, y, z) + std::vector getChainClosestObstaclePosition(const std::string& pName, const int& space); + + /// + /// Allow to know if the collision protection is activated on the given chain. + /// + /// The chain name {"LArm" or "RArm"}. + /// Return true is the collision protection of the given Arm is activated. + bool getCollisionProtectionEnabled(const std::string& pChainName); + + /// + /// Give the state of the diagnosis effect. + /// + /// + /// Return true is the diagnosis reflex is activated. + bool getDiagnosisEffectEnabled(); + + /// + /// Allow to know if the external collision protection is activated on the given name. + /// + /// The name {"All", "Move", "Arms", "LArm" or "RArm"}. + /// Return true is the external collision protection of the given name is activated. + bool getExternalCollisionProtectionEnabled(const std::string& pName); + + /// + /// Give the state of the fall manager. + /// + /// + /// Return true is the fall manager is activated. + bool getFallManagerEnabled(); + + /// + /// DEPRECATED. Use getMoveConfig function instead. + /// Gets the foot Gait config ("MaxStepX", "MaxStepY", "MaxStepTheta", "MaxStepFrequency", "StepHeight", "TorsoWx", "TorsoWy") + /// + /// a string should be "Max", "Min", "Default" + /// ["MaxStepY", value], + /// ["MaxStepTheta", value], + /// ["MaxStepFrequency", value], + /// ["StepHeight", value], + /// ["TorsoWx", value], + /// ["TorsoWy", value]] + /// + /// An ALvalue with the following form :[["MaxStepX", value], + AL::ALValue getFootGaitConfig(const std::string& config); + + /// + /// Get the foot steps. This is a non-blocking call. + /// + /// Give two list of foot steps. The first one give the unchangeable foot step. The second list give the changeable foot steps. Il you use setFootSteps or setFootStepsWithSpeed with clearExisting parmater equal true, walk engine execute unchangeable foot step and remove the other. + AL::ALValue getFootSteps(); + + /// + /// This function gets the status of idle posture management on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// + /// + /// Chain name. + /// True if breathing animation is enabled on the chain. + bool getIdlePostureEnabled(const std::string& pChain); + + /// + /// DEPRECATED. Use getBodyNames function instead. + /// + /// Name of a chain, "Arms", "Legs", "Body", "Chains", "JointActuators", "Joints" or "Actuators". + /// Vector of strings, one for each joint in the collection + std::vector getJointNames(const std::string& name); + + /// + /// Get the minAngle (rad), maxAngle (rad), and maxVelocity (rad.s-1) for a given joint or actuator in the body. + /// + /// Name of a joint, chain, "Body", "JointActuators", "Joints" or "Actuators". + /// Array of ALValue arrays containing the minAngle, maxAngle, maxVelocity and maxTorque for all the bodies specified. + AL::ALValue getLimits(const std::string& name); + + /// + /// Gets the mass of a joint, chain, "Body" or "Joints". + /// + /// Name of the body which we want the mass. "Body", "Joints" and "Com" give the total mass of nao. For the chain, it gives the total mass of the chain. + /// The mass in kg. + float getMass(const std::string& pName); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the motion cycle time in milliseconds. + /// + /// Expressed in milliseconds + int getMotionCycleTime(); + + /// + /// Gets if Arms Motions are enabled during the Move Process. + /// + /// Name of the chain. Could be: "LArm", "RArm" or "Arms" + /// For LArm and RArm true if the corresponding arm is enabled. For Arms, true if both are enabled. False otherwise. + bool getMoveArmsEnabled(const std::string& chainName); + + /// + /// Gets the move config. + /// + /// a string should be "Max", "Min", "Default" + /// An ALvalue with the move config + AL::ALValue getMoveConfig(const std::string& config); + + /// + /// Gets the World Absolute next Robot Position. + /// In fact in the walk algorithm some foot futur foot step are incompressible due to preview control, so this function give the next robot position which is incompressible. + /// If the robot doesn't walk this function is equivalent to getRobotPosition(false) + /// + /// + /// A vector containing the World Absolute next Robot position.(Absolute Position X, Absolute Position Y, Absolute Angle Z) + std::vector getNextRobotPosition(); + + /// + /// Gets the current orthogonal security distance. + /// + /// The current orthogonal security distance. + float getOrthogonalSecurityDistance(); + + /// + /// Gets a Position relative to the FRAME. Axis definition: the x axis is positive toward Nao's front, the y from right to left and the z is vertical. The angle convention of Position6D is Rot_z(wz).Rot_y(wy).Rot_x(wx). + /// + /// Name of the item. Could be: Head, LArm, RArm, LLeg, RLeg, Torso, CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4. Use getSensorNames for the list of sensors supported on your robot. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// If true, the sensor values will be used to determine the position. + /// Vector containing the Position6D using meters and radians (x, y, z, wx, wy, wz) + std::vector getPosition(const std::string& name, const int& space, const bool& useSensorValues); + + /// + /// Give the state of the push recovery. + /// + /// + /// Return true is the push recovery is activated. + bool getPushRecoveryEnabled(); + + /// + /// Get the robot configuration. + /// + /// ALValue arrays containing the robot parameter names and the robot parameter values. + AL::ALValue getRobotConfig(); + + /// + /// Gets the World Absolute Robot Position. + /// + /// If true, use the sensor values + /// A vector containing the World Absolute Robot Position. (Absolute Position X, Absolute Position Y, Absolute Angle Z) + std::vector getRobotPosition(const bool& useSensors); + + /// + /// Gets the World Absolute Robot Velocity. + /// + /// A vector containing the World Absolute Robot Velocity. (Absolute Velocity Translation X [m.s-1], Absolute Velocity Translation Y[m.s-1], Absolute Velocity Rotation WZ [rd.s-1]) + std::vector getRobotVelocity(); + + /// + /// Gets the list of sensors supported on your robot. + /// + /// Vector of sensor names + std::vector getSensorNames(); + + /// + /// Give the state of the smart Stiffness. + /// + /// + /// Return true is the smart Stiffnes is activated. + bool getSmartStiffnessEnabled(); + + /// + /// Gets stiffness of a joint or group of joints + /// + /// Name of the joints, chains, "Body", "Joints" or "Actuators". + /// One or more stiffnesses. 1.0 indicates maximum stiffness. 0.0 indicated minimum stiffness + std::vector getStiffnesses(const AL::ALValue& jointName); + + /// + /// Returns a string representation of the Model's state + /// + /// A formated string + std::string getSummary(); + + /// + /// Gets the current tangential security distance. + /// + /// The current tangential security distance. + float getTangentialSecurityDistance(); + + /// + /// Gets an ALValue structure describing the tasks in the Task List + /// + /// An ALValue containing an ALValue for each task. The inner ALValue contains: Name, MotionID + AL::ALValue getTaskList(); + + /// + /// Gets an Homogenous Transform relative to the FRAME. Axis definition: the x axis is positive toward Nao's front, the y from right to left and the z is vertical. + /// + /// Name of the item. Could be: any joint or chain or sensor (Head, LArm, RArm, LLeg, RLeg, Torso, HeadYaw, ..., CameraTop, CameraBottom, MicroFront, MicroRear, MicroLeft, MicroRight, Accelerometer, Gyrometer, Laser, LFsrFR, LFsrFL, LFsrRR, LFsrRL, RFsrFR, RFsrFL, RFsrRR, RFsrRL, USSensor1, USSensor2, USSensor3, USSensor4. Use getSensorNames for the list of sensors supported on your robot. + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// If true, the sensor values will be used to determine the position. + /// Vector of 16 floats corresponding to the values of the matrix, line by line. + std::vector getTransform(const std::string& name, const int& space, const bool& useSensorValues); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// DEPRECATED. Gets if Arms Motions are enabled during the Walk Process. + /// + /// True Arm Motions are controlled by the Walk Task. + AL::ALValue getWalkArmsEnabled(); + + /// + /// Give the collision state of a chain. If a chain has a collision state "none" or "near", it could be desactivated. + /// + /// The chain name {"Arms", "LArm" or "RArm"}. + /// + /// A string which notice the collision state: "none" there are no collision, "near" the collision is taking in account in the anti-collision algorithm, "collision" the chain is in contact with an other body. If the chain asked is "Arms" the most unfavorable result is given. + std::string isCollision(const std::string& pChainName); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Kills all tasks. + /// + void killAll(); + + /// + /// Emergency Stop on Move task: This method will end the move task brutally, without attempting to return to a balanced state. The robot could easily fall. + /// + void killMove(); + + /// + /// Kills a motion task. + /// + /// TaskID of the motion task you want to kill. + /// Return true if the specified motionTaskId has been killed. + bool killTask(const int& motionTaskID); + + /// + /// Kills all tasks that use any of the resources given. Only motion API's' blocking call takes resources and can be killed. Use getBodyNames("Body") to have the list of the available joint for your robot. + /// + /// A vector of resource joint names + void killTasksUsingResources(const std::vector& resourceNames); + + /// + /// DEPRECATED. Use killMove function instead. + /// + void killWalk(); + + /// + /// Makes the robot move at the given velocity. This is a non-blocking call. + /// + /// The velocity along x axis [m.s-1]. + /// The velocity along y axis [m.s-1]. + /// The velocity around z axis [rd.s-1]. + void move(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given velocity. This is a non-blocking call. + /// + /// The velocity along x axis [m.s-1]. + /// The velocity along y axis [m.s-1]. + /// The velocity around z axis [rd.s-1]. + /// An ALValue with custom move configuration. + void move(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Initialize the move process. Check the robot pose and take a right posture. This is blocking called. + /// + void moveInit(); + + /// + /// Check if the move process is actif. + /// + /// True if move is active + bool moveIsActive(); + + /// + /// Makes the robot move at the given position. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + void moveTo(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given position in fixed time. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// The time to reach the target position [s]. + void moveTo(const float& x, const float& y, const float& theta, const float& time); + + /// + /// Makes the robot move at the given position. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// An ALValue with custom move configuration. + void moveTo(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given position in fixed time. This is a non-blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The position around z axis [rd]. + /// The time to reach the target position [s]. + /// An ALValue with custom move configuration. + void moveTo(const float& x, const float& y, const float& theta, const float& time, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move to the given relative positions. This is a blocking call. + /// + /// An ALValue with the control points in FRAME_ROBOT. + /// Each control point is relative to the previous one. [[x1, y1, theta1], ..., [xN, yN, thetaN] + void moveTo(const AL::ALValue& controlPoint); + + /// + /// Makes the robot move to the given relative positions. This is a blocking call. + /// + /// An ALValue with all the control points in FRAME_ROBOT. + /// Each control point is relative to the previous one. [[x1, y1, theta1], ..., [xN, yN, thetaN] + /// An ALValue with custom move configuration. + void moveTo(const AL::ALValue& controlPoint, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given normalized velocity. This is a non-blocking call. + /// + /// The normalized velocity along x axis (between -1 and 1). + /// The normalized velocity along y axis (between -1 and 1). + /// The normalized velocity around z axis (between -1 and 1). + void moveToward(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given normalized velocity. This is a non-blocking call. + /// + /// The normalized velocity along x axis (between -1 and 1). + /// The normalized velocity along y axis (between -1 and 1). + /// The normalized velocity around z axis (between -1 and 1). + /// An ALValue with custom move configuration. + void moveToward(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// NAO stiffens the motors of desired hand. Then, he opens the hand, then cuts motor current to conserve energy. This is a blocking call. + /// + /// The name of the hand. Could be: "RHand or "LHand" + void openHand(const std::string& handName); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// DEPRECATED. Use positionInterpolations function instead. + /// + /// Name of the chain. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + void positionInterpolation(const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& durations, const bool& isAbsolute); + + /// + /// DEPRECATED. Use the other positionInterpolations function instead. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + void positionInterpolations(const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute); + + /// + /// Moves end-effectors to the given positions and orientations over time. This is a blocking call. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + void positionInterpolations(const AL::ALValue& effectorNames, const AL::ALValue& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes); + + /// + /// The robot will rest: go to a relax and safe position and set Motor OFF + /// + void rest(); + + /// + /// The robot will rest: go to a relax and safe position on the chain and set Motor OFF + /// + /// arg + void rest(const std::string& arg1); + + /// + /// return true if the robot is already wakeUp + /// + /// True if the robot is already wakeUp. + bool robotIsWakeUp(); + + /// + /// Sets angles. This is a non-blocking call. + /// + /// The name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more angles in radians + /// The fraction of maximum speed to use + void setAngles(const AL::ALValue& names, const AL::ALValue& angles, const float& fractionMaxSpeed); + + /// + /// This function configures the breathing animation. + /// + /// Breath configuration. + /// An ALValue of the form [["Bpm", pBpm], ["Amplitude", pAmplitude]]. + /// pBpm is a float between 10 and 50 setting the breathing frequency in beats per minute. + /// pAmplitude is a float between 0 and 1 setting the amplitude of the breathing animation. + void setBreathConfig(const AL::ALValue& pConfig); + + /// + /// This function starts or stops breathing animation on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// Head breathing animation will work only if Leg animation is active. + /// + /// Chain name. + /// Enables / disables the chain. + void setBreathEnabled(const std::string& pChain, const bool& pIsEnabled); + + /// + /// Enable Anticollision protection of the arms of the robot. Use api isCollision to know if a chain is in collision and can be disactivated. + /// + /// The chain name {"Arms", "LArm" or "RArm"}. + /// Activate or disactivate the anticollision of the desired Chain. + /// A bool which return always true. + bool setCollisionProtectionEnabled(const std::string& pChainName, const bool& pEnable); + + /// + /// Enable or disable the diagnosis effect into ALMotion + /// + /// Enable or disable the diagnosis effect. + void setDiagnosisEffectEnabled(const bool& pEnable); + + /// + /// Enable / Disable notifications. + /// + /// If True enable notifications. If False disable notifications. + void setEnableNotifications(const bool& enable); + + /// + /// Enable Anticollision protection of the arms and base move of the robot with external environment. + /// + /// The name {"All", "Move", "Arms", "LArm" or "RArm"}. + /// Activate or disactivate the anticollision of the desired name. + void setExternalCollisionProtectionEnabled(const std::string& pName, const bool& pEnable); + + /// + /// Enable The fall manager protection for the robot. When a fall is detected the robot adopt a joint configuration to protect himself and cut the stiffness. + /// . An memory event called "robotHasFallen" is generated when the fallManager have been activated. + /// + /// Activate or disactivate the smart stiffness. + void setFallManagerEnabled(const bool& pEnable); + + /// + /// Makes Nao do foot step planner. This is a non-blocking call. + /// + /// name of the leg to move('LLeg'or 'RLeg') + /// [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta] + /// time list of each foot step + /// Clear existing foot steps. + void setFootSteps(const std::vector& legName, const AL::ALValue& footSteps, const std::vector& timeList, const bool& clearExisting); + + /// + /// Makes Nao do foot step planner with speed. This is a blocking call. + /// + /// name of the leg to move('LLeg'or 'RLeg') + /// [x, y, theta], [Position along X/Y, Orientation round Z axis] of the leg relative to the other Leg in [meters, meters, radians]. Must be less than [MaxStepX, MaxStepY, MaxStepTheta] + /// speed of each foot step. Must be between 0 and 1. + /// Clear existing foot steps. + void setFootStepsWithSpeed(const std::vector& legName, const AL::ALValue& footSteps, const std::vector& fractionMaxSpeed, const bool& clearExisting); + + /// + /// Starts or stops idle posture management on a chain. + /// Chain name can be "Body", "Arms", "LArm", "RArm", "Legs" or "Head". + /// + /// Chain name. + /// Enables / disables the chain. + void setIdlePostureEnabled(const std::string& pChain, const bool& pIsEnabled); + + /// + /// Internal Use. + /// + /// Internal: An array of ALValues [i][0]: name, [i][1]: value + void setMotionConfig(const AL::ALValue& config); + + /// + /// Sets if Arms Motions are enabled during the Move Process. + /// + /// if true Left Arm motions are controlled by the Move Task + /// if true Right Arm mMotions are controlled by the Move Task + void setMoveArmsEnabled(const bool& leftArmEnabled, const bool& rightArmEnabled); + + /// + /// Defines the orthogonal security distance used with external collision protection "Move". + /// + /// The orthogonal security distance. + void setOrthogonalSecurityDistance(const float& securityDistance); + + /// + /// Moves an end-effector to DEPRECATED. Use setPositions function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// 6D position array (x,y,z,wx,wy,wz) in meters and radians + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void setPosition(const std::string& chainName, const int& space, const std::vector& position, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// Moves multiple end-effectors to the given position and orientation position6d. This is a non-blocking call. + /// + /// The name or names of effector. + /// The task frame or task frames {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Position6D arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void setPositions(const AL::ALValue& names, const AL::ALValue& spaces, const AL::ALValue& positions, const float& fractionMaxSpeed, const AL::ALValue& axisMask); + + /// + /// Enable The push recovery protection for the robot. + /// + /// Enable the push recovery. + void setPushRecoveryEnabled(const bool& pEnable); + + /// + /// Enable Smart Stiffness for all the joints (True by default), the update take one motion cycle for updating. The smart Stiffness is a gestion of joint maximum torque. More description is available on the red documentation of ALMotion module. + /// + /// Activate or disactivate the smart stiffness. + void setSmartStiffnessEnabled(const bool& pEnable); + + /// + /// Sets the stiffness of one or more joints. This is a non-blocking call. + /// + /// Names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// One or more stiffnesses between zero and one. + void setStiffnesses(const AL::ALValue& names, const AL::ALValue& stiffnesses); + + /// + /// Defines the tangential security distance used with external collision protection "Move". + /// + /// The tangential security distance. + void setTangentialSecurityDistance(const float& securityDistance); + + /// + /// Moves an end-effector to DEPRECATED. Use setTransforms function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void setTransform(const std::string& chainName, const int& space, const std::vector& transform, const float& fractionMaxSpeed, const int& axisMask); + + /// + /// Moves multiple end-effectors to the given position and orientation transforms. This is a non-blocking call. + /// + /// The name or names of effector. + /// The task frame or task frames {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Transform arrays + /// The fraction of maximum speed to use + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + void setTransforms(const AL::ALValue& names, const AL::ALValue& spaces, const AL::ALValue& transforms, const float& fractionMaxSpeed, const AL::ALValue& axisMask); + + /// + /// DEPRECATED. Sets if Arms Motions are enabled during the Walk Process. + /// + /// if true Left Arm motions are controlled by the Walk Task + /// if true Right Arm mMotions are controlled by the Walk Task + void setWalkArmsEnabled(const bool& leftArmEnabled, const bool& rightArmEnabled); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + void setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + /// An ALValue with the custom gait configuration for both feet + void setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& feetGaitConfig); + + /// + /// DEPRECATED. Use moveToward() function instead. + /// + /// Fraction of MaxStepX. Use negative for backwards. [-1.0 to 1.0] + /// Fraction of MaxStepY. Use negative for right. [-1.0 to 1.0] + /// Fraction of MaxStepTheta. Use negative for clockwise [-1.0 to 1.0] + /// Fraction of MaxStepFrequency [0.0 to 1.0] + /// An ALValue with custom move configuration for the left foot + /// An ALValue with custom move configuration for the right foot + void setWalkTargetVelocity(const float& x, const float& y, const float& theta, const float& frequency, const AL::ALValue& leftFootMoveConfig, const AL::ALValue& rightFootMoveConfig); + + /// + /// Interpolates one or multiple joints to a target stiffness or along timed trajectories of stiffness. This is a blocking call. + /// + /// Name or names of joints, chains, "Body", "JointActuators", "Joints" or "Actuators". + /// An stiffness, list of stiffnesses or list of list of stiffnesses + /// A time, list of times or list of list of times. + void stiffnessInterpolation(const AL::ALValue& names, const AL::ALValue& stiffnessLists, const AL::ALValue& timeLists); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop Move task safely as fast as possible. The move task is ended less brutally than killMove but more quickly than move(0.0, 0.0, 0.0). + /// This is a blocking call. + /// + void stopMove(); + + /// + /// DEPRECATED. Use stopMove function instead. + /// + void stopWalk(); + + /// + /// DEPRECATED. Use the other transformInterpolations function instead. + /// + /// Name of the chain. Could be: "Head", "LArm","RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of Transform arrays + /// Axis mask. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + void transformInterpolation(const std::string& chainName, const int& space, const AL::ALValue& path, const int& axisMask, const AL::ALValue& duration, const bool& isAbsolute); + + /// + /// DEPRECATED. Use the other transformInterpolations function instead. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of transforms arrays. + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + /// If true, the movement is absolute else relative + void transformInterpolations(const std::vector& effectorNames, const int& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes, const bool& isAbsolute); + + /// + /// Moves end-effectors to the given positions and orientations over time. This is a blocking call. + /// + /// Vector of chain names. Could be: "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso" + /// Task frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 6D position arrays (x,y,z,wx,wy,wz) in meters and radians + /// Vector of Axis Masks. True for axes that you wish to control. e.g. 7 for position only, 56 for rotation only and 63 for both + /// Vector of times in seconds corresponding to the path points + void transformInterpolations(const AL::ALValue& effectorNames, const AL::ALValue& taskSpaceForAllPaths, const AL::ALValue& paths, const AL::ALValue& axisMasks, const AL::ALValue& relativeTimes); + + /// + /// Update the target to follow by the head of NAO. + /// DEPRECATED Function. Please use ALTracker::lookAt. + /// + /// + /// The target position wy in FRAME_ROBOT + /// The target position wz in FRAME_ROBOT + /// The time in Ms since the target was detected + /// If true, the target is follow in cartesian space by the Head with whole Body constraints. + void updateTrackerTarget(const float& pTargetPositionWy, const float& pTargetPositionWz, const int& pTimeSinceDetectionMs, const bool& pUseOfWholeBody); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Waits until the move process is finished: This method can be used to block your script/code execution until the move task is totally finished. + /// + void waitUntilMoveIsFinished(); + + /// + /// DEPRECATED. Use waitUntilMoveIsFinished function instead. + /// + void waitUntilWalkIsFinished(); + + /// + /// The robot will wake up: set Motor ON and go to initial position if needed + /// + void wakeUp(); + + /// + /// DEPRECATED. Use moveInit function instead. + /// + void walkInit(); + + /// + /// DEPRECATED. Use moveIsActive function instead. + /// + bool walkIsActive(); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// Distance along the X axis in meters. + /// Distance along the Y axis in meters. + /// Rotation around the Z axis in radians [-3.1415 to 3.1415]. + void walkTo(const float& x, const float& y, const float& theta); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// Distance along the X axis in meters. + /// Distance along the Y axis in meters. + /// Rotation around the Z axis in radians [-3.1415 to 3.1415]. + /// An ALValue with the custom gait configuration for both feet. + void walkTo(const float& x, const float& y, const float& theta, const AL::ALValue& feetGaitConfig); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// An ALValue with all the control point in NAO SPACE[[x1,y1,theta1], ..., [xN,yN,thetaN] + void walkTo(const AL::ALValue& controlPoint); + + /// + /// DEPRECATED. Use moveTo() function instead. + /// + /// An ALValue with all the control point in NAO SPACE[[x1,y1,theta1], ..., [xN,yN,thetaN] + /// An ALValue with the custom gait configuration for both feet + void walkTo(const AL::ALValue& controlPoint, const AL::ALValue& feetGaitConfig); + + /// + /// UserFriendly Whole Body API: enable Whole Body Balancer. It's a Generalized Inverse Kinematics which deals with cartesian control, balance, redundancy and task priority. The main goal is to generate and stabilized consistent motions without precomputed trajectories and adapt nao's behaviour to the situation. The generalized inverse kinematic problem takes in account equality constraints (keep foot fix), inequality constraints (joint limits, balance, ...) and quadratic minimization (cartesian / articular desired trajectories). We solve each step a quadratic programming on the robot. + /// + /// Active / Disactive Whole Body Balancer. + void wbEnable(const bool& isEnabled); + + /// + /// UserFriendly Whole Body API: enable to keep balance in support polygon. + /// + /// Enable Nao to keep balance. + /// Name of the support leg: "Legs", "LLeg", "RLeg". + void wbEnableBalanceConstraint(const bool& isEnable, const std::string& supportLeg); + + /// + /// UserFriendly Whole Body API: enable whole body cartesian control of an effector. + /// + /// Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position. + /// Active / Disactive Effector Control. + void wbEnableEffectorControl(const std::string& effectorName, const bool& isEnabled); + + /// + /// Advanced Whole Body API: enable to control an effector as an optimization. + /// + /// Name of the effector : "All", "Arms", "Legs", "Head", "LArm", "RArm", "LLeg", "RLeg", "Torso", "Com". + /// if true, the effector control is taken in acount in the optimization criteria. + void wbEnableEffectorOptimization(const std::string& effectorName, const bool& isActive); + + /// + /// UserFriendly Whole Body API: set the foot state: fixed foot, constrained in a plane or free. + /// + /// Name of the foot state. "Fixed" set the foot fixed. "Plane" constrained the Foot in the plane. "Free" set the foot free. + /// Name of the foot. "LLeg", "RLeg" or "Legs". + void wbFootState(const std::string& stateName, const std::string& supportLeg); + + /// + /// Advanced Whole Body API: "Com" go to a desired support polygon. This is a blocking call. + /// + /// Name of the support leg: "Legs", "LLeg", "RLeg". + /// Time in seconds. Must be upper 0.5 s. + void wbGoToBalance(const std::string& supportLeg, const float& duration); + + /// + /// UserFriendly Whole Body API: set new target for controlled effector. This is a non-blocking call. + /// + /// Name of the effector : "Head", "LArm" or "RArm". Nao goes to posture init. He manages his balance and keep foot fix. "Head" is controlled in rotation. "LArm" and "RArm" are controlled in position. + /// "Head" is controlled in rotation (WX, WY, WZ). "LArm" and "RArm" are controlled in position (X, Y, Z). TargetCoordinate must be absolute and expressed in FRAME_ROBOT. If the desired position/orientation is unfeasible, target is resize to the nearest feasible motion. + void wbSetEffectorControl(const std::string& effectorName, const AL::ALValue& targetCoordinate); + + + detail::ALMotionProxyPostHandler post; + }; + +} +#endif // ALMOTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almotionrecorderproxy.h b/naoModule/libnaoqi_files/include/alproxies/almotionrecorderproxy.h new file mode 100755 index 0000000..4d73356 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almotionrecorderproxy.h @@ -0,0 +1,238 @@ +// Generated for ALMotionRecorder version 0 + +#ifndef ALMOTIONRECORDERPROXY_H_ +#define ALMOTIONRECORDERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMotionRecorderProxy; + + namespace detail { + class ALMotionRecorderProxyPostHandler + { + protected: + ALMotionRecorderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMotionRecorderProxy; + + /// + /// Called by ALMemory when subcription data is updated. INTERNAL + /// + /// Name of the subscribed data. + /// Value of the the subscribed data + /// The message give when subscribing. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int dataChanged(const std::string& dataName, const AL::ALValue& data, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Start recording the motion in an interactive mode + /// + /// Names of joints that must be recorded + /// Default number of poses to record + /// Set to true to ignore nbPoses and keep recording new poses as long as record is not manually stopped + /// Indicates which interactive mode must be used. 1 : Use right bumper to enslave and left bumper to store the pose (deprecated); 2 : Use chest button to store the pose + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startInteractiveRecording(const std::vector& jointsToRecord, const int& nbPoses, const bool& extensionAllowed, const int& mode); + + /// + /// Start recording the motion in a periodic mode + /// + /// Names of joints that must be recorded + /// Default number of poses to record + /// set to true to ignore nbPoses and keep recording new poses as long as record is not manually stopped + /// Time in seconds to wait between two poses + /// Names of joints that must be replayed + /// An ALValue holding data for replayed joints. It holds two ALValues. The first one is an ALValue where each line corresponds to a joint, and column elements are times of control points The second one is also an ALValue where each line corresponds to a joint, but column elements are arrays containing [float angle, Handle1, Handle2] elements, where Handle is [int InterpolationType, float dAngle, float dTime] describing the handle offsets relative to the angle and time of the point. The first bezier param describes the handle that controls the curve preceding the point, the second describes the curve following the point. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startPeriodicRecording(const std::vector& jointsToRecord, const int& nbPoses, const bool& extensionAllowed, const float& timeStep, const std::vector& jointsToReplay, const AL::ALValue& replayData); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMotionRecorderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMotionRecorderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMotionRecorderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMotionRecorderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMotionRecorderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Called by ALMemory when subcription data is updated. INTERNAL + /// + /// Name of the subscribed data. + /// Value of the the subscribed data + /// The message give when subscribing. + void dataChanged(const std::string& dataName, const AL::ALValue& data, const std::string& message); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Start recording the motion in an interactive mode + /// + /// Names of joints that must be recorded + /// Default number of poses to record + /// Set to true to ignore nbPoses and keep recording new poses as long as record is not manually stopped + /// Indicates which interactive mode must be used. 1 : Use right bumper to enslave and left bumper to store the pose (deprecated); 2 : Use chest button to store the pose + void startInteractiveRecording(const std::vector& jointsToRecord, const int& nbPoses, const bool& extensionAllowed, const int& mode); + + /// + /// Start recording the motion in a periodic mode + /// + /// Names of joints that must be recorded + /// Default number of poses to record + /// set to true to ignore nbPoses and keep recording new poses as long as record is not manually stopped + /// Time in seconds to wait between two poses + /// Names of joints that must be replayed + /// An ALValue holding data for replayed joints. It holds two ALValues. The first one is an ALValue where each line corresponds to a joint, and column elements are times of control points The second one is also an ALValue where each line corresponds to a joint, but column elements are arrays containing [float angle, Handle1, Handle2] elements, where Handle is [int InterpolationType, float dAngle, float dTime] describing the handle offsets relative to the angle and time of the point. The first bezier param describes the handle that controls the curve preceding the point, the second describes the curve following the point. + void startPeriodicRecording(const std::vector& jointsToRecord, const int& nbPoses, const bool& extensionAllowed, const float& timeStep, const std::vector& jointsToReplay, const AL::ALValue& replayData); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop recording the motion and return data + /// + /// Returns the recorded data as an ALValue: [[JointName1,[pos1, pos2, ...]], [JointName2,[pos1, pos2, ...]], ...] + AL::ALValue stopAndGetRecording(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALMotionRecorderProxyPostHandler post; + }; + +} +#endif // ALMOTIONRECORDERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almovementdetection3dproxy.h b/naoModule/libnaoqi_files/include/alproxies/almovementdetection3dproxy.h new file mode 100755 index 0000000..445ffff --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almovementdetection3dproxy.h @@ -0,0 +1,368 @@ +// Generated for ALMovementDetection3D version 1.18 + +#ifndef ALMOVEMENTDETECTION3DPROXY_H_ +#define ALMOVEMENTDETECTION3DPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMovementDetection3DProxy; + + namespace detail { + class ALMovementDetection3DProxyPostHandler + { + protected: + ALMovementDetection3DProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMovementDetection3DProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Enables to reset the movement detection when desired + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetDetection(); + + /// + /// Sets the value of the depth sensitivity (in meters) used for the detection of moving pixels in the image. + /// + /// New depth sensitivity (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDepthSensitivity(const float& sensitivity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMovementDetection3DProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMovementDetection3DProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMovementDetection3DProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMovementDetection3DProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMovementDetection3DProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// + /// + /// + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// gets the value of the depth sensitivity (in meters) + /// + /// Current depth sensitivity (in meters) + float getDepthSensitivity(); + + /// + /// + /// + /// + int getFrameRate(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// + /// + /// + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// + /// + /// + bool isPaused(); + + /// + /// + /// + /// + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// arg + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Enables to reset the movement detection when desired + /// + void resetDetection(); + + /// + /// + /// + /// arg + /// + bool setActiveCamera(const int& cameraID); + + /// + /// Sets the value of the depth sensitivity (in meters) used for the detection of moving pixels in the image. + /// + /// New depth sensitivity (in meters) + void setDepthSensitivity(const float& sensitivity); + + /// + /// + /// + /// arg + /// + bool setFrameRate(const int& value); + + /// + /// + /// + /// arg + /// + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALMovementDetection3DProxyPostHandler post; + }; + +} +#endif // ALMOVEMENTDETECTION3DPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/almovementdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/almovementdetectionproxy.h new file mode 100755 index 0000000..d129dbf --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/almovementdetectionproxy.h @@ -0,0 +1,409 @@ +// Generated for ALMovementDetection version 0 + +#ifndef ALMOVEMENTDETECTIONPROXY_H_ +#define ALMOVEMENTDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALMovementDetectionProxy; + + namespace detail { + class ALMovementDetectionProxyPostHandler + { + protected: + ALMovementDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALMovementDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Enables to reset the movement detection when desired + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetDetection(); + + /// + /// Sets the value of the color sensitivity used for the 2D detection of moving pixels in the image. + /// + /// New color sensitivity (between 0 and 1) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setColorSensitivity(const float& sensitivity); + + /// + /// Sets the value of the depth sensitivity (in meters) used for the detection 3D of moving pixels in the image. + /// + /// New depth sensitivity (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDepthSensitivity(const float& sensitivity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALMovementDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALMovementDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALMovementDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALMovementDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALMovementDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the value of the color sensitivity + /// + /// Current color sensitivity (between 0 and 1) + float getColorSensitivity(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// gets the value of the depth sensitivity (in meters) + /// + /// Current depth sensitivity (in meters) + float getDepthSensitivity(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Enables to reset the movement detection when desired + /// + void resetDetection(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the value of the color sensitivity used for the 2D detection of moving pixels in the image. + /// + /// New color sensitivity (between 0 and 1) + void setColorSensitivity(const float& sensitivity); + + /// + /// Sets the value of the depth sensitivity (in meters) used for the detection 3D of moving pixels in the image. + /// + /// New depth sensitivity (in meters) + void setDepthSensitivity(const float& sensitivity); + + /// + /// Sets extractor framerate + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALMovementDetectionProxyPostHandler post; + }; + +} +#endif // ALMOVEMENTDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alnavigationproxy.h b/naoModule/libnaoqi_files/include/alproxies/alnavigationproxy.h new file mode 100755 index 0000000..cf98f68 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alnavigationproxy.h @@ -0,0 +1,365 @@ +// Generated for ALNavigation version 0 + +#ifndef ALNAVIGATIONPROXY_H_ +#define ALNAVIGATIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALNavigationProxy; + + namespace detail { + class ALNavigationProxyPostHandler + { + protected: + ALNavigationProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALNavigationProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Makes the robot move at the given speed in S.I. units. This is a blocking call. + /// + /// The speed along x axis [m.s-1]. + /// The speed along y axis [m.s-1]. + /// The anglular speed around z axis [rad.s-1]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int move(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given speed in S.I. units. This is a blocking call. + /// + /// The speed along x axis [m.s-1]. + /// The speed along y axis [m.s-1]. + /// The anglular speed around z axis [rad.s-1]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int move(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given position.This is a blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The angle around z axis [rad]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given position.This is a blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The angle around z axis [rad]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveTo(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given speed in normalized speed fraction. This is a blocking call. + /// + /// The speed along x axis [0.0-1.0]. + /// The speed along y axis [0.0-1.0]. + /// The anglular speed around z axis [0.0-1.0]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveToward(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given speed in normalized speed fraction. This is a blocking call. + /// + /// The speed along x axis [0.0-1.0]. + /// The speed along y axis [0.0-1.0]. + /// The anglular speed around z axis [0.0-1.0]. + /// An ALValue with custom move configuration. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int moveToward(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// . + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int onTouchChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// Distance in meters fromwhich the robot should stop if there is an obstacle. + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSecurityDistance(const float& arg1); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops the navigateTo. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopNavigateTo(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALNavigationProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALNavigationProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALNavigationProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALNavigationProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALNavigationProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Distance in meters fromwhich the robot should stop if there is an obstacle. + /// + float getSecurityDistance(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Makes the robot move at the given speed in S.I. units. This is a blocking call. + /// + /// The speed along x axis [m.s-1]. + /// The speed along y axis [m.s-1]. + /// The anglular speed around z axis [rad.s-1]. + void move(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given speed in S.I. units. This is a blocking call. + /// + /// The speed along x axis [m.s-1]. + /// The speed along y axis [m.s-1]. + /// The anglular speed around z axis [rad.s-1]. + /// An ALValue with custom move configuration. + void move(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// . + /// + /// An ALValue describing a trajectory. + bool moveAlong(const AL::ALValue& trajectory); + + /// + /// Makes the robot move at the given position.This is a blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The angle around z axis [rad]. + void moveTo(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given position.This is a blocking call. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// The angle around z axis [rad]. + /// An ALValue with custom move configuration. + void moveTo(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot move at the given speed in normalized speed fraction. This is a blocking call. + /// + /// The speed along x axis [0.0-1.0]. + /// The speed along y axis [0.0-1.0]. + /// The anglular speed around z axis [0.0-1.0]. + void moveToward(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot move at the given speed in normalized speed fraction. This is a blocking call. + /// + /// The speed along x axis [0.0-1.0]. + /// The speed along y axis [0.0-1.0]. + /// The anglular speed around z axis [0.0-1.0]. + /// An ALValue with custom move configuration. + void moveToward(const float& x, const float& y, const float& theta, const AL::ALValue& moveConfig); + + /// + /// Makes the robot navigate to a relative metrical target pose2D expressed in FRAME_ROBOT. The robot computes a path to avoid obstacles. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + bool navigateTo(const float& x, const float& y); + + /// + /// Makes the robot navigate to a relative metrical target pose2D expressed in FRAME_ROBOT. The robot computes a path to avoid obstacles. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// Configuration ALValue. For example, [["SpeedFactor", 0.5]] sets speedFactor to 0.5 + bool navigateTo(const float& x, const float& y, const AL::ALValue& config); + + /// + /// Makes the robot navigate to a relative metrical target pose2D expressed in FRAME_ROBOT. The robot computes a path to avoid obstacles. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// Orientation of the robot (rad). + bool navigateTo(const float& x, const float& y, const float& theta); + + /// + /// Makes the robot navigate to a relative metrical target pose2D expressed in FRAME_ROBOT. The robot computes a path to avoid obstacles. + /// + /// The position along x axis [m]. + /// The position along y axis [m]. + /// Orientation of the robot (rad). + /// Configuration ALValue. For example, [["SpeedFactor", 0.5]] sets speedFactor to 0.5 + bool navigateTo(const float& x, const float& y, const float& theta, const AL::ALValue& config); + + /// + /// . + /// + /// arg + /// arg + /// arg + void onTouchChanged(const std::string& arg1, const AL::ALValue& arg2, const std::string& arg3); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Distance in meters fromwhich the robot should stop if there is an obstacle. + /// + /// arg + void setSecurityDistance(const float& arg1); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops the navigateTo. + /// + void stopNavigateTo(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALNavigationProxyPostHandler post; + }; + +} +#endif // ALNAVIGATIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alnotificationmanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alnotificationmanagerproxy.h new file mode 100755 index 0000000..798b146 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alnotificationmanagerproxy.h @@ -0,0 +1,206 @@ +// Generated for ALNotificationManager version 0 + +#ifndef ALNOTIFICATIONMANAGERPROXY_H_ +#define ALNOTIFICATIONMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALNotificationManagerProxy; + + namespace detail { + class ALNotificationManagerProxyPostHandler + { + protected: + ALNotificationManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALNotificationManagerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Remove a notification. + /// + /// Notification ID to remove. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int remove(const int& notificationId); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALNotificationManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALNotificationManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALNotificationManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALNotificationManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALNotificationManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Add a notification. + /// + /// Contain information for the notification + /// Notification ID. + int add(const AL::ALValue& notification); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Get one notification. + /// + /// Notification ID. + /// ALValue containing a Notification. + AL::ALValue notification(const int& notificationId); + + /// + /// Get the all array of pending notifications. + /// + /// An array of pending notification. + AL::ALValue notifications(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Remove a notification. + /// + /// Notification ID to remove. + void remove(const int& notificationId); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALNotificationManagerProxyPostHandler post; + }; + +} +#endif // ALNOTIFICATIONMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alobjectdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alobjectdetectionproxy.h new file mode 100755 index 0000000..36241b0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alobjectdetectionproxy.h @@ -0,0 +1,501 @@ +// Generated for ALObjectDetection version 1.18 + +#ifndef ALOBJECTDETECTIONPROXY_H_ +#define ALOBJECTDETECTIONPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALObjectDetectionProxy; + + namespace detail { + class ALObjectDetectionProxyPostHandler + { + protected: + ALObjectDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALObjectDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// set the cascade file to use + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCascadeFile(const std::string& strCascadeFilename); + + /// + /// Set the crop margins for saving the detected objects' images. + /// + /// Margin around object (default: 16) + /// (default:40) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCropMargin(const int& nCropWidthMargin, const int& nCropHeightMargin); + + /// + /// Enable some outputting, helping testing and understanding. + /// + /// true to enable debug mode. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDebugEnabled(const bool& bNewState); + + /// + /// Sets the minimum number of underlying detections (acts like a confidence threshold) + /// + /// new parameter to use (default: 2) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMinNeighbors(const int& nMinNeighbors); + + /// + /// Sets the minimum object size for detection + /// + /// Horizontal size + /// Vertical size + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMinSize(const int& nMinSizeX, const int& nMinSizeY); + + /// + /// Set the path where to save the detected objects' images. + /// + /// Path where to save images. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSavePath(const std::string& strDestinationPath); + + /// + /// Enable or disable the saving of each detected object's image. + /// + /// true to enable saving images. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSavingEnabled(const bool& bNewState); + + /// + /// change some cascade parameter(s) (will be updated on the fly on next frame) + /// + /// new parameter to use + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setScaleFactor(const float& rScaleFactor); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module uses an xml trainout file to detect objects by means of Haar-like features + /// \ingroup ALProxies + class ALPROXIES_API ALObjectDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALObjectDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALObjectDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALObjectDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALObjectDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Detect things from image file, using previously set cascade + /// + /// filename containing file + /// list of found area: [[x,y,w,h],neighbours,[headX,headY],(strCreatedCroppedFilename, empty or None if not applicable),(opencv image pointer (not dev)(empty or NONE))] neighbours give an idea of the confidence, it's an int roughly in [0..60]. strCreatedCroppedFilename: filename created containing objects (see saveDetected). + AL::ALValue analyzeFile(const std::string& strImageFilename); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// + /// + /// + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns the filename of the cascade file used for detection. + /// + /// Name of the cascade file. + AL::ALValue getCascadeFile(); + + /// + /// Returns the crop margins currently set for saving the detected objects' images. + /// + /// + AL::ALValue getCropMargin(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// + /// + /// + int getFrameRate(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Returns the minimum number of neighbors set for the algorithm. + /// + /// + AL::ALValue getMinNeighbors(); + + /// + /// Returns the minimum object size currently set for detection + /// + /// Minimum horizontal and vertical size + AL::ALValue getMinSize(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// + /// + /// + int getResolution(); + + /// + /// Returns the path currently set for saving the detected objects' images. + /// + /// Path where to save images. + AL::ALValue getSavePath(); + + /// + /// Returns used scale factor. + /// + /// Used scale factor. + AL::ALValue getScaleFactor(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if debug is enabled, else returns false + /// + /// + AL::ALValue isDebugEnabled(); + + /// + /// + /// + /// + bool isPaused(); + + /// + /// + /// + /// + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Returns true if saving is enabled, else returns false + /// + /// + AL::ALValue isSavingEnabled(); + + /// + /// + /// + /// arg + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// + /// + /// arg + /// + bool setActiveCamera(const int& cameraID); + + /// + /// set the cascade file to use + /// + /// arg + void setCascadeFile(const std::string& strCascadeFilename); + + /// + /// Set the crop margins for saving the detected objects' images. + /// + /// Margin around object (default: 16) + /// (default:40) + void setCropMargin(const int& nCropWidthMargin, const int& nCropHeightMargin); + + /// + /// Enable some outputting, helping testing and understanding. + /// + /// true to enable debug mode. + void setDebugEnabled(const bool& bNewState); + + /// + /// + /// + /// arg + /// + bool setFrameRate(const int& value); + + /// + /// Sets the minimum number of underlying detections (acts like a confidence threshold) + /// + /// new parameter to use (default: 2) + void setMinNeighbors(const int& nMinNeighbors); + + /// + /// Sets the minimum object size for detection + /// + /// Horizontal size + /// Vertical size + void setMinSize(const int& nMinSizeX, const int& nMinSizeY); + + /// + /// + /// + /// arg + /// + bool setResolution(const int& resolution); + + /// + /// Set the path where to save the detected objects' images. + /// + /// Path where to save images. + void setSavePath(const std::string& strDestinationPath); + + /// + /// Enable or disable the saving of each detected object's image. + /// + /// true to enable saving images. + void setSavingEnabled(const bool& bNewState); + + /// + /// change some cascade parameter(s) (will be updated on the fly on next frame) + /// + /// new parameter to use + void setScaleFactor(const float& rScaleFactor); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALObjectDetectionProxyPostHandler post; + }; + +} +#endif // ALOBJECTDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alpanoramacompassproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpanoramacompassproxy.h new file mode 100755 index 0000000..a514e37 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpanoramacompassproxy.h @@ -0,0 +1,274 @@ +// Generated for ALPanoramaCompass version 0 + +#ifndef ALPANORAMACOMPASSPROXY_H_ +#define ALPANORAMACOMPASSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPanoramaCompassProxy; + + namespace detail { + class ALPanoramaCompassProxyPostHandler + { + protected: + ALPanoramaCompassProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPanoramaCompassProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPanoramaCompassProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPanoramaCompassProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPanoramaCompassProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPanoramaCompassProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPanoramaCompassProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// arg + int clearAllPanoramas(const bool& arg1); + + /// + /// Delete all panorama files in the current working directory + /// + int clearAllPanoramas(); + + /// + /// Delete all files related to a given panorama in the current working directory + /// + /// Panorama identity + int clearPanorama(const int& pIdentity); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// + /// + /// Return an ALValue containing Panorama identity and contained Frames identity. + AL::ALValue getCurrentPanoramaDescriptor(); + + /// + /// Return the current orientation of the robot in the current panorama. + /// + AL::ALValue getCurrentPosition(); + + /// + /// Return the Frame corresponding to the input identity. It have to be in the current Panorama + /// + /// Identity of the resquested Frame. + /// arg + /// ALValue containing the Frame image part. + AL::ALValue getFrame(const int& id, const std::string& arg2); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if there is some panorama data + /// + bool isDataAvailable(); + + /// + /// Check if the robot is in the current Panorama. + /// + /// Error status. + int isInPanorama(); + + /// + /// Check if the robot is in the current Panorama. + /// + /// arg + /// Error status. + int isInPanorama(const int& arg1); + + /// + /// Is a relocalization movement required. + /// + bool isRelocalizationRequired(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Load the panorama corresponding to the input identity from the hard drive. It has to exist. + /// + /// Identity of the requested Panorama. + /// Error status. + int loadPanorama(const int& id); + + /// + /// Localize the robot using the scan. + /// + /// Localization mode + std::vector localize(); + + /// + /// Localize the robot using the scan. + /// + /// Localization mode + std::vector localize(const bool& pMode); + + /// + /// Localize the robot using the scan. + /// + /// Localization mode + std::vector localize(const int& pMode); + + /// + /// Localize the robot using the scan. + /// + /// Localization mode + /// arg + std::vector localize(const int& pMode, const bool& arg2); + + /// + /// Localize the robot using the scan,without hint. + /// + std::vector localizeNoHint(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Shoot a panorama at the current position. + /// + int setupPanorama(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPanoramaCompassProxyPostHandler post; + }; + +} +#endif // ALPANORAMACOMPASSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alpeopleperceptionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpeopleperceptionproxy.h new file mode 100755 index 0000000..20be55e --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpeopleperceptionproxy.h @@ -0,0 +1,503 @@ +// Generated for ALPeoplePerception version 0 + +#ifndef ALPEOPLEPERCEPTIONPROXY_H_ +#define ALPEOPLEPERCEPTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPeoplePerceptionProxy; + + namespace detail { + class ALPeoplePerceptionProxyPostHandler + { + protected: + ALPeoplePerceptionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPeoplePerceptionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Empties the tracked population. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetPopulation(); + + /// + /// Turns face detection on or off. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFaceDetectionEnabled(const bool& enable); + + /// + /// Turns fast mode on or off. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFastModeEnabled(const bool& enable); + + /// + /// Turns graphical display in Choregraphe on or off. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setGraphicalDisplayEnabled(const bool& enable); + + /// + /// Sets the maximum human body height (3D mode only). + /// + /// Maximum height in meters. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMaximumBodyHeight(const float& height); + + /// + /// Sets the maximum range for human detection and tracking. + /// + /// Maximum range in meters. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMaximumDetectionRange(const float& range); + + /// + /// Sets the minimum human body height (3D mode only). + /// + /// Minimum height in meters. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMinimumBodyHeight(const float& height); + + /// + /// Turns movement detection on or off. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMovementDetectionEnabled(const bool& enable); + + /// + /// Sets the time after which a person, supposed not to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTimeBeforePersonDisappears(const float& seconds); + + /// + /// Sets the time after which a person, supposed to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTimeBeforeVisiblePersonDisappears(const float& seconds); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPeoplePerceptionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPeoplePerceptionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPeoplePerceptionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPeoplePerceptionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPeoplePerceptionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets the current maximum body height used for human detection (3D mode only). + /// + /// Maximum height in meters. + float getMaximumBodyHeight(); + + /// + /// Gets the current maximum detection and tracking range. + /// + /// Maximum range in meters. + float getMaximumDetectionRange(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Gets the current minimum body height used for human detection (3D mode only). + /// + /// Minimum height in meters. + float getMinimumBodyHeight(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the time after which a person, supposed not to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + float getTimeBeforePersonDisappears(); + + /// + /// Gets the time after which a person, supposed to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + float getTimeBeforeVisiblePersonDisappears(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets the current status of face detection. + /// + /// True if face detection is enabled, False otherwise. + bool isFaceDetectionEnabled(); + + /// + /// Gets the current status of fast mode. + /// + /// True if fast mode is enabled, False otherwise. + bool isFastModeEnabled(); + + /// + /// Gets the current status of graphical display in Choregraphe. + /// + /// True if graphical display is enabled, False otherwise. + bool isGraphicalDisplayEnabled(); + + /// + /// Gets the current status of movement detection in Choregraphe. + /// + /// True if movement detection is enabled, False otherwise. + bool isMovementDetectionEnabled(); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Empties the tracked population. + /// + void resetPopulation(); + + /// + /// Turns face detection on or off. + /// + /// True to turn it on, False to turn it off. + void setFaceDetectionEnabled(const bool& enable); + + /// + /// Turns fast mode on or off. + /// + /// True to turn it on, False to turn it off. + void setFastModeEnabled(const bool& enable); + + /// + /// Turns graphical display in Choregraphe on or off. + /// + /// True to turn it on, False to turn it off. + void setGraphicalDisplayEnabled(const bool& enable); + + /// + /// Sets the maximum human body height (3D mode only). + /// + /// Maximum height in meters. + void setMaximumBodyHeight(const float& height); + + /// + /// Sets the maximum range for human detection and tracking. + /// + /// Maximum range in meters. + void setMaximumDetectionRange(const float& range); + + /// + /// Sets the minimum human body height (3D mode only). + /// + /// Minimum height in meters. + void setMinimumBodyHeight(const float& height); + + /// + /// Turns movement detection on or off. + /// + /// True to turn it on, False to turn it off. + void setMovementDetectionEnabled(const bool& enable); + + /// + /// Sets the time after which a person, supposed not to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + void setTimeBeforePersonDisappears(const float& seconds); + + /// + /// Sets the time after which a person, supposed to be in the field of view of the camera disappears if it has not been detected. + /// + /// Time in seconds. + void setTimeBeforeVisiblePersonDisappears(const float& seconds); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPeoplePerceptionProxyPostHandler post; + }; + +} +#endif // ALPEOPLEPERCEPTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alphotocaptureproxy.h b/naoModule/libnaoqi_files/include/alproxies/alphotocaptureproxy.h new file mode 100755 index 0000000..7c0a793 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alphotocaptureproxy.h @@ -0,0 +1,335 @@ +// Generated for ALPhotoCapture version 0 + +#ifndef ALPHOTOCAPTUREPROXY_H_ +#define ALPHOTOCAPTUREPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPhotoCaptureProxy; + + namespace detail { + class ALPhotoCaptureProxyPostHandler + { + protected: + ALPhotoCaptureProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPhotoCaptureProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Sets camera ID. + /// + /// ID of the camera to use. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCameraID(const int& cameraID); + + /// + /// Sets delay between two captures. + /// + /// New delay (in ms) between two pictures. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCaptureInterval(const int& captureInterval); + + /// + /// Sets color space. + /// + /// New color space. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setColorSpace(const int& colorSpace); + + /// + /// Enables or disables the half-press mode. + /// + /// True to enable, false to disable. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setHalfPressEnabled(const bool& enable); + + /// + /// Sets picture extension. + /// + /// New extension used to save pictures. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPictureFormat(const std::string& pictureFormat); + + /// + /// Sets resolution. + /// + /// New frame resolution. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPhotoCaptureProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPhotoCaptureProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPhotoCaptureProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPhotoCaptureProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPhotoCaptureProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns current camera ID. + /// + /// Current camera ID. + int getCameraID(); + + /// + /// Returns current delay between captures. + /// + /// Current delay (in ms) between two pictures. + int getCaptureInterval(); + + /// + /// Returns current color space. + /// + /// Current color space. + int getColorSpace(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Returns current picture format. + /// + /// Current picture format. + std::string getPictureFormat(); + + /// + /// Returns current resolution. + /// + /// Current frame resolution. + int getResolution(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Manually (un)subscribes to ALVideoDevice. + /// + /// True if eveything went well, False otherwise. + bool halfPress(); + + /// + /// Returns True if the "half press" mode is on. + /// + /// True or False. + bool isHalfPressEnabled(); + + /// + /// Returns True if the "half press" mode is on. + /// + /// True or False. + bool isHalfPressed(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets camera ID. + /// + /// ID of the camera to use. + void setCameraID(const int& cameraID); + + /// + /// Sets delay between two captures. + /// + /// New delay (in ms) between two pictures. + void setCaptureInterval(const int& captureInterval); + + /// + /// Sets color space. + /// + /// New color space. + void setColorSpace(const int& colorSpace); + + /// + /// Enables or disables the half-press mode. + /// + /// True to enable, false to disable. + void setHalfPressEnabled(const bool& enable); + + /// + /// Sets picture extension. + /// + /// New extension used to save pictures. + void setPictureFormat(const std::string& pictureFormat); + + /// + /// Sets resolution. + /// + /// New frame resolution. + void setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Takes one picture. + /// + /// Folder where the picture is saved. + /// Filename used to save the picture. + /// Full file name of the picture saved on the disk: [filename] + AL::ALValue takePicture(const std::string& folderPath, const std::string& fileName); + + /// + /// Takes one picture. + /// + /// Folder where the picture is saved. + /// Filename used to save the picture. + /// If false and the filename already exists, an error is thrown. + /// Full file name of the picture saved on the disk: [filename] + AL::ALValue takePicture(const std::string& folderPath, const std::string& fileName, const bool& overwrite); + + /// + /// Takes several pictures as quickly as possible + /// + /// Number of pictures to take + /// Folder where the pictures are saved. + /// Filename used to save the pictures. + /// List of all saved files: [[filename1, filename2...]] + AL::ALValue takePictures(const int& numberOfPictures, const std::string& folderPath, const std::string& fileName); + + /// + /// Takes several pictures as quickly as possible + /// + /// Number of pictures to take + /// Folder where the pictures are saved. + /// Filename used to save the pictures. + /// If false and the filename already exists, an error is thrown. + /// List of all saved files: [[filename1, filename2...]] + AL::ALValue takePictures(const int& numberOfPictures, const std::string& folderPath, const std::string& fileName, const bool& overwrite); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPhotoCaptureProxyPostHandler post; + }; + +} +#endif // ALPHOTOCAPTUREPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alpreferencemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpreferencemanagerproxy.h new file mode 100755 index 0000000..19a50e1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpreferencemanagerproxy.h @@ -0,0 +1,269 @@ +// Generated for ALPreferenceManager version 0 + +#ifndef ALPREFERENCEMANAGERPROXY_H_ +#define ALPREFERENCEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPreferenceManagerProxy; + + namespace detail { + class ALPreferenceManagerProxyPostHandler + { + protected: + ALPreferenceManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPreferenceManagerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Import a preferences XML file + /// + /// Preference domain: all preferences values found in XML file will be imported in that domain. + /// Application name: will be used to search for preference file on disk (in location of type /applicationName/filename). + /// Preference XML filename + /// Set this to true if you want to override preferences that already exist with preferences in imported XML file + /// brokerTaskID : The ID of the task assigned to it by the broker. + int importPrefFile(const std::string& domain, const std::string& applicationName, const std::string& filename, const bool& override); + + /// + /// Remove an entire preference domain + /// + /// Preference domain + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeDomainValues(const std::string& domain); + + /// + /// Remove specified preference + /// + /// Preference domain + /// Preference setting + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeValue(const std::string& domain, const std::string& setting); + + /// + /// Set specified preference + /// + /// Preference domain + /// Preference setting + /// Preference value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setValue(const std::string& domain, const std::string& setting, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Synchronizes local preferences with preferences stored on a server. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int update(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPreferenceManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPreferenceManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPreferenceManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPreferenceManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPreferenceManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get available preferences domain + /// + /// a list containing all the available domain names + std::vector getDomainList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get specified preference + /// + /// Preference domain + /// Preference setting + /// corresponding preferences value + AL::ALValue getValue(const std::string& domain, const std::string& setting); + + /// + /// Get preferences names and values for a given domain + /// + /// Preference domain + /// a list of preferences names and values associated to the domain + std::vector > getValueList(const std::string& domain); + + /// + /// Import a preferences XML file + /// + /// Preference domain: all preferences values found in XML file will be imported in that domain. + /// Application name: will be used to search for preference file on disk (in location of type /applicationName/filename). + /// Preference XML filename + /// Set this to true if you want to override preferences that already exist with preferences in imported XML file + void importPrefFile(const std::string& domain, const std::string& applicationName, const std::string& filename, const bool& override); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Remove an entire preference domain + /// + /// Preference domain + void removeDomainValues(const std::string& domain); + + /// + /// Remove specified preference + /// + /// Preference domain + /// Preference setting + void removeValue(const std::string& domain, const std::string& setting); + + /// + /// Set specified preference + /// + /// Preference domain + /// Preference setting + /// Preference value + void setValue(const std::string& domain, const std::string& setting, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Synchronizes local preferences with preferences stored on a server. + /// + void update(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPreferenceManagerProxyPostHandler post; + }; + +} +#endif // ALPREFERENCEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alpreferencesproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpreferencesproxy.h new file mode 100755 index 0000000..c6c1122 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpreferencesproxy.h @@ -0,0 +1,218 @@ +// Generated for ALPreferences version 0 + +#ifndef ALPREFERENCESPROXY_H_ +#define ALPREFERENCESPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPreferencesProxy; + + namespace detail { + class ALPreferencesProxyPostHandler + { + protected: + ALPreferencesProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPreferencesProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Remove the xml file. + /// + /// Name of the module associated to the preference. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removePrefFile(const std::string& fileName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Writes all preferences from ALValue to an xml file. + /// + /// Name of the module associated to the preference. + /// array reprenting the whole file. + /// If true all memory names will be removed before saving. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int writePrefFile(const std::string& fileName, const AL::ALValue& prefs, const bool& ignoreMemoryNames); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPreferencesProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPreferencesProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPreferencesProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPreferencesProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPreferencesProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Reads all preferences from an xml files and stores them in an ALValue. + /// + /// Name of the module associated to the preference. + /// If true a memory name will be generated for each non-array preference. + /// array reprenting the whole file. + AL::ALValue readPrefFile(const std::string& fileName, const bool& autoGenerateMemoryNames); + + /// + /// Remove the xml file. + /// + /// Name of the module associated to the preference. + void removePrefFile(const std::string& fileName); + + /// + /// Writes all preferences from ALValue to an xml file. + /// + /// array representing the whole file. + /// True upon success. + bool saveToMemory(const AL::ALValue& prefs); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Writes all preferences from ALValue to an xml file. + /// + /// Name of the module associated to the preference. + /// array reprenting the whole file. + /// If true all memory names will be removed before saving. + void writePrefFile(const std::string& fileName, const AL::ALValue& prefs, const bool& ignoreMemoryNames); + + + detail::ALPreferencesProxyPostHandler post; + }; + +} +#endif // ALPREFERENCESPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alproxies.h b/naoModule/libnaoqi_files/include/alproxies/alproxies.h new file mode 100755 index 0000000..3b81356 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alproxies.h @@ -0,0 +1,101 @@ +#ifndef __GENERATED_alproxies__ +#define __GENERATED_alproxies__ +#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 +#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 +#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 +#include +#include +#include +#include +#include +#endif diff --git a/naoModule/libnaoqi_files/include/alproxies/alpwtiupdateproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpwtiupdateproxy.h new file mode 100755 index 0000000..1d1ba83 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpwtiupdateproxy.h @@ -0,0 +1,468 @@ +// Generated for ALPwtiUpdate version 1.17 + +#ifndef ALPWTIUPDATEPROXY_H_ +#define ALPWTIUPDATEPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPwtiUpdateProxy; + + namespace detail { + class ALPwtiUpdateProxyPostHandler + { + protected: + ALPwtiUpdateProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPwtiUpdateProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsApproached(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsDecayNotVisible(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsDecayZone1(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsDecayZone2(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsDecayZone3(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsMadeNoiseLooking(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsMadeNoiseNotVisible(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsMovedAway(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsStartLooking(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsStopLooking(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsWaving(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsZone1(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsZone2(const float& arg1); + + /// + /// Points setter + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setPointsZone3(const float& arg1); + + /// + /// Shows points for differents events + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int showPointsValuesForEvents(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module computes an 'Interaction' score for each person who is near the robot. The score is increased when the person is looking for the robot's attention (waving, talking, ...) and is decreased when he/she is not + /// \ingroup ALProxies + class ALPROXIES_API ALPwtiUpdateProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPwtiUpdateProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPwtiUpdateProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPwtiUpdateProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPwtiUpdateProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + ///Exits and unregisters the module. + /// + void exit(); + + /// + ///Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + ///Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + ///Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + ///Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + ///Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + ///Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + ///Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + ///Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + ///Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + ///Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + ///Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + ///Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + ///Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + ///Points setter + /// + /// arg + void setPointsApproached(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsDecayNotVisible(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsDecayZone1(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsDecayZone2(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsDecayZone3(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsMadeNoiseLooking(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsMadeNoiseNotVisible(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsMovedAway(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsStartLooking(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsStopLooking(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsWaving(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsZone1(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsZone2(const float& arg1); + + /// + ///Points setter + /// + /// arg + void setPointsZone3(const float& arg1); + + /// + ///Shows points for differents events + /// + void showPointsValuesForEvents(); + + /// + ///returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + ///Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData(\"keyName\"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + ///Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + ///Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + ///Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + ///Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + ///Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPwtiUpdateProxyPostHandler post; + + }; + +} +#endif // ALPWTIUPDATEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alpythonbridgeproxy.h b/naoModule/libnaoqi_files/include/alproxies/alpythonbridgeproxy.h new file mode 100755 index 0000000..ab3acf0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alpythonbridgeproxy.h @@ -0,0 +1,194 @@ +// Generated for ALPythonBridge version 0 + +#ifndef ALPYTHONBRIDGEPROXY_H_ +#define ALPYTHONBRIDGEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALPythonBridgeProxy; + + namespace detail { + class ALPythonBridgeProxyPostHandler + { + protected: + ALPythonBridgeProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALPythonBridgeProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALPythonBridgeProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALPythonBridgeProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALPythonBridgeProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALPythonBridgeProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALPythonBridgeProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// eval script + /// + /// string to eval + /// if the evaluation has gone wrong + std::string eval(const std::string& stringToEvaluate); + + /// + /// evaluates script and returns an informative array. + /// + /// string to eval + /// an array containing [return value, exceptions, stdout, stderr] + AL::ALValue evalFull(const std::string& stringToEvaluate); + + /// + /// eval script and return result. evalReturn(2+2) will return 4 + /// + /// string to eval + /// the result of the evaluation + AL::ALValue evalReturn(const std::string& stringToEvaluate); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALPythonBridgeProxyPostHandler post; + }; + +} +#endif // ALPYTHONBRIDGEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alredballdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alredballdetectionproxy.h new file mode 100755 index 0000000..362f924 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alredballdetectionproxy.h @@ -0,0 +1,296 @@ +// Generated for ALRedBallDetection version 0 + +#ifndef ALREDBALLDETECTIONPROXY_H_ +#define ALREDBALLDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALRedBallDetectionProxy; + + namespace detail { + class ALRedBallDetectionProxyPostHandler + { + protected: + ALRedBallDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALRedBallDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALRedBallDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALRedBallDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALRedBallDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALRedBallDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALRedBallDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALRedBallDetectionProxyPostHandler post; + }; + +} +#endif // ALREDBALLDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alredballtrackerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alredballtrackerproxy.h new file mode 100755 index 0000000..24a2783 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alredballtrackerproxy.h @@ -0,0 +1,241 @@ +// Generated for ALRedBallTracker version 0 + +#ifndef ALREDBALLTRACKERPROXY_H_ +#define ALREDBALLTRACKERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALRedBallTrackerProxy; + + namespace detail { + class ALRedBallTrackerProxyPostHandler + { + protected: + ALRedBallTrackerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALRedBallTrackerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// If true, the tracking will be through a Whole Body Process. + /// + /// + /// The whole Body state + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWholeBodyOn(const bool& pWholeBodyOn); + + /// + /// Start the tracker by Subscribing to Event redBallDetected from ALRedBallDetection module. + /// Then Wait Event redBallDetected from ALRedBallDetection module. + /// And finally send information to motion for head tracking. + /// NOTE: Stiffness of Head must be set to 1.0 to move! + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startTracker(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop the tracker by Unsubscribing to Event redBallDetected from ALRedBallDetection module. + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopTracker(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALRedBallTrackerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALRedBallTrackerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALRedBallTrackerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALRedBallTrackerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALRedBallTrackerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Return the position of the red ball in FRAME_TORSO. + /// + /// + /// An Array of float containing the red ball position [x, y, z]. + std::vector getPosition(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Return true if the red Ball Tracker is running. + /// + /// + /// true if the red Ball Tracker is running. + bool isActive(); + + /// + /// Return true if a new Red Ball was detected since the last getPosition(). + /// + /// + /// true if a new Red Ball was detected since the last getPosition(). + bool isNewData(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// If true, the tracking will be through a Whole Body Process. + /// + /// + /// The whole Body state + void setWholeBodyOn(const bool& pWholeBodyOn); + + /// + /// Start the tracker by Subscribing to Event redBallDetected from ALRedBallDetection module. + /// Then Wait Event redBallDetected from ALRedBallDetection module. + /// And finally send information to motion for head tracking. + /// NOTE: Stiffness of Head must be set to 1.0 to move! + /// + /// + void startTracker(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop the tracker by Unsubscribing to Event redBallDetected from ALRedBallDetection module. + /// + /// + void stopTracker(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALRedBallTrackerProxyPostHandler post; + }; + +} +#endif // ALREDBALLTRACKERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alresourcemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alresourcemanagerproxy.h new file mode 100755 index 0000000..5cbccb7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alresourcemanagerproxy.h @@ -0,0 +1,394 @@ +// Generated for ALResourceManager version 0 + +#ifndef ALRESOURCEMANAGERPROXY_H_ +#define ALRESOURCEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALResourceManagerProxy; + + namespace detail { + class ALResourceManagerProxyPostHandler + { + protected: + ALResourceManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALResourceManagerProxy; + + /// + /// Wait and acquire a resource + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int acquireResource(const std::string& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// Wait for resource tree. Parent and children are not in conflict. Local function + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int acquireResourcesTree(const std::vector& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// Create a resource + /// + /// Resource name to create + /// Parent resource name or empty string for root resource + /// brokerTaskID : The ID of the task assigned to it by the broker. + int createResource(const std::string& resourceName, const std::string& parentResourceName); + + /// + /// True if a resource is in another parent resource + /// + /// Group name. Ex: Arm + /// Resource name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int createResourcesList(const std::vector& resourceGroupName, const std::string& resourceName); + + /// + /// Delete a root resource + /// + /// Resource name to delete + /// DEPRECATED: Delete child resources if true + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deleteResource(const std::string& resourceName, const bool& deleteChildResources); + + /// + /// Enable or disable a state resource + /// + /// The name of the resource that you wish enable of disable. e.g. Standing + /// True to enable, false to disable + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableStateResource(const std::string& resourceName, const bool& enabled); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Release resource + /// + /// Resource name + /// Existing owner name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int releaseResource(const std::string& resourceName, const std::string& ownerName); + + /// + /// Release resources list + /// + /// Resource names + /// Owner name + /// brokerTaskID : The ID of the task assigned to it by the broker. + int releaseResources(const std::vector& resourceNames, const std::string& ownerName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Wait resource + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int waitForResource(const std::string& resourceName, const std::string& ownerName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// Wait for resource tree. Parent and children are not in conflict. Local function + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int waitForResourcesTree(const std::vector& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALResourceManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALResourceManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALResourceManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALResourceManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALResourceManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Wait and acquire a resource + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + void acquireResource(const std::string& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// Wait for resource tree. Parent and children are not in conflict. Local function + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + void acquireResourcesTree(const std::vector& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// True if all resources are free + /// + /// Resource names + /// True if all the specify resources are free + bool areResourcesFree(const std::vector& resourceNames); + + /// + /// True if all the specified resources are owned by the owner + /// + /// Resource name + /// Owner pointer with hierarchy + /// True if all the specify resources are owned by the owner + bool areResourcesOwnedBy(const std::vector& resourceNameList, const std::string& ownerName); + + /// + /// check if all the state resource in the list are free + /// + /// Resource name + bool checkStateResourceFree(const std::vector& resourceName); + + /// + /// Create a resource + /// + /// Resource name to create + /// Parent resource name or empty string for root resource + void createResource(const std::string& resourceName, const std::string& parentResourceName); + + /// + /// True if a resource is in another parent resource + /// + /// Group name. Ex: Arm + /// Resource name + void createResourcesList(const std::vector& resourceGroupName, const std::string& resourceName); + + /// + /// Delete a root resource + /// + /// Resource name to delete + /// DEPRECATED: Delete child resources if true + void deleteResource(const std::string& resourceName, const bool& deleteChildResources); + + /// + /// Enable or disable a state resource + /// + /// The name of the resource that you wish enable of disable. e.g. Standing + /// True to enable, false to disable + void enableStateResource(const std::string& resourceName, const bool& enabled); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get tree of resources + /// + AL::ALValue getResources(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// True if a resource is in another parent resource + /// + /// Group name. Ex: Arm + /// Resource name + bool isInGroup(const std::string& resourceGroupName, const std::string& resourceName); + + /// + /// True if the resource is free + /// + /// Resource name + /// True if the specify resources is free + bool isResourceFree(const std::string& resourceNames); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// The tree of the resources owners. + /// + AL::ALValue ownersGet(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Release resource + /// + /// Resource name + /// Existing owner name + void releaseResource(const std::string& resourceName, const std::string& ownerName); + + /// + /// Release resources list + /// + /// Resource names + /// Owner name + void releaseResources(const std::vector& resourceNames, const std::string& ownerName); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Wait resource + /// + /// arg + /// arg + /// arg + /// arg + /// arg + std::vector waitForOptionalResourcesTree(const std::vector& arg1, const std::string& arg2, const std::string& arg3, const int& arg4, const std::vector& arg5); + + /// + /// Wait resource + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + void waitForResource(const std::string& resourceName, const std::string& ownerName, const std::string& callbackName, const int& timeoutSeconds); + + /// + /// Wait for resource tree. Parent and children are not in conflict. Local function + /// + /// Resource name + /// Module name + /// callback name + /// Timeout in seconds + void waitForResourcesTree(const std::vector& resourceName, const std::string& moduleName, const std::string& callbackName, const int& timeoutSeconds); + + + detail::ALResourceManagerProxyPostHandler post; + }; + +} +#endif // ALRESOURCEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alrobotmodelproxy.h b/naoModule/libnaoqi_files/include/alproxies/alrobotmodelproxy.h new file mode 100755 index 0000000..61dc9be --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alrobotmodelproxy.h @@ -0,0 +1,179 @@ +// Generated for ALRobotModel version 0 + +#ifndef ALROBOTMODELPROXY_H_ +#define ALROBOTMODELPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALRobotModelProxy; + + namespace detail { + class ALRobotModelProxyPostHandler + { + protected: + ALRobotModelProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALRobotModelProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALRobotModelProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALRobotModelProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALRobotModelProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALRobotModelProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALRobotModelProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Return the RobotConfig key/value pairs serialized in xml format + /// + /// the RobotConfig key/value pairs in xml format + std::string getConfig(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALRobotModelProxyPostHandler post; + }; + +} +#endif // ALROBOTMODELPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alrobotposeproxy.h b/naoModule/libnaoqi_files/include/alproxies/alrobotposeproxy.h new file mode 100755 index 0000000..dd51be4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alrobotposeproxy.h @@ -0,0 +1,188 @@ +// Generated for ALRobotPose version 1.16 + +#ifndef ALROBOTPOSEPROXY_H_ +#define ALROBOTPOSEPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALRobotPoseProxy; + + namespace detail { + class ALRobotPoseProxyPostHandler + { + protected: + ALRobotPoseProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALRobotPoseProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module give the estimated Nao PoseDetects. + /// + /// .A MicroEvent is generated when the robot pose changed. A temporization of 500ms is apply before generated this MicroEvent. + /// + /// The ALMemory Key is robotPoseChanged, its a string corresponding to the actual robot Pose. + /// + /// Also some fast access Memory key are available : + /// + /// robotPose An integer in relation with the actual pose(use getPoseNames() to have a relation between int and string) + /// + /// robotPoseSince A float corresponding to the time in second since the actual Pose is active. + /// \ingroup ALProxies + class ALPROXIES_API ALRobotPoseProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALRobotPoseProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALRobotPoseProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALRobotPoseProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALRobotPoseProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + ///Exits and unregisters the module. + /// + void exit(); + + /// + ///Get the actual robot pose and the time since this pose was activate. + /// + /// A ALValue array of size 2. With first a string of the robot pose and + /// + /// then a float with the time in second since this pose is activated. + AL::ALValue getActualPoseAndTime(); + + /// + ///Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + ///Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + ///Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + ///Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + ///Get the full list of pose possibly return by this module. + /// + /// A ALValue array of string containing the possible Poses. + AL::ALValue getPoseNames(); + + /// + ///Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + ///Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + ///Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + ///returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + ///Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + ///Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALRobotPoseProxyPostHandler post; + + }; + +} +#endif // ALROBOTPOSEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alrobotpostureproxy.h b/naoModule/libnaoqi_files/include/alproxies/alrobotpostureproxy.h new file mode 100755 index 0000000..fe321a2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alrobotpostureproxy.h @@ -0,0 +1,234 @@ +// Generated for ALRobotPosture version 0 + +#ifndef ALROBOTPOSTUREPROXY_H_ +#define ALROBOTPOSTUREPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALRobotPostureProxy; + + namespace detail { + class ALRobotPostureProxyPostHandler + { + protected: + ALRobotPostureProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALRobotPostureProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Set maximum of tries ongoToPosture fail. + /// + /// Number of retry if goToPosture fail. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMaxTryNumber(const int& pMaxTryNumber); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop the posture move. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopMove(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALRobotPostureProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALRobotPostureProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALRobotPostureProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALRobotPostureProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALRobotPostureProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Set the angle of the joints of the robot to the choosen posture. + /// + /// Name of the desired posture. Use getPostureList to get the list of posture name available. + /// A fraction. + /// Returns if the posture was reached or not. + bool applyPosture(const std::string& postureName, const float& maxSpeedFraction); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Determine posture. + /// + std::string getPosture(); + + /// + /// Returns the posture family for example Standing, LyingBelly,... + /// + /// Returns the posture family, e.g. Standing. + std::string getPostureFamily(); + + /// + /// Get the list of posture family names available. + /// + std::vector getPostureFamilyList(); + + /// + /// Get the list of posture names available. + /// + std::vector getPostureList(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Make the robot go to the choosenposture. + /// + /// Name of the desired posture. Use getPostureList to get the list of posture name available. + /// A fraction. + /// Returns if the posture was reached or not. + bool goToPosture(const std::string& postureName, const float& maxSpeedFraction); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set maximum of tries ongoToPosture fail. + /// + /// Number of retry if goToPosture fail. + void setMaxTryNumber(const int& pMaxTryNumber); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop the posture move. + /// + void stopMove(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALRobotPostureProxyPostHandler post; + }; + +} +#endif // ALROBOTPOSTUREPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsegmentation3dproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsegmentation3dproxy.h new file mode 100755 index 0000000..b82f069 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsegmentation3dproxy.h @@ -0,0 +1,428 @@ +// Generated for ALSegmentation3D version 0 + +#ifndef ALSEGMENTATION3DPROXY_H_ +#define ALSEGMENTATION3DPROXY_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSegmentation3DProxy; + + namespace detail { + class ALSegmentation3DProxyPostHandler + { + protected: + ALSegmentation3DProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSegmentation3DProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Sets the distance (in meters) for the blob tracker + /// + /// New value (in meters) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBlobTrackingDistance(const float& distance); + + /// + /// Turn the blob tracker on or off. When the blob tracker is running, events containing the position of the top of the tracked blob are raised. + /// + /// True to turn it on, False to turn it off. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setBlobTrackingEnabled(const bool& status); + + /// + /// Sets the value of the depth threshold (in meters) used for the segmentation + /// + /// New depth threshold (in meters) for the segmentation + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDeltaDepthThreshold(const float& value); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVerticalOffset(const float& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSegmentation3DProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSegmentation3DProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSegmentation3DProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSegmentation3DProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSegmentation3DProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// + /// + int getActiveCamera(); + + /// + /// Gets the distance (in meters) for the blob tracker + /// + float getBlobTrackingDistance(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Gets the value of the depth threshold (in meters) used for the segmentation + /// + /// Current depth threshold (in meters) + float getDeltaDepthThreshold(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// + /// + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// + /// + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Returns the position of the top of the blob most in the center of the depth image, at the given distance, in the given frame. + /// + /// Estimation of the distance (in meters) of the blob or -1 for the nearest blob + /// Frame in which to return the position (-1: FRAME_IMAGE, 0: FRAME_TORSO, 1: FRAME_WORLD, 2: FRAME_ROBOT + /// True to apply the VerticalOffset when computing the position, False otherwise + /// Position of the top of the corresponding blob (if one is found) in the given frame (Format: [yaw,pitch,distance] in FRAME_IMAGE, [x,y,z] in the other frame). + AL::ALValue getTopOfBlob(const float& distance, const int& frame, const bool& applyVerticalOffset); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// Current vertical offset of the blob tracker + float getVerticalOffset(); + + /// + /// Gets the current status of the blob tracker. When the blob tracker is running, events containing the position of the top of the tracked blob are raised. + /// + /// True if the blob tracker is enabled, False otherwise. + bool isBlobTrackingEnabled(); + + /// + /// + /// + bool isPaused(); + + /// + /// + /// + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// + /// + /// + bool setActiveCamera(const int& cameraID); + + /// + /// Sets the distance (in meters) for the blob tracker + /// + /// New value (in meters) + void setBlobTrackingDistance(const float& distance); + + /// + /// Turn the blob tracker on or off. When the blob tracker is running, events containing the position of the top of the tracked blob are raised. + /// + /// True to turn it on, False to turn it off. + void setBlobTrackingEnabled(const bool& status); + + /// + /// Sets the value of the depth threshold (in meters) used for the segmentation + /// + /// New depth threshold (in meters) for the segmentation + void setDeltaDepthThreshold(const float& value); + + /// + /// + /// + /// + bool setFrameRate(const int& value); + + /// + /// + /// + /// + bool setResolution(const int& resolution); + + /// + /// Sets the value of vertical offset (in meters) for the blob tracker + /// + /// New vertical offset (in meters), added if positive, substracted if negative + void setVerticalOffset(const float& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSegmentation3DProxyPostHandler post; + }; + +} +#endif // ALSEGMENTATION3DPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsensorsproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsensorsproxy.h new file mode 100755 index 0000000..70aa8b5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsensorsproxy.h @@ -0,0 +1,307 @@ +// Generated for ALSensors version 0 + +#ifndef ALSENSORSPROXY_H_ +#define ALSENSORSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSensorsProxy; + + namespace detail { + class ALSensorsProxyPostHandler + { + protected: + ALSensorsProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSensorsProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Monitors sensors. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int run(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSensorsProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSensorsProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSensorsProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSensorsProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSensorsProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Monitors sensors. + /// + void run(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSensorsProxyPostHandler post; + }; + +} +#endif // ALSENSORSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alservicemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/alservicemanagerproxy.h new file mode 100755 index 0000000..dc5065f --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alservicemanagerproxy.h @@ -0,0 +1,208 @@ +// Generated for ALServiceManager version 0 + +#ifndef ALSERVICEMANAGERPROXY_H_ +#define ALSERVICEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALServiceManagerProxy; + + namespace detail { + class ALServiceManagerProxyPostHandler + { + protected: + ALServiceManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALServiceManagerProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALServiceManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALServiceManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALServiceManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALServiceManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALServiceManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Tell if a service is running or not + /// + /// Service's name + bool isServiceRunning(const std::string& name); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Restart a service of a package + /// + /// Service's name + bool restartService(const std::string& name); + + /// + /// Get the service's memory usage + /// + /// Service's name + qi::uint32_t serviceMemoryUsage(const std::string& name); + + /// + /// Get all declared services + /// + std::vector services(); + + /// + /// Start a service of a package + /// + /// Service's name + bool startService(const std::string& name); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop a service of a package + /// + /// Service's name + bool stopService(const std::string& name); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALServiceManagerProxyPostHandler post; + }; + +} +#endif // ALSERVICEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsittingpeopledetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsittingpeopledetectionproxy.h new file mode 100755 index 0000000..b212c00 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsittingpeopledetectionproxy.h @@ -0,0 +1,340 @@ +// Generated for ALSittingPeopleDetection version 0 + +#ifndef ALSITTINGPEOPLEDETECTIONPROXY_H_ +#define ALSITTINGPEOPLEDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSittingPeopleDetectionProxy; + + namespace detail { + class ALSittingPeopleDetectionProxyPostHandler + { + protected: + ALSittingPeopleDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSittingPeopleDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Sets sitting threshold + /// + /// float, face height (in meter) from the ground under which we consider thatsomeone is sitting. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setSittingThreshold(const float& threshold); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSittingPeopleDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSittingPeopleDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSittingPeopleDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSittingPeopleDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSittingPeopleDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets sitting threshold + /// + /// Maximum face height in meter + float getSittingThreshold(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets sitting threshold + /// + /// float, face height (in meter) from the ground under which we consider thatsomeone is sitting. + void setSittingThreshold(const float& threshold); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSittingPeopleDetectionProxyPostHandler post; + }; + +} +#endif // ALSITTINGPEOPLEDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsonarproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsonarproxy.h new file mode 100755 index 0000000..0ecb3fb --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsonarproxy.h @@ -0,0 +1,301 @@ +// Generated for ALSonar version 0 + +#ifndef ALSONARPROXY_H_ +#define ALSONARPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSonarProxy; + + namespace detail { + class ALSonarProxyPostHandler + { + protected: + ALSonarProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSonarProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSonarProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSonarProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSonarProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSonarProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSonarProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Returns a vector with rightand left filtered sonar values (in this order). Theses valuesare the distances to the nearest detected obstacle. + /// + std::vector getFilteredValues(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSonarProxyPostHandler post; + }; + +} +#endif // ALSONARPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsounddetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsounddetectionproxy.h new file mode 100755 index 0000000..9aa7776 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsounddetectionproxy.h @@ -0,0 +1,336 @@ +// Generated for ALSoundDetection version 0 + +#ifndef ALSOUNDDETECTIONPROXY_H_ +#define ALSOUNDDETECTIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSoundDetectionProxy; + + namespace detail { + class ALSoundDetectionProxyPostHandler + { + protected: + ALSoundDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSoundDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundDetection/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSoundDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSoundDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSoundDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSoundDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSoundDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundDetection/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + void setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSoundDetectionProxyPostHandler post; + }; + +} +#endif // ALSOUNDDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsoundlocalizationproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsoundlocalizationproxy.h new file mode 100755 index 0000000..f883494 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsoundlocalizationproxy.h @@ -0,0 +1,336 @@ +// Generated for ALSoundLocalization version 0 + +#ifndef ALSOUNDLOCALIZATIONPROXY_H_ +#define ALSOUNDLOCALIZATIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSoundLocalizationProxy; + + namespace detail { + class ALSoundLocalizationProxyPostHandler + { + protected: + ALSoundLocalizationProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSoundLocalizationProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundLocalization/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSoundLocalizationProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSoundLocalizationProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSoundLocalizationProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSoundLocalizationProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSoundLocalizationProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set the specified parameter. + /// + /// Name of the parameter. "Sensibility" between 0 and 1 to adjust the capacity of NAO to locate quiet sounds. "EnergyComputation" (1 or 0) that activates the computation of the located source signal energy. This energy is added in the "ALSoundLocalization/SoundLocated" ALMemory key. + /// "Sensibility" : a float in [0,1]. "EnergyComputation" : (1 or 0). + void setParameter(const std::string& parameter, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSoundLocalizationProxyPostHandler post; + }; + +} +#endif // ALSOUNDLOCALIZATIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alspeechrecognitionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alspeechrecognitionproxy.h new file mode 100755 index 0000000..2aa9e1a --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alspeechrecognitionproxy.h @@ -0,0 +1,706 @@ +// Generated for ALSpeechRecognition version 0 + +#ifndef ALSPEECHRECOGNITIONPROXY_H_ +#define ALSPEECHRECOGNITIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSpeechRecognitionProxy; + + namespace detail { + class ALSpeechRecognitionProxyPostHandler + { + protected: + ALSpeechRecognitionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSpeechRecognitionProxy; + + /// + /// Activate all rules contained in the specified context. + /// + /// Name of the context to modify. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int activateAllRules(const std::string& contextName); + + /// + /// Activate a rule contained in the specified context. + /// + /// Name of the context to modify. + /// Name of the rule to activate. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int activateRule(const std::string& contextName, const std::string& ruleName); + + /// + /// Add a context from a LCF file. + /// + /// Path to a LCF file. This LCF file contains the set of rules that should be recognized by the speech recognition engine. + /// Name of the context of your choice. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addContext(const std::string& pathToLCFFile, const std::string& contextName); + + /// + /// Add a list of words in a slot. A slot is a part of a context which can be modified. You can add a list of words that should be recognized by the speech recognition engine + /// + /// Name of the context to modify. + /// Name of the slot to modify. + /// List of words to insert in the slot. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addWordListToSlot(const std::string& contextName, const std::string& slotName, const std::vector& wordList); + + /// + /// + /// + /// arg + /// arg + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int compile(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// Deactivate all rules contained in the specified context. + /// + /// Name of the context to modify. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deactivateAllRules(const std::string& contextName); + + /// + /// Deactivate a rule contained in the specified context. + /// + /// Name of the context to modify. + /// Name of the rule to deactivate. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int deactivateRule(const std::string& contextName, const std::string& ruleName); + + /// + /// Erase a saved context set of the speech recognition engine + /// + /// Name under which the context set is saved + /// brokerTaskID : The ID of the task assigned to it by the broker. + int eraseContextSet(const std::string& saveName); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Load a saved context set of the speech recognition engine + /// + /// Name under which the context set is saved + /// brokerTaskID : The ID of the task assigned to it by the broker. + int loadContextSet(const std::string& saveName); + + /// + /// Loads the vocabulary to recognized contained in a .lxd file. This method is not available with the ASR engine language set to Chinese. For more informations see the red documentation + /// + /// Name of the lxd file containing the vocabulary + /// brokerTaskID : The ID of the task assigned to it by the broker. + int loadVocabulary(const std::string& vocabularyFile); + + /// + /// Stops and restarts the speech recognition engine according to the input parameter This can be used to add contexts, activate or deactivate rules of a contex, add a words to a slot. + /// + /// Boolean to enable or disable pause of the speech recognition engine. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& pause); + + /// + /// Disable current contexts and restore saved contexts of the speech recognition engine. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int popContexts(); + + /// + /// Disable current contexts of the speech recognition engine and save them in a stack. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pushContexts(); + + /// + /// Remove all contexts from the speech recognition engine. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeAllContext(); + + /// + /// Remove one context from the speech recognition engine. + /// + /// Name of the context to remove from the speech recognition engine. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeContext(const std::string& contextName); + + /// + /// Remove all words from a slot. + /// + /// Name of the context to modify. + /// Name of the slot to modify. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeWordListFromSlot(const std::string& contextName, const std::string& slotName); + + /// + /// Enables or disables the playing of sounds indicating the state of the recognition engine. If this option is enabled, a sound is played at the beginning of the recognition process (after a call to the subscribe method), and a sound is played when the user call the unsubscribe method + /// + /// Enable (true) or disable it (false). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAudioExpression(const bool& setOrNot); + + /// + /// Set the given parameter for the specified context. + /// + /// Name of the context + /// Name of the parameter to change + /// New parameter value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setContextParam(const std::string& contextName, const std::string& paramName, const float& value); + + /// + /// Sets the language used by the speech recognition engine. The list of the available languages can be collected through the getAvailableLanguages method. If you want to set a language as the default language (loading automatically at module launch), please refer to the web page of the robot. + /// + /// Name of the language in English. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLanguage(const std::string& languageName); + + /// + /// Sets a parameter of the speech recognition engine. Note that when the ASR engine language is set to Chinese, no parameter can be set. + /// The parameters that can be set and the corresponding values are: + /// "Sensitivity" - Values : range is [0.0; 1.0]. + /// "Timeout" - Values : default values 3000 ms. Timeout for the remote recognition + /// "MinimumTrailingSilence" : Values : 0 (no) or 1 (yes) - Applies a High-Pass filter on the input signal - default value is 0. + /// + /// + /// Name of the parameter. + /// Value of the parameter. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const float& paramValue); + + /// + /// Sets a parameter of the speech recognition engine. Note that when the ASR engine language is set to Chinese, no parameter can be set. + /// The parameters that can be set and the corresponding values are: + /// "Sensitivity" - Values : range is [0.0; 1.0]. + /// "Timeout" - Values : default values 3000 ms. Timeout for the remote recognition + /// "MinimumTrailingSilence" : Values : 0 (no) or 1 (yes) - Applies a High-Pass filter on the input signal - default value is 0. + /// + /// + /// Name of the parameter. + /// Value of the parameter. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const bool& paramValue); + + /// + /// Enables or disables the leds animations showing the state of the recognition engine during the recognition process. + /// + /// Enable (true) or disable it (false). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVisualExpression(const bool& setOrNot); + + /// + /// Sets the LED animation mode + /// + /// animation mode: 0: deactivated, 1: eyes, 2: ears, 3: full + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVisualExpressionMode(const int& mode); + + /// + /// Sets the list of words (vocabulary) that should be recognized by the speech recognition engine. + /// + /// List of words that should be recognized + /// If disabled, the engine expects to hear one of the specified words, nothing more, nothing less. If enabled, the specified words can be pronounced in the middle of a whole speech stream, the engine will try to spot them. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVocabulary(const std::vector& vocabulary, const bool& enabledWordSpotting); + + /// + /// Sets the list of words (vocabulary) that should be recognized by the speech recognition engine. + /// + /// List of words that should be recognized + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWordListAsVocabulary(const std::vector& vocabulary); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSpeechRecognitionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSpeechRecognitionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSpeechRecognitionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSpeechRecognitionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSpeechRecognitionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Activate all rules contained in the specified context. + /// + /// Name of the context to modify. + void activateAllRules(const std::string& contextName); + + /// + /// Activate a rule contained in the specified context. + /// + /// Name of the context to modify. + /// Name of the rule to activate. + void activateRule(const std::string& contextName, const std::string& ruleName); + + /// + /// Add a context from a LCF file. + /// + /// Path to a LCF file. This LCF file contains the set of rules that should be recognized by the speech recognition engine. + /// Name of the context of your choice. + void addContext(const std::string& pathToLCFFile, const std::string& contextName); + + /// + /// Add a list of words in a slot. A slot is a part of a context which can be modified. You can add a list of words that should be recognized by the speech recognition engine + /// + /// Name of the context to modify. + /// Name of the slot to modify. + /// List of words to insert in the slot. + void addWordListToSlot(const std::string& contextName, const std::string& slotName, const std::vector& wordList); + + /// + /// + /// + /// arg + /// arg + /// arg + void compile(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// Deactivate all rules contained in the specified context. + /// + /// Name of the context to modify. + void deactivateAllRules(const std::string& contextName); + + /// + /// Deactivate a rule contained in the specified context. + /// + /// Name of the context to modify. + /// Name of the rule to deactivate. + void deactivateRule(const std::string& contextName, const std::string& ruleName); + + /// + /// Erase a saved context set of the speech recognition engine + /// + /// Name under which the context set is saved + void eraseContextSet(const std::string& saveName); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// To check if audio expression is enabled or disabled. + /// + bool getAudioExpression(); + + /// + /// Returns the list of the languages installed on the system. + /// + /// Array of strings that contains the list of the installed languages. + std::vector getAvailableLanguages(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get the given parameter for the specified context. + /// + /// Name of the context + /// Name of the parameter to get + /// Value of the fetched parameter + float getContextParam(const std::string& contextName, const std::string& paramName); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Returns the current language used by the speech recognition system. + /// + /// Current language used by the speech recognition engine. + std::string getLanguage(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets a parameter of the speech recognition engine. Note that when the ASR engine language is set to Chinese, no parameter can be retrieved + /// + /// Name of the parameter. + /// Value of the parameter. + float getParameter(const std::string& paramName); + + /// + /// Get all rules contained for a specific context. + /// + /// Name of the context to analyze. + /// Type of the required rules. + std::vector getRules(const std::string& contextName, const std::string& typeName); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Load a saved context set of the speech recognition engine + /// + /// Name under which the context set is saved + void loadContextSet(const std::string& saveName); + + /// + /// Loads the vocabulary to recognized contained in a .lxd file. This method is not available with the ASR engine language set to Chinese. For more informations see the red documentation + /// + /// Name of the lxd file containing the vocabulary + void loadVocabulary(const std::string& vocabularyFile); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Stops and restarts the speech recognition engine according to the input parameter This can be used to add contexts, activate or deactivate rules of a contex, add a words to a slot. + /// + /// Boolean to enable or disable pause of the speech recognition engine. + void pause(const bool& pause); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Disable current contexts and restore saved contexts of the speech recognition engine. + /// + void popContexts(); + + /// + /// Disable current contexts of the speech recognition engine and save them in a stack. + /// + void pushContexts(); + + /// + /// Remove all contexts from the speech recognition engine. + /// + void removeAllContext(); + + /// + /// Remove one context from the speech recognition engine. + /// + /// Name of the context to remove from the speech recognition engine. + void removeContext(const std::string& contextName); + + /// + /// Remove all words from a slot. + /// + /// Name of the context to modify. + /// Name of the slot to modify. + void removeWordListFromSlot(const std::string& contextName, const std::string& slotName); + + /// + /// Save current context set of the speech recognition engine + /// + /// Name under which to save + bool saveContextSet(const std::string& saveName); + + /// + /// Enables or disables the playing of sounds indicating the state of the recognition engine. If this option is enabled, a sound is played at the beginning of the recognition process (after a call to the subscribe method), and a sound is played when the user call the unsubscribe method + /// + /// Enable (true) or disable it (false). + void setAudioExpression(const bool& setOrNot); + + /// + /// Set the given parameter for the specified context. + /// + /// Name of the context + /// Name of the parameter to change + /// New parameter value + void setContextParam(const std::string& contextName, const std::string& paramName, const float& value); + + /// + /// Sets the language used by the speech recognition engine. The list of the available languages can be collected through the getAvailableLanguages method. If you want to set a language as the default language (loading automatically at module launch), please refer to the web page of the robot. + /// + /// Name of the language in English. + void setLanguage(const std::string& languageName); + + /// + /// Sets a parameter of the speech recognition engine. Note that when the ASR engine language is set to Chinese, no parameter can be set. + /// The parameters that can be set and the corresponding values are: + /// "Sensitivity" - Values : range is [0.0; 1.0]. + /// "Timeout" - Values : default values 3000 ms. Timeout for the remote recognition + /// "MinimumTrailingSilence" : Values : 0 (no) or 1 (yes) - Applies a High-Pass filter on the input signal - default value is 0. + /// + /// + /// Name of the parameter. + /// Value of the parameter. + void setParameter(const std::string& paramName, const float& paramValue); + + /// + /// Sets a parameter of the speech recognition engine. Note that when the ASR engine language is set to Chinese, no parameter can be set. + /// The parameters that can be set and the corresponding values are: + /// "Sensitivity" - Values : range is [0.0; 1.0]. + /// "Timeout" - Values : default values 3000 ms. Timeout for the remote recognition + /// "MinimumTrailingSilence" : Values : 0 (no) or 1 (yes) - Applies a High-Pass filter on the input signal - default value is 0. + /// + /// + /// Name of the parameter. + /// Value of the parameter. + void setParameter(const std::string& paramName, const bool& paramValue); + + /// + /// Enables or disables the leds animations showing the state of the recognition engine during the recognition process. + /// + /// Enable (true) or disable it (false). + void setVisualExpression(const bool& setOrNot); + + /// + /// Sets the LED animation mode + /// + /// animation mode: 0: deactivated, 1: eyes, 2: ears, 3: full + void setVisualExpressionMode(const int& mode); + + /// + /// Sets the list of words (vocabulary) that should be recognized by the speech recognition engine. + /// + /// List of words that should be recognized + /// If disabled, the engine expects to hear one of the specified words, nothing more, nothing less. If enabled, the specified words can be pronounced in the middle of a whole speech stream, the engine will try to spot them. + void setVocabulary(const std::vector& vocabulary, const bool& enabledWordSpotting); + + /// + /// Sets the list of words (vocabulary) that should be recognized by the speech recognition engine. + /// + /// List of words that should be recognized + void setWordListAsVocabulary(const std::vector& vocabulary); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSpeechRecognitionProxyPostHandler post; + }; + +} +#endif // ALSPEECHRECOGNITIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alstoreproxy.h b/naoModule/libnaoqi_files/include/alproxies/alstoreproxy.h new file mode 100755 index 0000000..3d4170e --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alstoreproxy.h @@ -0,0 +1,200 @@ +// Generated for ALStore version 0 + +#ifndef ALSTOREPROXY_H_ +#define ALSTOREPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALStoreProxy; + + namespace detail { + class ALStoreProxyPostHandler + { + protected: + ALStoreProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALStoreProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop the update. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopUpdate(); + + /// + /// Update applications + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int update(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALStoreProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALStoreProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALStoreProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALStoreProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALStoreProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Get package status. + /// + std::vector status(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop the update. + /// + void stopUpdate(); + + /// + /// Update applications + /// + void update(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALStoreProxyPostHandler post; + }; + +} +#endif // ALSTOREPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alsystemproxy.h b/naoModule/libnaoqi_files/include/alproxies/alsystemproxy.h new file mode 100755 index 0000000..9d46c99 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alsystemproxy.h @@ -0,0 +1,294 @@ +// Generated for ALSystem version 0 + +#ifndef ALSYSTEMPROXY_H_ +#define ALSYSTEMPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALSystemProxy; + + namespace detail { + class ALSystemProxyPostHandler + { + protected: + ALSystemProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALSystemProxy; + + /// + /// Change the user password. + /// + /// password The current password of the user. + /// password The new user password. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int changePassword(const std::string& old, const std::string& snew); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Reboot robot + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int reboot(); + + /// + /// Shutdown robot + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int shutdown(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Change the user password. + /// + /// Local path to a valid image. + /// Local path to a md5 checksum file, or empty string for no verification + /// brokerTaskID : The ID of the task assigned to it by the broker. + int upgrade(const std::string& image, const std::string& checksum); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALSystemProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALSystemProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALSystemProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALSystemProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALSystemProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Change the user password. + /// + /// password The current password of the user. + /// password The new user password. + void changePassword(const std::string& old, const std::string& snew); + + /// + /// Display free disk space + /// + /// Show all mount partions. + /// A vector with all partions' infos + std::vector diskFree(const bool& all); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Amount of available memory in heap + /// + /// amount of available memory in heap + int freeMemory(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Previous system version before software update (empty if this is not the 1st boot after a software update) + /// + /// Previous system version before software update. + std::string previousSystemVersion(); + + /// + /// Reboot robot + /// + void reboot(); + + /// + /// Robot icon + /// + /// icon of the robot + AL::ALValue robotIcon(); + + /// + /// System hostname + /// + /// name of the robot + std::string robotName(); + + /// + /// Set system hostname + /// + /// name to use + /// whether the operation was successful + bool setRobotName(const std::string& name); + + /// + /// Set current timezone + /// + /// timezone to use + /// whether the operation was successful + bool setTimezone(const std::string& timezone); + + /// + /// Shutdown robot + /// + void shutdown(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Running system version + /// + /// information about the system version + AL::ALValue systemInfo(); + + /// + /// Running system version + /// + /// running system version + std::string systemVersion(); + + /// + /// Current timezone + /// + /// current timezone + std::string timezone(); + + /// + /// Amount of total memory in heap + /// + /// amount of total memory in heap + int totalMemory(); + + /// + /// Change the user password. + /// + /// Local path to a valid image. + /// Local path to a md5 checksum file, or empty string for no verification + void upgrade(const std::string& image, const std::string& checksum); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALSystemProxyPostHandler post; + }; + +} +#endif // ALSYSTEMPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/altactilegestureproxy.h b/naoModule/libnaoqi_files/include/alproxies/altactilegestureproxy.h new file mode 100755 index 0000000..669e7ca --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/altactilegestureproxy.h @@ -0,0 +1,217 @@ +// Generated for ALTactileGesture version 0 + +#ifndef ALTACTILEGESTUREPROXY_H_ +#define ALTACTILEGESTUREPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALTactileGestureProxy; + + namespace detail { + class ALTactileGestureProxyPostHandler + { + protected: + ALTactileGestureProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALTactileGestureProxy; + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALTactileGestureProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALTactileGestureProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALTactileGestureProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALTactileGestureProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALTactileGestureProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Define touch gesture. + /// + /// :param sensor_sequence: List of strings that represent the + /// sequence of the desired gesture. For example, SingleFront + /// would be the following: ['000', '100', '000']. NOTE: All + /// sequences must start with '000' and all non-hold sequences + /// must end with '000'. Hold gestures should end with the touch + /// sequence you will be holding. For example, a SingleFrontHold + /// would be the following: ['000', '100']. + /// + /// :returns: If sequence is valid, the name of gesture to listen + /// for, RuntimeError otherwise. + /// + /// arg + std::string createGesture(const std::vector& arg1); + + /// + /// Define touch gesture. + /// + /// :param sensor_sequence: Comma-separated string that represents + /// the sequence of the desired gesture. For example, SingleFront + /// would be the following: "000,100,000". NOTE: All sequences + /// must start with '000' and all non-hold sequences must end with + /// '000'. Hold gestures should end with the touch sequence you + /// will be holding. For example, a SingleFrontHold would be the + /// following: "000,100". + /// + /// :returns: If sequence is valid, the name of gesture to listen + /// for, RuntimeError otherwise. + /// + /// arg + std::string createGesture(const std::string& arg1); + + /// + /// Get the sequence associated with a gesture name + /// + /// :param sequence: Sequence you want the gesture name of + /// + /// :returns: Sequence (as list of strings) if it exists, None otherwise + /// + /// arg + AL::ALValue getGesture(const std::vector& arg1); + + /// + /// Get the sequence associated with a gesture name + /// + /// :param sequence: Sequence you want the gesture name of + /// + /// :returns: Sequence (as list of strings) if it exists, None otherwise + /// + /// arg + AL::ALValue getGesture(const std::string& arg1); + + /// + /// Get all gestures that have been defined in the system + /// + /// :returns: Dictionary (Map>) of all gestures + /// + std::map > getGestures(); + + /// + /// Get the sequence associated with a gesture name + /// + /// :param gesture_name: Name of gesture you want the sequence of + /// + /// :returns: Sequence (as list of strings) if it exists, None otherwise + /// + /// + /// arg + std::vector getSequence(const std::string& arg1); + + /// + /// Set length of hold time. + /// + /// :param hold_time: Desired hold time, in seconds (Default: 0.8s) + /// + /// :returns: True if hold time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setHoldTime(const float& arg1); + + /// + /// Set length of hold time. + /// + /// :param hold_time: Desired hold time, in seconds (Default: 0.8s) + /// + /// :returns: True if hold time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setHoldTime(const std::string& arg1); + + /// + /// Set length of sequence time. + /// + /// :param sequence_time: Desired sequence time, in seconds (Default: 0.2s) + /// + /// :returns: True if sequence time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setSequenceTime(const std::string& arg1); + + /// + /// Update length of sequence time. + /// + /// :param sequence_time: Desired sequence time, in seconds (Default: 0.2s) + /// + /// :returns: True if sequence time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setSequenceTime(const float& arg1); + + /// + /// Update length of settling time. + /// + /// :param settle_time: Desired settling time, in seconds (Default: 0.04s) + /// + /// :returns: True if settle time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setSettleTime(const std::string& arg1); + + /// + /// Update length of settling time. + /// + /// :param settle_time: Desired settling time, in seconds (Default: 0.04s) + /// + /// :returns: True if settle time successfully updated, RuntimeError otherwise. + /// + /// arg + bool setSettleTime(const float& arg1); + + + detail::ALTactileGestureProxyPostHandler post; + }; + +} +#endif // ALTACTILEGESTUREPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/altelepatheproxy.h b/naoModule/libnaoqi_files/include/alproxies/altelepatheproxy.h new file mode 100755 index 0000000..6188de7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/altelepatheproxy.h @@ -0,0 +1,525 @@ +// Generated for ALTelepathe version 0 + +#ifndef ALTELEPATHEPROXY_H_ +#define ALTELEPATHEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALTelepatheProxy; + + namespace detail { + class ALTelepatheProxyPostHandler + { + protected: + ALTelepatheProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALTelepatheProxy; + + /// + /// Associates the robot to the given Aldebaran Robotics user. + /// The associated user is recalled in ALMemory as ALTelepathe/User + /// + /// A valid Aldebaran Robotics user name. + /// The matching password with the user name. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int associateUser(const std::string& login, const std::string& password); + + /// + /// Connects the robot to the messaging network. + /// Returns once connected. Throws runtime error otherwise. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int connectNetwork(); + + /// + /// Disconnects the robot from the messaging network. + /// Returns once disconnected. Does not throw. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int disconnectNetwork(); + + /// + /// Clears the login and password for accessing Aldebaran Robotics's network.Login can be tracked in the ALMemory key ALTelepathe/User + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int dissociateUser(); + + /// + /// Enables autoconnection to the network, using the saved user login information if present. + /// + /// + /// Whether to connect automatically at startup. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableAutoconnection(const bool& enabled); + + /// + /// Enable / disable RPC handling for received messages. + /// + /// Whether to enable RPC + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableRPC(const bool& enabled); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the timestamp of the buffer. + /// Provides the audio buffer as an ALValue. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int processRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& timestamp, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the audio buffer as an ALValue. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int processSoundRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& buffer); + + /// + /// Sends a text message to the chosen destination. + /// + /// The id of the destination contact. + /// The message to send to the contact. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sendMessage(const std::string& destination, const std::string& message); + + /// + /// enable/disable the printing of some debug information + /// + /// enable the functionnality when true. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setDebugMode(const bool& bSetOrUnset); + + /// + /// Starts a media call.Returns once the call is accepted remotely.Throws runtime error if the call can't be established.Timeouts after 30 seconds if call not accepted remotely. + /// + /// The contact id to call. + /// Whether audio is enabled for the call. + /// Whether video is enabled for the call. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startCall(const std::string& contact, const bool& audio, const bool& video); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stops the current media call. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopCall(); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALTelepatheProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALTelepatheProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALTelepatheProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALTelepatheProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALTelepatheProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Associates the robot to the given Aldebaran Robotics user. + /// The associated user is recalled in ALMemory as ALTelepathe/User + /// + /// A valid Aldebaran Robotics user name. + /// The matching password with the user name. + void associateUser(const std::string& login, const std::string& password); + + /// + /// Tells who is associated to the robot, if anyone. + /// This simply accesses to the ALMemory key ALTelepathe/User + /// + /// the name of the user, empty if none + std::string associatedUser(); + + /// + /// Connects the robot to the messaging network. + /// Returns once connected. Throws runtime error otherwise. + /// + void connectNetwork(); + + /// + /// Disconnects the robot from the messaging network. + /// Returns once disconnected. Does not throw. + /// + void disconnectNetwork(); + + /// + /// Clears the login and password for accessing Aldebaran Robotics's network.Login can be tracked in the ALMemory key ALTelepathe/User + /// + void dissociateUser(); + + /// + /// Enables autoconnection to the network, using the saved user login information if present. + /// + /// + /// Whether to connect automatically at startup. + void enableAutoconnection(const bool& enabled); + + /// + /// Enable / disable RPC handling for received messages. + /// + /// Whether to enable RPC + void enableRPC(const bool& enabled); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Says whether autoconnection is enabled or not. + /// + /// Whether autoconnection is enabled + bool isAutoconnectionEnabled(); + + /// + /// Says whether a media call is currently established. + /// + /// Whether ALTelepathe is calling or not. + bool isCalling(); + + /// + /// Gets the current connection status. + /// Value is the same as in the ALMemory key ALTelepathe/Connected + /// + /// Whether ALTelepathe is online or not. + bool isConnected(); + + /// + /// Says whether RPC is enabled or not. + /// + /// Whether RPC is enabled + bool isRPCEnabled(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the timestamp of the buffer. + /// Provides the audio buffer as an ALValue. + void processRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& timestamp, const AL::ALValue& buffer); + + /// + /// enable/disable the printing of some debug information + /// + /// Provides the number of channels of the buffer. + /// Provides the number of samples by channel. + /// Provides the audio buffer as an ALValue. + void processSoundRemote(const int& nbOfChannels, const int& nbOfSamplesByChannel, const AL::ALValue& buffer); + + /// + /// Sends a text message to the chosen destination. + /// + /// The id of the destination contact. + /// The message to send to the contact. + void sendMessage(const std::string& destination, const std::string& message); + + /// + /// Performs an Internet Remote Procedure Call. + /// Returns once call has been received.Throws runtime error otherwise. + /// + /// Target contact id + /// The target module + /// The method to call + /// The method arguments + /// The timeout after which the call should be aborted + /// RPC return value + AL::ALValue sendRPC(const std::string& destination, const std::string& module, const std::string& method, const AL::ALValue& args, const int& timeout); + + /// + /// Performs an Internet Remote Procedure Call. + /// Returns once call has been received.Throws runtime error otherwise. + /// + /// Target contact id + /// The target module + /// The method to call + /// The method arguments + /// RPC return value + AL::ALValue sendRPC(const std::string& destination, const std::string& module, const std::string& method, const AL::ALValue& args); + + /// + /// enable/disable the printing of some debug information + /// + /// enable the functionnality when true. + void setDebugMode(const bool& bSetOrUnset); + + /// + /// Starts a media call.Returns once the call is accepted remotely.Throws runtime error if the call can't be established.Timeouts after 30 seconds if call not accepted remotely. + /// + /// The contact id to call. + /// Whether audio is enabled for the call. + /// Whether video is enabled for the call. + void startCall(const std::string& contact, const bool& audio, const bool& video); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops the current media call. + /// + void stopCall(); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALTelepatheProxyPostHandler post; + }; + +} +#endif // ALTELEPATHEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/altexttospeechproxy.h b/naoModule/libnaoqi_files/include/alproxies/altexttospeechproxy.h new file mode 100755 index 0000000..96244b8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/altexttospeechproxy.h @@ -0,0 +1,423 @@ +// Generated for ALTextToSpeech version 0 + +#ifndef ALTEXTTOSPEECHPROXY_H_ +#define ALTEXTTOSPEECHPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALTextToSpeechProxy; + + namespace detail { + class ALTextToSpeechProxyPostHandler + { + protected: + ALTextToSpeechProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALTextToSpeechProxy; + + /// + /// Disables the notifications puted in ALMemory during the synthesis (TextStarted, TextDone, CurrentBookMark, CurrentWord, ...) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int disableNotifications(); + + /// + /// Enables the notifications puted in ALMemory during the synthesis (TextStarted, TextDone, CurrentBookMark, CurrentWord, ...) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableNotifications(); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Loads a set of voice parameters defined in a xml file contained in the preferences folder.The name of the xml file must begin with ALTextToSpeech_Voice_ + /// + /// Name of the voice preference. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int loadVoicePreference(const std::string& pPreferenceName); + + /// + /// Changes the parameters of the voice. For now, it is only possible to reset the voice speed. + /// + /// Name of the parameter. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetSpeed(); + + /// + /// Performs the text-to-speech operations : it takes a std::string as input and outputs a sound in both speakers. String encoding must be UTF8. + /// + /// Text to say, encoded in UTF-8. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int say(const std::string& stringToSay); + + /// + /// Performs the text-to-speech operations in a specific language: it takes a std::string as input and outputs a sound in both speakers. String encoding must be UTF8. Once the text is said, the language is set back to its initial value. + /// + /// Text to say, encoded in UTF-8. + /// Language used to say the text. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int say(const std::string& stringToSay, const std::string& language); + + /// + /// Performs the text-to-speech operations: it takes a std::string as input and outputs the corresponding audio signal in the specified file. + /// + /// Text to say, encoded in UTF-8. + /// RAW file where to store the generated signal. The signal is encoded with a sample rate of 22050Hz, format S16_LE, 2 channels. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sayToFile(const std::string& pStringToSay, const std::string& pFileName); + + /// + /// This method performs the text-to-speech operations: it takes a std::string, outputs the synthesis resulting audio signal in a file, and then plays the audio file. The file is deleted afterwards. It is useful when you want to perform a short synthesis, when few CPU is available. Do not use it if you want a low-latency synthesis or to synthesize a long std::string. + /// + /// Text to say, encoded in UTF-8. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int sayToFileAndPlay(const std::string& pStringToSay); + + /// + /// Changes the language used by the Text-to-Speech engine. It automatically changes the voice used since each of them is related to a unique language. If you want that change to take effect automatically after reboot of your robot, refer to the robot web page (setting page). + /// + /// Language name. Must belong to the languages available in TTS (can be obtained with the getAvailableLanguages method). It should be an identifier std::string. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLanguage(const std::string& pLanguage); + + /// + /// Sets a voice as the default voice for the corresponding language + /// + /// The language among those available on your robot as a String + /// The voice among those available on your robot as a String + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setLanguageDefaultVoice(const std::string& Language, const std::string& Voice); + + /// + /// Changes the parameters of the voice. The available parameters are: + /// pitchShift: applies a pitch shifting to the voice. The value indicates the ratio between the new fundamental frequencies and the old ones (examples: 2.0: an octave above, 1.5: a quint above). Correct range is (1.0 -- 4), or 0 to disable effect. + /// doubleVoice: adds a second voice to the first one. The value indicates the ratio between the second voice fundamental frequency and the first one. Correct range is (1.0 -- 4), or 0 to disable effect + /// doubleVoiceLevel: the corresponding value is the level of the double voice (1.0: equal to the main voice one). Correct range is (0 -- 4). + /// doubleVoiceTimeShift: the corresponding value is the delay between the double voice and the main one. Correct range is (0 -- 0.5) + /// If the effect value is not available, the effect parameter remains unchanged. + /// + /// Name of the parameter. + /// Value of the parameter. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& pEffectName, const float& pEffectValue); + + /// + /// Changes the voice used by the text-to-speech engine. The voice identifier must belong to the installed voices, that can be listed using the 'getAvailableVoices' method. If the voice is not available, it remains unchanged. No exception is thrown in this case. For the time being, only two voices are available by default : Kenny22Enhanced (English voice) and Julie22Enhanced (French voice) + /// + /// The voice (as a std::string). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVoice(const std::string& pVoiceID); + + /// + /// Sets the volume of text-to-speech output. + /// + /// Volume (between 0.0 and 1.0). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVolume(const float& volume); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// This method stops the current and all the pending tasks immediately. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopAll(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALTextToSpeechProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALTextToSpeechProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALTextToSpeechProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALTextToSpeechProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALTextToSpeechProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Disables the notifications puted in ALMemory during the synthesis (TextStarted, TextDone, CurrentBookMark, CurrentWord, ...) + /// + void disableNotifications(); + + /// + /// Enables the notifications puted in ALMemory during the synthesis (TextStarted, TextDone, CurrentBookMark, CurrentWord, ...) + /// + void enableNotifications(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Outputs the languages installed on the system. + /// + /// Array of std::string that contains the languages installed on the system. + std::vector getAvailableLanguages(); + + /// + /// Outputs the available voices. The returned list contains the voice IDs. + /// + /// Array of std::string containing the voices installed on the system. + std::vector getAvailableVoices(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns the language currently used by the text-to-speech engine. + /// + /// Language of the current voice. + std::string getLanguage(); + + /// + /// Returns the encoding that should be used with the specified language. + /// + /// Language name (as a std::string). Must belong to the languages available in TTS. + /// Encoding of the specified language. + std::string getLanguageEncoding(const std::string& pLanguage); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Returns the value of one of the voice parameters. The available parameters are: "pitchShift", "doubleVoice","doubleVoiceLevel" and "doubleVoiceTimeShift" + /// + /// Name of the parameter. + /// Value of the specified parameter + float getParameter(const std::string& pParameterName); + + /// + /// Outputs all the languages supported (may be installed or not). + /// + /// Array of std::string that contains all the supported languages (may be installed or not). + std::vector getSupportedLanguages(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns the voice currently used by the text-to-speech engine. + /// + /// Name of the current voice + std::string getVoice(); + + /// + /// Fetches the current volume the text to speech. + /// + /// Volume (integer between 0 and 100). + float getVolume(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Loads a set of voice parameters defined in a xml file contained in the preferences folder.The name of the xml file must begin with ALTextToSpeech_Voice_ + /// + /// Name of the voice preference. + void loadVoicePreference(const std::string& pPreferenceName); + + /// + /// Get the locale associate to the current language. + /// + /// A string with xx_XX format (region_country) + std::string locale(); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Changes the parameters of the voice. For now, it is only possible to reset the voice speed. + /// + /// Name of the parameter. + void resetSpeed(); + + /// + /// Performs the text-to-speech operations : it takes a std::string as input and outputs a sound in both speakers. String encoding must be UTF8. + /// + /// Text to say, encoded in UTF-8. + void say(const std::string& stringToSay); + + /// + /// Performs the text-to-speech operations in a specific language: it takes a std::string as input and outputs a sound in both speakers. String encoding must be UTF8. Once the text is said, the language is set back to its initial value. + /// + /// Text to say, encoded in UTF-8. + /// Language used to say the text. + void say(const std::string& stringToSay, const std::string& language); + + /// + /// Performs the text-to-speech operations: it takes a std::string as input and outputs the corresponding audio signal in the specified file. + /// + /// Text to say, encoded in UTF-8. + /// RAW file where to store the generated signal. The signal is encoded with a sample rate of 22050Hz, format S16_LE, 2 channels. + void sayToFile(const std::string& pStringToSay, const std::string& pFileName); + + /// + /// This method performs the text-to-speech operations: it takes a std::string, outputs the synthesis resulting audio signal in a file, and then plays the audio file. The file is deleted afterwards. It is useful when you want to perform a short synthesis, when few CPU is available. Do not use it if you want a low-latency synthesis or to synthesize a long std::string. + /// + /// Text to say, encoded in UTF-8. + void sayToFileAndPlay(const std::string& pStringToSay); + + /// + /// Changes the language used by the Text-to-Speech engine. It automatically changes the voice used since each of them is related to a unique language. If you want that change to take effect automatically after reboot of your robot, refer to the robot web page (setting page). + /// + /// Language name. Must belong to the languages available in TTS (can be obtained with the getAvailableLanguages method). It should be an identifier std::string. + void setLanguage(const std::string& pLanguage); + + /// + /// Sets a voice as the default voice for the corresponding language + /// + /// The language among those available on your robot as a String + /// The voice among those available on your robot as a String + void setLanguageDefaultVoice(const std::string& Language, const std::string& Voice); + + /// + /// Changes the parameters of the voice. The available parameters are: + /// pitchShift: applies a pitch shifting to the voice. The value indicates the ratio between the new fundamental frequencies and the old ones (examples: 2.0: an octave above, 1.5: a quint above). Correct range is (1.0 -- 4), or 0 to disable effect. + /// doubleVoice: adds a second voice to the first one. The value indicates the ratio between the second voice fundamental frequency and the first one. Correct range is (1.0 -- 4), or 0 to disable effect + /// doubleVoiceLevel: the corresponding value is the level of the double voice (1.0: equal to the main voice one). Correct range is (0 -- 4). + /// doubleVoiceTimeShift: the corresponding value is the delay between the double voice and the main one. Correct range is (0 -- 0.5) + /// If the effect value is not available, the effect parameter remains unchanged. + /// + /// Name of the parameter. + /// Value of the parameter. + void setParameter(const std::string& pEffectName, const float& pEffectValue); + + /// + /// Changes the voice used by the text-to-speech engine. The voice identifier must belong to the installed voices, that can be listed using the 'getAvailableVoices' method. If the voice is not available, it remains unchanged. No exception is thrown in this case. For the time being, only two voices are available by default : Kenny22Enhanced (English voice) and Julie22Enhanced (French voice) + /// + /// The voice (as a std::string). + void setVoice(const std::string& pVoiceID); + + /// + /// Sets the volume of text-to-speech output. + /// + /// Volume (between 0.0 and 1.0). + void setVolume(const float& volume); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// This method stops the current and all the pending tasks immediately. + /// + void stopAll(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALTextToSpeechProxyPostHandler post; + }; + +} +#endif // ALTEXTTOSPEECHPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/altouchproxy.h b/naoModule/libnaoqi_files/include/alproxies/altouchproxy.h new file mode 100755 index 0000000..2bd8841 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/altouchproxy.h @@ -0,0 +1,185 @@ +// Generated for ALTouch version 0 + +#ifndef ALTOUCHPROXY_H_ +#define ALTOUCHPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALTouchProxy; + + namespace detail { + class ALTouchProxyPostHandler + { + protected: + ALTouchProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALTouchProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALTouchProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALTouchProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALTouchProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALTouchProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALTouchProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Return the list of sensors managed by touch module and return by TouchChangedevent. + /// + /// A vector of sensor names manage by ALTouch. + std::vector getSensorList(); + + /// + /// Return the current status of all Touch groups. + /// + /// A vector of pair [name, bool], similar to TouchChanged event. + AL::ALValue getStatus(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALTouchProxyPostHandler post; + }; + +} +#endif // ALTOUCHPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/altrackerproxy.h b/naoModule/libnaoqi_files/include/alproxies/altrackerproxy.h new file mode 100755 index 0000000..c053a9d --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/altrackerproxy.h @@ -0,0 +1,667 @@ +// Generated for ALTracker version 0 + +#ifndef ALTRACKERPROXY_H_ +#define ALTRACKERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALTrackerProxy; + + namespace detail { + class ALTrackerProxyPostHandler + { + protected: + ALTrackerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALTrackerProxy; + + /// + /// DEPRECATED. Use setEffector instead. Add an end-effector to move for tracking. + /// + /// Name of effector. Could be: "Arms", "LArm" or "RArm". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addEffector(const std::string& pEffector); + + /// + /// DEPRECATED. Use registerTarget() instead. Add a predefined target. Subscribe to corresponding extractor if Tracker is running.. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a target parameters. (RedBall : set diameter of ball. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int addTarget(const std::string& pTarget, const AL::ALValue& pParams); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Look at the target position with head. + /// + /// + /// position 3D [x, y, z] x position must be striclty positif. + /// target frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// If true, use whole body constraints. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int lookAt(const std::vector& pPosition, const int& pFrame, const float& pFractionMaxSpeed, const bool& pUseWholeBody); + + /// + /// DEPRECATED. Use lookAt with frame instead. Look at the target position with head. + /// + /// + /// position 3D [x, y, z] to look in FRAME_TORSO. x position must be striclty positif. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// If true, use whole body constraints. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int lookAt(const std::vector& pPosition, const float& pFractionMaxSpeed, const bool& pUseWholeBody); + + /// + /// Point at the target position with arms. + /// + /// + /// effector name. Could be "Arms", "LArm", "RArm". + /// position 3D [x, y, z] to point in FRAME_TORSO. x position must be striclty positif. + /// target frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pointAt(const std::string& pEffector, const std::vector& pPosition, const int& pFrame, const float& pFractionMaxSpeed); + + /// + /// DEPRECATED. Use pointAt with frame instead. Point at the target position with arms. + /// + /// + /// effector name. Could be "Arms", "LArm", "RArm". + /// position 3D [x, y, z] to point in FRAME_TORSO. x position must be striclty positif. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pointAt(const std::string& pEffector, const std::vector& pPosition, const float& pFractionMaxSpeed); + + /// + /// Register a predefined target. Subscribe to corresponding extractor if Tracker is running.. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a target parameters. (RedBall : set diameter of ball. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int registerTarget(const std::string& pTarget, const AL::ALValue& pParams); + + /// + /// DEPRECATED. Use unregisterAllTargets() instead. Remove all managed targets except active target and stop corresponding extractor. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeAllTargets(); + + /// + /// DEPRECATED. Use setEffector("None") instead. Remove an end-effector from tracking. + /// + /// Name of effector. Could be: "Arms", "LArm" or "RArm". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeEffector(const std::string& pEffector); + + /// + /// DEPRECATED. Use unregisterTarget() instead. Remove target name and stop corresponding extractor. + /// + /// a predefined target to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeTarget(const std::string& pTarget); + + /// + /// DEPRECATED. Use unregisterTargets() instead. Remove a list of target names and stop corresponding extractor. + /// + /// a predefined target list to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removeTargets(const std::vector& pTarget); + + /// + /// Set an end-effector to move for tracking. + /// + /// Name of effector. Could be: "Arms", "LArm", "RArm" or "None". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setEffector(const std::string& pEffector); + + /// + /// Set a period for the corresponding target name extractor. + /// + /// a predefined target name.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a period in milliseconds + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setExtractorPeriod(const std::string& pTarget, const int& pPeriod); + + /// + /// set the maximum target detection distance in meter. + /// + /// The maximum distance for target detection in meter. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMaximumDistanceDetection(const float& pMaxDistance); + + /// + /// Set the tracker in the predefined mode.Could be "Head", "WholeBody" or "Move". + /// + /// a predefined mode. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMode(const std::string& pMode); + + /// + /// set a config for move modes. + /// + /// ALMotion GaitConfig + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMoveConfig(const AL::ALValue& config); + + /// + /// Set the robot position relative to target in Move mode. + /// + /// Set the final goal of the tracking. Could be [distance, thresholdX, thresholdY] or with LandMarks target name [coordX, coordY, coordWz, thresholdX, thresholdY, thresholdWz]. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setRelativePosition(const AL::ALValue& target); + + /// + /// Only work with LandMarks target name. Set objects coordinates. Could be [[first object coordinate], [second object coordinate]] [[x1, y1, z1], [x2, y2, z2]] + /// + /// objects coordinates. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTargetCoordinates(const AL::ALValue& pCoord); + + /// + /// set the timeout parameter for target lost. + /// + /// time in milliseconds. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setTimeOut(const int& pTimeMs); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop the tracker. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopTracker(); + + /// + /// Enables/disables the target search process. Target search process occurs only when the target is lost. + /// + /// If true and if the target is lost, the robot moves the head in order to find the target. If false and if the target is lost the robot does not move. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int toggleSearch(const bool& pSearch); + + /// + /// Set the predefided target to track and start the tracking process if not started. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int track(const std::string& pTarget); + + /// + /// Track event and start the tracking process if not started. + /// + /// a event name to track. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int trackEvent(const std::string& pEventName); + + /// + /// Unregister all targets except active target and stop corresponding extractor. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unregisterAllTargets(); + + /// + /// Unregister target name and stop corresponding extractor. + /// + /// a predefined target to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unregisterTarget(const std::string& pTarget); + + /// + /// Unregister a list of target names and stop corresponding extractor. + /// + /// a predefined target list to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unregisterTargets(const std::vector& pTarget); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALTrackerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALTrackerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALTrackerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALTrackerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALTrackerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// DEPRECATED. Use setEffector instead. Add an end-effector to move for tracking. + /// + /// Name of effector. Could be: "Arms", "LArm" or "RArm". + void addEffector(const std::string& pEffector); + + /// + /// DEPRECATED. Use registerTarget() instead. Add a predefined target. Subscribe to corresponding extractor if Tracker is running.. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a target parameters. (RedBall : set diameter of ball. + void addTarget(const std::string& pTarget, const AL::ALValue& pParams); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Return active target name. + /// + /// Tracked target name. + std::string getActiveTarget(); + + /// + /// Get the list of predefined mode. + /// + /// List of predefined mode. + std::vector getAvailableModes(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get active effector. + /// + /// Active effector name. Could be: "Arms", "LArm", "RArm" or "None". + std::string getEffector(); + + /// + /// Get the period of corresponding target name extractor. + /// + /// a predefined target name.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a period in milliseconds + int getExtractorPeriod(const std::string& pTarget); + + /// + /// DEPRECATED. Use getRegisteredTargets() instead. Return a list of managed targets names. + /// + /// Managed targets names. + std::vector getManagedTargets(); + + /// + /// get the maximum distance for target detection in meter. + /// + /// The maximum distance for target detection in meter. + float getMaximumDistanceDetection(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Get the tracker current mode. + /// + /// The current tracker mode. + std::string getMode(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the config for move modes. + /// + /// ALMotion GaitConfig + AL::ALValue getMoveConfig(); + + /// + /// Return a list of registered targets names. + /// + /// Registered targets names. + std::vector getRegisteredTargets(); + + /// + /// Get the robot position relative to target in Move mode. + /// + /// The final goal of the tracking. Could be [distance, thresholdX, thresholdY] or with LandMarks target name [coordX, coordY, coordWz, thresholdX, thresholdY, thresholdWz]. + AL::ALValue getRelativePosition(); + + /// + /// Only work with LandMarks target name. Returns the [x, y, z, wx, wy, wz] position of the robot in coordinate system setted with setMap API. This is done assuming an average target size, so it might not be very accurate. + /// + /// Vector of 6 floats corresponding to the robot position 6D. + std::vector getRobotPosition(); + + /// + /// Return a list of supported targets names. + /// + /// Supported targets names. + std::vector getSupportedTargets(); + + /// + /// Only work with LandMarks target name. Get objects coordinates. Could be [[first object coordinate], [second object coordinate]] [[x1, y1, z1], [x2, y2, z2]] + /// + /// objects coordinates. + AL::ALValue getTargetCoordinates(); + + /// + /// DEPRECATED. Use getSupportedTargets() instead. Return a list of targets names. + /// + /// Valid targets names. + std::vector getTargetNames(); + + /// + /// Returns the [x, y, z] position of the target in FRAME_TORSO. This is done assuming an average target size, so it might not be very accurate. + /// + /// target frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// Vector of 3 floats corresponding to the target position 3D. + std::vector getTargetPosition(const int& pFrame); + + /// + /// DEPRECATED. Use pointAt with frame instead. Returns the [x, y, z] position of the target in FRAME_TORSO. This is done assuming an average target size, so it might not be very accurate. + /// + /// Vector of 3 floats corresponding to the target position 3D. + std::vector getTargetPosition(); + + /// + /// get the timeout parameter for target lost. + /// + /// time in milliseconds. + int getTimeOut(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Return true if Tracker is running. + /// + /// True if Tracker is running. + bool isActive(); + + /// + /// Return true if a new target was detected. + /// + /// True if a new target was detected since the last getTargetPosition(). + bool isNewTargetDetected(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Return true if the target search process is enabled. + /// + /// If true the target search process is enabled. + bool isSearchEnabled(); + + /// + /// Return true if the target was lost. + /// + /// True if the target was lost. + bool isTargetLost(); + + /// + /// Look at the target position with head. + /// + /// + /// position 3D [x, y, z] x position must be striclty positif. + /// target frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// If true, use whole body constraints. + void lookAt(const std::vector& pPosition, const int& pFrame, const float& pFractionMaxSpeed, const bool& pUseWholeBody); + + /// + /// DEPRECATED. Use lookAt with frame instead. Look at the target position with head. + /// + /// + /// position 3D [x, y, z] to look in FRAME_TORSO. x position must be striclty positif. + /// The fraction of maximum speed to use. Must be between 0 and 1. + /// If true, use whole body constraints. + void lookAt(const std::vector& pPosition, const float& pFractionMaxSpeed, const bool& pUseWholeBody); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Point at the target position with arms. + /// + /// + /// effector name. Could be "Arms", "LArm", "RArm". + /// position 3D [x, y, z] to point in FRAME_TORSO. x position must be striclty positif. + /// target frame {FRAME_TORSO = 0, FRAME_WORLD = 1, FRAME_ROBOT = 2}. + /// The fraction of maximum speed to use. Must be between 0 and 1. + void pointAt(const std::string& pEffector, const std::vector& pPosition, const int& pFrame, const float& pFractionMaxSpeed); + + /// + /// DEPRECATED. Use pointAt with frame instead. Point at the target position with arms. + /// + /// + /// effector name. Could be "Arms", "LArm", "RArm". + /// position 3D [x, y, z] to point in FRAME_TORSO. x position must be striclty positif. + /// The fraction of maximum speed to use. Must be between 0 and 1. + void pointAt(const std::string& pEffector, const std::vector& pPosition, const float& pFractionMaxSpeed); + + /// + /// Register a predefined target. Subscribe to corresponding extractor if Tracker is running.. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a target parameters. (RedBall : set diameter of ball. + void registerTarget(const std::string& pTarget, const AL::ALValue& pParams); + + /// + /// DEPRECATED. Use unregisterAllTargets() instead. Remove all managed targets except active target and stop corresponding extractor. + /// + void removeAllTargets(); + + /// + /// DEPRECATED. Use setEffector("None") instead. Remove an end-effector from tracking. + /// + /// Name of effector. Could be: "Arms", "LArm" or "RArm". + void removeEffector(const std::string& pEffector); + + /// + /// DEPRECATED. Use unregisterTarget() instead. Remove target name and stop corresponding extractor. + /// + /// a predefined target to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + void removeTarget(const std::string& pTarget); + + /// + /// DEPRECATED. Use unregisterTargets() instead. Remove a list of target names and stop corresponding extractor. + /// + /// a predefined target list to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + void removeTargets(const std::vector& pTarget); + + /// + /// Set an end-effector to move for tracking. + /// + /// Name of effector. Could be: "Arms", "LArm", "RArm" or "None". + void setEffector(const std::string& pEffector); + + /// + /// Set a period for the corresponding target name extractor. + /// + /// a predefined target name.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + /// a period in milliseconds + void setExtractorPeriod(const std::string& pTarget, const int& pPeriod); + + /// + /// set the maximum target detection distance in meter. + /// + /// The maximum distance for target detection in meter. + void setMaximumDistanceDetection(const float& pMaxDistance); + + /// + /// Set the tracker in the predefined mode.Could be "Head", "WholeBody" or "Move". + /// + /// a predefined mode. + void setMode(const std::string& pMode); + + /// + /// set a config for move modes. + /// + /// ALMotion GaitConfig + void setMoveConfig(const AL::ALValue& config); + + /// + /// Set the robot position relative to target in Move mode. + /// + /// Set the final goal of the tracking. Could be [distance, thresholdX, thresholdY] or with LandMarks target name [coordX, coordY, coordWz, thresholdX, thresholdY, thresholdWz]. + void setRelativePosition(const AL::ALValue& target); + + /// + /// Only work with LandMarks target name. Set objects coordinates. Could be [[first object coordinate], [second object coordinate]] [[x1, y1, z1], [x2, y2, z2]] + /// + /// objects coordinates. + void setTargetCoordinates(const AL::ALValue& pCoord); + + /// + /// set the timeout parameter for target lost. + /// + /// time in milliseconds. + void setTimeOut(const int& pTimeMs); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop the tracker. + /// + void stopTracker(); + + /// + /// Enables/disables the target search process. Target search process occurs only when the target is lost. + /// + /// If true and if the target is lost, the robot moves the head in order to find the target. If false and if the target is lost the robot does not move. + void toggleSearch(const bool& pSearch); + + /// + /// Set the predefided target to track and start the tracking process if not started. + /// + /// a predefined target to track.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + void track(const std::string& pTarget); + + /// + /// Track event and start the tracking process if not started. + /// + /// a event name to track. + void trackEvent(const std::string& pEventName); + + /// + /// Unregister all targets except active target and stop corresponding extractor. + /// + void unregisterAllTargets(); + + /// + /// Unregister target name and stop corresponding extractor. + /// + /// a predefined target to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + void unregisterTarget(const std::string& pTarget); + + /// + /// Unregister a list of target names and stop corresponding extractor. + /// + /// a predefined target list to remove.Could be "RedBall", "Face", "LandMark", "LandMarks", "People" or "Sound". + void unregisterTargets(const std::vector& pTarget); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALTrackerProxyPostHandler post; + }; + +} +#endif // ALTRACKERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alusersessionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alusersessionproxy.h new file mode 100755 index 0000000..9631453 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alusersessionproxy.h @@ -0,0 +1,296 @@ +// Generated for ALUserSession version 0 + +#ifndef ALUSERSESSIONPROXY_H_ +#define ALUSERSESSIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALUserSessionProxy; + + namespace detail { + class ALUserSessionProxyPostHandler + { + protected: + ALUserSessionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALUserSessionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Set some data about a user. Will throw if user does not exist + /// + /// The int ID of the user whose data to set. + /// The key of the data to set. + /// The string name of the data source. + /// ALValue of the data. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setUserData(const int& uid, const std::string& data_name, const std::string& source_name, const AL::ALValue& data); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALUserSessionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALUserSessionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALUserSessionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALUserSessionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALUserSessionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Check if users have an open session. + /// + /// A list of int IDs of each user to check. + /// A bool, true if all users have open sessions. + bool areUserSessionsOpen(const std::vector& user_list); + + /// + /// Check if users exist in db. + /// + /// A list of int ID of the users to check. + /// A bool, true if all users exist. + bool doUsersExist(const std::vector& user_list); + + /// + /// Query if a particular has been applied to UserSession + /// + /// The string name of the binding source. + /// A bool, true if a binding source exists. + bool doesBindingSourceExist(const std::string& binding_name); + + /// + /// Check if a data source has been registered. + /// + /// The string name of the data source. + /// A bool, true if the source has been registered + bool doesUserDataSourceExist(const std::string& source_name); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Get the sources a user is bound to. + /// + /// The string name of the binding source. + /// The string ID of the user at the binding source. + /// The int IDs of the users with the passed binding_value. + std::vector findUsersWithBinding(const std::string& binding_name, const std::string& binding_value); + + /// + /// The list of binding sources that have been applied to UserSession + /// + /// A list of strings, one for each binding source. + std::vector getBindingSources(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get which user has the robot's focus. + /// + /// The int ID of the focused user. -1 if no focused user. + int getFocusedUser(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Get the count of users in db. + /// + /// An int of how many users exist + int getNumUsers(); + + /// + /// Get which users have an open session. + /// + /// A list of int IDs of each user with an open session. + std::vector getOpenUserSessions(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Get the a specific source a user is bound to. + /// + /// The int ID of the user. + /// The string name of the binding source. + /// The string value of the binding ID for the user. + std::string getUserBinding(const int& uid, const std::string& binding_name); + + /// + /// Get the sources a user is bound to. + /// + /// The int ID of the user. + /// A map of string binding names and their string values. + std::map getUserBindings(const int& uid); + + /// + /// Get some data about a user. Will throw if it does not exist + /// + /// The int ID of the user whose data to get. + /// The key of the data to get. + /// A map keyed by source_name of ALValues of the data. + std::map getUserData(const int& uid, const std::string& data_name); + + /// + /// Get some data about a user. Will throw if it does not exist + /// + /// The int ID of the user whose data to get. + /// The key of the data to get. + /// The string name of the data source. + /// ALValue of the data. + AL::ALValue getUserData(const int& uid, const std::string& data_name, const std::string& source_name); + + /// + /// Check what data sources have been registered. + /// + /// A list of strings of each registered data source. + std::vector getUserDataSources(); + + /// + /// Get a full list of the users. + /// + /// A list of int user IDs. + std::vector getUserList(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set some data about a user. Will throw if user does not exist + /// + /// The int ID of the user whose data to set. + /// The key of the data to set. + /// The string name of the data source. + /// ALValue of the data. + void setUserData(const int& uid, const std::string& data_name, const std::string& source_name, const AL::ALValue& data); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALUserSessionProxyPostHandler post; + }; + +} +#endif // ALUSERSESSIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvideodeviceproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvideodeviceproxy.h new file mode 100755 index 0000000..c0647a8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvideodeviceproxy.h @@ -0,0 +1,1004 @@ +// Generated for ALVideoDevice version 0 + +#ifndef ALVIDEODEVICEPROXY_H_ +#define ALVIDEODEVICEPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVideoDeviceProxy; + + namespace detail { + class ALVideoDeviceProxyPostHandler + { + protected: + ALVideoDeviceProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVideoDeviceProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Callback when client is disconnected + /// + /// The echoed event name + /// The name of the client that has disconnected + /// The message give when subscribing. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int onClientDisconnected(const std::string& eventName, const AL::ALValue& eventContents, const std::string& message); + + /// + /// Sets the value of a specific parameter for the video source. + /// + /// Camera parameter requested. + /// value requested. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParam(const int& pParam, const int& pNewValue); + + /// + /// Sets the value of a specific parameter for the video source. + /// + /// Camera parameter requested. + /// value requested. + /// Camera requested. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParam(const int& pParam, const int& pNewValue, const int& pCameraIndex); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParamDefault(const int& arg1); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Used to unsubscribe all instances for a given G.V.M. (e.g. VisionModule and VisionModule_5) from ALVideoDevice. + /// + /// Root name of the G.V.M. (e.g. with the example above this will be VisionModule). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribeAllInstances(const std::string& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALVideoDeviceProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVideoDeviceProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVideoDeviceProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVideoDeviceProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVideoDeviceProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// arg + bool closeCamera(const int& arg1); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Tells which camera is the default one + /// + /// 0: top camera - 1: bottom camera + int getActiveCamera(); + + /// + /// + /// + /// Name of the subscribing vision module + int getActiveCamera(const std::string& name); + + /// + /// + /// + /// Name of the subscribing vision module + AL::ALValue getActiveCameras(const std::string& name); + + /// + /// + /// + /// arg + std::vector getAngPosFromImgPos(const std::vector& arg1); + + /// + /// + /// + /// arg + std::vector getAngSizeFromImgSize(const std::vector& arg1); + + /// + /// + /// + /// arg + /// arg + std::vector getAngularPositionFromImagePosition(const int& arg1, const std::vector& arg2); + + /// + /// + /// + /// arg + /// arg + std::vector getAngularSizeFromImageSize(const int& arg1, const std::vector& arg2); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// + /// + AL::ALValue getCameraIndexes(); + + /// + /// + /// + /// Camera requested. + /// 1(kOV7670): VGA camera - 2(kMT9M114): HD camera + int getCameraModel(const int& cameraIndex); + + /// + /// + /// + int getCameraModelID(); + + /// + /// + /// + /// Camera requested. + /// CameraTop - CameraBottom - CameraDepth + std::string getCameraName(const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + int getCameraParameter(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + AL::ALValue getCameraParameterInfo(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + AL::ALValue getCameraParameterRange(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + AL::ALValue getCamerasParameter(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Camera requested. + int getColorSpace(const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + int getColorSpace(const std::string& name); + + /// + /// + /// + /// Name of the subscribing vision module + AL::ALValue getColorSpaces(const std::string& name); + + /// + /// Retrieves the latest image from the video source and returns a pointer to the locked ALImage, with data array pointing directly to raw data. There is no format conversion and no copy of the raw buffer. + /// Warning: When image is not necessary anymore, a call to releaseDirectRawImage() is requested. + /// Warning: When using this mode for several vision module, if they need raw data for more than 25ms check that you have strictly less modules in this mode than the amount of kernel buffers!! + /// Warning: Release all kernel buffers before any action requesting a modification in camera running mode (e.g. resolution, switch between cameras). + /// + /// Name of the subscribing vision module + /// Warning, image pointer is valid only for C++ dynamic library. + /// Pointer to the locked image buffer, NULL if error. + void* getDirectRawImageLocal(const std::string& name); + + /// + /// Fills an ALValue with data coming directly from raw buffer (no format conversion). + /// + /// + /// Name of the subscribing vision module + /// [0] : width; + /// [1] : height; + /// [2] : number of layers; + /// [3] : ColorSpace; + /// [4] : time stamp (highest 32 bits); + /// [5] : time stamp (lowest 32 bits); + /// [6] : array of size height * width * nblayers containing image data; + /// [7] : cameraID; + /// [8] : left angle; + /// [9] : top angle; + /// [10] : right angle; + /// [11] : bottom angle; + /// + /// Array containing image informations : + AL::ALValue getDirectRawImageRemote(const std::string& name); + + /// + /// Retrieves the latest image from the video source and returns a pointer to the locked ALImage, with data array pointing directly to raw data. There is no format conversion and no copy of the raw buffer. + /// Warning: When image is not necessary anymore, a call to releaseDirectRawImage() is requested. + /// Warning: When using this mode for several vision module, if they need raw data for more than 25ms check that you have strictly less modules in this mode than the amount of kernel buffers!! + /// Warning: Release all kernel buffers before any action requesting a modification in camera running mode (e.g. resolution, switch between cameras). + /// + /// Name of the subscribing vision module + /// Warning, image pointer is valid only for C++ dynamic library. + /// Array of pointer to the locked image buffer, NULL if error. + AL::ALValue getDirectRawImagesLocal(const std::string& name); + + /// + /// Fills an ALValue with data coming directly from raw buffer (no format conversion). + /// + /// + /// Name of the subscribing vision module + /// [0] : width; + /// [1] : height; + /// [2] : number of layers; + /// [3] : ColorSpace; + /// [4] : time stamp (highest 32 bits); + /// [5] : time stamp (lowest 32 bits); + /// [6] : array of size height * width * nblayers containing image data; + /// [7] : cameraID; + /// [8] : left angle; + /// [9] : top angle; + /// [10] : right angle; + /// [11] : bottom angle; + /// + /// Array containing image informations : + AL::ALValue getDirectRawImagesRemote(const std::string& name); + + /// + /// called by the simulator to know expected image parameters + /// + /// Camera requested. + /// ALValue of expected parameters, [int resolution, int framerate] + AL::ALValue getExpectedImageParameters(const int& cameraIndex); + + /// + /// called by the simulator to know expected image parameters + /// + /// ALValue of expected parameters, [int resolution, int framerate] + AL::ALValue getExpectedImageParameters(); + + /// + /// + /// + /// Camera requested. + int getFrameRate(const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + int getFrameRate(const std::string& name); + + /// + /// + /// + /// arg + int getGVMColorSpace(const std::string& arg1); + + /// + /// + /// + /// arg + int getGVMFrameRate(const std::string& arg1); + + /// + /// + /// + /// arg + int getGVMResolution(const std::string& arg1); + + /// + /// + /// + /// Camera requested. + float getHorizontalAperture(const int& cameraIndex); + + /// + /// + /// + /// Camera requested. + float getHorizontalFOV(const int& cameraIndex); + + /// + /// + /// + /// arg + /// arg + std::vector getImageInfoFromAngularInfo(const int& arg1, const std::vector& arg2); + + /// + /// + /// + /// arg + /// arg + /// arg + std::vector getImageInfoFromAngularInfoWithResolution(const int& arg1, const std::vector& arg2, const int& arg3); + + /// + /// Applies transformations to the last image from video source and returns a pointer to a locked ALImage. + /// When image is not necessary anymore, a call to releaseImage() is requested. + /// + /// + /// Name of the subscribing vision module + /// Pointer of the locked image buffer, NULL if error.Warning, image pointer is valid only for C++ dynamic library. + void* getImageLocal(const std::string& name); + + /// + /// + /// + /// arg + /// arg + std::vector getImagePositionFromAngularPosition(const int& arg1, const std::vector& arg2); + + /// + /// Applies transformations to the last image from video source and fills pFrameOut. + /// + /// + /// Name of the subscribing vision module + /// [0] : width; + /// [1] : height; + /// [2] : number of layers; + /// [3] : ColorSpace; + /// [4] : time stamp (highest 32 bits); + /// [5] : time stamp (lowest 32 bits); + /// [6] : array of size height * width * nblayers containing image data; + /// [7] : cameraID; + /// [8] : left angle; + /// [9] : top angle; + /// [10] : right angle; + /// [11] : bottom angle; + /// + /// Array containing image informations : + AL::ALValue getImageRemote(const std::string& name); + + /// + /// + /// + /// arg + /// arg + std::vector getImageSizeFromAngularSize(const int& arg1, const std::vector& arg2); + + /// + /// Applies transformations to the last image from video source and returns a pointer to a locked ALImage. + /// When image is not necessary anymore, a call to releaseImage() is requested. + /// + /// + /// Name of the subscribing vision module + /// Array of pointer of the locked image buffer, NULL if error.Warning, image pointer is valid only for C++ dynamic library. + AL::ALValue getImagesLocal(const std::string& name); + + /// + /// Applies transformations to the last image from video source and fills pFrameOut. + /// + /// + /// Name of the subscribing vision module + /// [0] : width; + /// [1] : height; + /// [2] : number of layers; + /// [3] : ColorSpace; + /// [4] : time stamp (highest 32 bits); + /// [5] : time stamp (lowest 32 bits); + /// [6] : array of size height * width * nblayers containing image data; + /// [7] : cameraID; + /// [8] : left angle; + /// [9] : top angle; + /// [10] : right angle; + /// [11] : bottom angle; + /// + /// Array containing image informations : + AL::ALValue getImagesRemote(const std::string& name); + + /// + /// + /// + /// arg + std::vector getImgInfoFromAngInfo(const std::vector& arg1); + + /// + /// + /// + /// arg + /// arg + std::vector getImgInfoFromAngInfoWithRes(const std::vector& arg1, const int& arg2); + + /// + /// + /// + /// arg + std::vector getImgPosFromAngPos(const std::vector& arg1); + + /// + /// + /// + /// arg + std::vector getImgSizeFromAngSize(const std::vector& arg1); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// + /// + /// Camera parameter requested. + int getParam(const int& pParam); + + /// + /// + /// + /// Camera parameter requested. + /// Camera requested. + int getParam(const int& pParam, const int& pCameraIndex); + + /// + /// + /// + /// Camera requested. + /// Camera parameter requested. + int getParameter(const int& cameraIndex, const int& parameterId); + + /// + /// + /// + /// Camera requested. + /// Camera parameter requested. + AL::ALValue getParameterInfo(const int& cameraIndex, const int& parameterId); + + /// + /// + /// + /// Camera requested. + /// Camera parameter requested. + AL::ALValue getParameterRange(const int& cameraIndex, const int& parameterId); + + /// + /// + /// + /// Camera requested. + int getResolution(const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + int getResolution(const std::string& name); + + /// + /// + /// + /// Name of the subscribing vision module + AL::ALValue getResolutions(const std::string& name); + + /// + /// + /// + AL::ALValue getSubscribers(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// + /// + int getVIMColorSpace(); + + /// + /// + /// + int getVIMFrameRate(); + + /// + /// + /// + int getVIMResolution(); + + /// + /// + /// + /// Camera requested. + float getVerticalAperture(const int& cameraIndex); + + /// + /// + /// + /// Camera requested. + float getVerticalFOV(const int& cameraIndex); + + /// + /// + /// + bool hasDepthCamera(); + + /// + /// + /// + /// arg + bool isCameraOpen(const int& arg1); + + /// + /// + /// + /// arg + bool isCameraStarted(const int& arg1); + + /// + /// + /// + /// Camera requested. + bool isFrameGrabberOff(const int& cameraIndex); + + /// + /// Advanced method that asks if the framegrabber is off. + /// + /// true if off + int isFrameGrabberOff(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Callback when client is disconnected + /// + /// The echoed event name + /// The name of the client that has disconnected + /// The message give when subscribing. + void onClientDisconnected(const std::string& eventName, const AL::ALValue& eventContents, const std::string& message); + + /// + /// + /// + /// arg + bool openCamera(const int& arg1); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Allow image buffer pushing + /// + /// Camera requested. + /// int width of image among 1280*960, 640*480, 320*240, 240*160 + /// int height of image + /// Image buffer in bitmap form + /// true if the put succeeded + bool putImage(const int& cameraIndex, const int& width, const int& height, const AL::ALValue& imageBuffer); + + /// + /// Allow image buffer pushing + /// + /// Image buffer in bitmap form + /// true if the put succeeded + bool putImage(const AL::ALValue& imageBuffer); + + /// + /// Background record of an .arv raw format video from the images processed by a vision module + /// Actualy it take picture each time the vision module call getDirectRawImageRemote(). + /// + /// Name under which the G.V.M. is known from the V.I.M. + /// path/name of the video to be recorded + /// number of images to be recorded. 0xFFFFFFFF for "unlimited" + /// one image recorded every pPeriod images + /// true if success + bool recordVideo(const std::string& id, const std::string& path, const int& totalNumber, const int& period); + + /// + /// Release image buffer locked by getDirectRawImageLocal(). + /// + /// + /// Name of the subscribing vision module + /// true if success + bool releaseDirectRawImage(const std::string& name); + + /// + /// Release image buffer locked by getDirectRawImagesLocal(). + /// + /// + /// Name of the subscribing vision module + /// true if success + AL::ALValue releaseDirectRawImages(const std::string& name); + + /// + /// Release image buffer locked by getImageLocal(). + /// If G.V.M. had no locked image buffer, does nothing. + /// + /// Name of the subscribing vision module + /// true if success + bool releaseImage(const std::string& name); + + /// + /// Release image buffer locked by getImageLocal(). + /// If G.V.M. had no locked image buffer, does nothing. + /// + /// Name of the subscribing vision module + /// true if success + AL::ALValue releaseImages(const std::string& name); + + /// + /// + /// + /// arg + bool resetCamera(const int& arg1); + + /// + /// + /// + /// arg + AL::ALValue resolutionToSizes(const int& arg1); + + /// + /// Set the active camera + /// + /// 0: top camera - 1: bottom camera + bool setActiveCamera(const int& activeCamera); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera requested. + bool setActiveCamera(const std::string& name, const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + /// Cameras requested. + AL::ALValue setActiveCameras(const std::string& name, const AL::ALValue& cameraIndexes); + + /// + /// + /// + /// Name of the subscribing vision module + bool setAllCameraParametersToDefault(const std::string& name); + + /// + /// + /// + /// Camera requested. + bool setAllParametersToDefault(const int& cameraIndex); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + /// value requested. + bool setCameraParameter(const std::string& name, const int& parameterId, const int& value); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + bool setCameraParameterToDefault(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + /// values requested. + AL::ALValue setCamerasParameter(const std::string& name, const int& parameterId, const AL::ALValue& values); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera parameter requested. + AL::ALValue setCamerasParameterToDefault(const std::string& name, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Color Space requested. + bool setColorSpace(const std::string& name, const int& colorSpace); + + /// + /// + /// + /// Name of the subscribing vision module + /// Color Spaces requested. + AL::ALValue setColorSpaces(const std::string& name, const AL::ALValue& colorSpaces); + + /// + /// + /// + /// Name of the subscribing vision module + /// Frame Rate requested. + bool setFrameRate(const std::string& name, const int& frameRate); + + /// + /// Sets the value of a specific parameter for the video source. + /// + /// Camera parameter requested. + /// value requested. + void setParam(const int& pParam, const int& pNewValue); + + /// + /// Sets the value of a specific parameter for the video source. + /// + /// Camera parameter requested. + /// value requested. + /// Camera requested. + void setParam(const int& pParam, const int& pNewValue, const int& pCameraIndex); + + /// + /// + /// + /// arg + void setParamDefault(const int& arg1); + + /// + /// + /// + /// Camera requested. + /// Camera parameter requested. + /// value requested. + bool setParameter(const int& cameraIndex, const int& parameterId, const int& value); + + /// + /// + /// + /// Camera requested. + /// Camera parameter requested. + bool setParameterToDefault(const int& cameraIndex, const int& parameterId); + + /// + /// + /// + /// Name of the subscribing vision module + /// Resolution requested. + bool setResolution(const std::string& name, const int& resolution); + + /// + /// + /// + /// Name of the subscribing vision module + /// Resolutions requested. + AL::ALValue setResolutions(const std::string& name, const AL::ALValue& resolutions); + + /// + /// called by the simulator to know expected image parameters + /// + /// int width of image among 1280*960, 640*480, 320*240, 240*160 + /// int height of image among 1280*960, 640*480, 320*240, 240*160 + /// true if setSize worked + bool setSimCamInputSize(const int& width, const int& height); + + /// + /// + /// + /// arg + /// arg + int sizesToResolution(const int& arg1, const int& arg2); + + /// + /// + /// + /// arg + bool startCamera(const int& arg1); + + /// + /// + /// + /// Camera requested. + bool startFrameGrabber(const int& cameraIndex); + + /// + /// Advanced method that opens and initialize video source device if it was not before. + /// Note that the first module subscribing to ALVideoDevice will launch it automatically. + /// + /// true if success + bool startFrameGrabber(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// + /// + /// arg + bool stopCamera(const int& arg1); + + /// + /// + /// + /// Camera requested. + bool stopFrameGrabber(const int& cameraIndex); + + /// + /// Advanced method that close video source device. + /// Note that the last module unsubscribing to ALVideoDevice will launch it automatically. + /// + /// true if success + bool stopFrameGrabber(); + + /// + /// Stop writing the video sequence + /// + /// Name under which the G.V.M. is known from ALVideoDevice. + /// true if success + bool stopVideo(const std::string& id); + + /// + /// Register to ALVideoDevice (formerly Video Input Module/V.I.M.). When a General Video Module(G.V.M.) registers to ALVideoDevice, a buffer of the requested image format is added to the buffers list. + /// Returns the name under which the G.V.M. is registered to ALVideoDevice (useful when two G.V.M. try to register using the same name + /// + /// Name of the subscribing G.V.M. + /// Resolution requested. { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA } + /// Colorspace requested. { 0 = kYuv, 9 = kYUV422, 10 = kYUV, 11 = kRGB, 12 = kHSY, 13 = kBGR } + /// Fps (frames per second) requested. { 5, 10, 15, 30 } + /// Name under which the G.V.M. is known from ALVideoDevice, 0 if failed. + std::string subscribe(const std::string& gvmName, const int& resolution, const int& colorSpace, const int& fps); + + /// + /// + /// + /// Name of the subscribing vision module + /// Camera requested. + /// Resolution requested.{0=kQQVGA, 1=kQVGA, 2=kVGA, 3=k4VGA} + /// Colorspace requested.{0=kYuv, 9=kYUV422, 10=kYUV, 11=kRGB, 12=kHSY, 13=kBGR} + /// Fps (frames per second) requested.{5, 10, 15, 30} + /// Name under which the vision module is known from ALVideoDevice + std::string subscribeCamera(const std::string& name, const int& cameraIndex, const int& resolution, const int& colorSpace, const int& fps); + + /// + /// + /// + /// Name of the subscribing vision module + /// Cameras requested. + /// Resolutions requested.{0=kQQVGA, 1=kQVGA, 2=kVGA, 3=k4VGA} + /// Colorspaces requested.{0=kYuv, 9=kYUV422, 10=kYUV, 11=kRGB, 12=kHSY, 13=kBGR} + /// Fps (frames per second) requested.{5, 10, 15, 30} + /// Name under which the vision module is known from ALVideoDevice + std::string subscribeCameras(const std::string& name, const AL::ALValue& cameraIndexes, const AL::ALValue& resolutions, const AL::ALValue& colorSpaces, const int& fps); + + /// + /// + /// + /// Name under which the vision module is known from ALVideoDevice. + /// True if success, false otherwise + bool unsubscribe(const std::string& nameId); + + /// + /// Used to unsubscribe all instances for a given G.V.M. (e.g. VisionModule and VisionModule_5) from ALVideoDevice. + /// + /// Root name of the G.V.M. (e.g. with the example above this will be VisionModule). + void unsubscribeAllInstances(const std::string& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALVideoDeviceProxyPostHandler post; + }; + +} +#endif // ALVIDEODEVICEPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvideorecorderproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvideorecorderproxy.h new file mode 100755 index 0000000..ab3800e --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvideorecorderproxy.h @@ -0,0 +1,312 @@ +// Generated for ALVideoRecorder version 0 + +#ifndef ALVIDEORECORDERPROXY_H_ +#define ALVIDEORECORDERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVideoRecorderProxy; + + namespace detail { + class ALVideoRecorderProxyPostHandler + { + protected: + ALVideoRecorderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVideoRecorderProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Sets camera ID. + /// + /// ID of the camera to use. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setCameraID(const int& cameraID); + + /// + /// Sets color space. + /// + /// New color space. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setColorSpace(const int& colorSpace); + + /// + /// Sets frame rate. + /// + /// New frame rate. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setFrameRate(const float& frameRate); + + /// + /// Sets resolution. + /// + /// New frame resolution. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setResolution(const int& resolution); + + /// + /// Sets video format. + /// + /// New video format. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setVideoFormat(const std::string& videoFormat); + + /// + /// Starts recording a video. Please note that only one record at a time can be made. + /// + /// Folder where the video is saved. + /// Filename used to save the video. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startRecording(const std::string& folderPath, const std::string& fileName); + + /// + /// Starts recording a video. Please note that only one record at a time can be made. + /// + /// Folder where the video is saved. + /// Filename used to save the video. + /// If false and the filename already exists, an exception is thrown. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startRecording(const std::string& folderPath, const std::string& fileName, const bool& overwrite); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALVideoRecorderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVideoRecorderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVideoRecorderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVideoRecorderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVideoRecorderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Returns current camera ID. + /// + /// Current camera ID. + int getCameraID(); + + /// + /// Returns current color space. + /// + /// Current color space. + int getColorSpace(); + + /// + /// Returns current frame rate. + /// + /// Current frame rate. + int getFrameRate(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Returns current resolution. + /// + /// Current resolution. + int getResolution(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns current video format. + /// + /// Current video format. + std::string getVideoFormat(); + + /// + /// Are we currently recording a video + /// + /// True/False + bool isRecording(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets camera ID. + /// + /// ID of the camera to use. + void setCameraID(const int& cameraID); + + /// + /// Sets color space. + /// + /// New color space. + void setColorSpace(const int& colorSpace); + + /// + /// Sets frame rate. + /// + /// New frame rate. + void setFrameRate(const float& frameRate); + + /// + /// Sets resolution. + /// + /// New frame resolution. + void setResolution(const int& resolution); + + /// + /// Sets video format. + /// + /// New video format. + void setVideoFormat(const std::string& videoFormat); + + /// + /// Starts recording a video. Please note that only one record at a time can be made. + /// + /// Folder where the video is saved. + /// Filename used to save the video. + void startRecording(const std::string& folderPath, const std::string& fileName); + + /// + /// Starts recording a video. Please note that only one record at a time can be made. + /// + /// Folder where the video is saved. + /// Filename used to save the video. + /// If false and the filename already exists, an exception is thrown. + void startRecording(const std::string& folderPath, const std::string& fileName, const bool& overwrite); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stops a video record that was launched with startRecording(). The function returns the number of frames that were recorded, as well as the video absolute file name. + /// + /// Array of two elements [numRecordedFrames, recordAbsolutePath] + AL::ALValue stopRecording(); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALVideoRecorderProxyPostHandler post; + }; + +} +#endif // ALVIDEORECORDERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvisionrecognitionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvisionrecognitionproxy.h new file mode 100755 index 0000000..d843b0c --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvisionrecognitionproxy.h @@ -0,0 +1,414 @@ +// Generated for ALVisionRecognition version 0 + +#ifndef ALVISIONRECOGNITIONPROXY_H_ +#define ALVISIONRECOGNITIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVisionRecognitionProxy; + + namespace detail { + class ALVisionRecognitionProxyPostHandler + { + protected: + ALVisionRecognitionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVisionRecognitionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// Set vision recognition parameters (deprecated in 1.22) + /// + /// Name of the parameter to be changed. Only "resolution" can be used. + /// Value of the resolution as an integer: 0(QQVGA) 1(QVGA) 2(VGA) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParam(const std::string& paramName, const AL::ALValue& paramValue); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALVisionRecognitionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVisionRecognitionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVisionRecognitionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVisionRecognitionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVisionRecognitionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// By default the database has the name "database" and is on the robot in /home/nao/naoqi/share/naoqi/vision/visionrecognition/current/ folder. This bound method allows to choose both another name and another folder for the database. + /// + /// + /// Absolute path of the database on the robot, or "" to set default path. + /// Name of the database (without extension), or "" to set default database name. + /// True if the operation succeded, false otherwise. + bool changeDatabase(const std::string& databasePath, const std::string& databaseName); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Get some vision recognition parameters. + /// + /// The name of the parameter to get. "db_path" and "db_name" can be used. + /// Value of the parameter as a string for "db_path" and "db_name" + AL::ALValue getParam(const std::string& paramName); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// Set vision recognition parameters (deprecated in 1.22) + /// + /// Name of the parameter to be changed. Only "resolution" can be used. + /// Value of the resolution as an integer: 0(QQVGA) 1(QVGA) 2(VGA) + void setParam(const std::string& paramName, const AL::ALValue& paramValue); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALVisionRecognitionProxyPostHandler post; + }; + +} +#endif // ALVISIONRECOGNITIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvisiontoolboxproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvisiontoolboxproxy.h new file mode 100755 index 0000000..3263a94 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvisiontoolboxproxy.h @@ -0,0 +1,305 @@ +// Generated for ALVisionToolbox version 1.18 + +#ifndef ALVISIONTOOLBOXPROXY_H_ +#define ALVISIONTOOLBOXPROXY_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVisionToolboxProxy; + + namespace detail { + class ALVisionToolboxProxyPostHandler + { + protected: + ALVisionToolboxProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVisionToolboxProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Prepare camera for shooting (like the auto-focus on standard and digital cameras) + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int halfPress(); + + /// + /// Set white balance by using Nao's white hands as reference. + /// + /// Camera we want to set white balance to : [0] top - [1] bottom - [2] both + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setWhiteBalance(const int& camera); + + /// + /// Start recording a video. The .avi video is stored on the robot in the \"/home/nao/.local/share/naoqi/vision\" folder. The record should be stopped by calling stopVideoRecord(). Resolution: 320*240, MJPG format, frame rate ~10-15 fps. Please note that only one record at a time can be made. + /// + /// Name of the video file to be recorded. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startVideoRecord(const std::string& videoName); + + /// + /// Start recording a video, with advanced options. Please note that only one record at a time can be made. + /// + /// Name of the video file to be recorded. + /// Record frame rate [0.1-50.0]. Warning: MJPG format requires framerate greater than 2.0. + /// ARV = raw YUV422 format; IYUV = raw avi, MJPG = compressed avi. + /// Resolution index. 0 = 160*120, 1 = 320*240, 2 = 640*480 + /// Number of frames to record. If less than 0, it records until stopVideoRecord() is called. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int startVideoRecord_adv(const std::string& videoName, const float& framerate, const std::string& format, const int& resIndex, const int& numFrames); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Stop an instance of takePictureRegularly() + /// + /// path and name root of the file we want to stop recording + /// formats of the file we want to stop recording + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stopTPR(const std::string& pathAndNameRoot, const std::string& imageRecordFormat); + + /// + /// Shoot 3 successives pictures and place them in the \"/home/nao/recordings/cameras/\" folder. If halfPress has not been called before, it will take longer between click and shoot. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int takePicture(); + + /// + /// Shoot regularly a picture to follow Nao's evolution in his environment + /// + /// how many seconds between two pictures? + /// path and the root of the name for the picture + /// do we need to overwrite the picture, or do we add a timestamp to the name? + /// such as jpeg, bmp, png, etc. + /// resolution for the image (e.g. kQQVGA, kQVGA) + /// brokerTaskID : The ID of the task assigned to it by the broker. + int takePictureRegularly(const float& secondsBetweenTwoShots, const std::string& pathAndNameRoot, const bool& overwriteImage, const std::string& imageRecordFormat, const int& resolution); + + /// + /// Shoot a specific number of successives pictures and place them in the \"/home/nao/recordings/cameras/\" folder. If halfPress has not been called before, it will take longer between click and shoot. + /// + /// how many pictures you want to take + /// brokerTaskID : The ID of the task assigned to it by the broker. + int takePictures(const int& numberOfPictures); + + private: + boost::shared_ptr _proxy; + }; + } + + /// This module contains different vision functionalities, like picture taking, video recording, white balance setting, etc ... Videos are recorded in \"/home/nao/.local/share/naoqi/vision\". Pictures are recorded in \"/home/nao/recordings/cameras/\" + /// \ingroup ALProxies + class ALPROXIES_API ALVisionToolboxProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVisionToolboxProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVisionToolboxProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVisionToolboxProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVisionToolboxProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Indicates if we might be in backlighting conditions. + /// + /// 0: no backlight - 1: possible backlight - 2 and more: backlight identified + int backlighting(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Prepare camera for shooting (like the auto-focus on standard and digital cameras) + /// + void halfPress(); + + /// + /// Tell if it is dark around. + /// + /// [0;4] outdoor - [5;100] indoor bright - [101;127] indoor artificial light - [128;210] indoor weak lights - [211;255] dark place + int isItDark(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Are we currently recording a video with startVideoRecord() or startVideoRecord_adv(). + /// + /// True/False + bool isVideoRecording(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set white balance by using Nao's white hands as reference. + /// + /// Camera we want to set white balance to : [0] top - [1] bottom - [2] both + void setWhiteBalance(const int& camera); + + /// + /// Start recording a video. The .avi video is stored on the robot in the \"/home/nao/.local/share/naoqi/vision\" folder. The record should be stopped by calling stopVideoRecord(). Resolution: 320*240, MJPG format, frame rate ~10-15 fps. Please note that only one record at a time can be made. + /// + /// Name of the video file to be recorded. + void startVideoRecord(const std::string& videoName); + + /// + /// Start recording a video, with advanced options. Please note that only one record at a time can be made. + /// + /// Name of the video file to be recorded. + /// Record frame rate [0.1-50.0]. Warning: MJPG format requires framerate greater than 2.0. + /// ARV = raw YUV422 format; IYUV = raw avi, MJPG = compressed avi. + /// Resolution index. 0 = 160*120, 1 = 320*240, 2 = 640*480 + /// Number of frames to record. If less than 0, it records until stopVideoRecord() is called. + void startVideoRecord_adv(const std::string& videoName, const float& framerate, const std::string& format, const int& resIndex, const int& numFrames); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Stop an instance of takePictureRegularly() + /// + /// path and name root of the file we want to stop recording + /// formats of the file we want to stop recording + void stopTPR(const std::string& pathAndNameRoot, const std::string& imageRecordFormat); + + /// + /// Stop a video record that was launched with startVideoRecord() or startVideoRecord_adv(). The function returns the number of frames that were recorded, as well as the video absolute file name. + /// + /// Array of two elements [numRecordedFrames, recordAbsolutePath] + AL::ALValue stopVideoRecord(); + + /// + /// Shoot 3 successives pictures and place them in the \"/home/nao/recordings/cameras/\" folder. If halfPress has not been called before, it will take longer between click and shoot. + /// + void takePicture(); + + /// + /// Shoot regularly a picture to follow Nao's evolution in his environment + /// + /// how many seconds between two pictures? + /// path and the root of the name for the picture + /// do we need to overwrite the picture, or do we add a timestamp to the name? + /// such as jpeg, bmp, png, etc. + /// resolution for the image (e.g. kQQVGA, kQVGA) + void takePictureRegularly(const float& secondsBetweenTwoShots, const std::string& pathAndNameRoot, const bool& overwriteImage, const std::string& imageRecordFormat, const int& resolution); + + /// + /// Shoot a specific number of successives pictures and place them in the \"/home/nao/recordings/cameras/\" folder. If halfPress has not been called before, it will take longer between click and shoot. + /// + /// how many pictures you want to take + void takePictures(const int& numberOfPictures); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALVisionToolboxProxyPostHandler post; + }; + +} +#endif // ALVISIONTOOLBOXPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvisualcompassproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvisualcompassproxy.h new file mode 100755 index 0000000..2298dcc --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvisualcompassproxy.h @@ -0,0 +1,440 @@ +// Generated for ALVisualCompass version 0 + +#ifndef ALVISUALCOMPASSPROXY_H_ +#define ALVISUALCOMPASSPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVisualCompassProxy; + + namespace detail { + class ALVisualCompassProxyPostHandler + { + protected: + ALVisualCompassProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVisualCompassProxy; + + /// + /// + /// + /// True if the reference is automatically refreshed at extractor startup; false to use the manually set reference image. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int enableReferenceRefresh(const bool& refresh); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& paused); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + /// + /// Block the current thread until the target is reached. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int waitUntilTargetReached(); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALVisualCompassProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVisualCompassProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVisualCompassProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVisualCompassProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVisualCompassProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// True if the reference is automatically refreshed at extractor startup; false to use the manually set reference image. + void enableReferenceRefresh(const bool& refresh); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets extractor active camera + /// + /// Id of the current active camera of the extractor + int getActiveCamera(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets extractor framerate + /// + /// Current value of the framerate of the extractor + int getFrameRate(); + + /// + /// Returns the reliability of the matching and the compass deviation computations. + /// [1]: Number of keypoints matching. + /// + /// [0]: Percentage of the matched keypoints that are used to compute the deviation (significant if over 50%) + AL::ALValue getMatchingQuality(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Returns an ALValue containing the image used as a reference. + /// + /// Reference image (formatted as the ALValue from getImageRemote of ALVideoDevice) + AL::ALValue getReferenceImage(); + + /// + /// Gets extractor resolution + /// + /// Current value of the resolution of the extractor + int getResolution(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Gets extractor pause status + /// + /// True if the extractor is paused, False if not + bool isPaused(); + + /// + /// Gets extractor running status + /// + /// True if the extractor is currently processing images, False if not + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// Move along the robot X axis. + /// + /// Algebric distance along the X axis in meters. + bool moveStraightTo(const float& x); + + /// + /// Go to input pose (in robot referential). + /// + /// Distance along the X axis in meters. + /// Distance along the Y axis in meters. + /// Rotation around the Z axis in radians [-3.1415 to 3.1415]. + bool moveTo(const float& x, const float& y, const float& theta); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Changes the pause status of the extractor + /// + /// New pause satus + void pause(const bool& paused); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Sets extractor active camera + /// + /// Id of the camera that will become the active camera + /// True if the update succeeded, False if not + bool setActiveCamera(const int& cameraId); + + /// + /// Sets the reference image for the compass. + /// + /// True if the reference image has been successfully set + bool setCurrentImageAsReference(); + + /// + /// Sets the extractor framerate for a chosen subscriber + /// + /// Name of the subcriber + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const std::string& subscriberName, const int& framerate); + + /// + /// Sets the extractor framerate for all the subscribers + /// + /// New framerate + /// True if the update succeeded, False if not + bool setFrameRate(const int& framerate); + + /// + /// DEPRECATED: Sets pause and resolution + /// + /// Name of the parameter to set + /// New value + void setParameter(const std::string& paramName, const AL::ALValue& value); + + /// + /// Sets extractor resolution + /// + /// New resolution + /// True if the update succeeded, False if not + bool setResolution(const int& resolution); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + /// + /// Block the current thread until the target is reached. + /// + void waitUntilTargetReached(); + + + detail::ALVisualCompassProxyPostHandler post; + }; + +} +#endif // ALVISUALCOMPASSPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alvisualspacehistoryproxy.h b/naoModule/libnaoqi_files/include/alproxies/alvisualspacehistoryproxy.h new file mode 100755 index 0000000..8927b4f --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alvisualspacehistoryproxy.h @@ -0,0 +1,326 @@ +// Generated for ALVisualSpaceHistory version 0 + +#ifndef ALVISUALSPACEHISTORYPROXY_H_ +#define ALVISUALSPACEHISTORYPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALVisualSpaceHistoryProxy; + + namespace detail { + class ALVisualSpaceHistoryProxyPostHandler + { + protected: + ALVisualSpaceHistoryProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALVisualSpaceHistoryProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Resets grid with current timestamp + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int resetGrid(); + + /// + /// Sets grid precision + /// + /// float, ratio between camera field of view and grid cell field of view in each dimension. Setting the grid precision will reset the grid. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setGridPrecision(const float& precision); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALVisualSpaceHistoryProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALVisualSpaceHistoryProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALVisualSpaceHistoryProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALVisualSpaceHistoryProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALVisualSpaceHistoryProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Gets grid precision + /// + /// Grid precision + float getGridPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Resets grid with current timestamp + /// + void resetGrid(); + + /// + /// Sets grid precision + /// + /// float, ratio between camera field of view and grid cell field of view in each dimension. Setting the grid precision will reset the grid. + void setGridPrecision(const float& precision); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALVisualSpaceHistoryProxyPostHandler post; + }; + +} +#endif // ALVISUALSPACEHISTORYPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alwavingdetectionproxy.h b/naoModule/libnaoqi_files/include/alproxies/alwavingdetectionproxy.h new file mode 100755 index 0000000..ab25129 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alwavingdetectionproxy.h @@ -0,0 +1,349 @@ +// Generated for ALWavingDetection version 0 + +#ifndef ALWAVINGDETECTIONPROXY_H_ +#define ALWAVINGDETECTIONPROXY_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALWavingDetectionProxy; + + namespace detail { + class ALWavingDetectionProxyPostHandler + { + protected: + ALWavingDetectionProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALWavingDetectionProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// + /// + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int pause(const bool& status); + + /// + /// Set maximum distance for waving detection + /// + /// New maximum distance (in meters), between 0.5m and 3m + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMaxDistance(const float& maxDistance); + + /// + /// Set minimum size of movement for waving detection + /// + /// New minimum size (in meters), between 0.05m and 0.3m + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setMinSize(const float& sensitivity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + /// brokerTaskID : The ID of the task assigned to it by the broker. + int updatePrecision(const std::string& name, const float& precision); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALWavingDetectionProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALWavingDetectionProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALWavingDetectionProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALWavingDetectionProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALWavingDetectionProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Gets the current period. + /// + /// Refresh period (in milliseconds). + int getCurrentPeriod(); + + /// + /// Gets the current precision. + /// + /// Precision of the extractor. + float getCurrentPrecision(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getEventList(); + + /// + /// Get maximum distance for waving detection + /// + /// Current maximum distance (in meters) + float getMaxDistance(); + + /// + /// Get the list of events updated in ALMemory. + /// + /// Array of events updated by this extractor in ALMemory + std::vector getMemoryKeyList(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Get minimum size of movement for waving detection + /// + /// Current minimum size (in meters) + float getMinSize(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the period for a specific subscription. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + int getMyPeriod(const std::string& name); + + /// + /// Gets the precision for a specific subscription. + /// + /// name of the module which has subscribed + /// precision of the extractor + float getMyPrecision(const std::string& name); + + /// + /// Get the list of values updated in ALMemory. + /// + /// Array of values updated by this extractor in ALMemory + std::vector getOutputNames(); + + /// + /// Gets the parameters given by the module. + /// + /// Array of names and parameters of all subscribers. + AL::ALValue getSubscribersInfo(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// + /// + bool isPaused(); + + /// + /// + /// + bool isProcessing(); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + /// + void pause(const bool& status); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Set maximum distance for waving detection + /// + /// New maximum distance (in meters), between 0.5m and 3m + void setMaxDistance(const float& maxDistance); + + /// + /// Set minimum size of movement for waving detection + /// + /// New minimum size (in meters), between 0.05m and 0.3m + void setMinSize(const float& sensitivity); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + /// Refresh period (in milliseconds) if relevant. + /// Precision of the extractor if relevant. + void subscribe(const std::string& name, const int& period, const float& precision); + + /// + /// Subscribes to the extractor. This causes the extractor to start writing information to memory using the keys described by getOutputNames(). These can be accessed in memory using ALMemory.getData("keyName"). In many cases you can avoid calling subscribe on the extractor by just calling ALMemory.subscribeToEvent() supplying a callback method. This will automatically subscribe to the extractor for you. + /// + /// Name of the module which subscribes. + void subscribe(const std::string& name); + + /// + /// Unsubscribes from the extractor. + /// + /// Name of the module which had subscribed. + void unsubscribe(const std::string& name); + + /// + /// Updates the period if relevant. + /// + /// Name of the module which has subscribed. + /// Refresh period (in milliseconds). + void updatePeriod(const std::string& name, const int& period); + + /// + /// Updates the precision if relevant. + /// + /// Name of the module which has subscribed. + /// Precision of the extractor. + void updatePrecision(const std::string& name, const float& precision); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALWavingDetectionProxyPostHandler post; + }; + +} +#endif // ALWAVINGDETECTIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/alworldrepresentationproxy.h b/naoModule/libnaoqi_files/include/alproxies/alworldrepresentationproxy.h new file mode 100755 index 0000000..55e17e1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/alworldrepresentationproxy.h @@ -0,0 +1,395 @@ +// Generated for ALWorldRepresentation version 0 + +#ifndef ALWORLDREPRESENTATIONPROXY_H_ +#define ALWORLDREPRESENTATIONPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class ALWorldRepresentationProxy; + + namespace detail { + class ALWorldRepresentationProxyPostHandler + { + protected: + ALWorldRepresentationProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::ALWorldRepresentationProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API ALWorldRepresentationProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + ALWorldRepresentationProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + ALWorldRepresentationProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + ALWorldRepresentationProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + ALWorldRepresentationProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Add an attribute to a category. + /// + /// arg + /// arg + /// arg + int addAttributeToCategory(const std::string& arg1, const std::string& arg2, const AL::ALValue& arg3); + + /// + /// Clear an object. + /// + /// arg + int clearObject(const std::string& arg1); + + /// + /// Clear recording of old positions. + /// + /// arg + /// arg + int clearOldPositions(const std::string& arg1, const int& arg2); + + /// + /// Create a new object category + /// + /// arg + /// arg + int createObjectCategory(const std::string& arg1, const bool& arg2); + + /// + /// Delete an object attribute + /// + /// arg + /// arg + /// arg + int deleteObjectAttribute(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Check that an object is present. + /// + /// arg + bool findObject(const std::string& arg1); + + /// + /// Get all attributes from a category if it exists. + /// + /// arg + AL::ALValue getAttributesFromCategory(const std::string& arg1); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Get the direct children of an object. + /// + /// arg + std::vector getChildrenNames(const std::string& arg1); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// + /// + /// arg + /// arg + /// arg + AL::ALValue getObjectAttributeValues(const std::string& arg1, const std::string& arg2, const int& arg3); + + /// + /// + /// + /// arg + AL::ALValue getObjectAttributes(const std::string& arg1); + + /// + /// Get the name of the database where the object is stored. + /// + /// arg + std::string getObjectCategory(const std::string& arg1); + + /// + /// + /// + /// arg + /// arg + AL::ALValue getObjectLatestAttributes(const std::string& arg1, const int& arg2); + + /// + /// Get the name of the objects. + /// + std::vector getObjectNames(); + + /// + /// + /// + /// arg + std::string getObjectParentName(const std::string& arg1); + + /// + /// Get the name of the objects stored in the database. + /// + /// arg + std::vector getObjectsInCategory(const std::string& arg1); + + /// + /// Get the position of an object with quaternion / translation. + /// + /// arg + /// arg + AL::ALValue getPosition(const std::string& arg1, const std::string& arg2); + + /// + /// Get the position from one object to another. + /// + /// arg + /// arg + std::vector getPosition6D(const std::string& arg1, const std::string& arg2); + + /// + /// Get the interpolated position of an object + /// + /// arg + /// arg + /// arg + /// arg + std::vector getPosition6DAtTime(const std::string& arg1, const std::string& arg2, const int& arg3, const int& arg4); + + /// + /// + /// + std::string getRootName(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// + /// + int load(); + + /// + /// Tells if an object category exists + /// + /// arg + bool objectCategoryExists(const std::string& arg1); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Remove an object category + /// + /// arg + int removeObjectCategory(const std::string& arg1); + + /// + /// + /// + int save(); + + /// + /// Select information from a database. + /// + /// arg + /// arg + /// arg + /// arg + AL::ALValue select(const std::string& arg1, const std::string& arg2, const std::string& arg3, const std::string& arg4); + + /// + /// Select ordered information from a database. + /// + /// arg + /// arg + /// arg + /// arg + /// arg + AL::ALValue selectWithOrder(const std::string& arg1, const std::string& arg2, const std::string& arg3, const std::string& arg4, const std::string& arg5); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// + /// + /// arg + /// arg + /// arg + /// arg + /// arg + int storeObject(const std::string& arg1, const std::string& arg2, const std::vector& arg3, const std::string& arg4, const AL::ALValue& arg5); + + /// + /// + /// + /// arg + /// arg + /// arg + int storeObjectAttribute(const std::string& arg1, const std::string& arg2, const AL::ALValue& arg3); + + /// + /// + /// + /// arg + /// arg + /// arg + /// arg + /// arg + /// arg + int storeObjectWithReference(const std::string& arg1, const std::string& arg2, const std::string& arg3, const std::vector& arg4, const std::string& arg5, const AL::ALValue& arg6); + + /// + /// + /// + /// arg + /// arg + /// arg + /// arg + int updateAttribute(const std::string& arg1, const std::string& arg2, const std::string& arg3, const AL::ALValue& arg4); + + /// + /// Update the position of an object. + /// + /// arg + /// arg + /// arg + int updatePosition(const std::string& arg1, const std::vector& arg2, const bool& arg3); + + /// + /// Update the position of an object relative to another. + /// + /// arg + /// arg + /// arg + /// arg + int updatePositionWithReference(const std::string& arg1, const std::string& arg2, const std::vector& arg3, const bool& arg4); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::ALWorldRepresentationProxyPostHandler post; + }; + +} +#endif // ALWORLDREPRESENTATIONPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/api.h b/naoModule/libnaoqi_files/include/alproxies/api.h new file mode 100755 index 0000000..dc23370 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/api.h @@ -0,0 +1,29 @@ +/** + * Author(s): + * - Cedric GESTES + * + * Copyright (C) 2011, 2012 Aldebaran Robotics + */ + +/** @file + * @brief dll import/export + */ + +#pragma once +#ifndef _LIBALPROXIES_ALPROXIES_API_H_ +#define _LIBALPROXIES_ALPROXIES_API_H_ + +#include + +#ifdef alproxies_EXPORTS +# define ALPROXIES_API QI_EXPORT_API +#else +# define ALPROXIES_API QI_IMPORT_API +#endif + +#undef ALPROXIES_API +#define ALPROXIES_API + + +#endif // _LIBALPROXIES_ALPROXIES_API_H_ + diff --git a/naoModule/libnaoqi_files/include/alproxies/audiofilterloaderproxy.h b/naoModule/libnaoqi_files/include/alproxies/audiofilterloaderproxy.h new file mode 100755 index 0000000..0c4589c --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/audiofilterloaderproxy.h @@ -0,0 +1,173 @@ +// Generated for AudioFilterLoader version 0 + +#ifndef AUDIOFILTERLOADERPROXY_H_ +#define AUDIOFILTERLOADERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class AudioFilterLoaderProxy; + + namespace detail { + class AudioFilterLoaderProxyPostHandler + { + protected: + AudioFilterLoaderProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::AudioFilterLoaderProxy; + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API AudioFilterLoaderProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + AudioFilterLoaderProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + AudioFilterLoaderProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + AudioFilterLoaderProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + AudioFilterLoaderProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::AudioFilterLoaderProxyPostHandler post; + }; + +} +#endif // AUDIOFILTERLOADERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/dcmproxy.h b/naoModule/libnaoqi_files/include/alproxies/dcmproxy.h new file mode 100755 index 0000000..6e26fcf --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/dcmproxy.h @@ -0,0 +1,272 @@ +// Generated for DCM version 0 + +#ifndef DCMPROXY_H_ +#define DCMPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class DCMProxy; + + namespace detail { + class DCMProxyPostHandler + { + protected: + DCMProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::DCMProxy; + + /// + /// Calibration of a joint + /// + /// A complex ALValue. See red documentation + /// brokerTaskID : The ID of the task assigned to it by the broker. + int calibration(const AL::ALValue& calibrationInput); + + /// + /// Exits and unregisters the module. + /// + /// brokerTaskID : The ID of the task assigned to it by the broker. + int exit(); + + /// + /// Call this function to send a timed-command list to an actuator + /// + /// AL::ALValue with all data + /// brokerTaskID : The ID of the task assigned to it by the broker. + int set(const AL::ALValue& commands); + + /// + /// Call this function to send timed-command list to an alias (list of actuators) + /// + /// AL::ALValue with all data + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAlias(const AL::ALValue& commands); + + /// + /// Call this function to send timed-command list to an alias (list of actuators) with "ClearAll" merge startegy + /// + /// alias name + /// time for the timed command + /// std::vector with all commands + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setAlias(const std::string& name, const int& time, const std::vector& commands); + + /// + /// Special DCM commands + /// + /// one string and could be Reset, Version, Chain, Diagnostic, Config + /// brokerTaskID : The ID of the task assigned to it by the broker. + int special(const std::string& result); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + /// brokerTaskID : The ID of the task assigned to it by the broker. + int stop(const int& id); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API DCMProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + DCMProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + DCMProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + DCMProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + DCMProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// Calibration of a joint + /// + /// A complex ALValue. See red documentation + void calibration(const AL::ALValue& calibrationInput); + + /// + /// Create or change an alias (list of actuators) + /// + /// Alias name and description + /// Same as pParams, but with the name removed if the actuator is not found + AL::ALValue createAlias(const AL::ALValue& alias); + + /// + /// Exits and unregisters the module. + /// + void exit(); + + /// + /// Gets the name of the parent broker. + /// + /// The name of the parent broker. + std::string getBrokerName(); + + /// + /// Retrieves a method's description. + /// + /// The name of the method. + /// A structure containing the method's description. + AL::ALValue getMethodHelp(const std::string& methodName); + + /// + /// Retrieves the module's method list. + /// + /// An array of method names. + std::vector getMethodList(); + + /// + /// Retrieves the module's description. + /// + /// A structure describing the module. + AL::ALValue getModuleHelp(); + + /// + /// Return the STM base name + /// + /// the STM base name for all device/sensors (1st string in the array) and all devices (2nd string in the array) + AL::ALValue getPrefix(); + + /// + /// Return the DCM time + /// + /// optional time in ms (signed) to add/remove + /// An integer (could be signed) with the DCM time + int getTime(const int& offset); + + /// + /// Gets the method usage string. This summarises how to use the method. + /// + /// The name of the method. + /// A string that summarises the usage of the method. + std::string getUsage(const std::string& name); + + /// + /// Returns true if the method is currently running. + /// + /// The ID of the method that was returned when calling the method using 'post' + /// True if the method is currently running + bool isRunning(const int& id); + + /// + /// NAOqi1 pCall method. + /// + AL::ALValue pCall(); + + /// + /// Just a ping. Always returns true + /// + /// returns true + bool ping(); + + /// + /// Save updated value from DCM in XML pref file + /// + /// string : 'Save' 'Load' 'Add' + /// string : 'Chest' 'Head' 'Main' 'All' + /// The name of the key if action = 'Add'. + /// The ALVAlue of the key to add + /// Nothing + int preferences(const std::string& action, const std::string& target, const std::string& keyName, const AL::ALValue& keyValue); + + /// + /// Call this function to send a timed-command list to an actuator + /// + /// AL::ALValue with all data + void set(const AL::ALValue& commands); + + /// + /// Call this function to send timed-command list to an alias (list of actuators) + /// + /// AL::ALValue with all data + void setAlias(const AL::ALValue& commands); + + /// + /// Call this function to send timed-command list to an alias (list of actuators) with "ClearAll" merge startegy + /// + /// alias name + /// time for the timed command + /// std::vector with all commands + void setAlias(const std::string& name, const int& time, const std::vector& commands); + + /// + /// Special DCM commands + /// + /// one string and could be Reset, Version, Chain, Diagnostic, Config + void special(const std::string& result); + + /// + /// returns true if the method is currently running + /// + /// the ID of the method to wait for + void stop(const int& id); + + /// + /// Returns the version of the module. + /// + /// A string containing the version of the module. + std::string version(); + + /// + /// Wait for the end of a long running method that was called using 'post' + /// + /// The ID of the method that was returned when calling the method using 'post' + /// The timeout period in ms. To wait indefinately, use a timeoutPeriod of zero. + /// True if the timeout period terminated. False if the method returned. + bool wait(const int& id, const int& timeoutPeriod); + + + detail::DCMProxyPostHandler post; + }; + +} +#endif // DCMPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alproxies/networkinfo.h b/naoModule/libnaoqi_files/include/alproxies/networkinfo.h new file mode 100755 index 0000000..2a9f8c0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/networkinfo.h @@ -0,0 +1,139 @@ +/* +** Author(s): +** - Julien MASSOT +** +** Copyright (C) 2012 Aldebaran Robotics +*/ + +#ifndef _ALPROXIES_NETWORKINFO_HPP_ +#define _ALPROXIES_NETWORKINFO_HPP_ + +#include +#include +#include +#include +#include + +class NetworkInfoPrivate; + +class ALPROXIES_API NetworkInfo +{ +public: + class IPInfoPrivate; + class ALPROXIES_API IPInfo + { + public: + IPInfo(const std::string &method, + const std::string &ipAddress, + const std::string &netmask, + const std::string &gateway); + + IPInfo(const std::string &method, + const std::string &ipAddress, + int prefix, + const std::string &gateway); + IPInfo(const IPInfo &other); + IPInfo(); + IPInfo(const AL::ALValue &alvalue); + + ~IPInfo(); + + std::string method() const; + std::string ipAddress() const; + std::string netmask() const; + int prefix() const; + std::string gateway() const; + + bool operator==(const IPInfo &other) const; + bool operator!=(const IPInfo &other) const; + IPInfo &operator=(const IPInfo &other); + + AL::ALValue toALValue() const; + private: + IPInfoPrivate *_private; + }; + + class ProxyInfoPrivate; + class ALPROXIES_API ProxyInfo + { + public: + ProxyInfo(const std::string &method, + const std::string &url, + const std::vector &servers, + const std::vector &excludes); + ProxyInfo(const AL::ALValue &alvalue); + ProxyInfo(const ProxyInfo &other); + ProxyInfo(); + + ~ProxyInfo(); + std::string method() const; + std::string url() const; + std::vector servers() const; + std::vector excludes() const; + ProxyInfo &operator=(const ProxyInfo &other); + bool operator==(const NetworkInfo::ProxyInfo &other) const; + bool operator!=(const NetworkInfo::ProxyInfo &other) const; + AL::ALValue toALValue() const; + private: + ProxyInfoPrivate* _private; + }; + + NetworkInfo(const std::string &name, + const std::string &type); + + NetworkInfo(const std::string &serviceId, + const std::string &name, + const std::string &type, + const std::string &state, + bool favorite, + bool autoconnect, + const std::vector &security, + const std::vector &domains, + const std::vector &nameserver, + IPInfo ipv4, + IPInfo ipv6, + ProxyInfo proxy, + int strength, + const std::string &error); + + NetworkInfo(const AL::ALValue &alvalue); + NetworkInfo(const NetworkInfo &other); + + virtual ~NetworkInfo(); + + std::string serviceId() const; + std::string name() const; + std::string type() const; + std::string state() const; + bool favorite() const; + bool autoconnect() const; + std::vector security() const; + std::vector domains() const; + std::vector nameserver() const; + IPInfo ipv4() const; + IPInfo ipv6() const; + ProxyInfo proxy() const; + int strength() const; + std::string error() const; + void setIPv4(const std::string &address, const std::string &netmask, const std::string &gateway); + void setIPv6(const std::string &address, int prefix, const std::string &gateway); + void setProxy(const std::string &method, const std::string &url, const std::vector &servers, const std::vector &excludes); + void setIPv4(const IPInfo &ipv4info); + void setIPv6(const IPInfo &ipv6info); + void setProxy(const ProxyInfo &proxyinfo); + void setDomains(const std::vector &domains); + void setNameservers(const std::vector &nameservers); + void setAutoconnect(bool autoconnect); + void setError(const std::string &error); + AL::ALValue toALValue() const; + NetworkInfo &operator=(const NetworkInfo &other); + +private: + NetworkInfoPrivate *_private; +}; + +std::ostream& operator<<(std::ostream &stream, const NetworkInfo::ProxyInfo &proxyinfo); +std::ostream& operator<<(std::ostream &stream, const NetworkInfo::IPInfo &ipinfo); +std::ostream& operator<<(std::ostream &stream, const NetworkInfo &networkinfo); + +#endif /* !_ALPROXIES_NETWORKINFO_HPP_ */ diff --git a/naoModule/libnaoqi_files/include/alproxies/notificationinfo.h b/naoModule/libnaoqi_files/include/alproxies/notificationinfo.h new file mode 100755 index 0000000..bb8be3b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/notificationinfo.h @@ -0,0 +1,53 @@ +/* +** Author(s): +** - Cuche Herve +** +** Copyright (C) 2012 Cuche Herve +*/ + +#ifndef _ALPROXIES_NOTIFICATIONINFO_H_ +# define _ALPROXIES_NOTIFICATIONINFO_H_ + +# include +# include +# include +# include + +namespace AL +{ + class NotificationInfoPrivate; + class ALPROXIES_API NotificationInfo + { + public: + NotificationInfo(const std::string &message, + const std::string &severity, + bool removeOnRead = true); + NotificationInfo(const AL::ALValue ¬ificationInfo); + NotificationInfo(const NotificationInfo &rhs); + NotificationInfo &operator=(const NotificationInfo &rhs); + + virtual ~NotificationInfo(); + + int id() const; + void setId(int id); + + std::string message() const; + void setMessage(const std::string &message); + + std::string severity() const; + void setSeverity(const std::string &severity); + + bool removeOnRead() const; + void setRemoveOnRead(bool removeOnRead); + + AL::ALValue toALValue() const; + + public: + NotificationInfoPrivate *_p; + }; +} + +std::ostream &operator<<(std::ostream &stream, + const AL::NotificationInfo ¬ificationInfo); + +#endif /* !_ALPROXIES_NOTIFICATIONINFO_H_ */ diff --git a/naoModule/libnaoqi_files/include/alproxies/packagemanagerproxy.h b/naoModule/libnaoqi_files/include/alproxies/packagemanagerproxy.h new file mode 100755 index 0000000..ae7ea2b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alproxies/packagemanagerproxy.h @@ -0,0 +1,196 @@ +// Generated for PackageManager version 0 + +#ifndef PACKAGEMANAGERPROXY_H_ +#define PACKAGEMANAGERPROXY_H_ + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace AL +{ + class ALBroker; + class ALProxy; + class PackageManagerProxy; + + namespace detail { + class PackageManagerProxyPostHandler + { + protected: + PackageManagerProxyPostHandler(boost::shared_ptr proxy); + + public: + friend class AL::PackageManagerProxy; + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int removePkg(const std::string& arg1); + + /// + /// + /// + /// arg + /// brokerTaskID : The ID of the task assigned to it by the broker. + int setServiceDirectory(const std::string& arg1); + + private: + boost::shared_ptr _proxy; + }; + } + + /// + /// \ingroup ALProxies + class ALPROXIES_API PackageManagerProxy + { + private: + boost::shared_ptr _proxy; + + public: + /// + /// Default Constructor. If there is a broker in your process, which is always the case + /// if you are in a module, then this will be found and used. + /// + PackageManagerProxy(); + + /// + /// Explicit Broker Constructor. If you have a smart pointer to a broker that you want + /// to specify, then you can use this constructor. In most cases, the default constructor + /// will do the work for you without passing a broker explicitly. + /// + /// A smart pointer to your broker + PackageManagerProxy(boost::shared_ptr broker); + + /// + /// Explicit Proxy Constructor. Create a specialised proxy from a generic proxy. + /// + /// A smart pointer to your broker + PackageManagerProxy(boost::shared_ptr proxy); + + /// + /// Remote Constructor. This constructor allows you to connect to a remote module by + /// explicit IP address and port. This is useful if you are not within a process that + /// has a broker, or want to connect to a remote instance of NAOqi such as another + /// robot. + /// + /// The IP address of the remote module you want to connect to + /// The port of the remote module, typically 9559 + PackageManagerProxy(const std::string &ip, int port=9559); + + /// + /// Gets the underlying generic proxy + /// + boost::shared_ptr getGenericProxy(); + + /// + /// + /// + /// arg + AL::ALValue getPackage(const std::string& arg1); + + /// + /// + /// + /// arg + AL::ALValue getPackageIcon(const std::string& arg1); + + /// + /// + /// + AL::ALValue getPackages(); + + /// + /// + /// + /// arg + bool hasPackage(const std::string& arg1); + + /// + /// + /// + /// arg + bool install(const std::string& arg1); + + /// + /// + /// + /// arg + /// arg + int install(const std::string& arg1, const std::string& arg2); + + /// + /// + /// + /// arg + /// arg + /// arg + int install(const std::string& arg1, const std::string& arg2, const std::string& arg3); + + /// + /// + /// + /// arg + /// arg + bool installCheckMd5(const std::string& arg1, const std::string& arg2); + + /// + /// + /// + /// arg + AL::ALValue package(const std::string& arg1); + + /// + /// + /// + /// arg + AL::ALValue package2(const std::string& arg1); + + /// + /// + /// + /// arg + std::string packageIcon(const std::string& arg1); + + /// + /// + /// + std::vector packages(); + + /// + /// + /// + std::vector packages2(); + + /// + /// + /// + /// arg + int remove(const std::string& arg1); + + /// + /// + /// + /// arg + void removePkg(const std::string& arg1); + + /// + /// + /// + /// arg + void setServiceDirectory(const std::string& arg1); + + + detail::PackageManagerProxyPostHandler post; + }; + +} +#endif // PACKAGEMANAGERPROXY_H_ diff --git a/naoModule/libnaoqi_files/include/alpythontools/alpython.h b/naoModule/libnaoqi_files/include/alpythontools/alpython.h new file mode 100755 index 0000000..9af840b --- /dev/null +++ b/naoModule/libnaoqi_files/include/alpythontools/alpython.h @@ -0,0 +1,22 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007 All Rights Reserved +*/ + +#pragma once + +#ifndef _LIB_ALPYTHONTOOLS_ALPYTHONTOOLS_ALPYTHON_H_ +#define _LIB_ALPYTHONTOOLS_ALPYTHONTOOLS_ALPYTHON_H_ + +// dmerej 2009-21-01: this is an hack for preventing warnings about +// redefinitions in Python.h and stdsoap.h + +// Should be fixed when we split alcommon +#undef HAVE_FTIME +#undef HAVE_TIMEGM +#undef _REENTRANT +#undef _XOPEN_SOURCE + +#include "Python.h" + +#endif diff --git a/naoModule/libnaoqi_files/include/alpythontools/alpythontools.h b/naoModule/libnaoqi_files/include/alpythontools/alpythontools.h new file mode 100755 index 0000000..9ccfc18 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alpythontools/alpythontools.h @@ -0,0 +1,61 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007 All Rights Reserved +*/ + +#pragma once + +#ifndef _LIB_ALPYTHONTOOLS_ALPYTHONTOOLS_ALPYTHONTOOLS_H_ +#define _LIB_ALPYTHONTOOLS_ALPYTHONTOOLS_ALPYTHONTOOLS_H_ + +#include "alpython.h" +#include + +/** +* All classes visible in python are here +*/ + + +namespace AL +{ + class ALValue; + + class ALCriticalSectionGILPython + { + public: + ALCriticalSectionGILPython() : fState(PyGILState_Ensure()){} + ~ALCriticalSectionGILPython() {PyGILState_Release(fState);} + + private: + PyGILState_STATE fState; + }; + + class ALCriticalSectionAllowThreadsPython + { + public: + ALCriticalSectionAllowThreadsPython() : fSave(PyEval_SaveThread()) {} + ~ALCriticalSectionAllowThreadsPython() {PyEval_RestoreThread(fSave);} + + private: + PyThreadState* fSave; + }; + + /** + * ALPythonTools + */ + class ALPythonTools + { + public: + + /** + * convert PyObject to AL::ALValue + */ + static std::string eval(const std::string& pModuleName, const std::string& pMethod, const AL::ALValue& pParams, AL::ALValue& pResult); + static std::string eval(const std::string& pToEval); + static ::AL::ALValue evalReturn(const std::string& pToEval); + static ::AL::ALValue evalFull(const std::string& pToEval); + static ::AL::ALValue convertPyObjectToALValue(PyObject *param); + static PyObject * convertALValueToPython(const ::AL::ALValue& value); + }; +} +#endif // _LIB_ALPYTHONTOOLS_ALPYTHONTOOLS_ALPYTHONTOOLS_H_ diff --git a/naoModule/libnaoqi_files/include/alserial/alserial.h b/naoModule/libnaoqi_files/include/alserial/alserial.h new file mode 100755 index 0000000..8842e5c --- /dev/null +++ b/naoModule/libnaoqi_files/include/alserial/alserial.h @@ -0,0 +1,222 @@ +/** + * @author Jerome Vuarand + * Copyright (c) Aldebaran Robotics 2010, 2012 All Rights Reserved + */ + +#pragma once + +#ifndef _LIB_ALSERIAL_SRC_ALSERIAL_ALSERIAL_H_ +#define _LIB_ALSERIAL_SRC_ALSERIAL_ALSERIAL_H_ + +// .:: System headers :: + +#include +#include +#include +#include + +class TiXmlElement; + +namespace AL +{ + // all std::string are in utf-8, whatever the platform + namespace Serial + { + bool forceVerboseXml(); + void setForceVerboseXml(bool value); + + std::string save(const bool& value); + bool load(const std::string& str, bool& value); + + std::string save(const int& value); + bool load(const std::string& str, int& value); + + std::string save(const float& value); + bool load(const std::string& str, float& value); + + std::string save(const double& value); + bool load(const std::string& str, double& value); + + std::string save(const char& value); + + std::string save(const char* value); + + std::string save(const std::string& value); + bool load(const std::string& str, std::string& value); + } + +////////////////////////////////////////////////////////////////////////////// + + // an element can have attributes, and contain either some content or children elements + // in backends supporting mixed text/element, only the first text is used + struct XmlElementData; + class XmlElement + { + private: + friend class XmlDocument; + + XmlElement(); + + public: + typedef std::list > List; + typedef std::list > CList; + + public: + XmlElement(const std::string& pBeacon); + + std::string beacon() const; + boost::shared_ptr clone() const; + + // all get* variants return true if the value was available + // variants without default value don't change pResult if the value isn't available + template boost::shared_ptr attribute(const std::string& pName) const; + template T attribute(const std::string& pName, const T& pDefault) const; + template bool getAttribute(const std::string& pName, T& pResult) const; + template bool getAttribute(const std::string& pName, T& pResult, const T& pDefault) const; + boost::shared_ptr text() const; + bool getText(std::string& pResult) const; + bool getText(std::string& pResult, const std::string& pDefault) const; + boost::shared_ptr firstChild(); + boost::shared_ptr firstChild() const; + /// @obsolete + boost::shared_ptr nextChild(boost::shared_ptr pChild); + /// @obsolete + boost::shared_ptr nextChild(boost::shared_ptr pChild) const; + + boost::shared_ptr firstChild(const std::string& pBeacon); + boost::shared_ptr firstChild(const std::string& pBeacon) const; + /// @obsolete + boost::shared_ptr nextChild(boost::shared_ptr pChild, const std::string& pBeacon); + /// @obsolete + boost::shared_ptr nextChild(boost::shared_ptr pChild, const std::string& pBeacon) const; + + List mixedChildren(); + CList mixedChildren() const; + List children() { return mixedChildren(); } // backward compatibility + CList children() const { return mixedChildren(); } // backward compatibility + List children(const std::string& pChildBeacon, const std::string& pGroupBeacon = ""); + CList children(const std::string& pChildBeacon, const std::string& pGroupBeacon = "") const; + + template void setAttribute(const std::string& pName, const T& pValue, bool pForceAttribute = false); + void setText(const std::string& pText, bool pCData = false); + void addChild(boost::shared_ptr pChild); + void addChildren(const List& pChildren, const std::string& pGroupBeacon = ""); + + void removeAttribute(const std::string& pName); + void removeChild(boost::shared_ptr pChild); + void removeChildren(const std::string& pChildBeacon, const std::string& pGroupBeacon); + + std::string saveToXmlString() const; + TiXmlElement* saveToTinyXmlElement() const; + + static boost::shared_ptr loadFromXmlString(const std::string& pString, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL); + static boost::shared_ptr loadFromTinyXmlElement(const TiXmlElement* pTiXml); + + private: + static boost::shared_ptr xWrap(TiXmlElement* pPtr, bool pOwned = false); + + private: + boost::shared_ptr fData; + }; + +////////////////////////////////////////////////////////////////////////////// + + struct XmlDocumentData; + class XmlDocument + { + private: + //Q_DECLARE_TR_FUNCTIONS(XmlDocument) + + public: + XmlDocument(); + + boost::shared_ptr root(); + boost::shared_ptr root() const; + boost::shared_ptr root(const std::string& pBeacon); + boost::shared_ptr root(const std::string& pBeacon) const; + void setRoot(boost::shared_ptr pValue); + + /// pFilename is in UTF-8 (conversion to UTF-16 is done on Windows) + static boost::shared_ptr loadFromXmlFile(const std::string& pFilename, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL); + static boost::shared_ptr loadFromXmlFile(FILE* pFile, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL); + static boost::shared_ptr loadFromXmlString(const std::string& pString, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL); + static boost::shared_ptr loadFromXmlStringIgnoringErrors(const std::string& pString, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL); + + /// pFilename is in UTF-8 (conversion to UTF-16 is done on Windows) + bool saveToXmlFile(const std::string& pFilename, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL) const; + bool saveToXmlFile(FILE* pFile, std::string* pErrorTitle = NULL, std::string* pErrorMessage = NULL) const; + std::string saveToXmlString() const; + + private: + boost::shared_ptr fData; + }; + +////////////////////////////////////////////////////////////////////////////// + + template + void XmlElement::setAttribute(const std::string& pName, const T& pValue, bool pForceAttribute) + { + setAttribute(pName, Serial::save(pValue), pForceAttribute); + } + + template <> + void XmlElement::setAttribute(const std::string& pName, const std::string& pValue, bool pForceAttribute); + + template + boost::shared_ptr XmlElement::attribute(const std::string& pName) const + { + std::string text; + if (!getAttribute(pName, text)) + return boost::shared_ptr(); + + boost::shared_ptr result(new T); + if (!Serial::load(text, *result)) + return boost::shared_ptr(); + + return result; + } + + template + T XmlElement::attribute(const std::string& pName, const T& pDefault) const + { + std::string text; + if (!getAttribute(pName, text)) + return pDefault; + + T result; + if (!Serial::load(text, result)) + return pDefault; + + return result; + } + + template + bool XmlElement::getAttribute(const std::string& pName, T& pResult) const + { + std::string text; + if (!getAttribute(pName, text)) + return false; + + if (!Serial::load(text, pResult)) + return false; + + return true; + } + + template <> + bool XmlElement::getAttribute(const std::string& pName, std::string& pResult) const; + + template + bool XmlElement::getAttribute(const std::string& pName, T& pResult, const T& pDefault) const + { + bool result = getAttribute(pName, pResult); + if (!result) + pResult = pDefault; + return result; + } + +////////////////////////////////////////////////////////////////////////////// + +} + +#endif // _LIB_ALSERIAL_SRC_ALSERIAL_ALSERIAL_H_ diff --git a/naoModule/libnaoqi_files/include/alsoap/ALH.h b/naoModule/libnaoqi_files/include/alsoap/ALH.h new file mode 100755 index 0000000..09137f6 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alsoap/ALH.h @@ -0,0 +1,948 @@ +/* ALH.h + Generated by gSOAP 2.7.12 from I_ALBroker.h + Copyright(C) 2000-2008, Robert van Engelen, Genivia Inc. All Rights Reserved. + This part of the software is released under one of the following licenses: + GPL, the gSOAP public license, or Genivia's license for commercial use. +*/ + +#ifndef ALH_H +#define ALH_H +#include "ALStub.h" + +namespace AL { +#ifndef WITH_NOIDREF +SOAP_FMAC3 void SOAP_FMAC4 soap_markelement(struct soap*, const void*, int); +SOAP_FMAC3 int SOAP_FMAC4 soap_putelement(struct soap*, const void*, const char*, int, int); +SOAP_FMAC3 void *SOAP_FMAC4 soap_getelement(struct soap*, int*); +SOAP_FMAC3 int SOAP_FMAC4 soap_putindependent(struct soap*); +SOAP_FMAC3 int SOAP_FMAC4 soap_getindependent(struct soap*); +#endif +SOAP_FMAC3 int SOAP_FMAC4 soap_ignore_element(struct soap*); + +SOAP_FMAC3 void * SOAP_FMAC4 soap_instantiate(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 int SOAP_FMAC4 soap_fdelete(struct soap_clist*); +SOAP_FMAC3 void* SOAP_FMAC4 soap_class_id_enter(struct soap*, const char*, void*, int, size_t, const char*, const char*); + +SOAP_FMAC3 void* SOAP_FMAC4 soap_container_id_forward(struct soap*, const char*, void*, size_t, int, int, size_t, unsigned int); + +SOAP_FMAC3 void SOAP_FMAC4 soap_container_insert(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_byte +#define SOAP_TYPE_AL_byte (3) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_byte(struct soap*, char *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_byte(struct soap*, const char *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_byte(struct soap*, const char*, int, const char *, const char*); +SOAP_FMAC3 char * SOAP_FMAC4 soap_get_byte(struct soap*, char *, const char*, const char*); +SOAP_FMAC3 char * SOAP_FMAC4 soap_in_byte(struct soap*, const char*, char *, const char*); + +#ifndef SOAP_TYPE_AL_xsd__int +#define SOAP_TYPE_AL_xsd__int (11) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_xsd__int(struct soap*, int *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__int(struct soap*, const int *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_xsd__int(struct soap*, const char*, int, const int *, const char*); +SOAP_FMAC3 int * SOAP_FMAC4 soap_get_xsd__int(struct soap*, int *, const char*, const char*); +SOAP_FMAC3 int * SOAP_FMAC4 soap_in_xsd__int(struct soap*, const char*, int *, const char*); + +#ifndef SOAP_TYPE_AL_int +#define SOAP_TYPE_AL_int (1) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_int(struct soap*, int *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_int(struct soap*, const int *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_int(struct soap*, const char*, int, const int *, const char*); +SOAP_FMAC3 int * SOAP_FMAC4 soap_get_int(struct soap*, int *, const char*, const char*); +SOAP_FMAC3 int * SOAP_FMAC4 soap_in_int(struct soap*, const char*, int *, const char*); + +#ifndef SOAP_TYPE_AL_xsd__float +#define SOAP_TYPE_AL_xsd__float (17) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_xsd__float(struct soap*, float *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__float(struct soap*, const float *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_xsd__float(struct soap*, const char*, int, const float *, const char*); +SOAP_FMAC3 float * SOAP_FMAC4 soap_get_xsd__float(struct soap*, float *, const char*, const char*); +SOAP_FMAC3 float * SOAP_FMAC4 soap_in_xsd__float(struct soap*, const char*, float *, const char*); + +#ifndef SOAP_TYPE_AL_float +#define SOAP_TYPE_AL_float (16) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_float(struct soap*, float *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_float(struct soap*, const float *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_float(struct soap*, const char*, int, const float *, const char*); +SOAP_FMAC3 float * SOAP_FMAC4 soap_get_float(struct soap*, float *, const char*, const char*); +SOAP_FMAC3 float * SOAP_FMAC4 soap_in_float(struct soap*, const char*, float *, const char*); + +#ifndef SOAP_TYPE_AL_xsd__double +#define SOAP_TYPE_AL_xsd__double (15) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_xsd__double(struct soap*, double *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__double(struct soap*, const double *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_xsd__double(struct soap*, const char*, int, const double *, const char*); +SOAP_FMAC3 double * SOAP_FMAC4 soap_get_xsd__double(struct soap*, double *, const char*, const char*); +SOAP_FMAC3 double * SOAP_FMAC4 soap_in_xsd__double(struct soap*, const char*, double *, const char*); + +#ifndef SOAP_TYPE_AL_double +#define SOAP_TYPE_AL_double (14) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_double(struct soap*, double *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_double(struct soap*, const double *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_double(struct soap*, const char*, int, const double *, const char*); +SOAP_FMAC3 double * SOAP_FMAC4 soap_get_double(struct soap*, double *, const char*, const char*); +SOAP_FMAC3 double * SOAP_FMAC4 soap_in_double(struct soap*, const char*, double *, const char*); + +#ifndef SOAP_TYPE_AL_xsd__bool +#define SOAP_TYPE_AL_xsd__bool (13) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_xsd__bool(struct soap*, bool *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__bool(struct soap*, const bool *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_xsd__bool(struct soap*, const char*, int, const bool *, const char*); + +SOAP_FMAC3S const char* SOAP_FMAC4S soap_xsd__bool2s(struct soap*, bool); +SOAP_FMAC3 bool * SOAP_FMAC4 soap_get_xsd__bool(struct soap*, bool *, const char*, const char*); +SOAP_FMAC3 bool * SOAP_FMAC4 soap_in_xsd__bool(struct soap*, const char*, bool *, const char*); + +SOAP_FMAC3S int SOAP_FMAC4S soap_s2xsd__bool(struct soap*, const char*, bool *); + +#ifndef SOAP_TYPE_AL_bool +#define SOAP_TYPE_AL_bool (12) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_bool(struct soap*, bool *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_bool(struct soap*, const bool *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_bool(struct soap*, const char*, int, const bool *, const char*); + +SOAP_FMAC3S const char* SOAP_FMAC4S soap_bool2s(struct soap*, bool); +SOAP_FMAC3 bool * SOAP_FMAC4 soap_get_bool(struct soap*, bool *, const char*, const char*); +SOAP_FMAC3 bool * SOAP_FMAC4 soap_in_bool(struct soap*, const char*, bool *, const char*); + +SOAP_FMAC3S int SOAP_FMAC4S soap_s2bool(struct soap*, const char*, bool *); + +#ifndef SOAP_TYPE_AL_al__ALModuleInfo +#define SOAP_TYPE_AL_al__ALModuleInfo (22) +#endif + +SOAP_FMAC3 int SOAP_FMAC4 soap_out_al__ALModuleInfo(struct soap*, const char*, int, const al__ALModuleInfo *, const char*); +SOAP_FMAC3 al__ALModuleInfo * SOAP_FMAC4 soap_get_al__ALModuleInfo(struct soap*, al__ALModuleInfo *, const char*, const char*); +SOAP_FMAC3 al__ALModuleInfo * SOAP_FMAC4 soap_in_al__ALModuleInfo(struct soap*, const char*, al__ALModuleInfo *, const char*); +SOAP_FMAC5 al__ALModuleInfo * SOAP_FMAC6 soap_new_al__ALModuleInfo(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_al__ALModuleInfo(struct soap*, al__ALModuleInfo*); +SOAP_FMAC3 al__ALModuleInfo * SOAP_FMAC4 soap_instantiate_al__ALModuleInfo(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_al__ALModuleInfo(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_xsd__anyType +#define SOAP_TYPE_AL_xsd__anyType (21) +#endif +SOAP_FMAC1 void SOAP_FMAC2 soap_default_xsd__anyType(struct soap*, ALValue *); +SOAP_FMAC1 void SOAP_FMAC2 soap_serialize_xsd__anyType(struct soap*, const ALValue *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__anyType(struct soap*, const ALValue *, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_out_xsd__anyType(struct soap*, const char*, int, const ALValue *, const char*); +SOAP_FMAC3 ALValue * SOAP_FMAC4 soap_get_xsd__anyType(struct soap*, ALValue *, const char*, const char*); +SOAP_FMAC1 ALValue * SOAP_FMAC2 soap_in_xsd__anyType(struct soap*, const char*, ALValue *, const char*); +SOAP_FMAC5 ALValue * SOAP_FMAC6 soap_new_xsd__anyType(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_xsd__anyType(struct soap*, ALValue*); +SOAP_FMAC3 ALValue * SOAP_FMAC4 soap_instantiate_xsd__anyType(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_xsd__anyType(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_xsd__string +#define SOAP_TYPE_AL_xsd__string (10) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_xsd__string(struct soap*, std::string *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_xsd__string(struct soap*, std::string const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_xsd__string(struct soap*, const std::string *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_xsd__string(struct soap*, const char*, int, const std::string*, const char*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_get_xsd__string(struct soap*, std::string *, const char*, const char*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_in_xsd__string(struct soap*, const char*, std::string*, const char*); +SOAP_FMAC5 std::string * SOAP_FMAC6 soap_new_xsd__string(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_xsd__string(struct soap*, std::string*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_instantiate_xsd__string(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_xsd__string(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_std__string +#define SOAP_TYPE_AL_std__string (9) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_std__string(struct soap*, std::string *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_std__string(struct soap*, const std::string *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_std__string(struct soap*, const std::string *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_std__string(struct soap*, const char*, int, const std::string*, const char*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_get_std__string(struct soap*, std::string *, const char*, const char*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_in_std__string(struct soap*, const char*, std::string*, const char*); +SOAP_FMAC5 std::string * SOAP_FMAC6 soap_new_std__string(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_std__string(struct soap*, std::string*); +SOAP_FMAC3 std::string * SOAP_FMAC4 soap_instantiate_std__string(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_std__string(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Fault +#define SOAP_TYPE_AL_SOAP_ENV__Fault (118) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_SOAP_ENV__Fault(struct soap*, struct SOAP_ENV__Fault *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_SOAP_ENV__Fault(struct soap*, const struct SOAP_ENV__Fault *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_SOAP_ENV__Fault(struct soap*, const struct SOAP_ENV__Fault *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_SOAP_ENV__Fault(struct soap*, const char*, int, const struct SOAP_ENV__Fault *, const char*); +SOAP_FMAC3 struct SOAP_ENV__Fault * SOAP_FMAC4 soap_get_SOAP_ENV__Fault(struct soap*, struct SOAP_ENV__Fault *, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Fault * SOAP_FMAC4 soap_in_SOAP_ENV__Fault(struct soap*, const char*, struct SOAP_ENV__Fault *, const char*); +SOAP_FMAC5 struct SOAP_ENV__Fault * SOAP_FMAC6 soap_new_SOAP_ENV__Fault(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_SOAP_ENV__Fault(struct soap*, struct SOAP_ENV__Fault*); +SOAP_FMAC3 struct SOAP_ENV__Fault * SOAP_FMAC4 soap_instantiate_SOAP_ENV__Fault(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_SOAP_ENV__Fault(struct soap*, int, int, void*, size_t, const void*, size_t); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Reason +#define SOAP_TYPE_AL_SOAP_ENV__Reason (117) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_SOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_SOAP_ENV__Reason(struct soap*, const struct SOAP_ENV__Reason *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_SOAP_ENV__Reason(struct soap*, const struct SOAP_ENV__Reason *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_SOAP_ENV__Reason(struct soap*, const char*, int, const struct SOAP_ENV__Reason *, const char*); +SOAP_FMAC3 struct SOAP_ENV__Reason * SOAP_FMAC4 soap_get_SOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason *, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Reason * SOAP_FMAC4 soap_in_SOAP_ENV__Reason(struct soap*, const char*, struct SOAP_ENV__Reason *, const char*); +SOAP_FMAC5 struct SOAP_ENV__Reason * SOAP_FMAC6 soap_new_SOAP_ENV__Reason(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_SOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason*); +SOAP_FMAC3 struct SOAP_ENV__Reason * SOAP_FMAC4 soap_instantiate_SOAP_ENV__Reason(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_SOAP_ENV__Reason(struct soap*, int, int, void*, size_t, const void*, size_t); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Detail +#define SOAP_TYPE_AL_SOAP_ENV__Detail (116) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_SOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_SOAP_ENV__Detail(struct soap*, const struct SOAP_ENV__Detail *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_SOAP_ENV__Detail(struct soap*, const struct SOAP_ENV__Detail *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_SOAP_ENV__Detail(struct soap*, const char*, int, const struct SOAP_ENV__Detail *, const char*); +SOAP_FMAC3 struct SOAP_ENV__Detail * SOAP_FMAC4 soap_get_SOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail *, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Detail * SOAP_FMAC4 soap_in_SOAP_ENV__Detail(struct soap*, const char*, struct SOAP_ENV__Detail *, const char*); +SOAP_FMAC5 struct SOAP_ENV__Detail * SOAP_FMAC6 soap_new_SOAP_ENV__Detail(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_SOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail*); +SOAP_FMAC3 struct SOAP_ENV__Detail * SOAP_FMAC4 soap_instantiate_SOAP_ENV__Detail(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_SOAP_ENV__Detail(struct soap*, int, int, void*, size_t, const void*, size_t); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Code +#define SOAP_TYPE_AL_SOAP_ENV__Code (114) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_SOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_SOAP_ENV__Code(struct soap*, const struct SOAP_ENV__Code *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_SOAP_ENV__Code(struct soap*, const struct SOAP_ENV__Code *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_SOAP_ENV__Code(struct soap*, const char*, int, const struct SOAP_ENV__Code *, const char*); +SOAP_FMAC3 struct SOAP_ENV__Code * SOAP_FMAC4 soap_get_SOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code *, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Code * SOAP_FMAC4 soap_in_SOAP_ENV__Code(struct soap*, const char*, struct SOAP_ENV__Code *, const char*); +SOAP_FMAC5 struct SOAP_ENV__Code * SOAP_FMAC6 soap_new_SOAP_ENV__Code(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_SOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code*); +SOAP_FMAC3 struct SOAP_ENV__Code * SOAP_FMAC4 soap_instantiate_SOAP_ENV__Code(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_SOAP_ENV__Code(struct soap*, int, int, void*, size_t, const void*, size_t); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Header +#define SOAP_TYPE_AL_SOAP_ENV__Header (113) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_SOAP_ENV__Header(struct soap*, struct SOAP_ENV__Header *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_SOAP_ENV__Header(struct soap*, const struct SOAP_ENV__Header *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_SOAP_ENV__Header(struct soap*, const struct SOAP_ENV__Header *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_SOAP_ENV__Header(struct soap*, const char*, int, const struct SOAP_ENV__Header *, const char*); +SOAP_FMAC3 struct SOAP_ENV__Header * SOAP_FMAC4 soap_get_SOAP_ENV__Header(struct soap*, struct SOAP_ENV__Header *, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Header * SOAP_FMAC4 soap_in_SOAP_ENV__Header(struct soap*, const char*, struct SOAP_ENV__Header *, const char*); +SOAP_FMAC5 struct SOAP_ENV__Header * SOAP_FMAC6 soap_new_SOAP_ENV__Header(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_SOAP_ENV__Header(struct soap*, struct SOAP_ENV__Header*); +SOAP_FMAC3 struct SOAP_ENV__Header * SOAP_FMAC4 soap_instantiate_SOAP_ENV__Header(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_SOAP_ENV__Header(struct soap*, int, int, void*, size_t, const void*, size_t); + +#endif + +#ifndef SOAP_TYPE_AL_albroker__getDebugTaskList +#define SOAP_TYPE_AL_albroker__getDebugTaskList (112) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getDebugTaskList(struct soap*, struct albroker__getDebugTaskList *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getDebugTaskList(struct soap*, const struct albroker__getDebugTaskList *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getDebugTaskList(struct soap*, const struct albroker__getDebugTaskList *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getDebugTaskList(struct soap*, const char*, int, const struct albroker__getDebugTaskList *, const char*); +SOAP_FMAC3 struct albroker__getDebugTaskList * SOAP_FMAC4 soap_get_albroker__getDebugTaskList(struct soap*, struct albroker__getDebugTaskList *, const char*, const char*); +SOAP_FMAC3 struct albroker__getDebugTaskList * SOAP_FMAC4 soap_in_albroker__getDebugTaskList(struct soap*, const char*, struct albroker__getDebugTaskList *, const char*); +SOAP_FMAC5 struct albroker__getDebugTaskList * SOAP_FMAC6 soap_new_albroker__getDebugTaskList(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getDebugTaskList(struct soap*, struct albroker__getDebugTaskList*); +SOAP_FMAC3 struct albroker__getDebugTaskList * SOAP_FMAC4 soap_instantiate_albroker__getDebugTaskList(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getDebugTaskList(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__stopTaskName +#define SOAP_TYPE_AL_albroker__stopTaskName (109) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__stopTaskName(struct soap*, struct albroker__stopTaskName *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__stopTaskName(struct soap*, const struct albroker__stopTaskName *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__stopTaskName(struct soap*, const struct albroker__stopTaskName *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__stopTaskName(struct soap*, const char*, int, const struct albroker__stopTaskName *, const char*); +SOAP_FMAC3 struct albroker__stopTaskName * SOAP_FMAC4 soap_get_albroker__stopTaskName(struct soap*, struct albroker__stopTaskName *, const char*, const char*); +SOAP_FMAC3 struct albroker__stopTaskName * SOAP_FMAC4 soap_in_albroker__stopTaskName(struct soap*, const char*, struct albroker__stopTaskName *, const char*); +SOAP_FMAC5 struct albroker__stopTaskName * SOAP_FMAC6 soap_new_albroker__stopTaskName(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__stopTaskName(struct soap*, struct albroker__stopTaskName*); +SOAP_FMAC3 struct albroker__stopTaskName * SOAP_FMAC4 soap_instantiate_albroker__stopTaskName(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__stopTaskName(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__stopTaskNameResponse +#define SOAP_TYPE_AL_albroker__stopTaskNameResponse (108) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__stopTaskNameResponse(struct soap*, struct albroker__stopTaskNameResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__stopTaskNameResponse(struct soap*, const struct albroker__stopTaskNameResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__stopTaskNameResponse(struct soap*, const struct albroker__stopTaskNameResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__stopTaskNameResponse(struct soap*, const char*, int, const struct albroker__stopTaskNameResponse *, const char*); +SOAP_FMAC3 struct albroker__stopTaskNameResponse * SOAP_FMAC4 soap_get_albroker__stopTaskNameResponse(struct soap*, struct albroker__stopTaskNameResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__stopTaskNameResponse * SOAP_FMAC4 soap_in_albroker__stopTaskNameResponse(struct soap*, const char*, struct albroker__stopTaskNameResponse *, const char*); +SOAP_FMAC5 struct albroker__stopTaskNameResponse * SOAP_FMAC6 soap_new_albroker__stopTaskNameResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__stopTaskNameResponse(struct soap*, struct albroker__stopTaskNameResponse*); +SOAP_FMAC3 struct albroker__stopTaskNameResponse * SOAP_FMAC4 soap_instantiate_albroker__stopTaskNameResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__stopTaskNameResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__stopTask +#define SOAP_TYPE_AL_albroker__stopTask (106) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__stopTask(struct soap*, struct albroker__stopTask *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__stopTask(struct soap*, const struct albroker__stopTask *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__stopTask(struct soap*, const struct albroker__stopTask *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__stopTask(struct soap*, const char*, int, const struct albroker__stopTask *, const char*); +SOAP_FMAC3 struct albroker__stopTask * SOAP_FMAC4 soap_get_albroker__stopTask(struct soap*, struct albroker__stopTask *, const char*, const char*); +SOAP_FMAC3 struct albroker__stopTask * SOAP_FMAC4 soap_in_albroker__stopTask(struct soap*, const char*, struct albroker__stopTask *, const char*); +SOAP_FMAC5 struct albroker__stopTask * SOAP_FMAC6 soap_new_albroker__stopTask(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__stopTask(struct soap*, struct albroker__stopTask*); +SOAP_FMAC3 struct albroker__stopTask * SOAP_FMAC4 soap_instantiate_albroker__stopTask(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__stopTask(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__stopTaskResponse +#define SOAP_TYPE_AL_albroker__stopTaskResponse (105) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__stopTaskResponse(struct soap*, struct albroker__stopTaskResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__stopTaskResponse(struct soap*, const struct albroker__stopTaskResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__stopTaskResponse(struct soap*, const struct albroker__stopTaskResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__stopTaskResponse(struct soap*, const char*, int, const struct albroker__stopTaskResponse *, const char*); +SOAP_FMAC3 struct albroker__stopTaskResponse * SOAP_FMAC4 soap_get_albroker__stopTaskResponse(struct soap*, struct albroker__stopTaskResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__stopTaskResponse * SOAP_FMAC4 soap_in_albroker__stopTaskResponse(struct soap*, const char*, struct albroker__stopTaskResponse *, const char*); +SOAP_FMAC5 struct albroker__stopTaskResponse * SOAP_FMAC6 soap_new_albroker__stopTaskResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__stopTaskResponse(struct soap*, struct albroker__stopTaskResponse*); +SOAP_FMAC3 struct albroker__stopTaskResponse * SOAP_FMAC4 soap_instantiate_albroker__stopTaskResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__stopTaskResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getInfo +#define SOAP_TYPE_AL_albroker__getInfo (103) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getInfo(struct soap*, struct albroker__getInfo *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getInfo(struct soap*, const struct albroker__getInfo *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getInfo(struct soap*, const struct albroker__getInfo *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getInfo(struct soap*, const char*, int, const struct albroker__getInfo *, const char*); +SOAP_FMAC3 struct albroker__getInfo * SOAP_FMAC4 soap_get_albroker__getInfo(struct soap*, struct albroker__getInfo *, const char*, const char*); +SOAP_FMAC3 struct albroker__getInfo * SOAP_FMAC4 soap_in_albroker__getInfo(struct soap*, const char*, struct albroker__getInfo *, const char*); +SOAP_FMAC5 struct albroker__getInfo * SOAP_FMAC6 soap_new_albroker__getInfo(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getInfo(struct soap*, struct albroker__getInfo*); +SOAP_FMAC3 struct albroker__getInfo * SOAP_FMAC4 soap_instantiate_albroker__getInfo(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getInfo(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerName +#define SOAP_TYPE_AL_albroker__getBrokerName (100) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerName(struct soap*, struct albroker__getBrokerName *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerName(struct soap*, const struct albroker__getBrokerName *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerName(struct soap*, const struct albroker__getBrokerName *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerName(struct soap*, const char*, int, const struct albroker__getBrokerName *, const char*); +SOAP_FMAC3 struct albroker__getBrokerName * SOAP_FMAC4 soap_get_albroker__getBrokerName(struct soap*, struct albroker__getBrokerName *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerName * SOAP_FMAC4 soap_in_albroker__getBrokerName(struct soap*, const char*, struct albroker__getBrokerName *, const char*); +SOAP_FMAC5 struct albroker__getBrokerName * SOAP_FMAC6 soap_new_albroker__getBrokerName(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerName(struct soap*, struct albroker__getBrokerName*); +SOAP_FMAC3 struct albroker__getBrokerName * SOAP_FMAC4 soap_instantiate_albroker__getBrokerName(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerName(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerNameResponse +#define SOAP_TYPE_AL_albroker__getBrokerNameResponse (99) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerNameResponse(struct soap*, struct albroker__getBrokerNameResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerNameResponse(struct soap*, const struct albroker__getBrokerNameResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerNameResponse(struct soap*, const struct albroker__getBrokerNameResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerNameResponse(struct soap*, const char*, int, const struct albroker__getBrokerNameResponse *, const char*); +SOAP_FMAC3 struct albroker__getBrokerNameResponse * SOAP_FMAC4 soap_get_albroker__getBrokerNameResponse(struct soap*, struct albroker__getBrokerNameResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerNameResponse * SOAP_FMAC4 soap_in_albroker__getBrokerNameResponse(struct soap*, const char*, struct albroker__getBrokerNameResponse *, const char*); +SOAP_FMAC5 struct albroker__getBrokerNameResponse * SOAP_FMAC6 soap_new_albroker__getBrokerNameResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerNameResponse(struct soap*, struct albroker__getBrokerNameResponse*); +SOAP_FMAC3 struct albroker__getBrokerNameResponse * SOAP_FMAC4 soap_instantiate_albroker__getBrokerNameResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerNameResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__sendBackIP +#define SOAP_TYPE_AL_albroker__sendBackIP (97) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__sendBackIP(struct soap*, struct albroker__sendBackIP *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__sendBackIP(struct soap*, const struct albroker__sendBackIP *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__sendBackIP(struct soap*, const struct albroker__sendBackIP *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__sendBackIP(struct soap*, const char*, int, const struct albroker__sendBackIP *, const char*); +SOAP_FMAC3 struct albroker__sendBackIP * SOAP_FMAC4 soap_get_albroker__sendBackIP(struct soap*, struct albroker__sendBackIP *, const char*, const char*); +SOAP_FMAC3 struct albroker__sendBackIP * SOAP_FMAC4 soap_in_albroker__sendBackIP(struct soap*, const char*, struct albroker__sendBackIP *, const char*); +SOAP_FMAC5 struct albroker__sendBackIP * SOAP_FMAC6 soap_new_albroker__sendBackIP(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__sendBackIP(struct soap*, struct albroker__sendBackIP*); +SOAP_FMAC3 struct albroker__sendBackIP * SOAP_FMAC4 soap_instantiate_albroker__sendBackIP(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__sendBackIP(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__sendBackIPResponse +#define SOAP_TYPE_AL_albroker__sendBackIPResponse (96) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__sendBackIPResponse(struct soap*, struct albroker__sendBackIPResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__sendBackIPResponse(struct soap*, const struct albroker__sendBackIPResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__sendBackIPResponse(struct soap*, const struct albroker__sendBackIPResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__sendBackIPResponse(struct soap*, const char*, int, const struct albroker__sendBackIPResponse *, const char*); +SOAP_FMAC3 struct albroker__sendBackIPResponse * SOAP_FMAC4 soap_get_albroker__sendBackIPResponse(struct soap*, struct albroker__sendBackIPResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__sendBackIPResponse * SOAP_FMAC4 soap_in_albroker__sendBackIPResponse(struct soap*, const char*, struct albroker__sendBackIPResponse *, const char*); +SOAP_FMAC5 struct albroker__sendBackIPResponse * SOAP_FMAC6 soap_new_albroker__sendBackIPResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__sendBackIPResponse(struct soap*, struct albroker__sendBackIPResponse*); +SOAP_FMAC3 struct albroker__sendBackIPResponse * SOAP_FMAC4 soap_instantiate_albroker__sendBackIPResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__sendBackIPResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__version +#define SOAP_TYPE_AL_albroker__version (94) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__version(struct soap*, struct albroker__version *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__version(struct soap*, const struct albroker__version *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__version(struct soap*, const struct albroker__version *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__version(struct soap*, const char*, int, const struct albroker__version *, const char*); +SOAP_FMAC3 struct albroker__version * SOAP_FMAC4 soap_get_albroker__version(struct soap*, struct albroker__version *, const char*, const char*); +SOAP_FMAC3 struct albroker__version * SOAP_FMAC4 soap_in_albroker__version(struct soap*, const char*, struct albroker__version *, const char*); +SOAP_FMAC5 struct albroker__version * SOAP_FMAC6 soap_new_albroker__version(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__version(struct soap*, struct albroker__version*); +SOAP_FMAC3 struct albroker__version * SOAP_FMAC4 soap_instantiate_albroker__version(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__version(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__versionResponse +#define SOAP_TYPE_AL_albroker__versionResponse (93) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__versionResponse(struct soap*, struct albroker__versionResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__versionResponse(struct soap*, const struct albroker__versionResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__versionResponse(struct soap*, const struct albroker__versionResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__versionResponse(struct soap*, const char*, int, const struct albroker__versionResponse *, const char*); +SOAP_FMAC3 struct albroker__versionResponse * SOAP_FMAC4 soap_get_albroker__versionResponse(struct soap*, struct albroker__versionResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__versionResponse * SOAP_FMAC4 soap_in_albroker__versionResponse(struct soap*, const char*, struct albroker__versionResponse *, const char*); +SOAP_FMAC5 struct albroker__versionResponse * SOAP_FMAC6 soap_new_albroker__versionResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__versionResponse(struct soap*, struct albroker__versionResponse*); +SOAP_FMAC3 struct albroker__versionResponse * SOAP_FMAC4 soap_instantiate_albroker__versionResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__versionResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__init +#define SOAP_TYPE_AL_albroker__init (90) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__init(struct soap*, struct albroker__init *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__init(struct soap*, const struct albroker__init *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__init(struct soap*, const struct albroker__init *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__init(struct soap*, const char*, int, const struct albroker__init *, const char*); +SOAP_FMAC3 struct albroker__init * SOAP_FMAC4 soap_get_albroker__init(struct soap*, struct albroker__init *, const char*, const char*); +SOAP_FMAC3 struct albroker__init * SOAP_FMAC4 soap_in_albroker__init(struct soap*, const char*, struct albroker__init *, const char*); +SOAP_FMAC5 struct albroker__init * SOAP_FMAC6 soap_new_albroker__init(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__init(struct soap*, struct albroker__init*); +SOAP_FMAC3 struct albroker__init * SOAP_FMAC4 soap_instantiate_albroker__init(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__init(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__initResponse +#define SOAP_TYPE_AL_albroker__initResponse (89) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__initResponse(struct soap*, struct albroker__initResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__initResponse(struct soap*, const struct albroker__initResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__initResponse(struct soap*, const struct albroker__initResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__initResponse(struct soap*, const char*, int, const struct albroker__initResponse *, const char*); +SOAP_FMAC3 struct albroker__initResponse * SOAP_FMAC4 soap_get_albroker__initResponse(struct soap*, struct albroker__initResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__initResponse * SOAP_FMAC4 soap_in_albroker__initResponse(struct soap*, const char*, struct albroker__initResponse *, const char*); +SOAP_FMAC5 struct albroker__initResponse * SOAP_FMAC6 soap_new_albroker__initResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__initResponse(struct soap*, struct albroker__initResponse*); +SOAP_FMAC3 struct albroker__initResponse * SOAP_FMAC4 soap_instantiate_albroker__initResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__initResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getMethodList +#define SOAP_TYPE_AL_albroker__getMethodList (84) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getMethodList(struct soap*, struct albroker__getMethodList *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getMethodList(struct soap*, const struct albroker__getMethodList *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getMethodList(struct soap*, const struct albroker__getMethodList *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getMethodList(struct soap*, const char*, int, const struct albroker__getMethodList *, const char*); +SOAP_FMAC3 struct albroker__getMethodList * SOAP_FMAC4 soap_get_albroker__getMethodList(struct soap*, struct albroker__getMethodList *, const char*, const char*); +SOAP_FMAC3 struct albroker__getMethodList * SOAP_FMAC4 soap_in_albroker__getMethodList(struct soap*, const char*, struct albroker__getMethodList *, const char*); +SOAP_FMAC5 struct albroker__getMethodList * SOAP_FMAC6 soap_new_albroker__getMethodList(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getMethodList(struct soap*, struct albroker__getMethodList*); +SOAP_FMAC3 struct albroker__getMethodList * SOAP_FMAC4 soap_instantiate_albroker__getMethodList(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getMethodList(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getMethodListResponse +#define SOAP_TYPE_AL_albroker__getMethodListResponse (83) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getMethodListResponse(struct soap*, struct albroker__getMethodListResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getMethodListResponse(struct soap*, const struct albroker__getMethodListResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getMethodListResponse(struct soap*, const struct albroker__getMethodListResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getMethodListResponse(struct soap*, const char*, int, const struct albroker__getMethodListResponse *, const char*); +SOAP_FMAC3 struct albroker__getMethodListResponse * SOAP_FMAC4 soap_get_albroker__getMethodListResponse(struct soap*, struct albroker__getMethodListResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getMethodListResponse * SOAP_FMAC4 soap_in_albroker__getMethodListResponse(struct soap*, const char*, struct albroker__getMethodListResponse *, const char*); +SOAP_FMAC5 struct albroker__getMethodListResponse * SOAP_FMAC6 soap_new_albroker__getMethodListResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getMethodListResponse(struct soap*, struct albroker__getMethodListResponse*); +SOAP_FMAC3 struct albroker__getMethodListResponse * SOAP_FMAC4 soap_instantiate_albroker__getMethodListResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getMethodListResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__exit +#define SOAP_TYPE_AL_albroker__exit (75) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__exit(struct soap*, struct albroker__exit *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__exit(struct soap*, const struct albroker__exit *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__exit(struct soap*, const struct albroker__exit *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__exit(struct soap*, const char*, int, const struct albroker__exit *, const char*); +SOAP_FMAC3 struct albroker__exit * SOAP_FMAC4 soap_get_albroker__exit(struct soap*, struct albroker__exit *, const char*, const char*); +SOAP_FMAC3 struct albroker__exit * SOAP_FMAC4 soap_in_albroker__exit(struct soap*, const char*, struct albroker__exit *, const char*); +SOAP_FMAC5 struct albroker__exit * SOAP_FMAC6 soap_new_albroker__exit(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__exit(struct soap*, struct albroker__exit*); +SOAP_FMAC3 struct albroker__exit * SOAP_FMAC4 soap_instantiate_albroker__exit(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__exit(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerInfo +#define SOAP_TYPE_AL_albroker__getBrokerInfo (73) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerInfo(struct soap*, struct albroker__getBrokerInfo *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerInfo(struct soap*, const struct albroker__getBrokerInfo *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerInfo(struct soap*, const struct albroker__getBrokerInfo *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerInfo(struct soap*, const char*, int, const struct albroker__getBrokerInfo *, const char*); +SOAP_FMAC3 struct albroker__getBrokerInfo * SOAP_FMAC4 soap_get_albroker__getBrokerInfo(struct soap*, struct albroker__getBrokerInfo *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerInfo * SOAP_FMAC4 soap_in_albroker__getBrokerInfo(struct soap*, const char*, struct albroker__getBrokerInfo *, const char*); +SOAP_FMAC5 struct albroker__getBrokerInfo * SOAP_FMAC6 soap_new_albroker__getBrokerInfo(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerInfo(struct soap*, struct albroker__getBrokerInfo*); +SOAP_FMAC3 struct albroker__getBrokerInfo * SOAP_FMAC4 soap_instantiate_albroker__getBrokerInfo(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerInfo(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__unregisterModuleReference +#define SOAP_TYPE_AL_albroker__unregisterModuleReference (70) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__unregisterModuleReference(struct soap*, struct albroker__unregisterModuleReference *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__unregisterModuleReference(struct soap*, const struct albroker__unregisterModuleReference *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__unregisterModuleReference(struct soap*, const struct albroker__unregisterModuleReference *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__unregisterModuleReference(struct soap*, const char*, int, const struct albroker__unregisterModuleReference *, const char*); +SOAP_FMAC3 struct albroker__unregisterModuleReference * SOAP_FMAC4 soap_get_albroker__unregisterModuleReference(struct soap*, struct albroker__unregisterModuleReference *, const char*, const char*); +SOAP_FMAC3 struct albroker__unregisterModuleReference * SOAP_FMAC4 soap_in_albroker__unregisterModuleReference(struct soap*, const char*, struct albroker__unregisterModuleReference *, const char*); +SOAP_FMAC5 struct albroker__unregisterModuleReference * SOAP_FMAC6 soap_new_albroker__unregisterModuleReference(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__unregisterModuleReference(struct soap*, struct albroker__unregisterModuleReference*); +SOAP_FMAC3 struct albroker__unregisterModuleReference * SOAP_FMAC4 soap_instantiate_albroker__unregisterModuleReference(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__unregisterModuleReference(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__unregisterBroker +#define SOAP_TYPE_AL_albroker__unregisterBroker (68) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__unregisterBroker(struct soap*, struct albroker__unregisterBroker *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__unregisterBroker(struct soap*, const struct albroker__unregisterBroker *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__unregisterBroker(struct soap*, const struct albroker__unregisterBroker *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__unregisterBroker(struct soap*, const char*, int, const struct albroker__unregisterBroker *, const char*); +SOAP_FMAC3 struct albroker__unregisterBroker * SOAP_FMAC4 soap_get_albroker__unregisterBroker(struct soap*, struct albroker__unregisterBroker *, const char*, const char*); +SOAP_FMAC3 struct albroker__unregisterBroker * SOAP_FMAC4 soap_in_albroker__unregisterBroker(struct soap*, const char*, struct albroker__unregisterBroker *, const char*); +SOAP_FMAC5 struct albroker__unregisterBroker * SOAP_FMAC6 soap_new_albroker__unregisterBroker(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__unregisterBroker(struct soap*, struct albroker__unregisterBroker*); +SOAP_FMAC3 struct albroker__unregisterBroker * SOAP_FMAC4 soap_instantiate_albroker__unregisterBroker(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__unregisterBroker(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__unregisterBrokerResponse +#define SOAP_TYPE_AL_albroker__unregisterBrokerResponse (67) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__unregisterBrokerResponse(struct soap*, struct albroker__unregisterBrokerResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__unregisterBrokerResponse(struct soap*, const struct albroker__unregisterBrokerResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__unregisterBrokerResponse(struct soap*, const struct albroker__unregisterBrokerResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__unregisterBrokerResponse(struct soap*, const char*, int, const struct albroker__unregisterBrokerResponse *, const char*); +SOAP_FMAC3 struct albroker__unregisterBrokerResponse * SOAP_FMAC4 soap_get_albroker__unregisterBrokerResponse(struct soap*, struct albroker__unregisterBrokerResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__unregisterBrokerResponse * SOAP_FMAC4 soap_in_albroker__unregisterBrokerResponse(struct soap*, const char*, struct albroker__unregisterBrokerResponse *, const char*); +SOAP_FMAC5 struct albroker__unregisterBrokerResponse * SOAP_FMAC6 soap_new_albroker__unregisterBrokerResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__unregisterBrokerResponse(struct soap*, struct albroker__unregisterBrokerResponse*); +SOAP_FMAC3 struct albroker__unregisterBrokerResponse * SOAP_FMAC4 soap_instantiate_albroker__unregisterBrokerResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__unregisterBrokerResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__registerBroker +#define SOAP_TYPE_AL_albroker__registerBroker (65) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__registerBroker(struct soap*, struct albroker__registerBroker *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__registerBroker(struct soap*, const struct albroker__registerBroker *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__registerBroker(struct soap*, const struct albroker__registerBroker *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__registerBroker(struct soap*, const char*, int, const struct albroker__registerBroker *, const char*); +SOAP_FMAC3 struct albroker__registerBroker * SOAP_FMAC4 soap_get_albroker__registerBroker(struct soap*, struct albroker__registerBroker *, const char*, const char*); +SOAP_FMAC3 struct albroker__registerBroker * SOAP_FMAC4 soap_in_albroker__registerBroker(struct soap*, const char*, struct albroker__registerBroker *, const char*); +SOAP_FMAC5 struct albroker__registerBroker * SOAP_FMAC6 soap_new_albroker__registerBroker(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__registerBroker(struct soap*, struct albroker__registerBroker*); +SOAP_FMAC3 struct albroker__registerBroker * SOAP_FMAC4 soap_instantiate_albroker__registerBroker(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__registerBroker(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__registerBrokerResponse +#define SOAP_TYPE_AL_albroker__registerBrokerResponse (64) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__registerBrokerResponse(struct soap*, struct albroker__registerBrokerResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__registerBrokerResponse(struct soap*, const struct albroker__registerBrokerResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__registerBrokerResponse(struct soap*, const struct albroker__registerBrokerResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__registerBrokerResponse(struct soap*, const char*, int, const struct albroker__registerBrokerResponse *, const char*); +SOAP_FMAC3 struct albroker__registerBrokerResponse * SOAP_FMAC4 soap_get_albroker__registerBrokerResponse(struct soap*, struct albroker__registerBrokerResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__registerBrokerResponse * SOAP_FMAC4 soap_in_albroker__registerBrokerResponse(struct soap*, const char*, struct albroker__registerBrokerResponse *, const char*); +SOAP_FMAC5 struct albroker__registerBrokerResponse * SOAP_FMAC6 soap_new_albroker__registerBrokerResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__registerBrokerResponse(struct soap*, struct albroker__registerBrokerResponse*); +SOAP_FMAC3 struct albroker__registerBrokerResponse * SOAP_FMAC4 soap_instantiate_albroker__registerBrokerResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__registerBrokerResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerList +#define SOAP_TYPE_AL_albroker__getBrokerList (61) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerList(struct soap*, struct albroker__getBrokerList *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerList(struct soap*, const struct albroker__getBrokerList *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerList(struct soap*, const struct albroker__getBrokerList *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerList(struct soap*, const char*, int, const struct albroker__getBrokerList *, const char*); +SOAP_FMAC3 struct albroker__getBrokerList * SOAP_FMAC4 soap_get_albroker__getBrokerList(struct soap*, struct albroker__getBrokerList *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerList * SOAP_FMAC4 soap_in_albroker__getBrokerList(struct soap*, const char*, struct albroker__getBrokerList *, const char*); +SOAP_FMAC5 struct albroker__getBrokerList * SOAP_FMAC6 soap_new_albroker__getBrokerList(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerList(struct soap*, struct albroker__getBrokerList*); +SOAP_FMAC3 struct albroker__getBrokerList * SOAP_FMAC4 soap_instantiate_albroker__getBrokerList(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerList(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getGlobalModuleList +#define SOAP_TYPE_AL_albroker__getGlobalModuleList (58) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getGlobalModuleList(struct soap*, struct albroker__getGlobalModuleList *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getGlobalModuleList(struct soap*, const struct albroker__getGlobalModuleList *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getGlobalModuleList(struct soap*, const struct albroker__getGlobalModuleList *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getGlobalModuleList(struct soap*, const char*, int, const struct albroker__getGlobalModuleList *, const char*); +SOAP_FMAC3 struct albroker__getGlobalModuleList * SOAP_FMAC4 soap_get_albroker__getGlobalModuleList(struct soap*, struct albroker__getGlobalModuleList *, const char*, const char*); +SOAP_FMAC3 struct albroker__getGlobalModuleList * SOAP_FMAC4 soap_in_albroker__getGlobalModuleList(struct soap*, const char*, struct albroker__getGlobalModuleList *, const char*); +SOAP_FMAC5 struct albroker__getGlobalModuleList * SOAP_FMAC6 soap_new_albroker__getGlobalModuleList(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getGlobalModuleList(struct soap*, struct albroker__getGlobalModuleList*); +SOAP_FMAC3 struct albroker__getGlobalModuleList * SOAP_FMAC4 soap_instantiate_albroker__getGlobalModuleList(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getGlobalModuleList(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getModuleList +#define SOAP_TYPE_AL_albroker__getModuleList (55) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getModuleList(struct soap*, struct albroker__getModuleList *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getModuleList(struct soap*, const struct albroker__getModuleList *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getModuleList(struct soap*, const struct albroker__getModuleList *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getModuleList(struct soap*, const char*, int, const struct albroker__getModuleList *, const char*); +SOAP_FMAC3 struct albroker__getModuleList * SOAP_FMAC4 soap_get_albroker__getModuleList(struct soap*, struct albroker__getModuleList *, const char*, const char*); +SOAP_FMAC3 struct albroker__getModuleList * SOAP_FMAC4 soap_in_albroker__getModuleList(struct soap*, const char*, struct albroker__getModuleList *, const char*); +SOAP_FMAC5 struct albroker__getModuleList * SOAP_FMAC6 soap_new_albroker__getModuleList(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getModuleList(struct soap*, struct albroker__getModuleList*); +SOAP_FMAC3 struct albroker__getModuleList * SOAP_FMAC4 soap_instantiate_albroker__getModuleList(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getModuleList(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__exploreToGetModuleByName +#define SOAP_TYPE_AL_albroker__exploreToGetModuleByName (51) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__exploreToGetModuleByName(struct soap*, struct albroker__exploreToGetModuleByName *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__exploreToGetModuleByName(struct soap*, const struct albroker__exploreToGetModuleByName *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__exploreToGetModuleByName(struct soap*, const struct albroker__exploreToGetModuleByName *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__exploreToGetModuleByName(struct soap*, const char*, int, const struct albroker__exploreToGetModuleByName *, const char*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByName * SOAP_FMAC4 soap_get_albroker__exploreToGetModuleByName(struct soap*, struct albroker__exploreToGetModuleByName *, const char*, const char*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByName * SOAP_FMAC4 soap_in_albroker__exploreToGetModuleByName(struct soap*, const char*, struct albroker__exploreToGetModuleByName *, const char*); +SOAP_FMAC5 struct albroker__exploreToGetModuleByName * SOAP_FMAC6 soap_new_albroker__exploreToGetModuleByName(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__exploreToGetModuleByName(struct soap*, struct albroker__exploreToGetModuleByName*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByName * SOAP_FMAC4 soap_instantiate_albroker__exploreToGetModuleByName(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__exploreToGetModuleByName(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getModuleByName +#define SOAP_TYPE_AL_albroker__getModuleByName (48) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getModuleByName(struct soap*, struct albroker__getModuleByName *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getModuleByName(struct soap*, const struct albroker__getModuleByName *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getModuleByName(struct soap*, const struct albroker__getModuleByName *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getModuleByName(struct soap*, const char*, int, const struct albroker__getModuleByName *, const char*); +SOAP_FMAC3 struct albroker__getModuleByName * SOAP_FMAC4 soap_get_albroker__getModuleByName(struct soap*, struct albroker__getModuleByName *, const char*, const char*); +SOAP_FMAC3 struct albroker__getModuleByName * SOAP_FMAC4 soap_in_albroker__getModuleByName(struct soap*, const char*, struct albroker__getModuleByName *, const char*); +SOAP_FMAC5 struct albroker__getModuleByName * SOAP_FMAC6 soap_new_albroker__getModuleByName(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getModuleByName(struct soap*, struct albroker__getModuleByName*); +SOAP_FMAC3 struct albroker__getModuleByName * SOAP_FMAC4 soap_instantiate_albroker__getModuleByName(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getModuleByName(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqi +#define SOAP_TYPE_AL_albroker__pCallNaoqi (45) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__pCallNaoqi(struct soap*, struct albroker__pCallNaoqi *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__pCallNaoqi(struct soap*, const struct albroker__pCallNaoqi *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__pCallNaoqi(struct soap*, const struct albroker__pCallNaoqi *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__pCallNaoqi(struct soap*, const char*, int, const struct albroker__pCallNaoqi *, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqi * SOAP_FMAC4 soap_get_albroker__pCallNaoqi(struct soap*, struct albroker__pCallNaoqi *, const char*, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqi * SOAP_FMAC4 soap_in_albroker__pCallNaoqi(struct soap*, const char*, struct albroker__pCallNaoqi *, const char*); +SOAP_FMAC5 struct albroker__pCallNaoqi * SOAP_FMAC6 soap_new_albroker__pCallNaoqi(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__pCallNaoqi(struct soap*, struct albroker__pCallNaoqi*); +SOAP_FMAC3 struct albroker__pCallNaoqi * SOAP_FMAC4 soap_instantiate_albroker__pCallNaoqi(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__pCallNaoqi(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqiN +#define SOAP_TYPE_AL_albroker__pCallNaoqiN (42) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__pCallNaoqiN(struct soap*, struct albroker__pCallNaoqiN *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__pCallNaoqiN(struct soap*, const struct albroker__pCallNaoqiN *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__pCallNaoqiN(struct soap*, const struct albroker__pCallNaoqiN *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__pCallNaoqiN(struct soap*, const char*, int, const struct albroker__pCallNaoqiN *, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqiN * SOAP_FMAC4 soap_get_albroker__pCallNaoqiN(struct soap*, struct albroker__pCallNaoqiN *, const char*, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqiN * SOAP_FMAC4 soap_in_albroker__pCallNaoqiN(struct soap*, const char*, struct albroker__pCallNaoqiN *, const char*); +SOAP_FMAC5 struct albroker__pCallNaoqiN * SOAP_FMAC6 soap_new_albroker__pCallNaoqiN(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__pCallNaoqiN(struct soap*, struct albroker__pCallNaoqiN*); +SOAP_FMAC3 struct albroker__pCallNaoqiN * SOAP_FMAC4 soap_instantiate_albroker__pCallNaoqiN(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__pCallNaoqiN(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi2 +#define SOAP_TYPE_AL_albroker__callNaoqi2 (39) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__callNaoqi2(struct soap*, struct albroker__callNaoqi2 *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__callNaoqi2(struct soap*, const struct albroker__callNaoqi2 *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__callNaoqi2(struct soap*, const struct albroker__callNaoqi2 *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__callNaoqi2(struct soap*, const char*, int, const struct albroker__callNaoqi2 *, const char*); +SOAP_FMAC3 struct albroker__callNaoqi2 * SOAP_FMAC4 soap_get_albroker__callNaoqi2(struct soap*, struct albroker__callNaoqi2 *, const char*, const char*); +SOAP_FMAC3 struct albroker__callNaoqi2 * SOAP_FMAC4 soap_in_albroker__callNaoqi2(struct soap*, const char*, struct albroker__callNaoqi2 *, const char*); +SOAP_FMAC5 struct albroker__callNaoqi2 * SOAP_FMAC6 soap_new_albroker__callNaoqi2(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__callNaoqi2(struct soap*, struct albroker__callNaoqi2*); +SOAP_FMAC3 struct albroker__callNaoqi2 * SOAP_FMAC4 soap_instantiate_albroker__callNaoqi2(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__callNaoqi2(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi +#define SOAP_TYPE_AL_albroker__callNaoqi (36) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__callNaoqi(struct soap*, struct albroker__callNaoqi *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__callNaoqi(struct soap*, const struct albroker__callNaoqi *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__callNaoqi(struct soap*, const struct albroker__callNaoqi *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__callNaoqi(struct soap*, const char*, int, const struct albroker__callNaoqi *, const char*); +SOAP_FMAC3 struct albroker__callNaoqi * SOAP_FMAC4 soap_get_albroker__callNaoqi(struct soap*, struct albroker__callNaoqi *, const char*, const char*); +SOAP_FMAC3 struct albroker__callNaoqi * SOAP_FMAC4 soap_in_albroker__callNaoqi(struct soap*, const char*, struct albroker__callNaoqi *, const char*); +SOAP_FMAC5 struct albroker__callNaoqi * SOAP_FMAC6 soap_new_albroker__callNaoqi(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__callNaoqi(struct soap*, struct albroker__callNaoqi*); +SOAP_FMAC3 struct albroker__callNaoqi * SOAP_FMAC4 soap_instantiate_albroker__callNaoqi(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__callNaoqi(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getDebugTaskListResponse +#define SOAP_TYPE_AL_albroker__getDebugTaskListResponse (33) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getDebugTaskListResponse(struct soap*, struct albroker__getDebugTaskListResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getDebugTaskListResponse(struct soap*, const struct albroker__getDebugTaskListResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getDebugTaskListResponse(struct soap*, const struct albroker__getDebugTaskListResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getDebugTaskListResponse(struct soap*, const char*, int, const struct albroker__getDebugTaskListResponse *, const char*); +SOAP_FMAC3 struct albroker__getDebugTaskListResponse * SOAP_FMAC4 soap_get_albroker__getDebugTaskListResponse(struct soap*, struct albroker__getDebugTaskListResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getDebugTaskListResponse * SOAP_FMAC4 soap_in_albroker__getDebugTaskListResponse(struct soap*, const char*, struct albroker__getDebugTaskListResponse *, const char*); +SOAP_FMAC5 struct albroker__getDebugTaskListResponse * SOAP_FMAC6 soap_new_albroker__getDebugTaskListResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getDebugTaskListResponse(struct soap*, struct albroker__getDebugTaskListResponse*); +SOAP_FMAC3 struct albroker__getDebugTaskListResponse * SOAP_FMAC4 soap_instantiate_albroker__getDebugTaskListResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getDebugTaskListResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getGlobalModuleListResponse +#define SOAP_TYPE_AL_albroker__getGlobalModuleListResponse (32) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getGlobalModuleListResponse(struct soap*, struct albroker__getGlobalModuleListResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getGlobalModuleListResponse(struct soap*, const struct albroker__getGlobalModuleListResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getGlobalModuleListResponse(struct soap*, const struct albroker__getGlobalModuleListResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getGlobalModuleListResponse(struct soap*, const char*, int, const struct albroker__getGlobalModuleListResponse *, const char*); +SOAP_FMAC3 struct albroker__getGlobalModuleListResponse * SOAP_FMAC4 soap_get_albroker__getGlobalModuleListResponse(struct soap*, struct albroker__getGlobalModuleListResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getGlobalModuleListResponse * SOAP_FMAC4 soap_in_albroker__getGlobalModuleListResponse(struct soap*, const char*, struct albroker__getGlobalModuleListResponse *, const char*); +SOAP_FMAC5 struct albroker__getGlobalModuleListResponse * SOAP_FMAC6 soap_new_albroker__getGlobalModuleListResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getGlobalModuleListResponse(struct soap*, struct albroker__getGlobalModuleListResponse*); +SOAP_FMAC3 struct albroker__getGlobalModuleListResponse * SOAP_FMAC4 soap_instantiate_albroker__getGlobalModuleListResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getGlobalModuleListResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerListResponse +#define SOAP_TYPE_AL_albroker__getBrokerListResponse (31) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerListResponse(struct soap*, struct albroker__getBrokerListResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerListResponse(struct soap*, const struct albroker__getBrokerListResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerListResponse(struct soap*, const struct albroker__getBrokerListResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerListResponse(struct soap*, const char*, int, const struct albroker__getBrokerListResponse *, const char*); +SOAP_FMAC3 struct albroker__getBrokerListResponse * SOAP_FMAC4 soap_get_albroker__getBrokerListResponse(struct soap*, struct albroker__getBrokerListResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerListResponse * SOAP_FMAC4 soap_in_albroker__getBrokerListResponse(struct soap*, const char*, struct albroker__getBrokerListResponse *, const char*); +SOAP_FMAC5 struct albroker__getBrokerListResponse * SOAP_FMAC6 soap_new_albroker__getBrokerListResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerListResponse(struct soap*, struct albroker__getBrokerListResponse*); +SOAP_FMAC3 struct albroker__getBrokerListResponse * SOAP_FMAC4 soap_instantiate_albroker__getBrokerListResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerListResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getModuleListResponse +#define SOAP_TYPE_AL_albroker__getModuleListResponse (29) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getModuleListResponse(struct soap*, struct albroker__getModuleListResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getModuleListResponse(struct soap*, const struct albroker__getModuleListResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getModuleListResponse(struct soap*, const struct albroker__getModuleListResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getModuleListResponse(struct soap*, const char*, int, const struct albroker__getModuleListResponse *, const char*); +SOAP_FMAC3 struct albroker__getModuleListResponse * SOAP_FMAC4 soap_get_albroker__getModuleListResponse(struct soap*, struct albroker__getModuleListResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getModuleListResponse * SOAP_FMAC4 soap_in_albroker__getModuleListResponse(struct soap*, const char*, struct albroker__getModuleListResponse *, const char*); +SOAP_FMAC5 struct albroker__getModuleListResponse * SOAP_FMAC6 soap_new_albroker__getModuleListResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getModuleListResponse(struct soap*, struct albroker__getModuleListResponse*); +SOAP_FMAC3 struct albroker__getModuleListResponse * SOAP_FMAC4 soap_instantiate_albroker__getModuleListResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getModuleListResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqiNResponse +#define SOAP_TYPE_AL_albroker__pCallNaoqiNResponse (28) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__pCallNaoqiNResponse(struct soap*, struct albroker__pCallNaoqiNResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__pCallNaoqiNResponse(struct soap*, const struct albroker__pCallNaoqiNResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__pCallNaoqiNResponse(struct soap*, const struct albroker__pCallNaoqiNResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__pCallNaoqiNResponse(struct soap*, const char*, int, const struct albroker__pCallNaoqiNResponse *, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqiNResponse * SOAP_FMAC4 soap_get_albroker__pCallNaoqiNResponse(struct soap*, struct albroker__pCallNaoqiNResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__pCallNaoqiNResponse * SOAP_FMAC4 soap_in_albroker__pCallNaoqiNResponse(struct soap*, const char*, struct albroker__pCallNaoqiNResponse *, const char*); +SOAP_FMAC5 struct albroker__pCallNaoqiNResponse * SOAP_FMAC6 soap_new_albroker__pCallNaoqiNResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__pCallNaoqiNResponse(struct soap*, struct albroker__pCallNaoqiNResponse*); +SOAP_FMAC3 struct albroker__pCallNaoqiNResponse * SOAP_FMAC4 soap_instantiate_albroker__pCallNaoqiNResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__pCallNaoqiNResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi2Response +#define SOAP_TYPE_AL_albroker__callNaoqi2Response (27) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__callNaoqi2Response(struct soap*, struct albroker__callNaoqi2Response *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__callNaoqi2Response(struct soap*, const struct albroker__callNaoqi2Response *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__callNaoqi2Response(struct soap*, const struct albroker__callNaoqi2Response *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__callNaoqi2Response(struct soap*, const char*, int, const struct albroker__callNaoqi2Response *, const char*); +SOAP_FMAC3 struct albroker__callNaoqi2Response * SOAP_FMAC4 soap_get_albroker__callNaoqi2Response(struct soap*, struct albroker__callNaoqi2Response *, const char*, const char*); +SOAP_FMAC3 struct albroker__callNaoqi2Response * SOAP_FMAC4 soap_in_albroker__callNaoqi2Response(struct soap*, const char*, struct albroker__callNaoqi2Response *, const char*); +SOAP_FMAC5 struct albroker__callNaoqi2Response * SOAP_FMAC6 soap_new_albroker__callNaoqi2Response(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__callNaoqi2Response(struct soap*, struct albroker__callNaoqi2Response*); +SOAP_FMAC3 struct albroker__callNaoqi2Response * SOAP_FMAC4 soap_instantiate_albroker__callNaoqi2Response(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__callNaoqi2Response(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__callNaoqiResponse +#define SOAP_TYPE_AL_albroker__callNaoqiResponse (26) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__callNaoqiResponse(struct soap*, struct albroker__callNaoqiResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__callNaoqiResponse(struct soap*, const struct albroker__callNaoqiResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__callNaoqiResponse(struct soap*, const struct albroker__callNaoqiResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__callNaoqiResponse(struct soap*, const char*, int, const struct albroker__callNaoqiResponse *, const char*); +SOAP_FMAC3 struct albroker__callNaoqiResponse * SOAP_FMAC4 soap_get_albroker__callNaoqiResponse(struct soap*, struct albroker__callNaoqiResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__callNaoqiResponse * SOAP_FMAC4 soap_in_albroker__callNaoqiResponse(struct soap*, const char*, struct albroker__callNaoqiResponse *, const char*); +SOAP_FMAC5 struct albroker__callNaoqiResponse * SOAP_FMAC6 soap_new_albroker__callNaoqiResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__callNaoqiResponse(struct soap*, struct albroker__callNaoqiResponse*); +SOAP_FMAC3 struct albroker__callNaoqiResponse * SOAP_FMAC4 soap_instantiate_albroker__callNaoqiResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__callNaoqiResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getModuleByNameResponse +#define SOAP_TYPE_AL_albroker__getModuleByNameResponse (25) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getModuleByNameResponse(struct soap*, struct albroker__getModuleByNameResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getModuleByNameResponse(struct soap*, const struct albroker__getModuleByNameResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getModuleByNameResponse(struct soap*, const struct albroker__getModuleByNameResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getModuleByNameResponse(struct soap*, const char*, int, const struct albroker__getModuleByNameResponse *, const char*); +SOAP_FMAC3 struct albroker__getModuleByNameResponse * SOAP_FMAC4 soap_get_albroker__getModuleByNameResponse(struct soap*, struct albroker__getModuleByNameResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getModuleByNameResponse * SOAP_FMAC4 soap_in_albroker__getModuleByNameResponse(struct soap*, const char*, struct albroker__getModuleByNameResponse *, const char*); +SOAP_FMAC5 struct albroker__getModuleByNameResponse * SOAP_FMAC6 soap_new_albroker__getModuleByNameResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getModuleByNameResponse(struct soap*, struct albroker__getModuleByNameResponse*); +SOAP_FMAC3 struct albroker__getModuleByNameResponse * SOAP_FMAC4 soap_instantiate_albroker__getModuleByNameResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getModuleByNameResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__exploreToGetModuleByNameResponse +#define SOAP_TYPE_AL_albroker__exploreToGetModuleByNameResponse (24) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__exploreToGetModuleByNameResponse(struct soap*, struct albroker__exploreToGetModuleByNameResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__exploreToGetModuleByNameResponse(struct soap*, const struct albroker__exploreToGetModuleByNameResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__exploreToGetModuleByNameResponse(struct soap*, const struct albroker__exploreToGetModuleByNameResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__exploreToGetModuleByNameResponse(struct soap*, const char*, int, const struct albroker__exploreToGetModuleByNameResponse *, const char*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByNameResponse * SOAP_FMAC4 soap_get_albroker__exploreToGetModuleByNameResponse(struct soap*, struct albroker__exploreToGetModuleByNameResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByNameResponse * SOAP_FMAC4 soap_in_albroker__exploreToGetModuleByNameResponse(struct soap*, const char*, struct albroker__exploreToGetModuleByNameResponse *, const char*); +SOAP_FMAC5 struct albroker__exploreToGetModuleByNameResponse * SOAP_FMAC6 soap_new_albroker__exploreToGetModuleByNameResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__exploreToGetModuleByNameResponse(struct soap*, struct albroker__exploreToGetModuleByNameResponse*); +SOAP_FMAC3 struct albroker__exploreToGetModuleByNameResponse * SOAP_FMAC4 soap_instantiate_albroker__exploreToGetModuleByNameResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__exploreToGetModuleByNameResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_albroker__getBrokerInfoResponse +#define SOAP_TYPE_AL_albroker__getBrokerInfoResponse (23) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_albroker__getBrokerInfoResponse(struct soap*, struct albroker__getBrokerInfoResponse *); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_albroker__getBrokerInfoResponse(struct soap*, const struct albroker__getBrokerInfoResponse *); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_albroker__getBrokerInfoResponse(struct soap*, const struct albroker__getBrokerInfoResponse *, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_albroker__getBrokerInfoResponse(struct soap*, const char*, int, const struct albroker__getBrokerInfoResponse *, const char*); +SOAP_FMAC3 struct albroker__getBrokerInfoResponse * SOAP_FMAC4 soap_get_albroker__getBrokerInfoResponse(struct soap*, struct albroker__getBrokerInfoResponse *, const char*, const char*); +SOAP_FMAC3 struct albroker__getBrokerInfoResponse * SOAP_FMAC4 soap_in_albroker__getBrokerInfoResponse(struct soap*, const char*, struct albroker__getBrokerInfoResponse *, const char*); +SOAP_FMAC5 struct albroker__getBrokerInfoResponse * SOAP_FMAC6 soap_new_albroker__getBrokerInfoResponse(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_albroker__getBrokerInfoResponse(struct soap*, struct albroker__getBrokerInfoResponse*); +SOAP_FMAC3 struct albroker__getBrokerInfoResponse * SOAP_FMAC4 soap_instantiate_albroker__getBrokerInfoResponse(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_albroker__getBrokerInfoResponse(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_PointerToSOAP_ENV__Reason +#define SOAP_TYPE_AL_PointerToSOAP_ENV__Reason (120) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_PointerToSOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_PointerToSOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_PointerToSOAP_ENV__Reason(struct soap*, const char *, int, struct SOAP_ENV__Reason *const*, const char *); +SOAP_FMAC3 struct SOAP_ENV__Reason ** SOAP_FMAC4 soap_get_PointerToSOAP_ENV__Reason(struct soap*, struct SOAP_ENV__Reason **, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Reason ** SOAP_FMAC4 soap_in_PointerToSOAP_ENV__Reason(struct soap*, const char*, struct SOAP_ENV__Reason **, const char*); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_PointerToSOAP_ENV__Detail +#define SOAP_TYPE_AL_PointerToSOAP_ENV__Detail (119) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_PointerToSOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_PointerToSOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_PointerToSOAP_ENV__Detail(struct soap*, const char *, int, struct SOAP_ENV__Detail *const*, const char *); +SOAP_FMAC3 struct SOAP_ENV__Detail ** SOAP_FMAC4 soap_get_PointerToSOAP_ENV__Detail(struct soap*, struct SOAP_ENV__Detail **, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Detail ** SOAP_FMAC4 soap_in_PointerToSOAP_ENV__Detail(struct soap*, const char*, struct SOAP_ENV__Detail **, const char*); + +#endif + +#ifndef WITH_NOGLOBAL + +#ifndef SOAP_TYPE_AL_PointerToSOAP_ENV__Code +#define SOAP_TYPE_AL_PointerToSOAP_ENV__Code (115) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_PointerToSOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_PointerToSOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_PointerToSOAP_ENV__Code(struct soap*, const char *, int, struct SOAP_ENV__Code *const*, const char *); +SOAP_FMAC3 struct SOAP_ENV__Code ** SOAP_FMAC4 soap_get_PointerToSOAP_ENV__Code(struct soap*, struct SOAP_ENV__Code **, const char*, const char*); +SOAP_FMAC3 struct SOAP_ENV__Code ** SOAP_FMAC4 soap_in_PointerToSOAP_ENV__Code(struct soap*, const char*, struct SOAP_ENV__Code **, const char*); + +#endif + +#ifndef SOAP_TYPE_AL_PointerToxsd__int +#define SOAP_TYPE_AL_PointerToxsd__int (76) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_PointerToxsd__int(struct soap*, int *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_PointerToxsd__int(struct soap*, int *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_PointerToxsd__int(struct soap*, const char *, int, int *const*, const char *); +SOAP_FMAC3 int ** SOAP_FMAC4 soap_get_PointerToxsd__int(struct soap*, int **, const char*, const char*); +SOAP_FMAC3 int ** SOAP_FMAC4 soap_in_PointerToxsd__int(struct soap*, const char*, int **, const char*); + +#ifndef SOAP_TYPE_AL__QName +#define SOAP_TYPE_AL__QName (5) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default__QName(struct soap*, char **); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize__QName(struct soap*, char *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put__QName(struct soap*, char *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out__QName(struct soap*, const char*, int, char*const*, const char*); +SOAP_FMAC3 char ** SOAP_FMAC4 soap_get__QName(struct soap*, char **, const char*, const char*); +SOAP_FMAC3 char * * SOAP_FMAC4 soap_in__QName(struct soap*, const char*, char **, const char*); + +#ifndef SOAP_TYPE_AL_string +#define SOAP_TYPE_AL_string (4) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_string(struct soap*, char **); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_string(struct soap*, char *const*); +SOAP_FMAC3 int SOAP_FMAC4 soap_put_string(struct soap*, char *const*, const char*, const char*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_string(struct soap*, const char*, int, char*const*, const char*); +SOAP_FMAC3 char ** SOAP_FMAC4 soap_get_string(struct soap*, char **, const char*, const char*); +SOAP_FMAC3 char * * SOAP_FMAC4 soap_in_string(struct soap*, const char*, char **, const char*); + +#ifndef SOAP_TYPE_AL_std__vectorTemplateOfxsd__string +#define SOAP_TYPE_AL_std__vectorTemplateOfxsd__string (80) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_std__vectorTemplateOfxsd__string(struct soap*, std::vector*); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_std__vectorTemplateOfxsd__string(struct soap*, const std::vector*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_std__vectorTemplateOfxsd__string(struct soap*, const char*, int, const std::vector*, const char*); +SOAP_FMAC3 std::vector* SOAP_FMAC4 soap_in_std__vectorTemplateOfxsd__string(struct soap*, const char*, std::vector*, const char*); +SOAP_FMAC5 std::vector * SOAP_FMAC6 soap_new_std__vectorTemplateOfxsd__string(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_std__vectorTemplateOfxsd__string(struct soap*, std::vector*); +SOAP_FMAC3 std::vector * SOAP_FMAC4 soap_instantiate_std__vectorTemplateOfxsd__string(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_std__vectorTemplateOfxsd__string(struct soap*, int, int, void*, size_t, const void*, size_t); + +#ifndef SOAP_TYPE_AL_std__vectorTemplateOfal__ALModuleInfo +#define SOAP_TYPE_AL_std__vectorTemplateOfal__ALModuleInfo (30) +#endif +SOAP_FMAC3 void SOAP_FMAC4 soap_default_std__vectorTemplateOfal__ALModuleInfo(struct soap*, std::vector*); +SOAP_FMAC3 void SOAP_FMAC4 soap_serialize_std__vectorTemplateOfal__ALModuleInfo(struct soap*, const std::vector*); +SOAP_FMAC3 int SOAP_FMAC4 soap_out_std__vectorTemplateOfal__ALModuleInfo(struct soap*, const char*, int, const std::vector*, const char*); +SOAP_FMAC3 std::vector* SOAP_FMAC4 soap_in_std__vectorTemplateOfal__ALModuleInfo(struct soap*, const char*, std::vector*, const char*); +SOAP_FMAC5 std::vector * SOAP_FMAC6 soap_new_std__vectorTemplateOfal__ALModuleInfo(struct soap*, int); +SOAP_FMAC5 void SOAP_FMAC6 soap_delete_std__vectorTemplateOfal__ALModuleInfo(struct soap*, std::vector*); +SOAP_FMAC3 std::vector * SOAP_FMAC4 soap_instantiate_std__vectorTemplateOfal__ALModuleInfo(struct soap*, int, const char*, const char*, size_t*); +SOAP_FMAC3 void SOAP_FMAC4 soap_copy_std__vectorTemplateOfal__ALModuleInfo(struct soap*, int, int, void*, size_t, const void*, size_t); + +} // namespace AL + + +#endif + +/* End of ALH.h */ diff --git a/naoModule/libnaoqi_files/include/alsoap/ALStub.h b/naoModule/libnaoqi_files/include/alsoap/ALStub.h new file mode 100755 index 0000000..4a62bef --- /dev/null +++ b/naoModule/libnaoqi_files/include/alsoap/ALStub.h @@ -0,0 +1,824 @@ +/* ALStub.h + Generated by gSOAP 2.7.12 from I_ALBroker.h + Copyright(C) 2000-2008, Robert van Engelen, Genivia Inc. All Rights Reserved. + This part of the software is released under one of the following licenses: + GPL, the gSOAP public license, or Genivia's license for commercial use. +*/ + +#ifndef ALStub_H +#define ALStub_H +#include +#include +#ifndef WITH_NOGLOBAL +#define WITH_NOGLOBAL +#endif +#include "stdsoap2.h" +#include + + +namespace AL { + +/******************************************************************************\ + * * + * Enumerations * + * * +\******************************************************************************/ + + +/******************************************************************************\ + * * + * Classes and Structs * + * * +\******************************************************************************/ + + +#if 0 /* volatile type: do not redeclare here */ + +#endif + + + +#if 0 /* volatile type: do not redeclare here */ + +#endif + + + +#ifndef SOAP_TYPE_AL_al__ALModuleInfo +#define SOAP_TYPE_AL_al__ALModuleInfo (22) +/* al:ALModuleInfo */ +class SOAP_CMAC al__ALModuleInfo +{ +public: + std::string name; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:string */ + int architecture; /* required element of type xsd:int */ + std::string ip; /* required element of type xsd:string */ + int port; /* required element of type xsd:int */ + int processId; /* required element of type xsd:int */ + int modulePointer; /* required element of type xsd:int */ + bool isABroker; /* required element of type xsd:bool */ + bool keepAlive; /* required element of type xsd:bool */ +public: + virtual int soap_type() const { return 22; } /* = unique id SOAP_TYPE_AL_al__ALModuleInfo */ + virtual void soap_default(struct soap*); + virtual void soap_serialize(struct soap*) const; + virtual int soap_put(struct soap*, const char*, const char*) const; + virtual int soap_out(struct soap*, const char*, int, const char*) const; + virtual void *soap_get(struct soap*, const char*, const char*); + virtual void *soap_in(struct soap*, const char*, const char*); + al__ALModuleInfo() : architecture(0), port(0), processId(0), modulePointer(0), isABroker((bool)0), keepAlive((bool)0) { } + virtual ~al__ALModuleInfo() { } +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerInfoResponse +#define SOAP_TYPE_AL_albroker__getBrokerInfoResponse (23) +/* albroker:getBrokerInfoResponse */ +struct albroker__getBrokerInfoResponse +{ +public: + al__ALModuleInfo _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__exploreToGetModuleByNameResponse +#define SOAP_TYPE_AL_albroker__exploreToGetModuleByNameResponse (24) +/* albroker:exploreToGetModuleByNameResponse */ +struct albroker__exploreToGetModuleByNameResponse +{ +public: + al__ALModuleInfo _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getModuleByNameResponse +#define SOAP_TYPE_AL_albroker__getModuleByNameResponse (25) +/* albroker:getModuleByNameResponse */ +struct albroker__getModuleByNameResponse +{ +public: + al__ALModuleInfo _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__callNaoqiResponse +#define SOAP_TYPE_AL_albroker__callNaoqiResponse (26) +/* albroker:callNaoqiResponse */ +struct albroker__callNaoqiResponse +{ +public: + ALValue _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi2Response +#define SOAP_TYPE_AL_albroker__callNaoqi2Response (27) +/* albroker:callNaoqi2Response */ +struct albroker__callNaoqi2Response +{ +public: + ALValue _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqiNResponse +#define SOAP_TYPE_AL_albroker__pCallNaoqiNResponse (28) +/* albroker:pCallNaoqiNResponse */ +struct albroker__pCallNaoqiNResponse +{ +public: + ALValue _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getModuleListResponse +#define SOAP_TYPE_AL_albroker__getModuleListResponse (29) +/* albroker:getModuleListResponse */ +struct albroker__getModuleListResponse +{ +public: + std::vector_return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* optional element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerListResponse +#define SOAP_TYPE_AL_albroker__getBrokerListResponse (31) +/* albroker:getBrokerListResponse */ +struct albroker__getBrokerListResponse +{ +public: + std::vector_return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* optional element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getGlobalModuleListResponse +#define SOAP_TYPE_AL_albroker__getGlobalModuleListResponse (32) +/* albroker:getGlobalModuleListResponse */ +struct albroker__getGlobalModuleListResponse +{ +public: + std::vector_return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* optional element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getDebugTaskListResponse +#define SOAP_TYPE_AL_albroker__getDebugTaskListResponse (33) +/* albroker:getDebugTaskListResponse */ +struct albroker__getDebugTaskListResponse +{ +public: + ALValue _return; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi +#define SOAP_TYPE_AL_albroker__callNaoqi (36) +/* albroker:callNaoqi */ +struct albroker__callNaoqi +{ +public: + std::string _mod; /* required element of type xsd:string */ + std::string _meth; /* required element of type xsd:string */ + ALValue _p; /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__callNaoqi2 +#define SOAP_TYPE_AL_albroker__callNaoqi2 (39) +/* albroker:callNaoqi2 */ +struct albroker__callNaoqi2 +{ +public: + std::string _mod; /* required element of type xsd:string */ + std::string _meth; /* required element of type xsd:string */ + ALValue _p; /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqiN +#define SOAP_TYPE_AL_albroker__pCallNaoqiN (42) +/* albroker:pCallNaoqiN */ +struct albroker__pCallNaoqiN +{ +public: + std::string _nIP; /* required element of type xsd:string */ + int _nPort; /* required element of type xsd:int */ + std::string _nMod; /* required element of type xsd:string */ + std::string _nMeth; /* required element of type xsd:string */ + std::string _mod; /* required element of type xsd:string */ + std::string _meth; /* required element of type xsd:string */ + ALValue _p; /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__pCallNaoqi +#define SOAP_TYPE_AL_albroker__pCallNaoqi (45) +/* albroker:pCallNaoqi */ +struct albroker__pCallNaoqi +{ +public: + std::string _mod; /* required element of type xsd:string */ + std::string _meth; /* required element of type xsd:string */ + ALValue _p; /* external */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getModuleByName +#define SOAP_TYPE_AL_albroker__getModuleByName (48) +/* albroker:getModuleByName */ +struct albroker__getModuleByName +{ +public: + std::string _pModuleName; /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__exploreToGetModuleByName +#define SOAP_TYPE_AL_albroker__exploreToGetModuleByName (51) +/* albroker:exploreToGetModuleByName */ +struct albroker__exploreToGetModuleByName +{ +public: + std::string _pModuleName; /* required element of type xsd:string */ + bool _pSearchUp; /* required element of type xsd:bool */ + bool _pSearchDown; /* required element of type xsd:bool */ + std::string _pDontLookIntoBrokerName; /* required element of type xsd:string */ + bool _pLoadLib; /* required element of type xsd:bool */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getModuleList +#define SOAP_TYPE_AL_albroker__getModuleList (55) +/* albroker:getModuleList */ +struct albroker__getModuleList +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getGlobalModuleList +#define SOAP_TYPE_AL_albroker__getGlobalModuleList (58) +/* albroker:getGlobalModuleList */ +struct albroker__getGlobalModuleList +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerList +#define SOAP_TYPE_AL_albroker__getBrokerList (61) +/* albroker:getBrokerList */ +struct albroker__getBrokerList +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__registerBrokerResponse +#define SOAP_TYPE_AL_albroker__registerBrokerResponse (64) +/* albroker:registerBrokerResponse */ +struct albroker__registerBrokerResponse +{ +public: + int _unused; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__registerBroker +#define SOAP_TYPE_AL_albroker__registerBroker (65) +/* albroker:registerBroker */ +struct albroker__registerBroker +{ +public: + al__ALModuleInfo _pBrokerToRegister; /* required element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__unregisterBrokerResponse +#define SOAP_TYPE_AL_albroker__unregisterBrokerResponse (67) +/* albroker:unregisterBrokerResponse */ +struct albroker__unregisterBrokerResponse +{ +public: + int _unused; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__unregisterBroker +#define SOAP_TYPE_AL_albroker__unregisterBroker (68) +/* albroker:unregisterBroker */ +struct albroker__unregisterBroker +{ +public: + al__ALModuleInfo _pBrokerToUnregister; /* required element of type al:ALModuleInfo */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__unregisterModuleReference +#define SOAP_TYPE_AL_albroker__unregisterModuleReference (70) +/* albroker:unregisterModuleReference */ +struct albroker__unregisterModuleReference +{ +public: + std::string _moduleName; /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerInfo +#define SOAP_TYPE_AL_albroker__getBrokerInfo (73) +/* albroker:getBrokerInfo */ +struct albroker__getBrokerInfo +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__exit +#define SOAP_TYPE_AL_albroker__exit (75) +/* albroker:exit */ +struct albroker__exit +{ +#ifdef WITH_NOEMPTYSTRUCT +private: + char dummy; /* dummy member to enable compilation */ +#endif +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getMethodListResponse +#define SOAP_TYPE_AL_albroker__getMethodListResponse (83) +/* albroker:getMethodListResponse */ +struct albroker__getMethodListResponse +{ +public: + std::vector_pMethodListName; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getMethodList +#define SOAP_TYPE_AL_albroker__getMethodList (84) +/* albroker:getMethodList */ +struct albroker__getMethodList +{ +public: + std::string _pModuleName; /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__initResponse +#define SOAP_TYPE_AL_albroker__initResponse (89) +/* albroker:initResponse */ +struct albroker__initResponse +{ +public: + int *_unused; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* optional element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__init +#define SOAP_TYPE_AL_albroker__init (90) +/* albroker:init */ +struct albroker__init +{ +public: + std::string _pBrokerName; /* required element of type xsd:string */ + std::string _pIP; /* required element of type xsd:string */ + int _pPort; /* required element of type xsd:int */ + std::string _pParentBrokerIP; /* required element of type xsd:string */ + int _pParentBrokerPort; /* required element of type xsd:int */ + bool _pKeepAlive; /* required element of type xsd:bool */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__versionResponse +#define SOAP_TYPE_AL_albroker__versionResponse (93) +/* albroker:versionResponse */ +struct albroker__versionResponse +{ +public: + std::string _pVersion; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__version +#define SOAP_TYPE_AL_albroker__version (94) +/* albroker:version */ +struct albroker__version +{ +#ifdef WITH_NOEMPTYSTRUCT +private: + char dummy; /* dummy member to enable compilation */ +#endif +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__sendBackIPResponse +#define SOAP_TYPE_AL_albroker__sendBackIPResponse (96) +/* albroker:sendBackIPResponse */ +struct albroker__sendBackIPResponse +{ +public: + std::string pIP; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__sendBackIP +#define SOAP_TYPE_AL_albroker__sendBackIP (97) +/* albroker:sendBackIP */ +struct albroker__sendBackIP +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerNameResponse +#define SOAP_TYPE_AL_albroker__getBrokerNameResponse (99) +/* albroker:getBrokerNameResponse */ +struct albroker__getBrokerNameResponse +{ +public: + std::string _pBrokerName; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getBrokerName +#define SOAP_TYPE_AL_albroker__getBrokerName (100) +/* albroker:getBrokerName */ +struct albroker__getBrokerName +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getInfo +#define SOAP_TYPE_AL_albroker__getInfo (103) +/* albroker:getInfo */ +struct albroker__getInfo +{ +public: + std::string _pModuleName; /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__stopTaskResponse +#define SOAP_TYPE_AL_albroker__stopTaskResponse (105) +/* albroker:stopTaskResponse */ +struct albroker__stopTaskResponse +{ +public: + int _num; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__stopTask +#define SOAP_TYPE_AL_albroker__stopTask (106) +/* albroker:stopTask */ +struct albroker__stopTask +{ +public: + int _id; /* required element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__stopTaskNameResponse +#define SOAP_TYPE_AL_albroker__stopTaskNameResponse (108) +/* albroker:stopTaskNameResponse */ +struct albroker__stopTaskNameResponse +{ +public: + int _num; /* SOAP 1.2 RPC return element (when namespace qualified) */ /* required element of type xsd:int */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__stopTaskName +#define SOAP_TYPE_AL_albroker__stopTaskName (109) +/* albroker:stopTaskName */ +struct albroker__stopTaskName +{ +public: + std::string _name; /* required element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_albroker__getDebugTaskList +#define SOAP_TYPE_AL_albroker__getDebugTaskList (112) +/* albroker:getDebugTaskList */ +struct albroker__getDebugTaskList +{ +public: + void *_; /* transient */ +}; +#endif + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Header +#define SOAP_TYPE_AL_SOAP_ENV__Header (113) +/* SOAP Header: */ +struct SOAP_ENV__Header +{ +#ifdef WITH_NOEMPTYSTRUCT +private: + char dummy; /* dummy member to enable compilation */ +#endif +}; +#endif + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Code +#define SOAP_TYPE_AL_SOAP_ENV__Code (114) +/* SOAP Fault Code: */ +struct SOAP_ENV__Code +{ +public: + char *SOAP_ENV__Value; /* optional element of type xsd:QName */ + struct SOAP_ENV__Code *SOAP_ENV__Subcode; /* optional element of type SOAP-ENV:Code */ +}; +#endif + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Detail +#define SOAP_TYPE_AL_SOAP_ENV__Detail (116) +/* SOAP-ENV:Detail */ +struct SOAP_ENV__Detail +{ +public: + int __type; /* any type of element (defined below) */ + void *fault; /* transient */ + char *__any; +}; +#endif + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Reason +#define SOAP_TYPE_AL_SOAP_ENV__Reason (117) +/* SOAP-ENV:Reason */ +struct SOAP_ENV__Reason +{ +public: + char *SOAP_ENV__Text; /* optional element of type xsd:string */ +}; +#endif + +#ifndef SOAP_TYPE_AL_SOAP_ENV__Fault +#define SOAP_TYPE_AL_SOAP_ENV__Fault (118) +/* SOAP Fault: */ +struct SOAP_ENV__Fault +{ +public: + char *faultcode; /* optional element of type xsd:QName */ + char *faultstring; /* optional element of type xsd:string */ + char *faultactor; /* optional element of type xsd:string */ + struct SOAP_ENV__Detail *detail; /* optional element of type SOAP-ENV:Detail */ + struct SOAP_ENV__Code *SOAP_ENV__Code; /* optional element of type SOAP-ENV:Code */ + struct SOAP_ENV__Reason *SOAP_ENV__Reason; /* optional element of type SOAP-ENV:Reason */ + char *SOAP_ENV__Node; /* optional element of type xsd:string */ + char *SOAP_ENV__Role; /* optional element of type xsd:string */ + struct SOAP_ENV__Detail *SOAP_ENV__Detail; /* optional element of type SOAP-ENV:Detail */ +}; +#endif + +/******************************************************************************\ + * * + * Types with Custom Serializers * + * * +\******************************************************************************/ + +#ifndef SOAP_TYPE_AL_xsd__anyType +#define SOAP_TYPE_AL_xsd__anyType (21) +typedef ALValue xsd__anyType; +#endif + +/******************************************************************************\ + * * + * Typedefs * + * * +\******************************************************************************/ + +#ifndef SOAP_TYPE_AL__QName +#define SOAP_TYPE_AL__QName (5) +typedef char *_QName; +#endif + +#ifndef SOAP_TYPE_AL__XML +#define SOAP_TYPE_AL__XML (6) +typedef char *_XML; +#endif + +#ifndef SOAP_TYPE_AL_xsd__string +#define SOAP_TYPE_AL_xsd__string (10) +typedef std::string xsd__string; +#endif + +#ifndef SOAP_TYPE_AL_xsd__int +#define SOAP_TYPE_AL_xsd__int (11) +typedef int xsd__int; +#endif + +#ifndef SOAP_TYPE_AL_xsd__bool +#define SOAP_TYPE_AL_xsd__bool (13) +typedef bool xsd__bool; +#endif + +#ifndef SOAP_TYPE_AL_xsd__double +#define SOAP_TYPE_AL_xsd__double (15) +typedef double xsd__double; +#endif + +#ifndef SOAP_TYPE_AL_xsd__float +#define SOAP_TYPE_AL_xsd__float (17) +typedef float xsd__float; +#endif + + +/******************************************************************************\ + * * + * Typedef Synonyms * + * * +\******************************************************************************/ + + +/******************************************************************************\ + * * + * Externals * + * * +\******************************************************************************/ + + +/******************************************************************************\ + * * + * Service Operations * + * * +\******************************************************************************/ + + +SOAP_FMAC5 int SOAP_FMAC6 albroker__callNaoqi(struct soap*, std::string _mod, std::string _meth, ALValue _p, struct albroker__callNaoqiResponse &_r); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__callNaoqi2(struct soap*, std::string _mod, std::string _meth, ALValue _p, struct albroker__callNaoqi2Response &_r); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__pCallNaoqiN(struct soap*, std::string _nIP, int _nPort, std::string _nMod, std::string _nMeth, std::string _mod, std::string _meth, ALValue _p, struct albroker__pCallNaoqiNResponse &_r); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__pCallNaoqi(struct soap*, std::string _mod, std::string _meth, ALValue _p); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getModuleByName(struct soap*, std::string _pModuleName, struct albroker__getModuleByNameResponse &_pModInfo); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__exploreToGetModuleByName(struct soap*, std::string _pModuleName, bool _pSearchUp, bool _pSearchDown, std::string _pDontLookIntoBrokerName, bool _pLoadLib, struct albroker__exploreToGetModuleByNameResponse &_pModInfo); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getModuleList(struct soap*, void *_, struct albroker__getModuleListResponse &_pModuleList); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getGlobalModuleList(struct soap*, void *_, struct albroker__getGlobalModuleListResponse &_pModuleList); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getBrokerList(struct soap*, void *_, struct albroker__getBrokerListResponse &_pBrokerList); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__registerBroker(struct soap*, al__ALModuleInfo _pBrokerToRegister, int &_unused); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__unregisterBroker(struct soap*, al__ALModuleInfo _pBrokerToUnregister, int &_unused); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__unregisterModuleReference(struct soap*, std::string _moduleName); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getBrokerInfo(struct soap*, void *_, struct albroker__getBrokerInfoResponse &_getBrokerInfoResponse); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__exit(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getMethodList(struct soap*, std::string _pModuleName, std::vector&_pMethodListName); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__init(struct soap*, std::string _pBrokerName, std::string _pIP, int _pPort, std::string _pParentBrokerIP, int _pParentBrokerPort, bool _pKeepAlive, int *_unused); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__version(struct soap*, std::string &_pVersion); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__sendBackIP(struct soap*, void *_, std::string &pIP); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getBrokerName(struct soap*, void *_, std::string &_pBrokerName); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getInfo(struct soap*, std::string _pModuleName, al__ALModuleInfo &_pModuleInfo); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__stopTask(struct soap*, int _id, int &_num); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__stopTaskName(struct soap*, std::string _name, int &_num); + +SOAP_FMAC5 int SOAP_FMAC6 albroker__getDebugTaskList(struct soap*, void *_, struct albroker__getDebugTaskListResponse &_r); + +/******************************************************************************\ + * * + * Stubs * + * * +\******************************************************************************/ + + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__callNaoqi(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _mod, std::string _meth, ALValue _p, struct albroker__callNaoqiResponse &_r); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__callNaoqi2(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _mod, std::string _meth, ALValue _p, struct albroker__callNaoqi2Response &_r); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__pCallNaoqiN(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _nIP, int _nPort, std::string _nMod, std::string _nMeth, std::string _mod, std::string _meth, ALValue _p, struct albroker__pCallNaoqiNResponse &_r); + +SOAP_FMAC5 int SOAP_FMAC6 soap_send_albroker__pCallNaoqi(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _mod, std::string _meth, ALValue _p); + +SOAP_FMAC5 int SOAP_FMAC6 soap_recv_albroker__pCallNaoqi(struct soap *soap, struct albroker__pCallNaoqi *_param_1); + + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getModuleByName(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _pModuleName, struct albroker__getModuleByNameResponse &_pModInfo); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__exploreToGetModuleByName(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _pModuleName, bool _pSearchUp, bool _pSearchDown, std::string _pDontLookIntoBrokerName, bool _pLoadLib, struct albroker__exploreToGetModuleByNameResponse &_pModInfo); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getModuleList(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, struct albroker__getModuleListResponse &_pModuleList); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getGlobalModuleList(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, struct albroker__getGlobalModuleListResponse &_pModuleList); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getBrokerList(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, struct albroker__getBrokerListResponse &_pBrokerList); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__registerBroker(struct soap *soap, const char *soap_endpoint, const char *soap_action, al__ALModuleInfo _pBrokerToRegister, int &_unused); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__unregisterBroker(struct soap *soap, const char *soap_endpoint, const char *soap_action, al__ALModuleInfo _pBrokerToUnregister, int &_unused); + +SOAP_FMAC5 int SOAP_FMAC6 soap_send_albroker__unregisterModuleReference(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _moduleName); + +SOAP_FMAC5 int SOAP_FMAC6 soap_recv_albroker__unregisterModuleReference(struct soap *soap, struct albroker__unregisterModuleReference *_param_2); + + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getBrokerInfo(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, struct albroker__getBrokerInfoResponse &_getBrokerInfoResponse); + +SOAP_FMAC5 int SOAP_FMAC6 soap_send_albroker__exit(struct soap *soap, const char *soap_endpoint, const char *soap_action); + +SOAP_FMAC5 int SOAP_FMAC6 soap_recv_albroker__exit(struct soap *soap, struct albroker__exit *_); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getMethodList(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _pModuleName, std::vector&_pMethodListName); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__init(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _pBrokerName, std::string _pIP, int _pPort, std::string _pParentBrokerIP, int _pParentBrokerPort, bool _pKeepAlive, int *_unused); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__version(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string &_pVersion); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__sendBackIP(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, std::string &pIP); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getBrokerName(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, std::string &_pBrokerName); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getInfo(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _pModuleName, al__ALModuleInfo &_pModuleInfo); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__stopTask(struct soap *soap, const char *soap_endpoint, const char *soap_action, int _id, int &_num); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__stopTaskName(struct soap *soap, const char *soap_endpoint, const char *soap_action, std::string _name, int &_num); + +SOAP_FMAC5 int SOAP_FMAC6 soap_call_albroker__getDebugTaskList(struct soap *soap, const char *soap_endpoint, const char *soap_action, void *_, struct albroker__getDebugTaskListResponse &_r); + +/******************************************************************************\ + * * + * Skeletons * + * * +\******************************************************************************/ + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_request(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__callNaoqi(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__callNaoqi2(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__pCallNaoqiN(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__pCallNaoqi(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getModuleByName(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__exploreToGetModuleByName(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getModuleList(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getGlobalModuleList(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getBrokerList(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__registerBroker(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__unregisterBroker(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__unregisterModuleReference(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getBrokerInfo(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__exit(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getMethodList(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__init(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__version(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__sendBackIP(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getBrokerName(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getInfo(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__stopTask(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__stopTaskName(struct soap*); + +SOAP_FMAC5 int SOAP_FMAC6 soap_serve_albroker__getDebugTaskList(struct soap*); + +} // namespace AL + + +#endif + +/* End of ALStub.h */ diff --git a/naoModule/libnaoqi_files/include/alsoap/soapdefs.h b/naoModule/libnaoqi_files/include/alsoap/soapdefs.h new file mode 100755 index 0000000..abf84f5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alsoap/soapdefs.h @@ -0,0 +1,26 @@ +/** + * @author Jerome Monceaux + * Copyright (c) Aldebaran Robotics 2007 All Rights Reserved + * + */ +/* +#ifndef WITH_LEAN +#define WITH_LEAN +#endif + +#ifndef WITH_LEANER +#define WITH_LEANER +#endif +*/ +//#define WITH_NONAMESPACES +//#define WITH_NOHTTP +// #undef WITH_DOM +#ifndef SOAP_BUFLEN +#define SOAP_BUFLEN 65536 +#endif +//# define WITH_IPV6 +//#define WITH_LEANER +#ifndef WITH_NOIDREF +#define WITH_NOIDREF +#endif +//#define SOAP_DEBUG diff --git a/naoModule/libnaoqi_files/include/alsoap/stdsoap2.h b/naoModule/libnaoqi_files/include/alsoap/stdsoap2.h new file mode 100755 index 0000000..4df049d --- /dev/null +++ b/naoModule/libnaoqi_files/include/alsoap/stdsoap2.h @@ -0,0 +1,2327 @@ +/* + stdsoap2.h 2.7.12 + + gSOAP runtime engine + +gSOAP XML Web services tools +Copyright (C) 2000-2008, Robert van Engelen, Genivia Inc., All Rights Reserved. +This part of the software is released under ONE of the following licenses: +GPL, or the gSOAP public license, or Genivia's license for commercial use. +-------------------------------------------------------------------------------- +Contributors: + +Wind River Systems, Inc., for the following additions + - vxWorks compatible +-------------------------------------------------------------------------------- +gSOAP public license. + +The contents of this file are subject to the gSOAP Public License Version 1.3 +(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.cs.fsu.edu/~engelen/soaplicense.html +Software distributed under the License is distributed on an "AS IS" basis, +WITHOUT WARRANTY OF ANY KIND, either express or implied. See the License +for the specific language governing rights and limitations under the License. + +The Initial Developer of the Original Code is Robert A. van Engelen. +Copyright (C) 2000-2008, Robert van Engelen, Genivia Inc., All Rights Reserved. +-------------------------------------------------------------------------------- +GPL license. + +This program is free software; you can redistribute it and/or modify it under +the terms of the GNU General Public License as published by the Free Software +Foundation; either version 2 of the License, or (at your option) any later +version. + +This program is distributed in the hope that it will be useful, but WITHOUT ANY +WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A +PARTICULAR PURPOSE. See the GNU General Public License for more details. + +You should have received a copy of the GNU General Public License along with +this program; if not, write to the Free Software Foundation, Inc., 59 Temple +Place, Suite 330, Boston, MA 02111-1307 USA + +Author contact information: +engelen@genivia.com / engelen@acm.org + +This program is released under the GPL with the additional exemption that +compiling, linking, and/or using OpenSSL is allowed. +-------------------------------------------------------------------------------- +A commercial use license is available from Genivia, Inc., contact@genivia.com +-------------------------------------------------------------------------------- +*/ +#ifndef STDSOAP2_H +#define STDSOAP2_H + +#ifdef WITH_SOAPDEFS_H +# include "soapdefs.h" /* include user-defined stuff */ +#endif + +#ifndef _THREAD_SAFE +# define _THREAD_SAFE +#endif + +#ifndef OPENSERVER +# ifndef _REENTRANT +# define _REENTRANT +# endif +#endif + +#ifndef SOAP_FMAC1 /* stdsoap2.h declaration macro */ +# define SOAP_FMAC1 +#endif + +#ifndef SOAP_FMAC2 /* stdsoap2.h declaration macro */ +# define SOAP_FMAC2 +#endif + +#ifndef SOAP_FMAC3 /* (de)serializer declaration macro */ +# define SOAP_FMAC3 +#endif + +#ifndef SOAP_FMAC3S /* string converter for (de)serializer declaration macro */ +# define SOAP_FMAC3S SOAP_FMAC3 +#endif + +#ifndef SOAP_FMAC4 /* (de)serializer declaration macro */ +# define SOAP_FMAC4 +#endif + +#ifndef SOAP_FMAC4S /* string converter for (de)serializer declaration macro */ +# define SOAP_FMAC4S SOAP_FMAC4 +#endif + +#ifndef SOAP_FMAC5 /* stub/skeleton declaration macro */ +# define SOAP_FMAC5 +#endif + +#ifndef SOAP_FMAC6 /* stub/skeleton declaration macro */ +# define SOAP_FMAC6 +#endif + +#ifndef SOAP_CMAC /* class declaration macro */ +# define SOAP_CMAC +#endif + +#ifndef SOAP_NMAC /* namespace table declaration macro */ +# define SOAP_NMAC +#endif + +#ifndef SOAP_SOURCE_STAMP +# define SOAP_SOURCE_STAMP(str) +#endif + +/* gSOAP 2.7.4 and higher: fast look-aside buffering is stable */ +#ifndef WITH_FAST +# define WITH_FAST +#endif + +#ifdef WITH_LEANER +# ifndef WITH_LEAN +# define WITH_LEAN +# endif +#endif + +#ifdef WITH_LEAN +# ifdef WITH_COOKIES +# error "Cannot build WITH_LEAN code WITH_COOKIES enabled" +# endif +#endif + +#ifndef STDSOAP_H +#define STDSOAP_H + +#if defined(__vxworks) || defined(__VXWORKS__) +# define VXWORKS +#endif + +#ifdef _WIN32 +# ifndef WIN32 +# define WIN32 +# endif +#endif + +#ifdef _WIN32_WCE +# ifndef UNDER_CE +# define UNDER_CE _WIN32_WCE +# endif +#endif + +#ifdef UNDER_CE +# ifndef WIN32 +# define WIN32 +# endif +#endif + +#ifdef __BORLANDC__ +# ifdef __WIN32__ +# ifndef WIN32 +# define WIN32 +# endif +# endif +#endif + +#ifdef __CYGWIN__ +# ifndef CYGWIN +# define CYGWIN +# endif +#endif + +#ifdef __SYMBIAN32__ +# define SYMBIAN +# undef WIN32 +#endif + +#if defined(__palmos__) || defined(PALM_GCC) || defined(__PALMOS_TRAPS__) +# ifndef PALM +# define PALM +# endif +#endif + +#if defined(__hpux) +# ifndef HP_UX +# define HP_UX +# endif +#endif + +#if defined(__digital__) && defined(__unix__) +# ifndef TRU64 +# define TRU64 +# endif +#endif + +#ifdef __MVS__ +# ifndef OS390 +# define OS390 +# endif +#endif + +#ifdef HAVE_CONFIG_H + +# if defined(WITH_OPENSSL) +# ifndef HAVE_OPENSSL_SSL_H +# undef WITH_OPENSSL +# endif +# endif +# if defined(WITH_ZLIB) || defined(WITH_GZIP) +# ifndef HAVE_ZLIB_H +# undef WITH_ZLIB +# undef WITH_GZIP +# endif +# endif +#else +# if defined(UNDER_CE) +# define WITH_LEAN +# define HAVE_SSCANF +# elif defined(WIN32) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# define SOAP_LONG_FORMAT "%I64d" +# define SOAP_ULONG_FORMAT "%I64u" +# elif defined(CYGWIN) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(__APPLE__) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOD_L +# define HAVE_SSCANF_L +# define HAVE_SPRINTF_L +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_TIMEGM +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(_AIX43) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(_AIX41) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(HP_UX) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(FREEBSD) || defined(__FreeBSD__) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOD_L +# define HAVE_SSCANF_L +# define HAVE_SPRINTF_L +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_STRTOLL +# define HAVE_STRTOULL +# define HAVE_GETTIMEOFDAY +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# define SOAP_LONG_FORMAT "%qd" +# define SOAP_ULONG_FORMAT "%qu" +# elif defined(__VMS) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(__GLIBC__) || defined(__GNU__) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOD_L +# define HAVE_SSCANF_L +# define HAVE_SPRINTF_L +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_STRTOLL +# define HAVE_STRTOULL +# define HAVE_SYS_TIMEB_H +#ifndef HAVE_FTIME +# define HAVE_FTIME +#endif +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +#ifndef HAVE_TIMEGM +# define HAVE_TIMEGM +#endif +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# define HAVE_ISNAN +# elif defined(TRU64) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_GETTIMEOFDAY +# define HAVE_SYS_TIMEB_H +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define __USE_STD_IOSTREAM +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# define SOAP_LONG_FORMAT "%ld" +# define SOAP_ULONG_FORMAT "%lu" +# elif defined(MAC_CARBON) +# define WITH_NOIO +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOD_L +# define HAVE_SSCANF_L +# define HAVE_SPRINTF_L +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GETHOSTBYNAME_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(PALM) +# define WITH_LEAN +# define HAVE_STRTOD /* strtod() is defined in palmFunctions.h */ +# include /* Needs to be included before unix headers */ +# include +# define IGNORE_STDIO_STUBS +# include +# define O_NONBLOCK FNONBIO +# include +# include "palmFunctions.h" +# elif defined(SYMBIAN) +# define WITH_LEAN +# define WITH_NONAMESPACES +# define HAVE_STRTOD /* use STRTOD since sscanf doesn't seem to work */ +# include +# include +# elif defined(VXWORKS) +# ifdef _WRS_KERNEL +# define _POSIX_THREADS 1 +# endif +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_GMTIME +# define HAVE_LOCALTIME +# define HAVE_MKTIME +# elif defined(OS390) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(AS400) +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# elif defined(__QNX__) || defined(QNX) +/* QNX does not have a working version of strtof */ +# undef HAVE_STRTOF +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GETHOSTBYNAME_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +# define HAVE_WCTOMB +# define HAVE_MBTOWC +# define LONG64 long +# define ULONG64 unsigned LONG64 +# define SOAP_LONG_FORMAT "%ld" +# define SOAP_ULONG_FORMAT "%lu" +# else +/* Default asumptions on supported functions */ +# define HAVE_STRRCHR +# define HAVE_STRTOD +# define HAVE_SSCANF +# define HAVE_STRTOL +# define HAVE_STRTOUL +# define HAVE_SYS_TIMEB_H +# define HAVE_FTIME +# define HAVE_RAND_R +# define HAVE_GETHOSTBYNAME_R +# define HAVE_GMTIME_R +# define HAVE_LOCALTIME_R +#ifndef ANDROID +# define HAVE_WCTOMB +# define HAVE_MBTOWC +#endif +# endif +#endif + +/* native Win and HP-UX compilers don't like empty structs */ +#if defined(WIN32) || defined(HP_UX) +# define WITH_NOEMPTYSTRUCT +#endif + +#ifdef HP_UX +# undef HAVE_STRTOLL +# undef HAVE_STRTOULL +#endif + +#ifdef WITH_C_LOCALE +# include +#else +# undef HAVE_STRTOF_L +# undef HAVE_STRTOD_L +# undef HAVE_SSCANF_L +# undef HAVE_SPRINTF_L +#endif + +#ifndef WITH_NOSTDLIB +# include +# ifndef PALM +# include +# include +# endif +# include +# include +#endif + +#if defined(__cplusplus) && !defined(WITH_LEAN) && !defined(WITH_COMPAT) +# include +# include +#endif + +#ifdef WITH_NOHTTP +# ifndef WITH_NOIO +# define WITH_NOIO +# undef WITH_COOKIES +# endif +#endif + +/* Suggestion when SOAP_FD_EXCEEDED error occurs: + Some systems allow increasing FD_SETSIZE before including sys/types.h: +#define FD_SETSIZE (2048) +*/ + +#ifndef UNDER_CE +# ifndef PALM +# ifndef WITH_NOIO +# include +# include +# endif +# ifndef WITH_LEAN +# ifdef HAVE_SYS_TIMEB_H +# include /* for ftime() */ +# endif +# include +# endif +# endif +#endif + +#ifdef OPENSERVER +# include +# include +# include + extern int h_errno; +#endif + +#ifndef WITH_NOIO +# ifndef WIN32 +# ifndef PALM +# include +# ifdef VXWORKS +# include +# include +# ifndef _WRS_KERNEL +# include +# endif +# else +# ifndef SYMBIAN +# include +# endif +# endif +# ifdef SUN_OS +# include /* SUN */ +# include /* SUN < 2.8 (?) */ +# endif +# ifdef VXWORKS +# ifdef _WRS_KERNEL +# include +# endif +# else +# include +# endif +# include +# ifdef OS390 +# include +# else +# include /* TCP_NODELAY */ +# endif +# include +# endif +# endif +#endif + +#ifdef WIN32 +# define SOAP_WINSOCKINT int +#else +# define SOAP_WINSOCKINT size_t +#endif + +#ifdef WIN32 +# ifndef UNDER_CE +# include +# include +# endif +# ifdef WITH_IPV6 +# include /* Visual Studio 2005 users: you must install the Platform SDK (R2) */ +# include +# include +# define SOAP_GAI_STRERROR gai_strerrorA +# else +/*# include Visual Studio 2005 users: you must install the Platform SDK (R2) */ +# include /* Alternative: use winsock2 (not available with eVC) */ +# endif +#else +# ifdef VXWORKS +# include +# include +# include +# endif +# ifndef WITH_NOIO +# ifndef PALM +# include +# include +# include +# include +# ifdef _AIX41 +# include +# endif +# endif +# endif +#endif + +#ifdef WITH_FASTCGI +# include +#endif + +#ifdef WITH_OPENSSL +# define OPENSSL_NO_KRB5 +# include +# include +# include +# include +# include +# ifndef ALLOW_OLD_VERSIONS +# if (OPENSSL_VERSION_NUMBER < 0x00905100L) +# error "Must use OpenSSL 0.9.6 or later" +# endif +# endif +#endif + +#ifdef WITH_GZIP +# ifndef WITH_ZLIB +# define WITH_ZLIB +# endif +#endif + +#ifdef WITH_CASEINSENSITIVETAGS +# define SOAP_STRCMP soap_tag_cmp /* case insensitve XML element/attribute names */ +#else +# define SOAP_STRCMP strcmp /* case sensitive XML element/attribute names */ +#endif + +#ifdef WITH_ZLIB +# include +#endif + +#ifndef WITH_NOSTDLIB +# ifndef PALM +# include /* for isnan() */ +# endif +#endif + +/* #define DEBUG */ /* Uncomment to debug sending (in file SENT.log) receiving (in file RECV.log) and messages (in file TEST.log) */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Portability: define SOAP_SOCKLEN_T */ +#if defined(_AIX) +# if defined(_AIX43) +# define SOAP_SOCKLEN_T socklen_t +# else +# define SOAP_SOCKLEN_T int +# endif +#elif defined(SOCKLEN_T) +# define SOAP_SOCKLEN_T SOCKLEN_T +#elif defined(__socklen_t_defined) || defined(_SOCKLEN_T) || defined(CYGWIN) || defined(FREEBSD) || defined(__FreeBSD__) || defined(__QNX__) || defined(QNX) || defined(OS390) || defined(ANDROID) +# define SOAP_SOCKLEN_T socklen_t +#elif defined(IRIX) || defined(WIN32) || defined(__APPLE__) || defined(HP_UX) || defined(SUN_OS) || defined(OPENSERVER) || defined(TRU64) || defined(VXWORKS) +# define SOAP_SOCKLEN_T int +#else +# define SOAP_SOCKLEN_T size_t +#endif + +#ifndef SOAP_SOCKET +# ifdef WIN32 +# define SOAP_SOCKET SOCKET +# define soap_closesocket(n) closesocket(n) +# else +# define SOAP_SOCKET int +# define soap_closesocket(n) close(n) +# endif +#endif + +#define SOAP_INVALID_SOCKET ((SOAP_SOCKET)-1) +#define soap_valid_socket(n) ((n) != SOAP_INVALID_SOCKET) + +#ifndef SOAP_GAI_STRERROR +# define SOAP_GAI_STRERROR gai_strerror +#endif + +#ifndef FD_SETSIZE +# define FD_SETSIZE (1024) +#endif + +#if defined(SYMBIAN) +# define LONG64 long +# define ULONG64 unsigned LONG64 +#elif !defined(WIN32) || defined(CYGWIN) || defined(__GLIBC__) || defined(__GNU__) +# ifndef LONG64 +# if defined(HAVE_STDINT_H) +# include +# define LONG64 int64_t +# define ULONG64 uint64_t +# elif defined(__GLIBC__) +# include +# if (__WORDSIZE == 64) +# define LONG64 int64_t +# define ULONG64 uint64_t +# ifndef SOAP_LONG_FORMAT +# define SOAP_LONG_FORMAT "%ld" +# endif +# ifndef SOAP_ULONG_FORMAT +# define SOAP_ULONG_FORMAT "%lu" +# endif +# else +# define LONG64 long long +# define ULONG64 unsigned LONG64 +# endif +# else +# define LONG64 long long +# define ULONG64 unsigned LONG64 +# endif +# endif +#elif defined(UNDER_CE) +# define LONG64 __int64 +# define ULONG64 unsigned LONG64 +#elif defined(__BORLANDC__) +# define LONG64 __int64 +# define ULONG64 unsigned LONG64 +#endif + +#ifndef SOAP_LONG_FORMAT +# define SOAP_LONG_FORMAT "%lld" /* printf format for 64 bit ints */ +#endif + +#ifndef SOAP_ULONG_FORMAT +# define SOAP_ULONG_FORMAT "%llu" /* printf format for unsigned 64 bit ints */ +#endif + +#if defined(WIN32) && !defined(CYGWIN) +# define soap_int32 __int32 +#elif defined(SYMBIAN) +# define soap_int32 long +#elif defined(PALM) +# define soap_int32 Int32 +#elif defined(_AIX) +# if defined(_AIX43) +# define soap_int32 int32_t +# else +# define soap_int32 signed int +# endif +#else +# define soap_int32 int32_t +#endif + +#ifdef WIN32 +# define SOAP_ERANGE ERANGE +# define SOAP_EINTR WSAEINTR +# define SOAP_EAGAIN WSAEWOULDBLOCK +# define SOAP_EWOULDBLOCK WSAEWOULDBLOCK +# define SOAP_EINPROGRESS WSAEINPROGRESS +# define SOAP_EADDRINUSE WSAEADDRINUSE +#else +# define SOAP_ERANGE ERANGE +# define SOAP_EINTR EINTR +# define SOAP_EAGAIN EAGAIN +# define SOAP_EADDRINUSE EADDRINUSE +# ifdef SYMBIAN +# define SOAP_EWOULDBLOCK 9898 +# define SOAP_EINPROGRESS 9899 +# else +# define SOAP_EWOULDBLOCK EWOULDBLOCK +# define SOAP_EINPROGRESS EINPROGRESS +# endif +#endif + +#ifdef WIN32 +# ifdef UNDER_CE +# define soap_errno GetLastError() +# define soap_socket_errno(s) GetLastError() +# define soap_reset_errno SetLastError(0) +# else +# define soap_errno GetLastError() +# define soap_socket_errno(s) WSAGetLastError() +# define soap_reset_errno SetLastError(0) +# endif +#else +# ifndef WITH_NOIO +# define soap_errno errno +# define soap_socket_errno(s) errno +# define soap_reset_errno (errno = 0) +# else +# define soap_errno 0 +# define soap_socket_errno(s) 0 +# define soap_reset_errno +# endif +#endif + +#ifndef SOAP_BUFLEN +# ifndef WITH_LEAN +# define SOAP_BUFLEN (65536) /* buffer length for socket packets, also used by gethostbyname_r and UDP messages, so don't make this too small */ +# else +# define SOAP_BUFLEN (2048) +# endif +#endif +#ifndef SOAP_LABLEN +# define SOAP_LABLEN (256) /* initial look-aside buffer length */ +#endif +#ifndef SOAP_PTRBLK +# define SOAP_PTRBLK (32) /* block allocation for pointer hash table chains */ +#endif +#ifndef SOAP_PTRHASH +# ifndef WITH_LEAN +# define SOAP_PTRHASH (1024) /* size of pointer analysis hash table (must be power of 2) */ +# else +# define SOAP_PTRHASH (32) +# endif +#endif +#ifndef SOAP_IDHASH +# ifndef WITH_LEAN +# define SOAP_IDHASH (1999) /* prime size of hash table for parsed id/ref */ +# else +# define SOAP_IDHASH (19) /* 19, 199 */ +# endif +#endif +#ifndef SOAP_BLKLEN +# ifndef WITH_LEAN +# define SOAP_BLKLEN (256) /* size of blocks to collect long strings and XML attributes */ +# else +# define SOAP_BLKLEN (32) +# endif +#endif +#ifndef SOAP_TAGLEN +# ifndef WITH_LEAN +# define SOAP_TAGLEN (1024) /* maximum length of XML element tag/attribute name or host/path name + 1 */ +# else +# define SOAP_TAGLEN (64) +# endif +#endif +#ifndef SOAP_HDRLEN +# ifndef WITH_LEAN +# define SOAP_HDRLEN (8192) /* maximum length of HTTP header line (must be >4096 to read cookies) */ +# else +# define SOAP_HDRLEN (1024) +# endif +#endif +#ifndef SOAP_MAXDIMS +# ifndef WITH_LEAN +# define SOAP_MAXDIMS (16) /* maximum array dimensions (array nestings) must be less than 64 to protect soap->tmpbuf */ +# else +# define SOAP_MAXDIMS (4) +# endif +#endif + +#ifndef SOAP_MAXLOGS +# define SOAP_MAXLOGS (3) /* max number of debug logs per struct soap environment */ +# define SOAP_INDEX_RECV (0) +# define SOAP_INDEX_SENT (1) +# define SOAP_INDEX_TEST (2) +#endif + +/* Max iterations in soap_serve() to keep server connection alive */ +#ifndef SOAP_MAXKEEPALIVE +# define SOAP_MAXKEEPALIVE (100) +#endif + +/* Trusted max size of inbound SOAP array for compound array allocation. + Increase if necessary to allow larger arrays. +*/ +#ifndef SOAP_MAXARRAYSIZE +# define SOAP_MAXARRAYSIZE (1000000) +#endif + +#ifdef VXWORKS +# ifdef __INCmathh +# include +# ifndef HAVE_ISNAN +# define HAVE_ISNAN +# endif +# define soap_isnan(num) isNan(num) +# endif +#endif + +#ifdef WIN32 +# include +# ifndef HAVE_ISNAN +# define HAVE_ISNAN +# endif +# define soap_isnan(num) _isnan(num) +#endif + +#ifdef SUN_OS +# define HAVE_ISNAN +#endif + +#ifdef __APPLE__ +# ifdef __cplusplus +# ifndef isnan +extern "C" int isnan(double); +# endif +# endif +# define HAVE_ISNAN +#endif + +#if !defined(HAVE_ISNAN) && (defined(_MATH_H) || defined(_MATH_INCLUDED)) +# define HAVE_ISNAN +#endif + +extern const struct soap_double_nan { unsigned int n1, n2; } soap_double_nan; + +#ifdef VXWORKS +# ifndef FLT_MAX +# define FLT_MAX _ARCH_FLT_MAX +# endif +# ifndef DBL_MAX +# define DBL_MAX _ARCH_DBL_MAX +# endif +#endif + +#ifndef FLT_NAN +# define FLT_NAN (*(float*)(void*)&soap_double_nan) +#endif + +#ifndef FLT_PINFTY +# if defined(FLT_MAX) +# define FLT_PINFTY FLT_MAX +# elif defined(HUGE_VALF) +# define FLT_PINFTY (float)HUGE_VALF +# elif defined(HUGE_VAL) +# define FLT_PINFTY (float)HUGE_VAL +# elif defined(FLOAT_MAX) +# define FLT_PINFTY FLOAT_MAX +# else +# define FLT_PINFTY (3.40282347e+38F) +# endif +#endif + +#ifndef FLT_NINFTY +# define FLT_NINFTY (-FLT_PINFTY) +#endif + +#ifndef DBL_NAN +# define DBL_NAN (*(double*)(void*)&soap_double_nan) +#endif + +#ifndef DBL_PINFTY +# if defined(DBL_MAX) +# define DBL_PINFTY DBL_MAX +# elif defined(HUGE_VALF) +# define DBL_PINFTY (double)HUGE_VALF +# elif defined(HUGE_VAL) +# define DBL_PINFTY (double)HUGE_VAL +# elif defined(DOUBLE_MAX) +# define DBL_PINFTY DOUBLE_MAX +# else +# define DBL_PINFTY (1.7976931348623157e+308) +# endif +#endif + +#ifndef DBL_NINFTY +# define DBL_NINFTY (-DBL_PINFTY) +#endif + +#ifndef soap_isnan +# ifdef HAVE_ISNAN +# define soap_isnan(n) isnan(n) +# else +# define soap_isnan(n) (0) +# endif +#endif + +#define soap_ispinfd(n) ((n) >= DBL_PINFTY) +#define soap_ispinff(n) ((n) >= FLT_PINFTY) +#define soap_isninfd(n) ((n) <= DBL_NINFTY) +#define soap_isninff(n) ((n) <= FLT_NINFTY) + +/* gSOAP error codes */ + +#define SOAP_EOF EOF +#define SOAP_ERR EOF +#define SOAP_OK 0 +#define SOAP_CLI_FAULT 1 +#define SOAP_SVR_FAULT 2 +#define SOAP_TAG_MISMATCH 3 +#define SOAP_TYPE 4 +#define SOAP_SYNTAX_ERROR 5 +#define SOAP_NO_TAG 6 +#define SOAP_IOB 7 +#define SOAP_MUSTUNDERSTAND 8 +#define SOAP_NAMESPACE 9 +#define SOAP_USER_ERROR 10 +#define SOAP_FATAL_ERROR 11 +#define SOAP_FAULT 12 +#define SOAP_NO_METHOD 13 +#define SOAP_NO_DATA 14 +#define SOAP_GET_METHOD 15 +#define SOAP_PUT_METHOD 16 +#define SOAP_DEL_METHOD 17 +#define SOAP_HEAD_METHOD 18 +#define SOAP_HTTP_METHOD 19 +#define SOAP_EOM 20 +#define SOAP_MOE 21 +#define SOAP_HDR 22 +#define SOAP_NULL 23 +#define SOAP_DUPLICATE_ID 24 +#define SOAP_MISSING_ID 25 +#define SOAP_HREF 26 +#define SOAP_UDP_ERROR 27 +#define SOAP_TCP_ERROR 28 +#define SOAP_HTTP_ERROR 29 +#define SOAP_SSL_ERROR 30 +#define SOAP_ZLIB_ERROR 31 +#define SOAP_DIME_ERROR 32 +#define SOAP_DIME_HREF 33 +#define SOAP_DIME_MISMATCH 34 +#define SOAP_DIME_END 35 +#define SOAP_MIME_ERROR 36 +#define SOAP_MIME_HREF 37 +#define SOAP_MIME_END 38 +#define SOAP_VERSIONMISMATCH 39 +#define SOAP_PLUGIN_ERROR 40 +#define SOAP_DATAENCODINGUNKNOWN 41 +#define SOAP_REQUIRED 42 +#define SOAP_PROHIBITED 43 +#define SOAP_OCCURS 44 +#define SOAP_LENGTH 45 +#define SOAP_FD_EXCEEDED 46 + +#define soap_xml_error_check(e) ((e) == SOAP_TAG_MISMATCH || (e) == SOAP_NO_TAG || (e) == SOAP_SYNTAX_ERROR || (e) == SOAP_NAMESPACE || (e) == SOAP_DUPLICATE_ID || (e) == SOAP_MISSING_ID || (e) == SOAP_REQUIRED || (e) == SOAP_PROHIBITED || (e) == SOAP_OCCURS || (e) == SOAP_LENGTH || (e) == SOAP_NULL || (e) == SOAP_HREF) +#define soap_soap_error_check(e) ((e) == SOAP_CLI_FAULT || (e) == SOAP_SVR_FAULT || (e) == SOAP_VERSIONMISMATCH || (e) == SOAP_MUSTUNDERSTAND || (e) == SOAP_FAULT || (e) == SOAP_NO_METHOD) +#define soap_tcp_error_check(e) ((e) == SOAP_EOF || (e) == SOAP_TCP_ERROR) +#define soap_ssl_error_check(e) ((e) == SOAP_SSL_ERROR) +#define soap_zlib_error_check(e) ((e) == SOAP_ZLIB_ERROR) +#define soap_http_error_check(e) ((e) == SOAP_HTTP_ERROR || ((e) >= SOAP_GET_METHOD && (e) <= SOAP_HTTP_METHOD)|| (e) == SOAP_NO_DATA || ((e) >= 100 && (e) < 600)) + +/* gSOAP HTTP response status codes 100 to 599 are reserved */ + +/* Codes 600 to 999 are user definable */ + +/* Exceptional gSOAP HTTP response status codes >= 1000 */ + +#define SOAP_STOP 1000 /* No HTTP response */ +#define SOAP_FORM 1001 /* Form request/response */ +#define SOAP_HTML 1002 /* Custom HTML response */ +#define SOAP_FILE 1003 /* Custom file-based response */ + +/* gSOAP HTTP method codes */ + +#define SOAP_POST 2000 +#define SOAP_GET 2001 + +/* gSOAP DIME */ + +#define SOAP_DIME_CF 0x01 +#define SOAP_DIME_ME 0x02 +#define SOAP_DIME_MB 0x04 +#define SOAP_DIME_VERSION 0x08 /* DIME version 1 */ +#define SOAP_DIME_MEDIA 0x10 +#define SOAP_DIME_ABSURI 0x20 + +/* gSOAP ZLIB */ + +#define SOAP_ZLIB_NONE 0x00 +#define SOAP_ZLIB_DEFLATE 0x01 +#define SOAP_ZLIB_INFLATE 0x02 +#define SOAP_ZLIB_GZIP 0x02 + +/* gSOAP transport, connection, and content encoding modes */ + +typedef soap_int32 soap_mode; + +#define SOAP_IO 0x00000003 /* IO mask */ +#define SOAP_IO_FLUSH 0x00000000 /* flush output immediately, no buffering */ +#define SOAP_IO_BUFFER 0x00000001 /* buffer output in packets of size SOAP_BUFLEN */ +#define SOAP_IO_STORE 0x00000002 /* store entire output to determine length for transport */ +#define SOAP_IO_CHUNK 0x00000003 /* use HTTP chunked transfer AND buffer packets */ + +#define SOAP_IO_UDP 0x00000004 /* TCP or UDP */ + +#define SOAP_IO_LENGTH 0x00000008 /* calc message length (internal) */ +#define SOAP_IO_KEEPALIVE 0x00000010 /* keep connection alive */ + +#define SOAP_ENC_LATIN 0x00000020 /* accept iso-8859-1 encoding */ +#define SOAP_ENC_XML 0x00000040 /* plain XML encoding, no HTTP header */ +#define SOAP_ENC_DIME 0x00000080 +#define SOAP_ENC_MIME 0x00000100 +#define SOAP_ENC_MTOM 0x00000200 +#define SOAP_ENC_ZLIB 0x00000400 +#define SOAP_ENC_SSL 0x00000800 + +#define SOAP_ENC 0x00000FFF /* IO and ENC mask */ + +#define SOAP_XML_STRICT 0x00001000 /* apply strict validation */ +#define SOAP_XML_INDENT 0x00002000 /* emit indented XML */ +#define SOAP_XML_CANONICAL 0x00004000 /* EXC C14N canonical XML */ +#define SOAP_XML_TREE 0x00008000 /* emit XML tree (no id/ref) */ +#define SOAP_XML_GRAPH 0x00010000 +#define SOAP_XML_NIL 0x00020000 +#define SOAP_XML_DOM 0x00040000 +#define SOAP_XML_SEC 0x00080000 /* reserved for WS security */ + +#define SOAP_C_NOIOB 0x00100000 /* don't fault on array index out of bounds (just ignore) */ +#define SOAP_C_UTFSTRING 0x00200000 /* (de)serialize strings with UTF8 content */ +#define SOAP_C_MBSTRING 0x00400000 /* (de)serialize strings with multi-byte content */ +#define SOAP_C_NILSTRING 0x00800000 /* serialize empty strings as nil (omitted) */ + +#define SOAP_DOM_TREE 0x01000000 +#define SOAP_DOM_NODE 0x02000000 +#define SOAP_DOM_ASIS 0x04000000 + +#define SOAP_MIME_POSTCHECK 0x10000000 /* MIME flag (internal) */ + +#define SOAP_IO_DEFAULT SOAP_IO_FLUSH + +/* SSL client/server authentication settings */ + +#define SOAP_SSL_NO_AUTHENTICATION 0x00 /* for testing purposes */ +#define SOAP_SSL_REQUIRE_SERVER_AUTHENTICATION 0x01 /* client requires server to authenticate */ +#define SOAP_SSL_REQUIRE_CLIENT_AUTHENTICATION 0x02 /* server requires client to authenticate */ +#define SOAP_SSL_SKIP_HOST_CHECK 0x04 /* client does not check the common name of the host in certificate */ +#define SOAP_SSL_ALLOW_EXPIRED_CERTIFICATE 0x08 /* client does not check the expiration date of the host certificate */ +#define SOAP_SSL_NO_DEFAULT_CA_PATH 0x10 /* don't use default_verify_paths */ +#define SOAP_SSL_RSA 0x20 /* use RSA */ +#define SOAP_SSLv3 0x40 /* SSL v3 only */ +#define SOAP_TLSv1 0x80 /* TLS v1 only */ +#define SOAP_SSLv3_TLSv1 0x00 /* SSL v3 and TLS v1 support by default */ + +#define SOAP_SSL_DEFAULT (SOAP_SSL_REQUIRE_SERVER_AUTHENTICATION | SOAP_SSLv3_TLSv1) + +/* state */ + +#define SOAP_NONE 0 +#define SOAP_INIT 1 +#define SOAP_COPY 2 + +#define soap_check_state(soap) (!(soap) || ((soap)->state != SOAP_INIT && (soap)->state != SOAP_COPY)) + +/* part */ + +#define SOAP_BEGIN 0 +#define SOAP_IN_ENVELOPE 2 +#define SOAP_IN_HEADER 3 +#define SOAP_END_HEADER 4 +#define SOAP_NO_BODY 5 +#define SOAP_IN_BODY 6 +#define SOAP_END_BODY 7 +#define SOAP_END_ENVELOPE 8 +#define SOAP_END 9 +#define SOAP_BEGIN_SECURITY 10 +#define SOAP_IN_SECURITY 11 +#define SOAP_END_SECURITY 12 + +/* DEBUG macros */ + +#ifndef WITH_LEAN +# ifdef DEBUG +# ifndef SOAP_DEBUG +# define SOAP_DEBUG +# endif +# ifndef SOAP_MEM_DEBUG +# define SOAP_MEM_DEBUG +# endif +# endif +#endif + +#ifdef SOAP_MEM_DEBUG +# ifndef SOAP_MALLOC +# define SOAP_MALLOC(soap, size) soap_track_malloc(soap, __FILE__, __LINE__, size) +# endif +# ifndef SOAP_FREE +# define SOAP_FREE(soap, ptr) soap_track_free(soap, __FILE__, __LINE__, ptr) +# endif +#endif + +#ifndef SOAP_MALLOC /* use libc malloc */ +# define SOAP_MALLOC(soap, size) malloc(size) +#endif + +#ifndef SOAP_FREE /* use libc free */ +# define SOAP_FREE(soap, ptr) free(ptr) +#endif + +#ifdef SOAP_DEBUG +# ifndef SOAP_MESSAGE +# define SOAP_MESSAGE fprintf +# endif +# ifndef DBGLOG +# define DBGLOG(DBGFILE, CMD) \ +{ if (soap)\ + { if (!soap->fdebug[SOAP_INDEX_##DBGFILE])\ + soap_open_logfile((struct soap*)soap, SOAP_INDEX_##DBGFILE);\ + if (soap->fdebug[SOAP_INDEX_##DBGFILE])\ + { FILE *fdebug = soap->fdebug[SOAP_INDEX_##DBGFILE];\ + CMD;\ + fflush(fdebug);\ + }\ + }\ +} +# endif +# ifndef DBGMSG +# define DBGMSG(DBGFILE, MSG, LEN) \ +{ if (soap)\ + { if (!soap->fdebug[SOAP_INDEX_##DBGFILE])\ + soap_open_logfile((struct soap*)soap, SOAP_INDEX_##DBGFILE);\ + if (soap->fdebug[SOAP_INDEX_##DBGFILE])\ + { fwrite((MSG), 1, (LEN), soap->fdebug[SOAP_INDEX_##DBGFILE]);\ + fflush(soap->fdebug[SOAP_INDEX_##DBGFILE]);\ + }\ + }\ +} +# endif +# ifndef DBGFUN +# define DBGFUN(FNAME) DBGLOG(TEST, SOAP_MESSAGE(fdebug, "%s(%d): %s()\n", __FILE__, __LINE__, FNAME)) +# define DBGFUN1(FNAME, FMT, ARG) DBGLOG(TEST, SOAP_MESSAGE(fdebug, "%s(%d): %s("FMT")\n", __FILE__, __LINE__, FNAME, (ARG))) +# define DBGFUN2(FNAME, FMT1, ARG1, FMT2, ARG2) DBGLOG(TEST, SOAP_MESSAGE(fdebug, "%s(%d): %s("FMT1", "FMT2")\n", __FILE__, __LINE__, FNAME, (ARG1), (ARG2))) +# define DBGFUN3(FNAME, FMT1, ARG1, FMT2, ARG2, FMT3, ARG3) DBGLOG(TEST, SOAP_MESSAGE(fdebug, "%s(%d): %s("FMT1", "FMT2", "FMT3")\n", __FILE__, __LINE__, FNAME, (ARG1), (ARG2), (ARG3))) +# endif +# ifndef DBGHEX +# define DBGHEX(DBGFILE, MSG, LEN) \ +{ if (soap)\ + { if (!soap->fdebug[SOAP_INDEX_##DBGFILE])\ + soap_open_logfile(soap, SOAP_INDEX_##DBGFILE);\ + if (soap->fdebug[SOAP_INDEX_##DBGFILE])\ + { int i; char *s;\ + for (s = (char*)(MSG), i = (LEN); i; i--)\ + fprintf(soap->fdebug[SOAP_INDEX_##DBGFILE], "%2.2X ", (int)*s++&0xFF);\ + fflush(soap->fdebug[SOAP_INDEX_##DBGFILE]);\ + }\ + }\ +} +# endif +#else +# define DBGLOG(DBGFILE, CMD) +# define DBGMSG(DBGFILE, MSG, LEN) +# define DBGFUN(FNAME) +# define DBGFUN1(FNAME, FMT, ARG) +# define DBGFUN2(FNAME, FMT1, ARG1, FMT2, ARG2) +# define DBGFUN3(FNAME, FMT1, ARG1, FMT2, ARG2, FMT3, ARG3) +# define DBGHEX(DBGFILE, MSG, LEN) +#endif + +/* UCS-4 requires 32 bits (0-7FFFFFFF, the sign bit is used by gSOAP to distinguish XML entities) */ +typedef soap_int32 soap_wchar; + +/* namespace table row */ +struct Namespace +{ const char *id; + const char *ns; + const char *in; + char *out; +}; + +/* namespace stack */ +struct soap_nlist +{ struct soap_nlist *next; + unsigned int level; /* nesting depth level */ + short index; /* corresponding entry in ns mapping table */ + char *ns; /* only set when parsed ns URI is not in the ns mapping table */ + char id[1]; /* the actual string value flows into the allocated region below this struct */ +}; + +/* block stack for nested block allocations */ +struct soap_blist +{ struct soap_blist *next; + char *ptr; + size_t size; +}; + +/* array layout */ +struct soap_array +{ void *__ptr; + int __size; +}; + +/* pointer serialization management */ +struct soap_plist +{ struct soap_plist *next; + const void *ptr; + const struct soap_array *array; + int type; + int id; + char mark1; + char mark2; +}; + +/* block allocation for pointer serialization management */ +struct soap_pblk +{ struct soap_pblk *next; + struct soap_plist plist[SOAP_PTRBLK]; +}; + +#ifdef SOAP_MEM_DEBUG +/* malloc/free tracking for debugging */ +struct soap_mlist +{ struct soap_mlist *next; + const void *ptr; + const char *file; + int line; + short live; +}; +#endif + +/* class allocation list */ +struct soap_clist +{ struct soap_clist *next; + void *ptr; + int type; + int size; + int (*fdelete)(struct soap_clist*); +}; + +/* attributes */ +struct soap_attribute +{ struct soap_attribute *next; + char *value; + size_t size; + char *ns; + short visible; + char name[1]; /* the actual name string flows into the allocated region below this struct */ +}; + +#ifndef WITH_LEAN +struct soap_cookie +{ struct soap_cookie *next; + char *name; + char *value; + char *domain; + char *path; + time_t expire; /* client-side: local time to expire */ + long maxage; /* server-side: seconds to expire */ + unsigned int version; + short secure; + short session; /* server-side */ + short env; /* server-side: got cookie from client and should not be (re)send */ + short modified; /* server-side: client cookie was modified and should be send */ +}; +#endif + +#ifdef __cplusplus +SOAP_FMAC1 struct soap_multipart* SOAP_FMAC2 soap_next_multipart(struct soap_multipart*); + +class soap_multipart_iterator +{ public: + struct soap_multipart *content; + bool operator==(const soap_multipart_iterator& iter) const + { return (bool)(content == iter.content); } + bool operator!=(const soap_multipart_iterator& iter) const + { return (bool)(content != iter.content); } + struct soap_multipart &operator*() const + { return *content; } + soap_multipart_iterator &operator++() + { content = soap_next_multipart(content); return *this; } + soap_multipart_iterator() : content(NULL) + { } + soap_multipart_iterator(struct soap_multipart *p) : content(p) + { } +}; +#endif + +#ifndef WITH_LEANER +struct soap_dime +{ size_t count; + size_t size; + size_t chunksize; + size_t buflen; + char flags; + char *ptr; + const char *id; + const char *type; + const char *options; + struct soap_multipart *list; /* list of DIME attachments received */ + struct soap_multipart *first, *last; /* temporary in/out queue */ +#ifdef __cplusplus + soap_multipart_iterator begin() + { soap_multipart_iterator iter(list); return iter; }; + soap_multipart_iterator end() + { soap_multipart_iterator iter(NULL); return iter; }; +#endif +}; +#endif + +#ifndef WITH_LEANER +struct soap_mime +{ char *boundary; /* MIME boundary */ + const char *start; /* MIME start ID */ + struct soap_multipart *list; /* list of MIME attachments received */ + struct soap_multipart *first, *last; /* temporary in/out queue */ +#ifdef __cplusplus + soap_multipart_iterator begin() + { soap_multipart_iterator iter(list); return iter; }; + soap_multipart_iterator end() + { soap_multipart_iterator iter(NULL); return iter; }; +#endif +}; +#endif + +#ifndef WITH_LEANER +/* RFC2045 MIME content transfer encodings */ +enum soap_mime_encoding +{ SOAP_MIME_NONE, + SOAP_MIME_7BIT, + SOAP_MIME_8BIT, + SOAP_MIME_BINARY, + SOAP_MIME_QUOTED_PRINTABLE, + SOAP_MIME_BASE64, + SOAP_MIME_IETF_TOKEN, + SOAP_MIME_X_TOKEN +}; +#endif + +#ifndef WITH_LEANER +/* DIME/MIME multipart list */ +struct soap_multipart +{ struct soap_multipart *next; + char *ptr; /* points to raw data content */ + size_t size; /* size of data content */ + const char *id; /* DIME/MIME content ID or form data name */ + const char *type; /* DIME/MIME type (MIME type format) */ + const char *options; /* DIME options */ + enum soap_mime_encoding encoding; /* MIME Content-Transfer-Encoding */ + const char *location; /* MIME Content-Location (optional) */ + const char *description; /* MIME Content-Description (optional) */ +#ifdef __cplusplus + typedef soap_multipart_iterator iterator; +#endif +}; +#endif + +#ifndef WITH_LEANER +/* attachment DIME and MTOM XOP forwarding */ +struct soap_xlist +{ struct soap_xlist *next; + unsigned char **ptr; + int *size; + char *id; + char **type; + char **options; +}; +#endif + +/******************************************************************************/ + +#ifndef WITH_LEANER +#ifdef __cplusplus +class soap_dom_attribute_iterator +{ public: + struct soap_dom_attribute *att; + const char *nstr; + const char *name; + bool operator==(const soap_dom_attribute_iterator&) const; + bool operator!=(const soap_dom_attribute_iterator&) const; + struct soap_dom_attribute &operator*() const; + soap_dom_attribute_iterator &operator++(); + soap_dom_attribute_iterator(); + soap_dom_attribute_iterator(struct soap_dom_attribute*); + ~soap_dom_attribute_iterator(); +}; +#endif +#endif + +#ifndef WITH_LEANER +struct soap_dom_attribute +{ struct soap_dom_attribute *next; + const char *nstr; + char *name; + char *data; + wchar_t *wide; + struct soap *soap; +#ifdef __cplusplus + typedef soap_dom_attribute_iterator iterator; + struct soap_dom_attribute &set(const char *nstr, const char *name); /* set namespace and name */ + struct soap_dom_attribute &set(const char *data); /* set data */ + soap_dom_attribute_iterator begin(); + soap_dom_attribute_iterator end(); + soap_dom_attribute_iterator find(const char *nstr, const char *name); + void unlink(); + soap_dom_attribute(); + soap_dom_attribute(struct soap *soap); + soap_dom_attribute(struct soap *soap, const char *nstr, const char *name, const char *data); + ~soap_dom_attribute(); +#endif +}; +#endif + +#ifndef WITH_LEANER +#ifdef __cplusplus +class soap_dom_element_iterator +{ public: + struct soap_dom_element *elt; + const char *nstr; + const char *name; + int type; + bool operator==(const soap_dom_element_iterator&) const; + bool operator!=(const soap_dom_element_iterator&) const; + struct soap_dom_element &operator*() const; + soap_dom_element_iterator &operator++(); + soap_dom_element_iterator(); + soap_dom_element_iterator(struct soap_dom_element*); + ~soap_dom_element_iterator(); +}; +#endif +#endif + +#ifndef WITH_LEANER +struct soap_dom_element +{ struct soap_dom_element *next; /* next sibling */ + struct soap_dom_element *prnt; /* parent */ + struct soap_dom_element *elts; /* list of child elements */ + struct soap_dom_attribute *atts; /* list of attributes */ + const char *nstr; /* namespace string */ + char *name; /* element tag name */ + char *data; /* element content data (with SOAP_C_UTFSTRING flag set) */ + wchar_t *wide; /* element content data */ + int type; /* optional: serialized C/C++ data type */ + void *node; /* optional: pointer to serialized C/C++ data */ + char *head; /* leading whitespace to start tag */ + char *tail; /* leading whitespace to end tag */ + struct soap *soap; /* soap context that manages this node */ +#ifdef __cplusplus + typedef soap_dom_element_iterator iterator; + struct soap_dom_element &set(const char *nstr, const char *name); + struct soap_dom_element &set(const char *data); + struct soap_dom_element &set(void *node, int type); + struct soap_dom_element &add(struct soap_dom_element*); + struct soap_dom_element &add(struct soap_dom_element&); + struct soap_dom_element &add(struct soap_dom_attribute*); + struct soap_dom_element &add(struct soap_dom_attribute&); + soap_dom_element_iterator begin(); + soap_dom_element_iterator end(); + soap_dom_element_iterator find(const char *nstr, const char *name); + soap_dom_element_iterator find(int type); + void unlink(); + soap_dom_element(); + soap_dom_element(struct soap *soap); + soap_dom_element(struct soap *soap, const char *nstr, const char *name); + soap_dom_element(struct soap *soap, const char *nstr, const char *name, const char *data); + soap_dom_element(struct soap *soap, const char *nstr, const char *name, void *node, int type); + ~soap_dom_element(); +#endif +}; +SOAP_FMAC1 struct soap_dom_element * SOAP_FMAC2 soap_dom_next_element(struct soap_dom_element *elt); +SOAP_FMAC1 struct soap_dom_attribute * SOAP_FMAC2 soap_dom_next_attribute(struct soap_dom_attribute *att); +#endif + +#if defined(__cplusplus) && !defined(WITH_LEAN) && !defined(WITH_COMPAT) +} +extern std::ostream &operator<<(std::ostream&, const struct soap_dom_element&); +extern std::istream &operator>>(std::istream&, struct soap_dom_element&); +extern "C" { +#endif + +/******************************************************************************/ + +#ifdef WIN32 +# ifdef SOAP_STD_EXPORTS +# define SOAP_STD_API __declspec(dllexport) +# else +# define SOAP_STD_API +# endif +#else +# define SOAP_STD_API +#endif + +struct SOAP_STD_API soap +{ short state; /* 0 = uninitialized, 1 = initialized, 2 = copy of another soap struct */ + short version; /* 1 = SOAP1.1 and 2 = SOAP1.2 (set automatically from namespace URI in nsmap table) */ + soap_mode mode; + soap_mode imode; + soap_mode omode; + const char *float_format; /* user-definable format string for floats (<1024 chars) */ + const char *double_format; /* user-definable format string for doubles (<1024 chars) */ + const char *dime_id_format; /* user-definable format string for integer DIME id ( 0, gives socket recv timeout in seconds, < 0 in usec */ + int send_timeout; /* when > 0, gives socket send timeout in seconds, < 0 in usec */ + int connect_timeout; /* when > 0, gives socket connect() timeout in seconds, < 0 in usec */ + int accept_timeout; /* when > 0, gives socket accept() timeout in seconds, < 0 in usec */ + int socket_flags; /* socket recv() and send() flags, e.g. set to MSG_NOSIGNAL to disable sigpipe */ + int connect_flags; /* connect() SOL_SOCKET sockopt flags, e.g. set to SO_DEBUG to debug socket */ + int bind_flags; /* bind() SOL_SOCKET sockopt flags, e.g. set to SO_REUSEADDR to enable reuse */ + int accept_flags; /* accept() SOL_SOCKET sockopt flags */ + unsigned short linger_time; /* linger time for SO_LINGER option */ + const struct Namespace *namespaces; /* Pointer to global namespace mapping table */ + struct Namespace *local_namespaces; /* Local namespace mapping table */ + struct soap_nlist *nlist; /* namespace stack */ + struct soap_blist *blist; /* block allocation stack */ + struct soap_clist *clist; /* class instance allocation list */ + void *alist; /* memory allocation (malloc) list */ + struct soap_ilist *iht[SOAP_IDHASH]; + struct soap_plist *pht[SOAP_PTRHASH]; + struct soap_pblk *pblk; /* plist block allocation */ + short pidx; /* plist block allocation */ + struct SOAP_ENV__Header *header; + struct SOAP_ENV__Fault *fault; + int idnum; + void *user; /* to pass user-defined data */ + struct soap_plugin *plugins; /* linked list of plug-in data */ + char *userid; /* HTTP Basic authorization userid */ + char *passwd; /* HTTP Basic authorization passwd */ + int (*fpost)(struct soap*, const char*, const char*, int, const char*, const char*, size_t); + int (*fget)(struct soap*); + int (*fput)(struct soap*); + int (*fdel)(struct soap*); + int (*fhead)(struct soap*); + int (*fform)(struct soap*); + int (*fposthdr)(struct soap*, const char*, const char*); + int (*fresponse)(struct soap*, int, size_t); + int (*fparse)(struct soap*); + int (*fparsehdr)(struct soap*, const char*, const char*); + int (*fheader)(struct soap*); + int (*fresolve)(struct soap*, const char*, struct in_addr* inaddr); + int (*fconnect)(struct soap*, const char*, const char*, int); + int (*fdisconnect)(struct soap*); + int (*fclosesocket)(struct soap*, SOAP_SOCKET); + int (*fshutdownsocket)(struct soap*, SOAP_SOCKET, int); + SOAP_SOCKET (*fopen)(struct soap*, const char*, const char*, int); + SOAP_SOCKET (*faccept)(struct soap*, SOAP_SOCKET, struct sockaddr*, int *n); + int (*fclose)(struct soap*); + int (*fsend)(struct soap*, const char*, size_t); + size_t (*frecv)(struct soap*, char*, size_t); + int (*fpoll)(struct soap*); + void (*fseterror)(struct soap*, const char **c, const char **s); + int (*fignore)(struct soap*, const char*); + int (*fserveloop)(struct soap*); + void *(*fplugin)(struct soap*, const char*); + void *(*fmalloc)(struct soap*, size_t); +#ifndef WITH_LEANER + int (*fprepareinit)(struct soap*); + int (*fpreparesend)(struct soap*, const char*, size_t); + int (*fpreparerecv)(struct soap*, const char*, size_t); + int (*fpreparefinal)(struct soap*); + void *(*fdimereadopen)(struct soap*, void*, const char*, const char*, const char*); + void *(*fdimewriteopen)(struct soap*, const char*, const char*, const char*); + void (*fdimereadclose)(struct soap*, void*); + void (*fdimewriteclose)(struct soap*, void*); + size_t (*fdimeread)(struct soap*, void*, char*, size_t); + int (*fdimewrite)(struct soap*, void*, const char*, size_t); + void *(*fmimereadopen)(struct soap*, void*, const char*, const char*, const char*); + void *(*fmimewriteopen)(struct soap*, void*, const char*, const char*, const char*, enum soap_mime_encoding); + void (*fmimereadclose)(struct soap*, void*); + void (*fmimewriteclose)(struct soap*, void*); + size_t (*fmimeread)(struct soap*, void*, char*, size_t); + int (*fmimewrite)(struct soap*, void*, const char*, size_t); +#endif + SOAP_SOCKET master; + SOAP_SOCKET socket; +#if defined(__cplusplus) && !defined(WITH_LEAN) && !defined(WITH_COMPAT) + std::ostream *os; + std::istream *is; +#else + void *os; /* preserve struct size */ + void *is; /* preserve struct size */ +#endif +#ifndef UNDER_CE + int sendfd; + int recvfd; +#else + FILE *sendfd; + FILE *recvfd; +#endif + size_t bufidx; /* index in soap.buf[] */ + size_t buflen; /* length of soap.buf[] content */ + soap_wchar ahead; /* parser lookahead */ + short cdata; /* CDATA parser state */ + short body; /* parsed XML element has a body or not */ + unsigned int level; /* XML nesting level */ + size_t count; /* message length counter */ + size_t length; /* message length as set by HTTP header */ + char *labbuf; /* look-aside buffer */ + size_t lablen; /* look-aside buffer allocated length */ + size_t labidx; /* look-aside buffer index to available part */ + char buf[SOAP_BUFLEN];/* send and receive buffer */ + char msgbuf[1024]; /* in/out buffer for HTTP/MIME headers >=1024 bytes */ + char tmpbuf[1024]; /* in/out buffer for HTTP/MIME headers, simpleType values, element and attribute tag names, and DIME must be >=1024 bytes */ + char tag[SOAP_TAGLEN]; + char id[SOAP_TAGLEN]; + char href[SOAP_TAGLEN]; + char type[SOAP_TAGLEN]; + char arrayType[SOAP_TAGLEN]; + char arraySize[SOAP_TAGLEN]; + char arrayOffset[SOAP_TAGLEN]; + short other; + short position; + int positions[SOAP_MAXDIMS]; + short root; + struct soap_attribute *attributes; /* attribute list */ + short encoding; /* when set, output encodingStyle */ + short mustUnderstand; /* a mustUnderstand element was parsed or is output */ + short null; /* parsed XML is xsi:nil */ + short ns; /* when not set, output full xmlns bindings */ + short part; /* parsing state */ + short alloced; + short peeked; + size_t chunksize; + size_t chunkbuflen; + char endpoint[SOAP_TAGLEN]; + char path[SOAP_TAGLEN]; + char host[SOAP_TAGLEN]; + char *action; + char *authrealm; /* HTTP authentication realm */ + char *prolog; /* XML declaration prolog */ + unsigned long ip; /* IP number */ + int port; /* port number */ + short keep_alive; /* connection should be kept open */ + short tcp_keep_alive; /* enable SO_KEEPALIVE */ + unsigned int tcp_keep_idle; /* set TCP_KEEPIDLE */ + unsigned int tcp_keep_intvl; /* set TCP_KEEPINTVL */ + unsigned int tcp_keep_cnt; /* set TCP_KEEPCNT */ + unsigned int max_keep_alive; /* maximum keep-alive session (default=100) */ + const char *proxy_http_version;/* HTTP version of proxy "1.0" or "1.1" */ + const char *proxy_host; /* Proxy Server host name */ + int proxy_port; /* Proxy Server port (default = 8080) */ + const char *proxy_userid; /* Proxy Authorization user name */ + const char *proxy_passwd; /* Proxy Authorization password */ + const char *proxy_from; /* X-Forwarding-For header returned by proxy */ + int status; /* -1 when request, else error code to be returned by server */ + int error; + int errmode; + int errnum; +#ifndef WITH_LEANER + struct soap_dom_element *dom; + struct soap_dime dime; + struct soap_mime mime; + struct soap_xlist *xlist; +#endif +#if !defined(WITH_LEAN) || defined(SOAP_DEBUG) + const char *logfile[SOAP_MAXLOGS]; + FILE *fdebug[SOAP_MAXLOGS]; + struct soap_mlist *mht[SOAP_PTRHASH]; +#endif +#ifndef WITH_LEAN + const char *c14ninclude; + const char *c14nexclude; + struct soap_cookie *cookies; + const char *cookie_domain; + const char *cookie_path; + int cookie_max; +#endif +#ifndef WITH_NOIO + int ipv6_multicast_if; /* always include this to keep the soap struct size the same in v4 and v6 */ + char* ipv4_multicast_if; /* always include this to keep the soap struct size the same in v4 and v6 */ + int ipv4_multicast_ttl; /* multicast scope */ +#ifdef WITH_IPV6 + struct sockaddr_storage peer; /* IPv6: set by soap_accept and by UDP recv */ +#else + struct sockaddr_in peer; /* IPv4: set by soap_connect/soap_accept and by UDP recv */ +#endif +#endif + size_t peerlen; +#ifdef WITH_OPENSSL + int (*fsslauth)(struct soap*); + int (*fsslverify)(int, X509_STORE_CTX*); + BIO *bio; + SSL *ssl; + SSL_CTX *ctx; + SSL_SESSION *session; +#else + void *fsslauth; /* dummy members, to preserve struct size */ + void *fsslverify; + void *bio; + void *ssl; + void *ctx; + void *session; +#endif + unsigned short ssl_flags; + const char *keyfile; + const char *password; + const char *dhfile; + const char *cafile; + const char *capath; + const char *crlfile; + const char *randfile; + char session_host[SOAP_TAGLEN]; + int session_port; +#ifdef WITH_C_LOCALE + locale_t c_locale; /* set to C locale by default */ +#else + void *c_locale; +#endif +#ifdef WITH_ZLIB + z_stream *d_stream; /* decompression stream */ + uLong z_crc; /* internal gzip crc */ +#else + void *d_stream; /* dummy members, to preserve struct size */ + soap_int32 z_crc; +#endif + short zlib_state; /* SOAP_ZLIB_NONE, SOAP_ZLIB_DEFLATE, or SOAP_ZLIB_INFLATE */ + short zlib_in; /* SOAP_ZLIB_NONE, SOAP_ZLIB_DEFLATE, or SOAP_ZLIB_GZIP */ + short zlib_out; /* SOAP_ZLIB_NONE, SOAP_ZLIB_DEFLATE, or SOAP_ZLIB_GZIP */ + char *z_buf; /* buffer */ + size_t z_buflen; + unsigned short z_level; /* compression level to be used (0=none, 1=fast to 9=best) */ + float z_ratio_in; /* detected compression ratio compressed_length/length of inbound message */ + float z_ratio_out; /* detected compression ratio compressed_length/length of outbound message */ +#ifdef WMW_RPM_IO + void *rpmreqid; +#endif +#ifdef __cplusplus + soap(); + soap(soap_mode); + soap(soap_mode, soap_mode); + soap(struct soap&); + virtual ~soap(); +#else + void (*dummy)(); +#endif +}; + +struct soap_code_map +{ long code; + const char *string; +}; + +/* forwarding list */ +struct soap_flist +{ struct soap_flist *next; + int type; + void *ptr; + unsigned int level; + size_t len; + void (*fcopy)(struct soap*, int, int, void*, size_t, const void*, size_t); +}; + +/* id-ref forwarding list */ +struct soap_ilist +{ struct soap_ilist *next; + int type; + size_t size; + void *link; + void *copy; + struct soap_flist *flist; + void *ptr; + unsigned int level; + char id[1]; /* the actual id string value flows into the allocated region below this struct */ +}; + +struct soap_plugin +{ struct soap_plugin *next; + const char *id; + void *data; + int (*fcopy)(struct soap *soap, struct soap_plugin *dst, struct soap_plugin *src); + void (*fdelete)(struct soap *soap, struct soap_plugin *p); /* should delete fields of plugin only and not free(p) */ +}; + +#ifndef WITH_NONAMESPACES +extern SOAP_NMAC struct Namespace namespaces[]; +#endif + +#ifndef WITH_LEAN +# define soap_get0(soap) (((soap)->bufidx>=(soap)->buflen && soap_recv(soap)) ? EOF : (unsigned char)(soap)->buf[(soap)->bufidx]) +# define soap_get1(soap) (((soap)->bufidx>=(soap)->buflen && soap_recv(soap)) ? EOF : (unsigned char)(soap)->buf[(soap)->bufidx++]) +#else +soap_wchar soap_get0(struct soap*); +soap_wchar soap_get1(struct soap*); +#endif + +#define soap_revget1(soap) ((soap)->bufidx--) +#define soap_unget(soap, c) ((soap)->ahead = c) +#define soap_register_plugin(soap, plugin) soap_register_plugin_arg(soap, plugin, NULL) +#define soap_imode(soap, n) ((soap)->mode = (soap)->imode = (n)) +#define soap_set_imode(soap, n) ((soap)->imode |= (n)) +#define soap_clr_imode(soap, n) ((soap)->imode &= ~(n)) +#define soap_omode(soap, n) ((soap)->mode = (soap)->omode = (n)) +#define soap_set_omode(soap, n) ((soap)->omode |= (n)) +#define soap_clr_omode(soap, n) ((soap)->omode &= ~(n)) +#define soap_set_mode(soap, n) ((soap)->imode |= (n), (soap)->omode |= (n)) +#define soap_clr_mode(soap, n) ((soap)->imode &= ~(n), (soap)->omode &= ~(n)) +#define soap_destroy(soap) soap_delete((soap), NULL) + +#ifdef HAVE_STRRCHR +# define soap_strrchr(s, t) strrchr(s, t) +#else + SOAP_FMAC1 char* SOAP_FMAC2 soap_strrchr(const char *s, int t); +#endif + +#ifdef HAVE_STRTOL +# define soap_strtol(s, t, b) strtol(s, t, b) +#else + SOAP_FMAC1 long SOAP_FMAC2 soap_strtol(const char *s, char **t, int b); +#endif + +#ifdef HAVE_STRTOUL +# define soap_strtoul(s, t, b) strtoul(s, t, b) +#else + SOAP_FMAC1 unsigned long SOAP_FMAC2 soap_strtoul(const char *s, char **t, int b); +#endif + +#if defined(WITH_OPENSSL) +# define soap_random soap_rand() +SOAP_FMAC1 int SOAP_FMAC2 soap_rand(void); +#elif defined(HAVE_RANDOM) +# define soap_random (int)random() +#else +# define soap_random rand() +#endif + +#ifdef WITH_NOIDREF +# define soap_embedded(s, p, t) (0) +# define soap_id_lookup(s, i, p, t, n, k) (p) +# define soap_id_forward(s, h, p, len, st, tt, n, k, fc) (p) +# define soap_reference(s, a, t) (1) +# define soap_array_reference(s, p, a, n, t) (1) +# define soap_embed(s, p, a, n, t, pp) (0) +# define soap_embedded_id(s, i, p, t) (i) +# define soap_is_embedded(s, p) (0) +# define soap_is_single(s, p) (1) +# define soap_lookup_type(s, i) (0) +# define soap_getindependent(s) (0) +# define soap_putindependent(s) (0) +# define soap_getelement(s, n) (n) +# define soap_putelement(s, p, t, i, n) (0) +# define soap_markelement(s, p, n) (0) +#endif + +SOAP_FMAC1 void SOAP_FMAC2 soap_header(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_fault(struct soap*); +SOAP_FMAC1 const char** SOAP_FMAC2 soap_faultcode(struct soap*); +SOAP_FMAC1 const char** SOAP_FMAC2 soap_faultsubcode(struct soap*); +SOAP_FMAC1 const char** SOAP_FMAC2 soap_faultstring(struct soap*); +SOAP_FMAC1 const char** SOAP_FMAC2 soap_faultdetail(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_serializeheader(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putheader(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getheader(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_serializefault(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putfault(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getfault(struct soap*); + +SOAP_FMAC1 void SOAP_FMAC2 soap_ssl_init(); +SOAP_FMAC1 int SOAP_FMAC2 soap_poll(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_connect_command(struct soap*, int, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_connect(struct soap*, const char*, const char*); +SOAP_FMAC1 SOAP_SOCKET SOAP_FMAC2 soap_bind(struct soap*, const char*, int, int); +SOAP_FMAC1 SOAP_SOCKET SOAP_FMAC2 soap_accept(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_ssl_accept(struct soap*); +SOAP_FMAC1 const char * SOAP_FMAC2 soap_ssl_error(struct soap*, int); + +SOAP_FMAC1 int SOAP_FMAC2 soap_ssl_server_context(struct soap*, unsigned short, const char*, const char*, const char*, const char*, const char*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_ssl_client_context(struct soap*, unsigned short, const char*, const char*, const char*, const char*, const char*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_puthttphdr(struct soap*, int status, size_t count); + +SOAP_FMAC1 const char* SOAP_FMAC2 soap_get_header_attribute(struct soap*, const char*, const char*); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_decode_key(char*, size_t, const char*); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_decode_val(char*, size_t, const char*); + +SOAP_FMAC1 size_t SOAP_FMAC2 soap_hash(const char*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_endpoint(struct soap*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_flush_raw(struct soap*, const char*, size_t); +SOAP_FMAC1 int SOAP_FMAC2 soap_flush(struct soap*); +SOAP_FMAC1 soap_wchar SOAP_FMAC2 soap_get(struct soap*); +SOAP_FMAC1 soap_wchar SOAP_FMAC2 soap_getchar(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_tag_cmp(const char*, const char*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_fault(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_sender_fault(struct soap*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_sender_fault_subcode(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_receiver_fault(struct soap*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_receiver_fault_subcode(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_set_sender_error(struct soap*, const char*, const char*, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_set_receiver_error(struct soap*, const char*, const char*, int); + +SOAP_FMAC1 int SOAP_FMAC2 soap_send_raw(struct soap*, const char*, size_t); +SOAP_FMAC1 int SOAP_FMAC2 soap_recv_raw(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_recv(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_send(struct soap*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_send2(struct soap*, const char*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_send3(struct soap*, const char*, const char*, const char*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_pututf8(struct soap*, unsigned long); +SOAP_FMAC1 soap_wchar SOAP_FMAC2 soap_getutf8(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_putbase64(struct soap*, const unsigned char*, int); +SOAP_FMAC1 unsigned char* SOAP_FMAC2 soap_getbase64(struct soap*, int*, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_puthex(struct soap*, const unsigned char*, int); +SOAP_FMAC1 unsigned char* SOAP_FMAC2 soap_gethex(struct soap*, int*); + +#ifndef WITH_LEANER +SOAP_FMAC1 int SOAP_FMAC2 soap_xop_forward(struct soap*, unsigned char**, int*, char**, char**, char**); +SOAP_FMAC1 int SOAP_FMAC2 soap_dime_forward(struct soap*, unsigned char**, int*, char**, char**, char**); +#endif + +#ifndef WITH_NOIDREF +SOAP_FMAC1 int SOAP_FMAC2 soap_pointer_lookup_id(struct soap*, void *p, int t, struct soap_plist**); +SOAP_FMAC1 int SOAP_FMAC2 soap_pointer_lookup(struct soap*, const void *p, int t, struct soap_plist**); +SOAP_FMAC1 int SOAP_FMAC2 soap_pointer_enter(struct soap*, const void *p, const struct soap_array *a, int n, int t, struct soap_plist**); +SOAP_FMAC1 int SOAP_FMAC2 soap_array_pointer_lookup(struct soap*, const void *p, const struct soap_array *a, int n, int t, struct soap_plist**); +SOAP_FMAC1 int SOAP_FMAC2 soap_embed(struct soap *soap, const void *p, const struct soap_array *a, int n, const char *tag, int type); +SOAP_FMAC1 struct soap_ilist* SOAP_FMAC2 soap_lookup(struct soap*, const char*); +SOAP_FMAC1 struct soap_ilist* SOAP_FMAC2 soap_enter(struct soap*, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_resolve(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_embedded(struct soap*, const void *p, int t); +SOAP_FMAC1 int SOAP_FMAC2 soap_reference(struct soap*, const void *p, int t); +SOAP_FMAC1 int SOAP_FMAC2 soap_array_reference(struct soap*, const void *p, const struct soap_array *a, int n, int t); +SOAP_FMAC1 int SOAP_FMAC2 soap_embedded_id(struct soap*, int id, const void *p, int t); +SOAP_FMAC1 int SOAP_FMAC2 soap_is_embedded(struct soap*, struct soap_plist*); +SOAP_FMAC1 int SOAP_FMAC2 soap_is_single(struct soap*, struct soap_plist*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_embedded(struct soap*, struct soap_plist*); +#endif + +SOAP_FMAC1 int SOAP_FMAC2 soap_begin_count(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_end_count(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_begin_send(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_end_send(struct soap*); + +SOAP_FMAC1 const struct soap_code_map* SOAP_FMAC2 soap_code(const struct soap_code_map*, const char*); +SOAP_FMAC1 long SOAP_FMAC2 soap_code_int(const struct soap_code_map*, const char*, long); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_code_str(const struct soap_code_map*, long); +SOAP_FMAC1 long SOAP_FMAC2 soap_code_bits(const struct soap_code_map*, const char*); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_code_list(struct soap*, const struct soap_code_map*, long); + +SOAP_FMAC1 int SOAP_FMAC2 soap_getline(struct soap*, char*, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_begin_recv(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_end_recv(struct soap*); + +SOAP_FMAC1 void* SOAP_FMAC2 soap_malloc(struct soap*, size_t); +SOAP_FMAC1 void SOAP_FMAC2 soap_dealloc(struct soap*, void*); +SOAP_FMAC1 struct soap_clist * SOAP_FMAC2 soap_link(struct soap*, void*, int, int, int (*fdelete)(struct soap_clist*)); +SOAP_FMAC1 void SOAP_FMAC2 soap_unlink(struct soap*, const void*); +SOAP_FMAC1 void SOAP_FMAC2 soap_free_temp(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_del(struct soap*); + +SOAP_FMAC1 void* SOAP_FMAC2 soap_track_malloc(struct soap*, const char*, int, size_t); +SOAP_FMAC1 void SOAP_FMAC2 soap_track_free(struct soap*, const char*, int, void*); + +#ifndef WITH_NOIDREF +SOAP_FMAC1 int SOAP_FMAC2 soap_lookup_type(struct soap*, const char *id); +SOAP_FMAC1 void* SOAP_FMAC2 soap_id_lookup(struct soap*, const char *id, void **p, int t, size_t n, unsigned int k); +SOAP_FMAC1 void* SOAP_FMAC2 soap_id_forward(struct soap*, const char *id, void *p, size_t len, int st, int tt, size_t n, unsigned int k, void(*fcopy)(struct soap*, int, int, void*, size_t, const void*, size_t)); +#endif +SOAP_FMAC1 void* SOAP_FMAC2 soap_id_enter(struct soap*, const char *id, void *p, int t, size_t n, unsigned int k, const char *type, const char *arrayType, void *(*finstantiate)(struct soap*, int, const char*, const char*, size_t*)); +SOAP_FMAC1 void SOAP_FMAC2 soap_fcopy(struct soap *soap, int st, int tt, void *p, size_t, const void *q, size_t n); + +SOAP_FMAC1 int SOAP_FMAC2 soap_size(const int *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_getoffsets(const char *, const int *, int *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_getsize(const char *, const char *, int *); +SOAP_FMAC1 int SOAP_FMAC2 soap_getsizes(const char *, int *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_getposition(const char *, int *); + +SOAP_FMAC1 char* SOAP_FMAC2 soap_putsize(struct soap*, const char *, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_putsizesoffsets(struct soap*, const char *, const int *, const int *, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_putsizes(struct soap*, const char *, const int *, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_putoffset(struct soap*, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_putoffsets(struct soap*, const int *, int); + +SOAP_FMAC1 int SOAP_FMAC2 soap_closesock(struct soap*); + +SOAP_FMAC1 struct soap *SOAP_FMAC2 soap_new(void); +SOAP_FMAC1 struct soap *SOAP_FMAC2 soap_new1(soap_mode); +SOAP_FMAC1 struct soap *SOAP_FMAC2 soap_new2(soap_mode, soap_mode); +SOAP_FMAC1 void SOAP_FMAC2 soap_free(struct soap*); +SOAP_FMAC1 struct soap *SOAP_FMAC2 soap_copy(const struct soap*); +SOAP_FMAC1 struct soap *SOAP_FMAC2 soap_copy_context(struct soap*, const struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_copy_stream(struct soap*, struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_init(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_init1(struct soap*, soap_mode); +SOAP_FMAC1 void SOAP_FMAC2 soap_init2(struct soap*, soap_mode, soap_mode); +SOAP_FMAC1 void SOAP_FMAC2 soap_done(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_cleanup(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_begin(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_end(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_delete(struct soap*, void*); + +#ifdef SOAP_DEBUG +SOAP_FMAC1 void SOAP_FMAC2 soap_set_recv_logfile(struct soap*, const char*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_sent_logfile(struct soap*, const char*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_test_logfile(struct soap*, const char*); +SOAP_FMAC1 void SOAP_FMAC2 soap_close_logfiles(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_open_logfile(struct soap*, int); +#endif + +SOAP_FMAC1 const char* SOAP_FMAC2 soap_value(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_match_tag(struct soap*, const char*, const char *); +SOAP_FMAC1 int SOAP_FMAC2 soap_match_array(struct soap*, const char*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_element(struct soap*, const char*, int, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_begin_out(struct soap*, const char *tag, int id, const char *type); +SOAP_FMAC1 int SOAP_FMAC2 soap_array_begin_out(struct soap*, const char *tag, int id, const char *type, const char *offset); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_ref(struct soap*, const char *tag, int id, int href); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_href(struct soap*, const char *tag, int id, const char *ref, const char *val); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_null(struct soap*, const char *tag, int id, const char *type); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_id(struct soap*, const char *tag, int id, const void *p, const struct soap_array *a, int d, const char *type, int n); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_result(struct soap*, const char *tag); +SOAP_FMAC1 void SOAP_FMAC2 soap_check_result(struct soap*, const char *tag); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_end_out(struct soap*, const char *tag); +SOAP_FMAC1 int SOAP_FMAC2 soap_element_start_end_out(struct soap*, const char *tag); + +SOAP_FMAC1 int SOAP_FMAC2 soap_attribute(struct soap*, const char*, const char*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_element_begin_in(struct soap*, const char *tag, int nillable, const char *type); + +SOAP_FMAC1 int SOAP_FMAC2 soap_element_end_in(struct soap*, const char *tag); + +SOAP_FMAC1 int SOAP_FMAC2 soap_peek_element(struct soap*); + +SOAP_FMAC1 void SOAP_FMAC2 soap_retry(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_revert(struct soap*); + +SOAP_FMAC1 char* SOAP_FMAC2 soap_strdup(struct soap*, const char*); +SOAP_FMAC1 wchar_t* SOAP_FMAC2 soap_wstrdup(struct soap*, const wchar_t*); +SOAP_FMAC1 const char * SOAP_FMAC2 soap_strsearch(const char *big, const char *little); + +SOAP_FMAC1 int SOAP_FMAC2 soap_string_out(struct soap*, const char *s, int flag); +SOAP_FMAC1 char* SOAP_FMAC2 soap_string_in(struct soap*, int, long, long); + +#ifndef WITH_LEANER +SOAP_FMAC1 int SOAP_FMAC2 soap_wstring_out(struct soap*, const wchar_t *s, int flag); +SOAP_FMAC1 wchar_t* SOAP_FMAC2 soap_wstring_in(struct soap*, int, long, long); +#endif + +SOAP_FMAC1 int SOAP_FMAC2 soap_match_namespace(struct soap*, const char *, const char*, size_t n1, size_t n2); + +SOAP_FMAC1 int SOAP_FMAC2 soap_set_namespaces(struct soap*, const struct Namespace*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_local_namespaces(struct soap*); + +SOAP_FMAC1 void SOAP_FMAC2 soap_pop_namespace(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_push_namespace(struct soap*, const char *,const char *); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_current_namespace(struct soap *soap, const char *tag); + +SOAP_FMAC1 struct soap_nlist* SOAP_FMAC2 soap_lookup_ns(struct soap *soap, const char *tag, size_t n); + +SOAP_FMAC1 int SOAP_FMAC2 soap_store_lab(struct soap*, const char*, size_t); +SOAP_FMAC1 int SOAP_FMAC2 soap_append_lab(struct soap*, const char*, size_t); + +SOAP_FMAC1 struct soap_blist* SOAP_FMAC2 soap_new_block(struct soap*); +SOAP_FMAC1 void* SOAP_FMAC2 soap_push_block(struct soap*, struct soap_blist*, size_t); +SOAP_FMAC1 void SOAP_FMAC2 soap_pop_block(struct soap*, struct soap_blist*); +SOAP_FMAC1 size_t SOAP_FMAC2 soap_size_block(struct soap*, struct soap_blist*, size_t); +SOAP_FMAC1 char* SOAP_FMAC2 soap_first_block(struct soap*, struct soap_blist*); +SOAP_FMAC1 char* SOAP_FMAC2 soap_next_block(struct soap*, struct soap_blist*); +SOAP_FMAC1 size_t SOAP_FMAC2 soap_block_size(struct soap*, struct soap_blist*); +SOAP_FMAC1 char* SOAP_FMAC2 soap_save_block(struct soap*, struct soap_blist*, char*, int); +SOAP_FMAC1 void SOAP_FMAC2 soap_end_block(struct soap*, struct soap_blist*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_envelope_begin_out(struct soap*); +SOAP_FMAC1 int soap_envelope_end_out(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_envelope_begin_in(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_envelope_end_in(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_body_begin_out(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_body_end_out(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_body_begin_in(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_body_end_in(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_recv_header(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_response(struct soap*, int); + +SOAP_FMAC1 int SOAP_FMAC2 soap_send_empty_response(struct soap*, int status); +SOAP_FMAC1 int SOAP_FMAC2 soap_recv_empty_response(struct soap*); + +SOAP_FMAC1 int SOAP_FMAC2 soap_send_fault(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_recv_fault(struct soap*); + +#ifndef WITH_NOSTDLIB +SOAP_FMAC1 void SOAP_FMAC2 soap_print_fault(struct soap*, FILE*); +SOAP_FMAC1 void SOAP_FMAC2 soap_print_fault_location(struct soap*, FILE*); +# ifndef WITH_LEAN +# ifdef __cplusplus +SOAP_FMAC1 void SOAP_FMAC2 soap_stream_fault(struct soap*, std::ostream&); +# endif +SOAP_FMAC1 char* SOAP_FMAC2 soap_sprint_fault(struct soap*, char*, size_t); +# endif +#endif + +SOAP_FMAC1 int SOAP_FMAC2 soap_s2byte(struct soap*, const char*, char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2short(struct soap*, const char*, short*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2int(struct soap*, const char*, int*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2long(struct soap*, const char*, long*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2LONG64(struct soap*, const char*, LONG64*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2float(struct soap*, const char*, float*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2double(struct soap*, const char*, double*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2unsignedByte(struct soap*, const char*, unsigned char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2unsignedShort(struct soap*, const char*, unsigned short*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2unsignedInt(struct soap*, const char*, unsigned int*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2unsignedLong(struct soap*, const char*, unsigned long*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2ULONG64(struct soap*, const char*, ULONG64*); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2string(struct soap*, const char*, char**); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2QName(struct soap*, const char*, char**); + +#ifndef WITH_LEAN +SOAP_FMAC1 int SOAP_FMAC2 soap_s2wchar(struct soap*, const char*, wchar_t**); +SOAP_FMAC1 int SOAP_FMAC2 soap_s2dateTime(struct soap*, const char*, time_t*); +SOAP_FMAC1 char* SOAP_FMAC2 soap_s2base64(struct soap*, const unsigned char*, char*, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_s2hex(struct soap*, const unsigned char*, char*, int); +#endif + +SOAP_FMAC1 const char* SOAP_FMAC2 soap_byte2s(struct soap*, char); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_short2s(struct soap*, short); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_int2s(struct soap*, int); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_long2s(struct soap*, long); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_LONG642s(struct soap*, LONG64); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_float2s(struct soap*, float); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_double2s(struct soap*, double); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_unsignedByte2s(struct soap*, unsigned char); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_unsignedShort2s(struct soap*, unsigned short); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_unsignedInt2s(struct soap*, unsigned int); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_unsignedLong2s(struct soap*, unsigned long); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_ULONG642s(struct soap*, ULONG64); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_QName2s(struct soap*, const char*); + +#ifndef WITH_LEAN +SOAP_FMAC1 const char* SOAP_FMAC2 soap_wchar2s(struct soap*, const wchar_t*); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_dateTime2s(struct soap*, time_t); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_base642s(struct soap*, const char*, char*, size_t, int*); +SOAP_FMAC1 const char* SOAP_FMAC2 soap_hex2s(struct soap*, const char*, char*, size_t, int*); +#endif + + +SOAP_FMAC1 int* SOAP_FMAC2 soap_inint(struct soap*, const char *tag, int *p, const char *, int); +SOAP_FMAC1 char* SOAP_FMAC2 soap_inbyte(struct soap*, const char *tag, char *p, const char *, int); +SOAP_FMAC1 long* SOAP_FMAC2 soap_inlong(struct soap*, const char *tag, long *p, const char *, int); +SOAP_FMAC1 LONG64* SOAP_FMAC2 soap_inLONG64(struct soap*, const char *tag, LONG64 *p, const char *, int); +SOAP_FMAC1 short* SOAP_FMAC2 soap_inshort(struct soap*, const char *tag, short *p, const char *, int); +SOAP_FMAC1 float* SOAP_FMAC2 soap_infloat(struct soap*, const char *tag, float *p, const char *, int); +SOAP_FMAC1 double* SOAP_FMAC2 soap_indouble(struct soap*, const char *tag, double *p, const char *, int); +SOAP_FMAC1 unsigned char* SOAP_FMAC2 soap_inunsignedByte(struct soap*, const char *tag, unsigned char *p, const char *, int); +SOAP_FMAC1 unsigned short* SOAP_FMAC2 soap_inunsignedShort(struct soap*, const char *tag, unsigned short *p, const char *, int); +SOAP_FMAC1 unsigned int* SOAP_FMAC2 soap_inunsignedInt(struct soap*, const char *tag, unsigned int *p, const char *, int); +SOAP_FMAC1 unsigned long* SOAP_FMAC2 soap_inunsignedLong(struct soap*, const char *tag, unsigned long *p, const char *, int); +SOAP_FMAC1 ULONG64* SOAP_FMAC2 soap_inULONG64(struct soap*, const char *tag, ULONG64 *p, const char *, int); +SOAP_FMAC1 char** SOAP_FMAC2 soap_instring(struct soap*, const char *tag, char **p, const char *, int, int, long, long); +SOAP_FMAC1 char** SOAP_FMAC2 soap_inliteral(struct soap*, const char *tag, char **p); + +#ifndef WITH_LEAN +SOAP_FMAC1 time_t* SOAP_FMAC2 soap_indateTime(struct soap*, const char *tag, time_t *p, const char *, int); +SOAP_FMAC1 time_t SOAP_FMAC2 soap_timegm(struct tm*); +#endif + +#ifndef WITH_LEANER +SOAP_FMAC1 wchar_t** SOAP_FMAC2 soap_inwstring(struct soap*, const char *tag, wchar_t **p, const char *, int, long, long); +SOAP_FMAC1 wchar_t** SOAP_FMAC2 soap_inwliteral(struct soap*, const char *tag, wchar_t **p); +#endif + +SOAP_FMAC1 int SOAP_FMAC2 soap_outbyte(struct soap*, const char *tag, int id, const char *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outshort(struct soap*, const char *tag, int id, const short *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outint(struct soap*, const char *tag, int id, const int *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outlong(struct soap*, const char *tag, int id, const long *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outLONG64(struct soap*, const char *tag, int id, const LONG64 *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outfloat(struct soap*, const char *tag, int id, const float *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outdouble(struct soap*, const char *tag, int id, const double *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outunsignedByte(struct soap*, const char *tag, int id, const unsigned char *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outunsignedShort(struct soap*, const char *tag, int id, const unsigned short *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outunsignedInt(struct soap*, const char *tag, int id, const unsigned int *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outunsignedLong(struct soap*, const char *tag, int id, const unsigned long *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outULONG64(struct soap*, const char *tag, int id, const ULONG64 *p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outstring(struct soap*, const char *tag, int id, char *const*p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outliteral(struct soap*, const char *tag, char *const*p, const char *type); + +#ifndef WITH_LEAN +SOAP_FMAC1 int SOAP_FMAC2 soap_outdateTime(struct soap*, const char *tag, int id, const time_t *p, const char *, int); +#endif + +#ifndef WITH_LEANER +SOAP_FMAC1 int SOAP_FMAC2 soap_outwstring(struct soap*, const char *tag, int id, wchar_t *const*p, const char *, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_outwliteral(struct soap*, const char *tag, wchar_t *const*p, const char *type); +#endif + +#ifndef WITH_LEANER +SOAP_FMAC1 int SOAP_FMAC2 soap_attachment(struct soap *, const char*, int, const void*, const struct soap_array*, const char*, const char*, const char*, int, const char*, int); +SOAP_FMAC1 int SOAP_FMAC2 soap_move(struct soap*, long); +SOAP_FMAC1 size_t SOAP_FMAC2 soap_tell(struct soap*); +SOAP_FMAC1 char* SOAP_FMAC2 soap_dime_option(struct soap*, unsigned short, const char*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getdimehdr(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getdime(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putdimehdr(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putdime(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getmimehdr(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_getmime(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putmimehdr(struct soap*, struct soap_multipart*); +SOAP_FMAC1 int SOAP_FMAC2 soap_putmime(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_dime(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_set_mime(struct soap*, const char *boundary, const char *start); +SOAP_FMAC1 void SOAP_FMAC2 soap_clr_dime(struct soap*); +SOAP_FMAC1 void SOAP_FMAC2 soap_clr_mime(struct soap*); +SOAP_FMAC1 int SOAP_FMAC2 soap_set_dime_attachment(struct soap*, char *ptr, size_t size, const char *type, const char *id, unsigned short optype, const char *option); +SOAP_FMAC1 int SOAP_FMAC2 soap_set_mime_attachment(struct soap*, char *ptr, size_t size, enum soap_mime_encoding encoding, const char *type, const char *id, const char *location, const char *description); +SOAP_FMAC1 void SOAP_FMAC2 soap_post_check_mime_attachments(struct soap *soap); +SOAP_FMAC1 int SOAP_FMAC2 soap_check_mime_attachments(struct soap *soap); +SOAP_FMAC1 struct soap_multipart* SOAP_FMAC2 soap_get_mime_attachment(struct soap *soap, void *handle); +SOAP_FMAC1 struct soap_multipart* SOAP_FMAC2 soap_next_multipart(struct soap_multipart*); +SOAP_FMAC1 int SOAP_FMAC2 soap_match_cid(struct soap*, const char*, const char*); +#endif + +SOAP_FMAC1 int SOAP_FMAC2 soap_register_plugin_arg(struct soap*, int (*fcreate)(struct soap*, struct soap_plugin*, void*), void*); +SOAP_FMAC1 void* SOAP_FMAC2 soap_lookup_plugin(struct soap*, const char*); + +SOAP_FMAC1 const char* SOAP_FMAC2 soap_attr_value(struct soap *soap, const char *name, int flag); +SOAP_FMAC1 int SOAP_FMAC2 soap_set_attr(struct soap *soap, const char *name, const char *value); +SOAP_FMAC1 void SOAP_FMAC2 soap_clr_attr(struct soap *soap); + +#ifdef WITH_COOKIES +SOAP_FMAC1 void SOAP_FMAC2 soap_getcookies(struct soap *soap, const char *val); +SOAP_FMAC1 size_t SOAP_FMAC2 soap_encode_cookie(const char*, char*, size_t); +SOAP_FMAC1 extern struct soap_cookie* SOAP_FMAC2 soap_set_cookie(struct soap*, const char*, const char*, const char*, const char*); +SOAP_FMAC1 extern struct soap_cookie* SOAP_FMAC2 soap_cookie(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern char* SOAP_FMAC2 soap_cookie_value(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern char* SOAP_FMAC2 soap_env_cookie_value(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern time_t SOAP_FMAC2 soap_cookie_expire(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern int SOAP_FMAC2 soap_set_cookie_expire(struct soap*, const char*, long, const char*, const char*); +SOAP_FMAC1 extern int SOAP_FMAC2 soap_set_cookie_session(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern int SOAP_FMAC2 soap_clr_cookie_session(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern void SOAP_FMAC2 soap_clr_cookie(struct soap*, const char*, const char*, const char*); +SOAP_FMAC1 extern int SOAP_FMAC2 soap_getenv_cookies(struct soap*); +SOAP_FMAC1 extern struct soap_cookie* SOAP_FMAC2 soap_copy_cookies(struct soap*, const struct soap*); +SOAP_FMAC1 extern void SOAP_FMAC2 soap_free_cookies(struct soap*); +#endif + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif + +#endif diff --git a/naoModule/libnaoqi_files/include/althread/alconditionmanager.h b/naoModule/libnaoqi_files/include/althread/alconditionmanager.h new file mode 100755 index 0000000..e380f80 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alconditionmanager.h @@ -0,0 +1,62 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2010, 2011 All Rights Reserved. +* +* ALConditionManager maintains a list of conditions and +* for each condition a list of those who are waiting for +* the condition. +* +* A call to addCondition adds a named condition. +* A call to waitForCondition waits for the condition to be triggered +* A call to triggerCondition releases all those who are waiting +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALCONDITIONMANAGER_H_ +#define _LIBALTHREAD_ALTHREAD_ALCONDITIONMANAGER_H_ + +#include +#include +#include +#include + +namespace AL +{ + class ALMutex; + class ALCondition; + + class ALTHREAD_API ALConditionManager + { + + public: + ALConditionManager(); + + virtual ~ALConditionManager(); + + /** + * Creates a condition for synchronization between threads + * @param pConditionName The name of the new signal + */ + void addCondition(const std::string &pConditionName); + + /** + * Waits until the named condition is triggered + * @pConditionName The name of the signal to wait for + */ + void waitForCondition(const std::string &pConditionName); + + /** + * Triggers the condition of all those who are waiting + * @param pConditionName The name of the signal to trigger + */ + void triggerCondition(const std::string &pConditionName); + + protected: + typedef std::map, boost::shared_ptr > > TSynchronizerMap; + typedef TSynchronizerMap::iterator ITSynchronizerMap; + + TSynchronizerMap fSynchonizer; + }; +} +#endif // _LIBALTHREAD_ALTHREAD_ALCONDITIONMANAGER_H_ diff --git a/naoModule/libnaoqi_files/include/althread/alcriticalsection.h b/naoModule/libnaoqi_files/include/althread/alcriticalsection.h new file mode 100755 index 0000000..18bd9b5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alcriticalsection.h @@ -0,0 +1,31 @@ +/** +* @author Aldebaran-Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALCRITICALSECTION_H_ +#define _LIBALTHREAD_ALTHREAD_ALCRITICALSECTION_H_ + +#include +#include + +namespace AL +{ + class ALMutex; + + class ALTHREAD_API ALCriticalSection + { + public: + ALCriticalSection(boost::shared_ptr mutex); + ~ALCriticalSection(void); + + void forceUnlockNow(void); + + private: + boost::shared_ptr fMutexSmartPtr; + }; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALCRITICALSECTION_H_ diff --git a/naoModule/libnaoqi_files/include/althread/alcriticalsectionread.h b/naoModule/libnaoqi_files/include/althread/alcriticalsectionread.h new file mode 100755 index 0000000..a1e8d4e --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alcriticalsectionread.h @@ -0,0 +1,28 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONREAD_H_ +#define _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONREAD_H_ + +#include +#include + +namespace AL +{ + class ALMutexRW; + + class ALTHREAD_API ALCriticalSectionRead + { + public: + ALCriticalSectionRead(boost::shared_ptr pMutex); + ~ALCriticalSectionRead(void); + + private: + boost::shared_ptr fMutexSmartPtr; + }; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONREAD_H_ diff --git a/naoModule/libnaoqi_files/include/althread/alcriticalsectionwrite.h b/naoModule/libnaoqi_files/include/althread/alcriticalsectionwrite.h new file mode 100755 index 0000000..a0bd772 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alcriticalsectionwrite.h @@ -0,0 +1,29 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONWRITE_H_ +#define _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONWRITE_H_ + +#include +#include + +namespace AL +{ + class ALMutexRW; + + class ALTHREAD_API ALCriticalSectionWrite + { + public: + ALCriticalSectionWrite(boost::shared_ptr pMutex); + ~ALCriticalSectionWrite(void); + + private: + boost::shared_ptr fMutexSmartPtr; + }; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALCRITICALSECTIONWRITE_H_ diff --git a/naoModule/libnaoqi_files/include/althread/alcriticaltrueiflocked.h b/naoModule/libnaoqi_files/include/althread/alcriticaltrueiflocked.h new file mode 100755 index 0000000..9d88a40 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alcriticaltrueiflocked.h @@ -0,0 +1,31 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALCRITICALTRUEIFLOCKED_H_ +#define _LIBALTHREAD_ALTHREAD_ALCRITICALTRUEIFLOCKED_H_ + +#include +#include + +namespace AL +{ + class ALMutex; + + class ALTHREAD_API ALCriticalTrueIfLocked + { + public: + ALCriticalTrueIfLocked(boost::shared_ptr mutex, bool &alreadyLocked); + ~ALCriticalTrueIfLocked(void); + + void forceUnlockNow(void); + + private: + void *fMutex; + bool fAlreadyLocked; + }; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALCRITICALTRUEIFLOCKED_H_ diff --git a/naoModule/libnaoqi_files/include/althread/almonitor.h b/naoModule/libnaoqi_files/include/althread/almonitor.h new file mode 100755 index 0000000..d06c3aa --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/almonitor.h @@ -0,0 +1,86 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALMONITOR_H_ +#define _LIBALTHREAD_ALTHREAD_ALMONITOR_H_ + +#include +#include +#include + +namespace AL +{ + class ALMutex; + class ALThreadPool; + class ALTask; + + class ALTHREAD_API ALMonitor + { + public: + + /** + * \brief Constructor. Init cycle, threshold, offset and reference to pool. + * + * Intialize all variables : cycle, threshold (in seconds), offset and reference to the pool. + */ + ALMonitor(int pUpdateCycle, + int pUpdateThreshold, + int pUdpateOffset, + boost::shared_ptr pThreadPool); + + /** + * \brief Destructor. Nothing to do. + * + * Nothing to do. + */ + ~ALMonitor(); + + /** + * \brief assimilate. Take a task, read datas and update stats. + * + * Assimilate take a task and read idle and execution time of the task. Adjust the + * number of thread according to these stats. + * + * @param pTask task to study. + */ + void assimilate(boost::shared_ptr pTask); + + /** + * \brief adjustPool. Readjust the thread number according to its stats. + * + * This function will adjust the number of threads in the pool according to the + * needs of the program. See the documentation to know which algorithm is used. + */ + void adjustPool(); + + private: + + //! Associated Thread Pool + boost::shared_ptr fThreadPool; + + //! Mutex for task assimilation + boost::shared_ptr fAssimilator; + + //! Number of cycle between each thread adjustment + int fUpdateCycle; + + //! Threshold from which an update is done (in seconds of idle time) + int fUpdateThreshold; + + //! Number of thread added or removed at each adjustment + int fUpdateOffset; + + //! Counter of cycle + int fCounterCycle; + + // int fTaskIdle; // WARNING: limits to 1h11 + qi::os::timeval fTaskIdle; + + int fThreadIdle; + }; +} //namespace AL +#endif // _LIBALTHREAD_ALTHREAD_ALMONITOR_H_ diff --git a/naoModule/libnaoqi_files/include/althread/almutex.h b/naoModule/libnaoqi_files/include/althread/almutex.h new file mode 100755 index 0000000..48b5ab0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/almutex.h @@ -0,0 +1,77 @@ +/** +* @author Aldebaran-robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALMUTEX_H_ +#define _LIBALTHREAD_ALTHREAD_ALMUTEX_H_ + +#include +#include + +namespace AL +{ + class ALTHREAD_API ALMutex + { + friend class ALCriticalSection; + friend class ALCriticalTrueIfLocked; + friend class ALCondition; + + public: + static boost::shared_ptr createALMutex(); + virtual ~ALMutex(void); + + void lock(); + void unlock(); + + protected: + ALMutex(); + + private: + //pthread_mutex_t* + void *fMutex; + }; + + + class ALTHREAD_API ALMutexRW + { + friend class ALCriticalSectionRead; + friend class ALCriticalSectionWrite; + + public: + static boost::shared_ptr createALMutexRW(); + virtual ~ALMutexRW(void); + + void readLock(); + void writeLock(); + void unlock(); + + protected: + ALMutexRW(); + + private: + //pthread_rwlock_t + void *fMutex; + }; + + + class ALTHREAD_API ALCondition + { + public: + static boost::shared_ptr createALCondition(); + void wait(boost::shared_ptr pMutex); + void broadcast(); + void signal(); + virtual ~ALCondition(void); + + protected: + ALCondition(); + + private: + //pthread_cond_t + void *fCondition; + }; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALMUTEX_H_ diff --git a/naoModule/libnaoqi_files/include/althread/alprocesssignals.h b/naoModule/libnaoqi_files/include/althread/alprocesssignals.h new file mode 100755 index 0000000..40a4c8e --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/alprocesssignals.h @@ -0,0 +1,91 @@ +/** +* @author Aldebaran Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved. +* +* +* ALProcessSignals offers two signals: preProcess and postProcesss. +* Connected method pointers will be called in the host thread's context. +* +* Typically this is used as a base class of a class which does recurrent +* processing. Other classes can attach themselves to the preProcess or +* postProcess so that they can do small ammounts of work at a specific +* point of a processing loop. Please note that all attached workers +* will do their work in your context. If you are in a real time thread +* they will also be in a real time thread, and should respect the +* constraints that this implies. +* +* call preProcess +* -> all connected methods are called +* ... do your work ... +* call postProcess +* -> all connected methods are called +* ... possibly sleep until next time you want to work +* +* See althread/alconditionmanager.h for a sychronizer that is based +* on conditions rather than signals so that work takes place is other +* threads. +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALPROCESSSIGNALS_H_ +#define _LIBALTHREAD_ALTHREAD_ALPROCESSSIGNALS_H_ + +#include +#include + +namespace AL +{ + class ALProcessSignals + { + public : + ALProcessSignals() {} + ~ALProcessSignals() {} + + typedef boost::signal ProcessSignal; + typedef boost::signal::slot_function_type ProcessSignalSlot; + typedef boost::signals::connect_position ProcessSignalPosition; + typedef boost::signals::connection ProcessSignalConnection; + + /** + * Connect to the preProcess signal + */ + inline ProcessSignalConnection atPreProcess( + ProcessSignalSlot subscriber, + ProcessSignalPosition pos = boost::signals::at_back) + { + return fPreProcess.connect(subscriber, pos); + } + + /// Connect to the postProcess signal + inline ProcessSignalConnection atPostProcess( + ProcessSignalSlot subscriber, + ProcessSignalPosition pos = boost::signals::at_back) + { + return fPostProcess.connect(subscriber, pos); + } + + inline void removeAllPreProcess(void) { + fPreProcess.disconnect_all_slots(); + } + + inline void removeAllPostProcess(void) { + fPostProcess.disconnect_all_slots(); + } + + /// Trigger methods attached to preProcess + inline void preProcess(void) { + fPreProcess(); + } + + /// Trigger methods attached to postProcess + inline void postProcess(void) { + fPostProcess(); + } + + protected: + ProcessSignal fPreProcess; + ProcessSignal fPostProcess; + }; +} +#endif // _LIBALTHREAD_ALTHREAD_ALPROCESSSIGNALS_H_ diff --git a/naoModule/libnaoqi_files/include/althread/altask.h b/naoModule/libnaoqi_files/include/althread/altask.h new file mode 100755 index 0000000..b54b5ee --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/altask.h @@ -0,0 +1,148 @@ +/** +* @author Aldebaran-Robotics +* Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved +*/ + + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALTASK_H_ +#define _LIBALTHREAD_ALTHREAD_ALTASK_H_ + +#include +#include +#include +#include +#include + +namespace AL +{ + class ALThread; + + class ALTHREAD_API ALTask + { + public: + + /** + * Indicates the state of the task, it is either IDLE, RUNNING or ENDED + */ + typedef enum { IDLE, RUNNING, ENDED } ALTPState; + + /** + * Constructor. User defined. Must stock in private fields run parameters. + * + * Defined by users. If a user wants to access to some parameters during execution, + * he should stock them as private fields. + */ + ALTask(); + + /** + * Users may define their own destructors while constructing their class. + */ + virtual ~ALTask(); + + /** + * Instruction to run in the thread. parameters should be private members of the + * class. User should use privete members to get the result too. + */ + virtual void run() = 0; + + virtual void exitTask() {} + + /** + * @brief Set the name of the task. + * @param name the name of the task. + */ + void setTaskName(const std::string& pName); + + private: + /** + * setCreationTime + */ + void setCreationTime(); + + /** + * setExecutionTime + * Execution task time + */ + void setExecutionTime(); + + /** + * setEndTime + * End task time + */ + void setEndTime(); + + public : + /** + * Thread affectation + */ + void setThread(boost::shared_ptr pThread); + + /** + * set state machine + */ + void setState(ALTPState pState) + { + fState = pState; + } + + /** + * Get the name of the task. + * @return name the name of the task. + */ + virtual const std::string& getTaskName () const; + + /** + * getIdleTime + * return IdleTime in usec. + */ + int getIdleTime(); + + /** + * getExecutionTime + * return execution time in usec. + */ + int getExecutionTime(); + + + /** + * getThread + * return ALThread. + */ + boost::weak_ptr getThread() { + return fThread; + } + + /** + * getState + * return machine state + */ + ALTPState getState() { + return fState; + } + + void waitForEndOfTask(); + + std::string toString() const; + + /** + * fAutoDelete + * Tell if the task must be deleted after the treatment + */ + bool fAutoDelete; + + private: + std::string fName; + struct qi::os::timeval fCreationTime; + struct qi::os::timeval fExecutionTime; + struct qi::os::timeval fEndTime; + + // State of the task : IDLE / RUNNING / ENDED + volatile ALTPState fState; + + protected: + // Thread treating this task + boost::weak_ptr fThread; + }; +} // namespace AL +#endif // _LIBALTHREAD_ALTHREAD_ALTASK_H_ diff --git a/naoModule/libnaoqi_files/include/althread/althread.h b/naoModule/libnaoqi_files/include/althread/althread.h new file mode 100755 index 0000000..8b5e7db --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/althread.h @@ -0,0 +1,192 @@ +/** + * @author Aldebaran-Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALTHREAD_H_ +#define _LIBALTHREAD_ALTHREAD_ALTHREAD_H_ + +#include +#include +#include +#include +#include +#include +#include + +namespace AL +{ + ALTHREAD_API void * _AL_Thread_Pool_Atom(void * pALThread); + + class ALMutex; + class ALMutexRW; + class ALCondition; + + class ALTHREAD_API ALThread: public ::boost::enable_shared_from_this + { + friend void * _AL_Thread_Pool_Atom(void * pALThread); + + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + typedef boost::weak_ptr WeakPtr; + typedef boost::weak_ptr WeakConstPtr; + + inline boost::shared_ptr getThis() { + return ::boost::enable_shared_from_this::shared_from_this(); + } + + inline boost::shared_ptr getThis() const { + return ::boost::enable_shared_from_this::shared_from_this(); + } + + /** + * \brief Constructor. Enqueue the thread in the thread pool. + * + * Create the structure and enqueue the thread into the thread pool. + * Store the unique ID of the thread for its future destruction. + * + * @param pThreadPool the thread pool managing this thread. + * @param pID unique ID of the thread + * @param pThreadWait mutex blocking a task when it has nothing to do + * @param pWaitForTask cond associated to the mutex + */ + ALThread(boost::shared_ptr pThreadPool, + int pID, + boost::shared_ptr pThreadWait, + boost::shared_ptr pWaitForTask + ); + + /** + * Do nothing. + */ + ~ALThread(); + + /** + * Create and launch the pthread + * @return pthread_create error code + */ + int launch(); + + /** + * Give a new task to the thread. + * @return true if a task is assigned. + */ + bool getTask(); + + /** + * Start the new task. + */ + void runTask(); + + /** + * \brief setStackSize. set default thread stack size + */ + static void setStackSize(int pStackSize); + + /** + * \brief setThreadName. set the name of the calling thread (as visible in + * debuggers) + */ + static void setThreadName(const char* pName); + + /** + * \brief apoptosis. Asks the pool for dying. + * + * Thread scheduling implies creating threads when needed but also deleting threads + * when they are no more needed. This function asks the pool thread if the thread + * is still needed or not. + * + * @return true if the thread should kill itself. + */ + bool apoptosis(); + + /** + * \brief setID. Set a new ID to the thread + * + * Since a thread ID is its position in the pool, it can be moved and this ID can + * change. This function, called ONLY by the thread pool, is here for this purpose + * + * @param pID new ID + */ + void setID(int pID) + { + fID = pID; + } + + /** + * Return the ThreadID + * @return Thread ID + */ + pthread_t getThreadID() + { + return fThreadID; + } + + /** + * Return the ID of the thread + * @return ID + */ + int getID() + { + return fID; + } + + struct qi::os::timeval GetIdleSum(void) const + { + return fIdleSum; + } + + void ResetIdleSum(void) + { + fIdleSum.tv_sec = 0; + fIdleSum.tv_usec = 0; + } + + protected: + // Mutex to stop execution of thread if no task + boost::shared_ptr fThreadWait; + // Blocking condition + boost::shared_ptr fWaitForTask; + // Task Mutex + boost::shared_ptr fTaskMutex; + + public: + inline boost::shared_ptr getThreadPool(void) + { + boost::shared_ptr returnPtr = fThreadPool.lock(); + // it can be possible that the task has to thread pool, but this function should never be called when it's the case. + // indeed the thread pool set the task to kill itself when that's the case, and therefore it should exit the thread. + return returnPtr; + } + + /** + * This thread has been ask to kill its pthread. You just have to wake it up now ! + */ + void killThread(); + + private : + // last time of beginning of an idle period + struct qi::os::timeval fIdleDate; + + // Thread Idle Time (in usec) + // int fIdleTime; // limited to duration shorter than 1h11 !!!!! + struct qi::os::timeval fIdleSum; + + // Unique ID of the thread. + int fID; + + // Unique ID of the pthread + pthread_t fThreadID; + + // Parent Thread Pool + boost::weak_ptr fThreadPool; + + bool fKillThread; + + // Current task + boost::shared_ptr fTask; // not owned (set to NULL if no task) + }; +} +#endif // _LIBALTHREAD_ALTHREAD_ALTHREAD_H_ diff --git a/naoModule/libnaoqi_files/include/althread/althreadpool.h b/naoModule/libnaoqi_files/include/althread/althreadpool.h new file mode 100755 index 0000000..7e03048 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/althreadpool.h @@ -0,0 +1,286 @@ +/** + * @author Aldebaran-Robotics + * Copyright (c) Aldebaran Robotics 2007 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_ALTHREADPOOL_H_ +#define _LIBALTHREAD_ALTHREAD_ALTHREADPOOL_H_ + +#define POOL_INITIAL_THREAD 92 +#define POOL_MAX_THREAD 184 +#define POOL_UPDATE_CYCLE 800 +#define POOL_UPDATE_THRESHOLD 500 +#define POOL_UPDATE_OFFSET 0 + +#define AL_THREAD_POOL_STOP_KILL true +#define AL_THREAD_POOL_STOP_WAIT false + + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER + //provide struct timeval (from BSD netstack) + #include +#else + #include +#endif + +namespace AL +{ +class ALTask; +class ALThread; +class ALMonitor; +class ALMutex; +class ALMutexRW; +class ALCondition; + +class ALThreadPool: public ::boost::enable_shared_from_this +{ + public: + typedef boost::shared_ptr Ptr; + typedef boost::shared_ptr ConstPtr; + typedef boost::weak_ptr WeakPtr; + typedef boost::weak_ptr WeakConstPtr; + + inline boost::shared_ptr getThis() { + return ::boost::enable_shared_from_this::shared_from_this(); + } + + inline boost::shared_ptr getThis() const { + return ::boost::enable_shared_from_this::shared_from_this(); + } + + void init(int pInitialThread, + int pMaxThread, + int pUpdateCycle, + int pUpdateThreshold, + int pUpdateOffset); + + /** + * \brief Constructor. Init the pool of thread, the queue of task and the monitor. + * + * The constructor init the queue of thread with pInitialThread threads. It also + * init the monitor dans make the pool ready to get a task. + * + * @param pInitialThread initial number of thread (default is POOL_INITIAL_THREAD). + * @param pMaxThread maximum number of thread (default is POOL_MAX_THREAD). + * @param pUpdateCycle number of task between each thread pool adjustment + * (default is POOL_UPDATE_CYCLE) + * @param pUpdateThreshold (in percent) threshold from which an adjustement is done + * (default is POOL_UPDATE_THRESHOLD, see monitor documentation) + * @param pUpdateOffset number of thread created or destroyed at each adjustment. + * (default is POOL_UPDATE_OFFSET) + */ + + ALThreadPool ( + int pInitialThread = POOL_INITIAL_THREAD, + int pMaxThread = POOL_MAX_THREAD, + int pUpdateCycle = POOL_UPDATE_CYCLE, + int pUpdateThreshold = POOL_UPDATE_THRESHOLD, + int pUpdateOffset = POOL_UPDATE_OFFSET); + + + /** + * Free all memory, destruct dependecies + * + * @param pKillProcess AL_THREAD_POOL_STOP_KILL (= true) if all working threads must be killed + * (default is AL_THREAD_POOL_STOP_WAIT (=false)) + */ + ~ALThreadPool(); + + /** + * Shutdown the process, wait or kill all working threads. + * + * If pKillProcess is set to AL_THREAD_POOL_STOP_KILL, all working threads are destroyed whereas + * if it is not set or set to AL_THREAD_POOL_STOP_WAIT, it will wait termination of all threads + * before deleting them. It also send back waiting tasks. + * After the shutdown, ThreadPool is ready to be deleted. Any function call + * behaviour is undefined. + * + * @param pKillProcess AL_THREAD_POOL_STOP_KILL (= true) if all working threads must be killed + * (default is AL_THREAD_POOL_STOP_WAIT (=false)) + */ + + void shutdown(bool pKillProcess = AL_THREAD_POOL_STOP_WAIT); + + /** + * Enqueue the task and launch the dispatch. + * + * @param pTask task to treat. + * @return the unique ID of the task (maybe to enable pausing later?) + */ + int enqueue(boost::shared_ptr pTask); + + /** + * \brief adjustThread. Allow the monitor ONLY to add or remove new threads. + * + * Add or remove pNbThread. If some threads must be removed and all are working, + * the thread pool will wait for a thread to finish and kill it. The parameter + * is given there if someone wants to make a dynamic adjustment of the update + * offset. + * If the new thread number is contained between 0 and max thread, the adjustment + * is done, whereas nothing is done. + * + * @param pNbThread number of thread to add or remove. + * @return true if the adjustment is done, false otherwise. + */ + + bool adjustThread(int pNbThread); + + /** + * \brief taskEnded. Treat an ended task. + * + * Take the ended task and send it to the monitor. Then put its termination flag. + * (maybe send a callback?) + * + * @param pTask ended task + */ + void taskEnded(boost::shared_ptr pTask); + + + /** + * \brief getTask. Return a waiting task if any. + * + * Called by a free Thread, this function return a waiting task if there is one + * or NULL in order to make the thread wait. + * + * @return a pointer to a task + */ + boost::shared_ptr getTask(); + + /** + * \brief apoptosis. Tell a thread if it must kill itself. + * + * Thread scheduling implies creating threads when needed but also deleting threads + * when they are no more needed. This function is called by a thread when its task + * is finished in order to know if it must kill itself. + * + * @param pThread the thread calling the function + * + * @return true if the thread should kill itself. + */ + bool apoptosis(boost::shared_ptr pThread); + + /** + * \brief getNbThread. Return the current number of thread. + * + * This function is for diagnostic purpose. + * + * @return the number of thread + */ + int getNbThread() + { + return fNbThread; + } + + /** + * \brief getNbTask waiting for a thread + * + * This function is for diagnostic purpose. + * + * @return the number of task + */ + int getNbTask() + { + return fWaitingTasks.size(); + } + + + /** + * \brief computeSumThreadIdle. Compute the sum of idle time of each thread. + * + * WARNING: please don't call it too much often... + * + * @return a timeval containing the sum + */ + qi::os::timeval computeSumThreadIdle(void); // can't const because mutex use + + void resetSumThreadIdle(void); + + inline void increaseUsedThread() + { + ALCriticalSectionWrite sectionNbThread(fUsedThreadMutex); + fUsedThread++; + } + + inline void decreaseUsedThread() + { + ALCriticalSectionWrite sectionNbThread(fUsedThreadMutex); + fUsedThread--; + } + + inline int getUsedThread() + { + ALCriticalSectionRead sectionNbThread(fUsedThreadMutex); + return fUsedThread; + } + + private: + + /** + * xIncreaseThread. Increase the number of thread. (same as adjustThread, but simpler, tested and working) + * + * @return true if the enlargement is done, false otherwise. + */ + bool xIncreaseThread(void); + +private: + + // ! Number of cycle between each thread adjustment + int fUpdateCycle; + + // ! Threshold from which an update is done (in seconds of idle time) + int fUpdateThreshold; + + // ! Number of thread added or removed at each adjustment + int fUpdateOffset; + + // ! Array of threads + std::vector > fThreadPool; + + // HACK we dont want to destroy remanining altask (thread are not killed when we call shutdown.. too lame + std::vector > fThreadPoolRestHome; + + // ! Queue of tasks waiting to be executed + std::queue > fWaitingTasks; + + // ! Number of threads + int fNbThread; + + // ! Max number of threadsb + int fMaxThread; + + // ! Monitor adjusting the pool parameters. + boost::shared_ptr fMonitor; + + // ! Number of threads to be killed (to be removed) + int fnbrSuperfluThreads; + + // ! fThreadPool Mutex + const boost::shared_ptr fThreadPoolMutex; + + // ! fThreadPool Mutex + boost::shared_ptr fUsedThreadMutex; + + + // ! fWaitingTasks Mutex + const boost::shared_ptr fWaitingTasksMutex; + + // ! global mutex for waiting + const boost::shared_ptr fThreadWait; + + // ! global condition to wait + const boost::shared_ptr fWaitForTask; + + int fUsedThread; +}; +} + +#endif // _LIBALTHREAD_ALTHREAD_ALTHREADPOOL_H_ diff --git a/naoModule/libnaoqi_files/include/althread/config.h b/naoModule/libnaoqi_files/include/althread/config.h new file mode 100755 index 0000000..2133233 --- /dev/null +++ b/naoModule/libnaoqi_files/include/althread/config.h @@ -0,0 +1,27 @@ +/** + * Author(s): + * - Cedric GESTES + * + * Copyright (C) 2011 Aldebaran Robotics + */ + +/** @file + * @brief dll import/export + */ + +#pragma once +#ifndef _LIBALTHREAD_ALTHREAD_CONFIG_H_ +#define _LIBALTHREAD_ALTHREAD_CONFIG_H_ + +#include + +#ifdef althread_EXPORTS +# define ALTHREAD_API QI_EXPORT_API +#elif defined(althread_IMPORTS) +# define ALTHREAD_API QI_IMPORT_API +#else +# define ALTHREAD_API +#endif + +#endif // _LIBALTHREAD_ALTHREAD_CONFIG_H_ + diff --git a/naoModule/libnaoqi_files/include/alvalue/alvalue.h b/naoModule/libnaoqi_files/include/alvalue/alvalue.h new file mode 100755 index 0000000..a15a4e8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvalue/alvalue.h @@ -0,0 +1,907 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2007, 2011 All Rights Reserved + */ + +/** @file + * @brief + */ + +#pragma once +#ifndef _LIBALVALUE_ALVALUE_ALVALUE_H_ +#define _LIBALVALUE_ALVALUE_ALVALUE_H_ + +# include +# include +# include + +# include + +namespace AL +{ + +/** + * \def ALVALUE_VERBOSITY + * \brief Definition of the ALValue verbosity. + */ +#ifndef ALVALUE_VERBOSITY +# define ALVALUE_VERBOSITY + /** + * @enum _TVerbosity + * plop + * @typedef enum AL::_TVerbosity Verbosity + * ALValue verbosity level + */ + typedef enum ALVALUE_API _TVerbosity + { + VerbosityNone=0, /**< none */ + VerbosityMini, /**< address, type, value */ + VerbosityMedium, /**< all information on one line */ + VerbosityFull /**< all infromation on some line and xml */ + } Verbosity; +#endif + + /** + * \class ALValue alvalue.h "alvalue/alvalue.h" + * \brief ALValue is a class to manipulate differente value type. + * + * It's using to convert multiple value type to one type, to ease the + * communication or storage of differente values. + * \ingroup libalvalue + */ + class ALVALUE_API ALValue + { + friend void ConvertALValueToSoapXml(const ALValue *pAlValue, + std::string &strToFill, + bool bInAnArray); + friend class ALNetwork; + + public: + /** + * \typedef TALValueInt + * \brief Type definition to int. + */ + typedef int TALValueInt; + /** + * \typedef TALValueFloat + * \brief Type definition to float. + */ + typedef float TALValueFloat; + /** + * \typedef TALValueDouble + * \brief Type definition to double. + */ + typedef double TALValueDouble; + /** + * \typedef TALValueBool + * \brief Type definition to bool. + */ + typedef bool TALValueBool; + /** + * \typedef TALValueString + * \brief Type definition to std::string. + */ + typedef std::string TALValueString; + + /** + * \typedef TAlValueBinaryData + * \brief Vector of unsigned char used for binary data. + */ + typedef std::vector TAlValueBinaryData; + /** + * \typedef ITAlValueBinaryData + * \brief Iterator to a vector of unsigned char used for binary data. + */ + typedef TAlValueBinaryData::iterator ITAlValueBinaryData; + /** + * \typedef CITAlValueBinaryData + * \brief Const iterator to a vector of unsigned char used for binary data. + */ + typedef TAlValueBinaryData::const_iterator CITAlValueBinaryData; + + /** + * \typedef TAlValueArray + * \brief Vector of ALValue. + */ + typedef std::vector TAlValueArray; + /** + * \typedef ITAlValueArray + * \brief Iterator to a vector of ALValue. + */ + typedef TAlValueArray::iterator ITAlValueArray; + /** + * \typedef CITAlValueArray + * \brief Const iterator to a vector of ALValue. + */ + typedef TAlValueArray::const_iterator CITAlValueArray; + + /** + * \union unionValue alvalue.h "alvalue/alvalue.h" + * \brief unionValue is a union to different type of ALValue. + */ + union unionValue { + TAlValueArray *asArray; /**< Used for vector of ALValue */ + TALValueBool asBool; /**< Used for boolean */ + TALValueInt asInt; /**< Used for integer */ + TALValueFloat asFloat; /**< Used for float and double */ + TALValueString *asString; /**< Used for std::string */ + TAlValueBinaryData *asObject; /**< Used for binary object */ + TAlValueBinaryData *asBinary; /**< Used for binary data */ + }; + + public: + /** + * \enum Type + * \brief Type of ALValue. + * \warning this enum order matter, it is used in paramtype.h + * \warning double support cannot be added. + * This would break: + \code + ALValue v; + v = 0.1; \endcode + * sometime the compiler will use the double constructor instead + * of the float one, breaking too much user code. + */ + enum Type { + TypeInvalid = 0, /**< Invalid type. */ + TypeArray, /**< Array type. */ + TypeBool, /**< Boolean type. */ + TypeInt, /**< Integer type. */ + TypeFloat, /**< Float type. */ + TypeString, /**< String type. */ + TypeObject, /**< Object type. */ + TypeBinary /**< Base64 type. */ + }; + + public: + /** \brief Default constructor. */ + ALValue(); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const bool &value); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const int &value); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const double &value); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const float &value); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const std::string &value); + /** + * \brief Constructor. + * \param value value of the ALValue + */ + ALValue(const char *value); + + /** + * \brief Constructor. + * \param pListString value of the ALValue + */ + ALValue(const std::vector &pListString); + /** + * \brief Constructor. + * \param pListFloat value of the ALValue + */ + ALValue(const std::vector &pListFloat); + /** + * \brief Constructor. + * \param pListInt value of the ALValue + */ + ALValue(const std::vector &pListInt); + + /** + * \brief Constructor. + * \param value value of the ALValue + * \param nBytes size of the value + */ + ALValue(const void *value, int nBytes); + /** + * \brief Constructor. + * \param pArrayOfString value of the ALValue + * \param nNbrString string's number + */ + ALValue(const char **pArrayOfString, int nNbrString); + /** + * \brief Constructor. + * \param pFloat value of the ALValue + * \param nNbrElement float's number + */ + ALValue(const float *pFloat, int nNbrElement); + /** + * \brief Constructor. + * \param pInt value of the ALValue + * \param nNbrElement int's number + */ + ALValue(const int *pInt, int nNbrElement); + + /** + * \brief Copy constructor form binary data. + * \param rhs value copied + */ + ALValue(const TAlValueBinaryData &rhs); + /** + * \brief Copy constructor + * \param rhs value copied + */ + ALValue(ALValue const &rhs); + + /** \brief Desctuctor. */ + virtual ~ALValue(); + + /** \brief Erase the current value. */ + void clear(); + + /** + * \brief Makes a copy of rhs, discarding previous content, + * so that the new content of is equivalent in both type + * and value to rhs. + * \param rhs value copied + */ + ALValue& operator=(const ALValue &rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const bool &rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const int &rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const double &rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const float &rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const char *rhs); + /** \copydoc ALValue::operator= */ + ALValue& operator=(const TAlValueBinaryData &rhs); + + /** + * \brief alvalue.Type == other.alvalue.Type + * && alvalue.unionValue == other.alvalue.unionValue + * \return true if equal ALValue, false otherwise + */ + bool operator==(ALValue const &other) const; + /** + * \brief alvalue.Type != other.alvalue.Type + * && alvalue.unionValue != other.alvalue.unionValue + * \return true if not equal ALValue, false otherwise + */ + bool operator!=(ALValue const &other) const; + + /** + * \brief Conversion operator to bool. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator bool&(); + /** + * \brief Conversion operator to const bool. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const bool() const; + /** + * \brief Conversion operator to int. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator int&(); + /** + * \brief Conversion operator to const int. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const int() const; + /** + * \brief Conversion operator to float. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator float&(); + /** + * \brief Conversion operator to const float. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const float() const; + + /** + * \brief Conversion operator to const double. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const double() const; + + /** + * \brief Conversion operator to std::string. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator std::string&(); + /** + * \brief Conversion operator to const std::string. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const std::string&() const; + + /** + * \brief Conversion operator to binary data. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator TAlValueBinaryData&(); + /** + * \brief Conversion operator to const binary data. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const TAlValueBinaryData&() const; + /** + * \brief Conversion operator to const void*. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator const void*() const; + + /** + * \typedef TStringArray + * \brief Vector of std::string. + */ + typedef std::vector TStringArray; + /** + * \typedef TFloatArray + * \brief Vector of float. + */ + typedef std::vector TFloatArray; + /** + * \typedef TIntArray + * \brief Vector of int. + */ + typedef std::vector TIntArray; + + /** + * \brief Conversion operator to a vector of stf::string. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator TStringArray() const; + /** + * \brief Conversion operator to a vector of float. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator TFloatArray() const; + /** + * \brief Conversion operator to a vector of int. + * + * Assert the object is compatible with a wanted type. + * If the object is unitialiazed, it will be changed to the good type + * \throw ALERROR + */ + operator TIntArray() const; + + /** + * \brief Set ALValue with an object data. + * \param pData pointer to data + * \param nDataSizeInBytes data's size + * \return ALValue with the data. + */ + ALValue& setObject(const void* pData, int nDataSizeInBytes); + + /** + * \brief Set ALValue with a binary data. + * \param rhs pointer to data + * \param nDataSizeInBytes data's size + */ + void SetBinary(const void *rhs, int nDataSizeInBytes); + /** + * \brief Set ALValue with a binary data. It won't copy the data. + * \param rhs pointer to data + * \param nDataSizeInBytes (unused) + * \return ALValue with the data. + */ + ALValue& SetBinaryNoCopy(const void *rhs, int nDataSizeInBytes); + + /** + * \brief Explicit operator to convert to const void* + * \return A pointer on value. + */ + const void* GetBinary() const; + /** + * \brief Explicit operator to convert to const void* + * \return A pointer on value. + */ + const void* getObject() const; + + /** + * \brief Get pointer on value, only allowed with 32bits variable. + * \return A pointer on value. + */ + void *getPtrValue(); + + /** + * \brief Explicit convert to vector. + * + * \param pArrayToFill the value to fill with string value from the ALValue + * \param bInsertDefaultOnError a flag to inform what to do on a not wanted + * type. If set to false, invalid value are + * skipped, on true empty string will be + * inserted in the vector + */ + void ToStringArray(TStringArray &pArrayToFill, + bool bInsertDefaultOnError = false) const; + /** + * \brief Explicit convert to vector. + * + * \param pArrayToFill the value to fill with string value from the ALValue + * \param bInsertDefaultOnError a flag to inform what to do on a not wanted + * type. If set to false, invalid value are + * skipped, on true empty string will be + * inserted in the vector + */ + void ToFloatArray(TFloatArray &pArrayToFill, + bool bInsertDefaultOnError = false) const; + /** + * \brief Explicit convert to vector. + * + * \param pArrayToFill the value to fill with string value from the ALValue + * \param bInsertDefaultOnError a flag to inform what to do on a not wanted + * type. If set to false, invalid value are + * skipped, on true empty string will be + * inserted in the vector + */ + void ToIntArray(TIntArray &pArrayToFill, + bool bInsertDefaultOnError = false) const; + + + /** + * \brief Get a reference to the ALValue at position i in the vector. + * \param i position in the vector + * \return a reference to the ALValue + * \throw ALERROR if alvalue.type != TypeArray || i out of range. + */ + ALValue& operator[](int i); + + /** + * \brief Get a reference to the ALValue at position i in the vector. + * \param i position in the vector + * \return a reference to the ALValue + * \throw ALERROR if alvalue.type != TypeArray || i out of range. + */ + const ALValue& operator[](int i) const; + + /** + * \brief Gat the type of the stored value. \see Type. + * \return the type of the value. + */ + enum Type getType() const; + + /** + * \brief Check if the value has been set. + * \return true if alvalue.type != TypeInvalid, false otherswise + */ + bool isValid () const; + /** + * \brief Check if the value is an array. + * \return true if alvalue.type == TypeArray, false otherswise + */ + bool isArray () const; + /** + * \brief Check if the value is a boolean. + * \return true if alvalue.type == TypeBool, false otherswise + */ + bool isBool () const; + /** + * \brief Check if the value is an integer. + * \return true if alvalue.type == TypeInt, false otherswise + */ + bool isInt () const; + /** + * \brief Check if the value is a float. + * \return true if alvalue.type == TypeFloat, false otherswise + */ + bool isFloat () const; + /** + * \brief Check if the value is a string. + * \return true if alvalue.type == TypeString, false otherswise + */ + bool isString() const; + /** + * \brief Check if the value is a binary object. + * \return true if alvalue.type == TypeObject, false otherswise + */ + bool isObject() const; + /** + * \brief Check if the value is a binary. + * \return true if alvalue.type == TypeBinary, false otherswise + */ + bool isBinary() const; + /** + * \brief Get raw value of. + * \return std::vector of object and binary. + */ + std::vector asRaw() const; + + /** + * \brief Get the size for string, objectm array, binary, invalid values. + * \return the size of the ALValue (0 if alvalue.type == InvalidType) + * \throw ALERROR if the value is null + */ + unsigned int getSize() const; + + + /** + * \brief Specify the size the array values will use. + * + * Requests that the capacity of the allocated storage space + * for the ALValue of the vector container be at least enough + * to hold \a size elements. + * \param size minimum amount desired as capacity of allocated storage + * \throw ALError if alvalue.type != TypeArray + */ + void arrayReserve(int size); + + /** + * \brief Specify the size of the array + * this will call vector::resize + * \param size the new size of the array + */ + void arraySetSize(int size); + + /** + * \brief Adds a new element at the end of the vector, + * after its current last element. + * + * The content of this new element is initialized to a copy of + * \a pSrcToCopyNotOwned. + * \param pSrcToCopyNotOwned Value to be copied to the new element. + * Push a new value in the array + */ + void arrayPush(const ALValue &pSrcToCopyNotOwned); + + /** + ** \brief Pop the first element of the array. Deleting it. + ** + ** Does completely delete the first element of the array, if the + ** AL::ALValue is an array, and if it is not empty. + ** + */ + void arrayPopFront(); + + /** + * \brief Get a string describing this object, for debug purpose. + * \param pnVerbosity style of ouput format + * \warning the VerbosityMini style is used in some code, + * it's the minimal description of the contents of an alvalue, + * with [] to describe array. + * \warning it's done to be directly evaluatable in script language + * (tested with: urbi and ruby) + * \throw ALERROR + */ + std::string toString(Verbosity pnVerbosity = VerbosityMini) const; + + /** + * \brief Build python buffer from ALValue binary. + * + * Decode a string containing some binaries encoded in + * B64 (binary 64 / uuencoded). + * \return python compatible string + * \warning public method called from FillAlValueFromXmlNodeContent... + * + */ + std::string toPythonBuffer() const; + + /** + * \brief Decode a buffer from B64 to binary. + * + * Decode a string containing some binaries encoded in + * B64 (binary 64 / uuencoded) + * \param pszB64 the buffer to decode + * \return true + * \warning public method called from FillAlValueFromXmlNodeContent... + */ + bool decodeB64(const char *pszB64); + + /** + * \brief Decode a buffer from B64 to binary object. + * + * Decode a string containing some binaries encoded in + * B64 (binary 64 / uuencoded) + * \param pszB64 the buffer to decode + * \return true + * \warning public method called from FillAlValueFromXmlNodeContent... + */ + bool decodeB64Object(const char *pszB64); + + /** + * \brief Encode a binaries alvalue to B64 (binary 64 / uuencoded). + * \param strOutput the buffer to receive or data encoded in B64 + */ + void encodeB64(std::string &strOutput) const; + + /** + * \brief Analyses a string and try to guess the type of data + * describe in the string. + * + * eg: "5" => int; + * "'toto'" => string; + * [3,5] => array ... + * \param szInput a text to analyse, eg: "[36, 3, "toto", 3.5, [1,2,3]]" + * \param nLimitToLen limit analysis to \a nLimitToLen first characters + * \return type of the value + * \throw ALERROR + */ + static enum Type deduceType(const char *szInput, + int nLimitToLen = 0x7FFFFFFF); + + /** + * \brief Create an ALValue from a text. + * \param szInput the source analysed to construct the alvalue, + * eg: "1" or "[36,3,"toto",3.5,[1,2,3]]" + * \param nLimitToLen limit analysis to \a nLimitToLen first characters + * (used in recursion) + * \throw ALERROR + */ + void unSerializeFromText(const char *szInput, + int nLimitToLen = 0x7FFFFFFF); + + /** + * \brief Create a text describing an ALValue. + * \return the new string + * \throw ALERROR + */ + std::string serializeToText(void) const; + + /** + * \brief Internal function to validate the correct functionnality + * of unSerializeFromText. + * \return true if test ok, false othewise + */ + static bool xUnSerializeFromText_InnerTest(void); + + template + static ALValue array(const T0 &a0); + template + static ALValue array(const T0 &a0, const T1 &a1); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7, const T8 &a8); + template + static ALValue array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7, const T8 &a8, const T9 &a9); + + protected: + /** \cond PRIVATE */ + void xInvalidate(); + void xAssertCompatibleType(enum Type pnWantedType); + void xAssertType(enum Type pnWantedType) const; + void xAssertArraySize(int pnSize) const; + /** + * \brief deprecated + * \deprecated use xAssertStruct + */ + void assertStruct(); + /** \endcond */ + + /** \brief Type of the ALValue */ + int _type; + /** \brief Value of the ALValue */ + union unionValue _value; + + public: + /** + * \brief Get the value of the ALValue + * \return the value + */ + const unionValue getUnionValue(); + + /** + * \brief Get pointer on array value. + * \return a pointer on the array + */ + TAlValueArray *getArrayPtr() const; + + /** + * \brief Get a string with name of ALValue type. + * \return "Invalid", "Array", "Bool", "Int", + * "Float", "String", "Object", "Binary" + */ + static std::string TypeToString(enum Type pnType); + + }; + + template + ALValue ALValue::array(const T0 &a0) + { + ALValue result; + result.arraySetSize(1); + result[0] = a0; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1) + { + ALValue result; + result.arraySetSize(2); + result[0] = a0; + result[1] = a1; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2) + { + ALValue result; + result.arraySetSize(3); + result[0] = a0; + result[1] = a1; + result[2] = a2; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3) + { + ALValue result; + result.arraySetSize(4); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4) + { + ALValue result; + result.arraySetSize(5); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5) + { + ALValue result; + result.arraySetSize(6); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + result[5] = a5; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6) + { + ALValue result; + result.arraySetSize(7); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + result[5] = a5; + result[6] = a6; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7) + { + ALValue result; + result.arraySetSize(8); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + result[5] = a5; + result[6] = a6; + result[7] = a7; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7, const T8 &a8) + { + ALValue result; + result.arraySetSize(9); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + result[5] = a5; + result[6] = a6; + result[7] = a7; + result[8] = a8; + return result; + } + + template + ALValue ALValue::array(const T0 &a0, const T1 &a1, const T2 &a2, const T3 &a3, const T4 &a4, const T5 &a5, const T6 &a6, const T7 &a7, const T8 &a8, const T9 &a9) + { + ALValue result; + result.arraySetSize(10); + result[0] = a0; + result[1] = a1; + result[2] = a2; + result[3] = a3; + result[4] = a4; + result[5] = a5; + result[6] = a6; + result[7] = a7; + result[8] = a8; + result[9] = a9; + return result; + } + ALVALUE_API bool operator <(const ALValue& a, const ALValue& b); +} // namespace AL + +/** + * \brief Stream operator for ALValue. + * \param os stream + * \param a ALValue + */ +std::ostream &operator<<(std::ostream &os, const AL::ALValue &a); + + +#endif // _LIBALVALUE_ALVALUE_ALVALUE_H_ diff --git a/naoModule/libnaoqi_files/include/alvalue/config.h b/naoModule/libnaoqi_files/include/alvalue/config.h new file mode 100755 index 0000000..02bd1ca --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvalue/config.h @@ -0,0 +1,41 @@ +/** + * Author(s): + * - Cedric GESTES + * + * Copyright (C) 2011 Aldebaran Robotics + */ + +/** @file + * @brief dll import/export + */ + +#pragma once +#ifndef _LIBALVALUE_ALVALUE_CONFIG_H_ +#define _LIBALVALUE_ALVALUE_CONFIG_H_ + +// For shared library +#if defined _WIN32 || defined __CYGWIN__ +# define ALVALUE_EXPORT_API __declspec(dllexport) +# if defined _WINDLL +# define ALVALUE_IMPORT_API __declspec(dllimport) +# else +# define ALVALUE_IMPORT_API +# endif +#elif __GNUC__ >= 4 +# define ALVALUE_EXPORT_API __attribute__ ((visibility("default"))) +# define ALVALUE_IMPORT_API __attribute__ ((visibility("default"))) +#else +# define ALVALUE_EXPORT_API +# define ALVALUE_IMPORT_API +#endif + +#ifdef alvalue_EXPORTS +# define ALVALUE_API ALVALUE_EXPORT_API +#elif defined(alvalue_IMPORTS) +# define ALVALUE_API ALVALUE_IMPORT_API +#else +# define ALVALUE_API +#endif + +#endif // _LIBALVALUE_ALVALUE_CONFIG_H_ + diff --git a/naoModule/libnaoqi_files/include/alvision/alimage.h b/naoModule/libnaoqi_files/include/alvision/alimage.h new file mode 100755 index 0000000..e5fccdd --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvision/alimage.h @@ -0,0 +1,356 @@ +/** + * @author Pierre-Emmanuel VIEL + * Copyright (c) Aldebaran Robotics 2008, 2011, 2012 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALVISION_ALVISION_ALIMAGE_H_ +#define _LIBALVISION_ALVISION_ALIMAGE_H_ + +#include +#include +#include +#include + +#include +#include + +/** \file alvision/alimage.h + * \brief handle image + */ + +namespace AL +{ +class ALValue; + +class ALImage +{ +public: + struct ROI { + ROI(int left, int top, int width, int height); + ROI(int left, int top, int width, int height, + float leftAngle, float topAngle, + float rightAngle, float bottomAngle); + int x; + int y; + int w; + int h; + float leftAngle; + float topAngle; + float rightAngle; + float bottomAngle; + }; + + // .:: methods :: + +public: + /** + *ALImage + *@brief constructor + *@param[in] pWidth width of the image + *@param[in] pHeight height of the image + *@param[in] pColorSpace color space of the image + *@param[in] pDataAreExternal is data buffer external, or is it allocated with the image? + *@param[in] pLeftAngle camera FOV left angle in radian + *@param[in] pTopAngle camera FOV top angle in radian + *@param[in] pRightAngle camera FOV right angle in radian + *@param[in] pBottomAngle camera FOV bottom angle in radian + */ + ALImage(int pWidth, int pHeight, int pColorSpace, bool pDataAreExternal = false, + float pLeftAngle = 0.f, float pTopAngle = 0.f, + float pRightAngle = 0.f, float pBottomAngle = 0.f); + + /** + *ALImage + *@brief constructor + *@param[in] pResolution resolution of the image + *@param[in] pColorSpace color space of the image + *@param[in] pDataAreExternal is data buffer external, or is it allocated with the image? + *@param[in] pLeftAngle camera FOV left angle in radian + *@param[in] pTopAngle camera FOV top angle in radian + *@param[in] pRightAngle camera FOV right angle in radian + *@param[in] pBottomAngle camera FOV bottom angle in radian + */ + ALImage(int pResolution, int pColorSpace, bool pDataAreExternal = false, + float pLeftAngle = 0.f, float pTopAngle = 0.f, + float pRightAngle = 0.f, float pBottomAngle = 0.f); + + ~ALImage(); + + /** + *toALValue + *@brief return an ALValue containing image structure + *@result[0] : [int] with of the image + *@result[1] : [int] height of the image + *@result[2] : [int] number of layers of the image + *@result[3] : [int] colorspace of the image + *@result[4] : [int] time stamp in second + *@result[5] : [int] time stamp in microsecond (and under second) + *@result[6] : [int] data of the image + *@result[7] : [int] camera ID + *@result[8] : [float] camera FOV left angle (radian) + *@result[9] : [float] camera FOV top angle (radian) + *@result[10]: [float] camera FOV right angle (radian) + *@result[11]: [float] camera FOV bottom angle (radian) + */ + ALValue toALValue(); + + /** @brief Allocate an ALImage and return a pointer on it using an ALValue to fill it. + * @param[in] image ALValue containing: + * image[0] : [int] with of the image + * image[1] : [int] height of the image + * image[2] : [int] number of layers of the image + * image[3] : [int] colorspace of the image + * image[4] : [int] time stamp in second + * image[5] : [int] time stamp in microsecond (and under second) + * image[6] : [int] data of the image + * image[7] : [int] camera ID + * image[8] : [float] camera FOV left angle (radian) + * image[9] : [float] camera FOV top angle (radian) + * image[10]: [float] camera FOV right angle (radian) + * image[11]: [float] camera FOV bottom angle (radian) + * @return a pointer to ALImage otherwise return a NULL pointer. + * @note This method performs a deep copy, so ALValue can be suppressed. + */ + static ALImage* fromALValue(const ALValue& image); + + inline void setWidth( const int width ) { fWidth = width; } + inline void setHeight( const int height ) { fHeight = height; } + inline void setLeftAngle( const float leftAngle ) { fFOV.leftAngle = leftAngle; } + inline void setTopAngle( const float topAngle ) { fFOV.topAngle = topAngle; } + inline void setRightAngle( const float rightAngle ) { fFOV.rightAngle = rightAngle; } + inline void setBottomAngle( const float bottomAngle ) { fFOV.bottomAngle = bottomAngle; } + inline void setAngles( const float leftAngle, const float topAngle, + const float rightAngle, const float bottomAngle ) + { fFOV.leftAngle = leftAngle; fFOV.topAngle = topAngle; + fFOV.rightAngle = rightAngle; fFOV.bottomAngle = bottomAngle; } + + /*! @brief set the Resolution of the image without changing the allocation size. + * @param[in] pResolution resolution of the image + * @deprecated you should not use this function.*/ + bool setSize(int pResolution) { return setResolution(pResolution); } + + /** + *setResolution + *@brief set the Resolution of the image without changing the allocation size. + *@param[in] pResolution resolution of the image. + */ + bool setResolution(int pResolution); + + /** + *setColorSpace + *@brief set the ColorSpace of the image without changing the allocation size. + *@param[in] pColorSpace ColorSpace of the image. + */ + bool setColorSpace(int pColorSpace); + + /** + *getFrame //DEPRECATED + *@brief return the reference to the image data. + *@result reference to the image data. + */ + inline const unsigned char* getFrame() const + { assert( fData != 0); + std::cout << "getFrame() is deprecated. Please replace by getData()." << std::endl; + return fData; } + + /** + *getData + *@brief return the reference to the image data. + *@result reference to the image data. + */ + inline const unsigned char* getData() const { assert( fData != 0); return fData; } + + // for the camera + /** + *getFrame //DEPRECATED + *@brief return the pointer to the image data. + *@result pointer to the image data. + */ + inline unsigned char* getFrame() + { assert( fData != 0); + std::cout << "getFrame() is deprecated. Please replace by getData()." << std::endl; + return fData; } + + /** + *getData + *@brief return the pointer to the image data. + *@result pointer to the image data. + */ + inline unsigned char* getData() { assert( fData != 0); return fData; } + + /** + *setData + *@brief set the image data pointer to point to the specified buffer. + *@param[in] pData pointer to the image data buffer. + */ + inline void setData(unsigned char* pData) { fData = pData; } + + /** + *setTimeStamp + *@brief set the image timestamp. + *@param[in] pTimeStamp timestamp to set. + */ + inline void setTimeStamp(const qi::os::timeval pTimeStamp) + { + if( (pTimeStamp.tv_usec < 0) || (pTimeStamp.tv_sec < 0) ) + { + fTimeStamp = -1; + return; + } + setTimeStamp(static_cast(pTimeStamp.tv_sec), static_cast(pTimeStamp.tv_usec)); + } + + /** + *setTimeStamp + *@brief set the image timestamp + *@param[in] pTimeStamp time in a long long format. + */ + inline void setTimeStamp(long long pTimeStamp) { fTimeStamp = pTimeStamp; } + + /** + *setTimeStamp + *@brief set the image timestamp + *@param[in] pSeconds time in seconds + *@param[in] pMicroSeconds time in µseconds + */ + inline void setTimeStamp(int pSeconds, int pMicroSeconds) + { + fTimeStamp = (long long)pSeconds*1000000LL + (long long)pMicroSeconds; + } + + + /** + *setCameraId + *@brief set the ID of the camera that shot the picture + *@param[in] pCameraId ID of the camera that shot the picture + */ + inline void setCameraId(char pCameraId) { fCameraId = pCameraId; } + + + /** + *getSize + *@return the size of the allocated memory for the image (the size of fData buffer) + */ + inline unsigned int getSize() const { return fWidth*fHeight*fNbLayers; } + + /* + * Accessor + */ + inline int getWidth( void ) const { return fWidth; } + inline int getHeight( void ) const { return fHeight; } + inline int getResolution( void ) const { return getResolutionFromSize(fWidth, fHeight); } + inline int getColorSpace( void ) const { return fColorSpace; } + inline int getNbLayers( void ) const { return fNbLayers; } + inline long long getTimeStamp( void ) const { return fTimeStamp; } + inline char getCameraId() const { return fCameraId; } + inline int getMaxResolution( void ) const { return fMaxResolution; } + inline int getNbOfLayersMax( void ) const { return fMaxNumberOfLayers; } + inline bool areDataExternal( void ) const { return fDataAreExternal; } + int getAllocatedSize() const { return fAllocatedSize; } + inline float getLeftAngle( void ) const { return fFOV.leftAngle; } + inline float getTopAngle( void ) const { return fFOV.topAngle; } + inline float getRightAngle( void ) const { return fFOV.rightAngle; } + inline float getBottomAngle( void ) const { return fFOV.bottomAngle; } + inline void getAngles( float& leftAngle, float& topAngle, float& rightAngle, float& bottomAngle ) + const { leftAngle = fFOV.leftAngle; topAngle = fFOV.topAngle; + rightAngle = fFOV.rightAngle; bottomAngle = fFOV.bottomAngle; } + + /* + * For debug purpose: print the object in an human format + */ + std::string toString( void ) const; + + int getNumOfROIs() const { return (int)fROIs.size(); } + + const ROI* getROI(int index) const { + if (index < 0 || index >= getNumOfROIs()) + return NULL; + return &(fROIs[index]); + } + + void addROI(const ROI& rect) { + fROIs.push_back(rect); + } + + void cleanROIs() { + fROIs.clear(); + } + + void setEnableROIs(bool enable) { + fROIEnabled = enable; + } + + bool isROIEnabled() const { + return fROIEnabled; + } + + + int writeFile(const char* _fileNameAndPath); + int readFile(const char* _fileNameAndPath); + int savePPM(const char* _fileNameAndPath); + + bool computeYUV422imageFromBGR(int height, int width, char *data); + bool computeBGRimageFromYUV422(const unsigned char* _dest); + bool computeYYYUUUVVVimageFromYUV422(const unsigned char* _dest); + bool computeYYYYUUVVimageFromYUV422(const unsigned char* _dest); +private: + bool reallocateDataSize(const int resolution, const int nbLayers); + + + // .:: members :: +private: + /// width of the image + int fWidth; + + /// height of the image + int fHeight; + + /// number of layers of the image + int fNbLayers; + + /// color space of the image + int fColorSpace; + + /// Time in microsecond when the image was captured + long long fTimeStamp; + + /// pointer to the image data + unsigned char* fData; + + /// ID of the camera that shot the picture + char fCameraId; + + /// Size of memory allocation + int fAllocatedSize; + + /// Maximum resolution accepted in the reserved memory + int fMaxResolution; + + /// Maximum number of layers accepted in the reserved memory + int fMaxNumberOfLayers; + + /// If true, image points to an external data buffer. + /// If false, data buffer was allocated while creating instance. + bool fDataAreExternal; + + /// Manage the field of view of the image that changes with camera model and cropping + struct FOV { + float leftAngle; + float topAngle; + float rightAngle; + float bottomAngle; + }; + struct FOV fFOV; + + std::vector fROIs; + + bool fROIEnabled; +}; +} + +// take a pixel in YUV and compute its RGB Value. RGB value are returned directly in params +void computeRgbFromYuv( unsigned char * pYR, unsigned char * pUG, unsigned char * pVB ); + + +#endif // _LIBALVISION_ALVISION_ALIMAGE_H_ diff --git a/naoModule/libnaoqi_files/include/alvision/alimage_opencv.h b/naoModule/libnaoqi_files/include/alvision/alimage_opencv.h new file mode 100755 index 0000000..f546763 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvision/alimage_opencv.h @@ -0,0 +1,144 @@ +/** + * @author Vincent Rabaud + * Aldebaran Robotics (c) 2013 All Rights Reserved + */ + +/** Set of functions to convert between ALImage and cv::Mat + * This is a header only implementation to be totally independent from OpenCV + * If you include this header, make sure you link properly to OPENCV2_CORE + */ +#ifndef LIBALVISION_ALVISION_ALIMAGE_OPENCV_H_ +#define LIBALVISION_ALVISION_ALIMAGE_OPENCV_H_ + +#include // for std::memcpy +#include + +#include + +#include "alimage.h" +#include "alvisiondefinitions.h" + +namespace AL +{ +/** Converts an ALImage to an OpenCV cv::Mat by NOT copying the data over: the cv::Mat does not own the data and will + * not delete it in its destructor. If you want to copy the data, just .clone the output cv::Mat() + * @param al_image + * @param cv_type if provided, it interprets the content of al_image as such + * @return + */ +static inline cv::Mat aLImageToCvMat(const AL::ALImage & al_image, int cv_type = -1) +{ + // OpenCV does not take a const void* because the object could be modified later. This pointer will only be used + // in a tmp local cv::Mat so it's fine + unsigned char *data = const_cast(al_image.getData()); + + if (cv_type >= 0) + return cv::Mat(al_image.getHeight(), al_image.getWidth(), cv_type, data); + + // Check the types + int n_layers = AL::getNumLayersInColorSpace(al_image.getColorSpace()); + int n_channels = AL::getNumChannelsInColorSpace(al_image.getColorSpace()); + if ((n_layers < 0) || (n_channels < 0)) { + std::stringstream ss; + ss << "Color space \"" << al_image.getColorSpace() << "\" not supported"; + throw AL::ALError("ALVision", "aLImageToCvMat", ss.str()); + } + int cv_depth; + switch (n_layers / n_channels) + { + case 4: + cv_depth = CV_32F; + break; + case 2: + cv_depth = CV_16U; + break; + case 1: + cv_depth = CV_8U; + break; + default: + std::stringstream ss; + ss << "Depth \"" << (n_layers / n_channels) << "\" not supported"; + throw AL::ALError("ALVision", "aLImageToCvMat", ss.str()); + } + + return cv::Mat(al_image.getHeight(), al_image.getWidth(), + CV_MAKETYPE(cv_depth, n_channels), data); +} + +/** Converts an OpenCV cv::Mat to an ALImage by NOT copying the data over. Be careful, if your cv::Mat goes out of + * scope, the ALImage pointer is invalid + * @param img the cv::Mat image the output image will link to + * @param colorSpace the color space as defined in ALVision + * @return + */ +static inline AL::ALImage* cvMatToALImage(const cv::Mat & img, int colorSpace, + float pLeftAngle = 0.0f, float pTopAngle = 0.0f, + float pRightAngle = 0.0f, float pBottomAngle = 0.0f) +{ + // Check the number of channels + if (AL::getNumChannelsInColorSpace(colorSpace) != img.channels()) + throw AL::ALError("ALVision", "cvMatToALImage", + "Channel number incompatibility between cv::Mat and colorSpace"); + + // Check the type + switch (img.depth()) + { + case CV_8U: + case CV_16U: + case CV_32F: + break; + default: + throw AL::ALError("ALVision", "cvMatToALImage", + "Type incompatibility between cv::Mat and colorSpace"); + } + + // Create an ALImage with the buffer + AL::ALImage *al_image = new AL::ALImage(img.cols, img.rows, colorSpace, true, + pLeftAngle, pTopAngle, pRightAngle, pBottomAngle); + al_image->setData(img.data); + + return al_image; +} + +/** Converts an OpenCV cv::Mat to an ALImage by COPYING the data over + * @param img the cv::Mat image the output image will copy + * @param colorSpace the color space as defined in ALVision + * @return + */ +static inline AL::ALImage* cvMatToALImageCopy(const cv::Mat & img, + int colorSpace, + float pLeftAngle = 0.0f, float pTopAngle = 0.0f, + float pRightAngle = 0.0f, float pBottomAngle = 0.0f) +{ + // Check the number of channels + if (AL::getNumChannelsInColorSpace(colorSpace) != img.channels()) + throw AL::ALError("ALVision", "cvMatToALImage", + "Channel number incompatibility between cv::Mat and colorSpace"); + + // Check the type + switch (img.type()) + { + case CV_8U: + case CV_16U: + case CV_32F: + break; + default: + throw AL::ALError("ALVision", "cvMatToALImage", + "Type incompatibility between cv::Mat and colorSpace"); + } + + // Copy the image data in a buffer + size_t data_size = img.cols * img.rows * img.elemSize(); + unsigned char *data = new unsigned char[data_size]; + std::memcpy(data, img.data, data_size); + + // Create an ALImage with the buffer + AL::ALImage *al_image = new AL::ALImage(img.cols, img.rows, colorSpace, false, + pLeftAngle, pTopAngle, pRightAngle, pBottomAngle); + al_image->setData(data); + + return al_image; +} +} + +#endif /* LIBALVISION_ALVISION_ALIMAGE_OPENCV_H_ */ diff --git a/naoModule/libnaoqi_files/include/alvision/alvideo.h b/naoModule/libnaoqi_files/include/alvision/alvideo.h new file mode 100755 index 0000000..314ed82 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvision/alvideo.h @@ -0,0 +1,121 @@ +/** + * @author Pierre-Emmanuel VIEL + * Copyright (c) Aldebaran Robotics 2008, 2011 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALVISION_ALVISION_ALVIDEO_H_ +#define _LIBALVISION_ALVISION_ALVIDEO_H_ + + +# include +# include +# include +# include +# include + +/** \file alvision/alvideo.h + * \brief handle video + */ + +namespace AL +{ + //structures for video raw stream recording + /* + * streamHeader + * @brief single stream header + */ + struct streamHeader + { + unsigned int width : 32; + unsigned int height: 32; + unsigned int colorSpace : 32; + unsigned int pixelDepth : 32; + }; + + /* + * videoHeader + * @brief multiple stream header global header with version field + */ + struct videoHeader + { + unsigned int magicNumber : 32; // magic number + unsigned int userSpaceSize : 32; + unsigned int numberOfFrames : 32; + unsigned int numberOfStreams : 32; + }; + + struct streamProperties + { + unsigned int width; + unsigned int height; + unsigned int resolution; + unsigned int colorSpace; + unsigned int nbLayers; + unsigned int pixelDepth; + unsigned int sizePerImage; + }; + + + class ALVideo + { + + // .:: methods :: + + public: + ALVideo(); + ~ALVideo(); + + bool recordVideo(const std::string pFilePath, const unsigned int pUserSpaceSize, const std::vector& pStreamHeaderVector); + bool readVideo(const std::string pFilePath); + void closeVideo(); + bool goToFrame(const unsigned int pFrameNumber, const unsigned int pStreamNumber); + bool getFrame(ALImage & pImage, const unsigned int pFrameNumber, const unsigned int pStreamNumber, const bool pCheckFormat = true); + bool getNextFrame(ALImage & pImage, const bool pCheckFormat = true); + bool getPrecedingFrame(ALImage & pImage, const bool pCheckFormat = true); + bool write(char* ptrImageData, const int pSizeData, const long long pTimeStamp = 0, const char pCameraId = 0, + const float pLeftAngle = 0, const float pTopAngle = 0, const float pRightAngle = 0, const float pBottomAngle = 0); + bool write(int height, int width, char *imageData, const long long pTimeStamp, const char pCameraId, + const float pLeftAngle, const float pTopAngle, const float pRightAngle, const float pBottomAngle); + + inline const unsigned char* getMagicNumber() const { return (unsigned char*)&fMagicNumber; }; + inline unsigned int getNumberOfFrames() const { return fNumberOfFrames; }; + inline unsigned int getNumberOfStreams() const { return fNumberOfStreams; }; + inline unsigned int getCurrentFrameNumber() const { return fCurrentFrameNumber; }; + inline unsigned int getCurrentStreamNumber() const { return fCurrentStreamNumber; }; + inline bool isOpenForReading() const { return fIsOpenForReading; }; + inline bool isOpenForWriting() const { return fIsOpenForWriting; }; + + inline int getStreamWidth(const unsigned int pStreamNumber) const { return (pStreamNumber fStreamPropertiesVector; + + unsigned int fCurrentStreamNumber; + unsigned int fCurrentFrameNumber; + }; +} + +#endif // _LIBALVISION_ALVISION_ALVIDEO_H_ diff --git a/naoModule/libnaoqi_files/include/alvision/alvisiondefinitions.h b/naoModule/libnaoqi_files/include/alvision/alvisiondefinitions.h new file mode 100755 index 0000000..b42c6c2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvision/alvisiondefinitions.h @@ -0,0 +1,177 @@ +/** + * @author Pierre-Emmanuel VIEL + * Copyright (c) Aldebaran Robotics 2008, 2011 All Rights Reserved + */ + +#pragma once +#ifndef _LIBALVISION_ALVISION_ALVISIONDEFINITIONS_H_ +#define _LIBALVISION_ALVISION_ALVISIONDEFINITIONS_H_ + +/** \file alvision/alvisiondefinitions.h + * \brief vision defines + */ + +namespace AL +{ + #define TORAD 3.14f/180.0f + + /** + *Camera Model ID + */ + const int kOV7670 = 1; + const int kMT9M114 = 2; + const int kOV5640 = 3; + const int kXTION = 4; + + /** + *Camera Index + */ + const int kTopCamera = 0; + const int kBottomCamera = 1; + const int kDepthCamera = 2; + + /** + *Cameras aperture + * @deprecated Should not be exposed. + */ + const float kApertureH_OV7670 = 47.8f; //!< @deprecated since 1.16 + const float kApertureV_OV7670 = 36.8f; //!< @deprecated since 1.16 + const float kApertureH_MT9M114 = 60.9f; //!< @deprecated since 1.16 + const float kApertureV_MT9M114 = 47.6f; //!< @deprecated since 1.16 + + /** + *Format of the image + */ + const int kQQVGA = 0; // 160*120 + const int kQVGA = 1; // 320*240 + const int kVGA = 2; // 640*480 + const int k4VGA = 3; //1280*960 + const int k960p = k4VGA; //deprecated + const int k16VGA = 4; //2560*1920 + const int k1920p = k16VGA; //2560*1920 + const int k720p = 5; //1280*720 + const int k1080p = 6; //1920*1080 + const int kQQQVGA = 7; // 80*60 + const int kQQQQVGA = 8; // 40*30 + + /** + *ColorSpace + */ + const int kYuvColorSpace = 0; + const int kyUvColorSpace = 1; + const int kyuVColorSpace = 2; + const int kRgbColorSpace = 3; + const int krGbColorSpace = 4; + const int krgBColorSpace = 5; + const int kHsyColorSpace = 6; + const int khSyColorSpace = 7; + const int khsYColorSpace = 8; + const int kYUV422ColorSpace = 9; + const int kYUV422InterlacedColorSpace = kYUV422ColorSpace; // deprecated + const int kYUVColorSpace = 10; + const int kRGBColorSpace = 11; + const int kHSYColorSpace = 12; + const int kBGRColorSpace = 13; // for opencv ease of use + const int kYYCbCrColorSpace = 14; // for tiff io implementation + const int kH2RGBColorSpace = 15; // H from HSY to RGB in fake colors + const int kHSMixedColorSpace = 16; // HS and (H +S)/2 + const int kDepthColorSpace = 17; + const int kARGBColorSpace = 18; + const int kXYZColorSpace = 19; + const int kInfraredColorSpace = 20; + const int kDistanceColorSpace = 21; //!< @since 1.22 + + /** + *Standard Id (used for camera registers configuration) + */ + const int kCameraBrightnessID = 0; + const int kCameraContrastID = 1; + const int kCameraSaturationID = 2; + const int kCameraHueID = 3; + const int kCameraRedChromaID = 4; + const int kCameraBlueChromaID = 5; + const int kCameraGainID = 6; + const int kCameraHFlipID = 7; + const int kCameraVFlipID = 8; + const int kCameraLensXID = 9; + const int kCameraLensYID = 10; + const int kCameraAutoExpositionID = 11; + const int kCameraAutoWhiteBalanceID = 12; + const int kCameraAutoGainID = 13; + const int kCameraResolutionID = 14; + const int kCameraFrameRateID = 15; + const int kCameraBufferSizeID = 16; + const int kCameraExposureID = 17; + const int kCameraSelectID = 18; + const int kCameraSetDefaultParamsID = 19; + const int kCameraColorSpaceID = 20; + const int kCameraExposureCorrectionID = 21; + const int kCameraExposureAlgorithmID = 22; + const int kCameraAecAlgorithmID = kCameraExposureAlgorithmID; // deprecated + const int kCameraFastSwitchID = 23; + const int kCameraSharpnessID = 24; + const int kCameraAwbGreenGainID = 25; + const int kCameraAblcID = 26; + const int kCameraAblcTargetID = 27; + const int kCameraAblcStableRangeID = 28; + const int kCameraBlcBlueID = 29; + const int kCameraBlcRedID = 30; + const int kCameraBlcGbID = 31; + const int kCameraBlcGrID = 32; + const int kCameraWhiteBalanceID = 33; + const int kCameraBacklightCompensationID = 34; + const int kCameraKeepAliveID = 35; //!< @since 1.16 + const int kCameraDepthConfidenceThresholdID = 36; //!< @since 1.16 + const int kCameraDepthFastFilterID = 37; //!< @since 1.16 + const int kCameraTemperatureID = 38; //!< @since 1.18 + const int kCameraAverageLuminanceID = 39; //!< @since 1.22.2 + const int kCameraAutoFocusID = 40; //!< @since 1.22.4 + + /*! @brief Utility function that checks that a resolution index is valid. + * (ie, present in the definitions just above)*/ + bool isResolutionValid(const int resIndex); + + /*! @brief Utility function that takes a resolution index as an input and returns + * the corresponding width and height values. + * If resolution index is unknown, width and height are set to -1.*/ + void setSizeFromResolution(const int resIndex, int& outWidth, int& outHeight); + + /*! @brief Utility function that takes width and height as inputs and returns the + * corresponding resolution index. + * @return The resolution index otherwise return -1.*/ + int getResolutionFromSize(const int width, const int height); + + /*! @brief Utility function that checks that a color space index is valid. + * (ie, present in the definitions just above)*/ + bool isColorSpaceValid(const int colorspace); + + /*! @brief Utility function that returns the number of layers for a given color space. + * @return the number of byte the colorspace use, otherwise returns -1 for unknown colorspace. + * @note Since this method is use by AL::ALImage to allocate memory with the + * assumption of 1 layer is stored in 1 byte. Thus if the color space store some channel + * in a 16bits container (e.g. Depth map), method will return 2 instead of 1. + */ + int getNumLayersInColorSpace(const int colorSpace); + + /*! + * @brief Utility function that returns the number of channels for a given color space. + * @return The number of channels for this color space. + * @note This method assumes that the data is stored with the correct type, + * for example it will return 1 for the AL::kDepthColorSpace because it corresponds + * to a 1-channel unsigned short image buffer, although it uses two layers. + */ + int getNumChannelsInColorSpace(const int colorSpace); + + inline float convertAngleValToNormalizedImgVal(const float& radValue, + const float& imageRadMin, + const float& imageRadMax) + { return ( radValue / (imageRadMax-imageRadMin)); } + + inline float convertAnglePosToNormalizedImgPos(const float& radPosition, + const float& imageRadMin, + const float& imageRadMax) + { return ((radPosition-imageRadMin) / (imageRadMax-imageRadMin)); } +} // namespace AL + + +#endif // _LIBALVISION_ALVISION_ALVISIONDEFINITIONS_H_ diff --git a/naoModule/libnaoqi_files/include/alvision/alvisionextractor.h b/naoModule/libnaoqi_files/include/alvision/alvisionextractor.h new file mode 100755 index 0000000..bf8472c --- /dev/null +++ b/naoModule/libnaoqi_files/include/alvision/alvisionextractor.h @@ -0,0 +1,188 @@ +/** + * @author Aldebaran Robotics + * Copyright (c) Aldebaran Robotics 2011, 2012 All Rights Reserved + */ + + +#ifndef ALVISIONEXTRACTOR_H +#define ALVISIONEXTRACTOR_H + +#include +#include +#include +#include +#include + +namespace AL { + +class ALValue; +class ALVideoDeviceProxy; +class ALVisionExtractorPrivate; + +/** + * \class ALVisionExtractor alvisionextractor.h + * \brief ALVisionExtractor is a generic vision extractor. + * + * ALVisionExtractor is an extractor dedicated to vision processing. It + * retrieves images from one of NAO's cameras, and gives them as input to a + * callback method process(). This method will be called each time an image is + * retrieved. + * + * The parameters concerning the image retrieval (resolution, colorspace, camera + * and framerate) can be set either at the construction (which is recommended) if + * you do not have to change them, or on the fly using dedicated method. + * + */ + +class ALVisionExtractor : public ALExtractor { + +public: + /** + * \brief Create a generic vision extractor. + * @param[in] pBroker Broker use to register the vision extractor. + * @param[in] pName Name of the Vision Extractor. + * \param resolution Resolution of the images the extractor will process at + * module startup. Default value is 1 (QVGA resolution). + * \param colorspace Colorspace of the images the extractor will process at + * module startup. Default value is BGR colorspace. + * \param framerate Framerate of the images the extractor will process at + * module startup. Default value is 30. + * @param[in] activecamera Index of the active camera -1 to use the default + * one. + */ + ALVisionExtractor(boost::shared_ptr pBroker, + const std::string& pName, + int resolution=kQVGA, int colorspace=kBGRColorSpace, + int framerate=30, int activecamera=-1); + + virtual ~ALVisionExtractor(); + + /** + * \brief Sets processed image colorspace on the fly. + * \param colorSpace Desired colorspace. + * \return True if the colorspace has been successfully set. + */ + virtual bool setColorSpace(const int& colorSpace); + + /** + * \brief Sets extractor framerate on the fly. + * \param framerate Desired extractor framerate. + * \return True if the framerate has been successfully set. + */ + virtual bool setFrameRate(const int& framerate); + virtual bool setFrameRate(const std::string &pSubscribedName, + const int& framerate); + + /** + * \brief Sets processed image resolution on the fly. + * \param resolution Desired resolution. + * \return True if the resolution has been successfully set. + */ + virtual bool setResolution(const int& resolution); + + /** + * \brief Sets the camera from which the image is taken. + * \param cameraId Desired camera ID. + * \return True if the camera has been successfully set. + */ + virtual bool setActiveCamera(const int& cameraId); + + boost::shared_ptr getVideoDeviceProxy(); + + int getColorSpace(); + + int getFrameRate(); + + int getResolution(); + + int getActiveCamera(); + + bool isPaused(); + bool isProcessing(); + + + /** + * \brief Set parameter value for resolution and pause. + * \param paramName Name of the parameter to set ("resolution" or "pause") + * \param paramValue ALValue array of the value to be set. + * \deprecated Use setResolution or pause instead. + */ + QI_API_DEPRECATED void setParameter(const std::string& paramName, + const ALValue& paramValue); + + /** + * \brief Method which will be called before each subscription to the extractor. + */ + virtual void start() = 0; + + /** + * \brief Method which will be called each time the extractor gets an image. + * \param img Pointer to the image class, which is retrieved according to the + * extractor parameters (colorspace, framerate, resolution, camera). + */ + virtual void process(ALImage* img) = 0; + + /** + * \brief Pause the extractor, without calling the stop method. + * \param paused true if the extractor must be paused, false else. + */ + void pause(const bool& paused); + + /** + * \brief Method which will be called when the module is unsubscribed. + */ + virtual void stop() = 0; + + /** + * \brief This method overrides the method inherited from ALExtractor. + * It computes the default period from the default framerate given + * in the constructor of the ALVisionExtractor. + * + * For an ALVisionExtractor, there is no need to override this method: + * the default period can be chosen by setting the default framerate + * in the constructor. + */ + int getDefaultPeriod(); + + + /** + * \brief This method overrides the method inherited from ALExtractor. + * It computes the minimum period from the highest framerate supported + * by the selected camera. + * + * For an ALVisionExtractor, there is no need to override this method. + */ + int getMinimumPeriod(); + + /** + * \brief This method overrides the method inherited from ALExtractor. + * It computes the maximum period from the lowest framerate supported + * by the selected camera. + * + * For an ALVisionExtractor, there is no need to override this method. + */ + int getMaximumPeriod(); + + +protected: + void xUpdateParameters(const int pPeriod, const float pPrecision); + void setSubscriptionParameters(const std::vector< std::pair >& parameters); + +private: + + //intentionnally undefined. + ALVisionExtractor(const ALVisionExtractor& extractor); + //intentionnally undefined. + ALVisionExtractor& operator =(const ALVisionExtractor& extractor); + + void xStartDetection(const int pPeriod, const float pPrecision); + void xStopDetection(); + + void xRun(); + + ALVisionExtractorPrivate* _pImpl; +}; + +} // namespace AL. + +#endif // ALVISIONEXTRACTOR_H diff --git a/naoModule/libnaoqi_files/include/qi/api.hpp b/naoModule/libnaoqi_files/include/qi/api.hpp new file mode 100755 index 0000000..00f3900 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/api.hpp @@ -0,0 +1,29 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/** @file + * @brief dll import/export and compiler message + */ + +#ifndef _QI_API_HPP_ +#define _QI_API_HPP_ + +#include +#include + +// qi_EXPORTS controls which symbols are exported when libqi +// is compiled as a SHARED lib. + +// To set your own QI_API macro, adapt the following line: +// #define MYLIB_API QI_LIB_API(mylib) + +#define QI_API QI_LIB_API(qi) + +#define QI_API_LEVEL 2 + + +#endif // _QI_API_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/application.hpp b/naoModule/libnaoqi_files/include/qi/application.hpp new file mode 100755 index 0000000..72154e2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/application.hpp @@ -0,0 +1,100 @@ +#pragma once +/* + * Copyright (c) 2012, 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_APPLICATION_HPP_ +#define _QI_APPLICATION_HPP_ + +#include +#include +#include + +namespace qi { + + class QI_API Application + { + public: + Application(int& argc, char** &argv); + Application(const std::string &name, int& argc, char** &argv); + ~Application(); + + static void run(); + static void stop(); + + static const std::vector& arguments(); + static int argc(); + static const char** argv(); + static void setName(const std::string &name); + static std::string name(); + static void setArguments(int argc, char** argv); + static void setArguments(const std::vector& arguments); + + static void* loadModule(const std::string& name, int flags=-1); + static void unloadModule(void* handle); + static bool terminated(); + static bool initialized(); + + static const char* program(); + + static bool atEnter(boost::function func); + static bool atExit(boost::function func); + static bool atStop(boost::function func); + static bool atSignal(boost::function func, int signal); + }; +} + +#define QI_AT_ENTER(func) \ +static bool QI_UNIQ_DEF(_qi_atenter) = ::qi::Application::atEnter(func); + +#define QI_AT_EXIT(func) \ +static bool QI_UNIQ_DEF(_qi_atexit) = ::qi::Application::atExit(func); + +//THIS IS INTERNAL +//API is not maintained for this function +//The user need to include and +//Use like this: +//namespace { +// _QI_COMMAND_LINE_OPTIONS( +// "Name of category", +// (option1) +// (option2) +// ) +//} +#define _QI_COMMAND_LINE_OPTIONS(desc, opts) \ +static void QI_UNIQ_DEF(_qi_opt_func)() { \ + namespace po = boost::program_options; \ + po::variables_map vm; \ + po::command_line_parser p(::qi::Application::arguments()); \ + po::options_description options(desc); \ + { \ + using namespace boost::program_options; \ + options.add_options() opts; \ + } \ + po::parsed_options res = p.options(options) \ + .allow_unregistered() \ + .run(); \ + po::store(res, vm); \ + /* Invoke notify callbacks*/ \ + po::notify(vm); \ + { \ + po::options_description descTmp; \ + descTmp.add_options() \ + ("help,h", ""); \ + po::variables_map vmTmp; \ + po::store(po::command_line_parser(qi::Application::arguments()) \ + .options(descTmp).allow_unregistered().run(), vmTmp); \ + if (vmTmp.count("help")) \ + std::cout << options << std::endl; \ + } \ + std::vector args \ + = po::collect_unrecognized(res.options, po::include_positional); \ + /* Set arguments to what was not used */ \ + ::qi::Application::setArguments(args); \ +} \ +QI_AT_ENTER(boost::bind(&(QI_UNIQ_DEF(_qi_opt_func)))) + + +#endif // _QI_APPLICATION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/atomic.hpp b/naoModule/libnaoqi_files/include/qi/atomic.hpp new file mode 100755 index 0000000..31ec0f5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/atomic.hpp @@ -0,0 +1,228 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#ifndef _QI_ATOMIC_HPP_ +#define _QI_ATOMIC_HPP_ + +#ifdef _MSC_VER +# include +# include + +extern "C" long __cdecl _InterlockedIncrement(long volatile *); +extern "C" long __cdecl _InterlockedDecrement(long volatile *); + +# pragma intrinsic(_InterlockedIncrement) +# pragma intrinsic(_InterlockedDecrement) + +#endif + +#include + +#include +#include + +namespace qi +{ + inline long testAndSet(long* cond) + { +#if defined __GNUC__ + return __sync_bool_compare_and_swap(cond, 0, 1); +#elif defined _MSC_VER + return 1 - InterlockedCompareExchange(cond, 1, 0); +#else + #error "Unknown platform, testAndSet not implemented" +#endif + } + + /* /!\ WARNING + * The 'volatile' is needed even though we use atomic compiler builtins. + * Without the volatile, a thread doing + * while (!setIfEquals(1,1)) + * Is never unstuck by a thread doing + * setIfEquals(0,1) + * + * AtomicBase has public member so that it can be initialized at + * static-initialization time (to make thread-safe static initialization inside + * functions) + */ + template + struct AtomicBase + { + public: + + + /* prefix operators */ + inline T operator++(); + inline T operator--(); + inline AtomicBase& operator=(T value); + /** If value is \p testValue, replace it with \p setValue. + * \return true if swap was performed + */ + inline bool setIfEquals(T testValue, T setValue); + + inline T swap(T value); + + inline T operator*() const + { + return _value; + } + + public: + BOOST_STATIC_ASSERT_MSG(sizeof(T) == sizeof(int), "qi::Atomic is only supprted for int-like types"); + + volatile +#ifdef _MSC_VER + long +#else + T +#endif + _value; + }; + + template + class Atomic: public AtomicBase + { + public: + Atomic() + { + this->_value = 0; + } + + Atomic(T value) + { + this->_value = value; + } + }; +#ifdef __GNUC__ + template + inline T AtomicBase::operator++() + { + return __sync_add_and_fetch(&_value, 1); + } + + template + inline T AtomicBase::operator--() + { + return __sync_sub_and_fetch(&_value, 1); + } + + template + inline AtomicBase& AtomicBase::operator=(T value) + { + __sync_lock_test_and_set(&_value, value); + return *this; + } + + template + inline T AtomicBase::swap(T value) + { + return __sync_lock_test_and_set(&_value, value); + } + template + inline bool AtomicBase::setIfEquals(T testValue, T setValue) + { + return __sync_bool_compare_and_swap(&_value, testValue, setValue); + } +#endif + +#ifdef _MSC_VER + + template <> + inline int AtomicBase::operator++() + { + return _InterlockedIncrement(&_value); + } + + template <> + inline int AtomicBase::operator--() + { + return _InterlockedDecrement(&_value); + } + + template<> + inline AtomicBase& AtomicBase::operator=(int value) + { + InterlockedExchange(&_value, value); + return *this; + } + + template<> + inline int AtomicBase::swap(int value) + { + return InterlockedExchange(&_value, value); + } + + template <> + inline bool AtomicBase::setIfEquals(int testValue, int setValue) + { + return _InterlockedCompareExchange(&_value, setValue, testValue) == testValue; + } + + template <> + inline unsigned int AtomicBase::operator++() + { + return _InterlockedIncrement(&_value); + } + + template <> + inline unsigned int AtomicBase::operator--() + { + return _InterlockedDecrement(&_value); + } + + template<> + inline AtomicBase& AtomicBase::operator=(unsigned int value) + { + InterlockedExchange(&_value, value); + return *this; + } + + template<> + inline unsigned int AtomicBase::swap(unsigned int value) + { + return InterlockedExchange(&_value, value); + } + + template <> + inline bool AtomicBase::setIfEquals(unsigned int testValue, unsigned int setValue) + { + return _InterlockedCompareExchange(&_value, setValue, testValue) == testValue; + } +#endif + +} + +#define _QI_INSTANCIATE(_, a, elem) ::qi::details::newAndAssign(&elem); + +/* The code below relies on the fact that initialisation of the qi::Atomic +* can happen at static initialization time, and that proper memory barriers +* are setup by its ++, swap and get operations. + */ +/** Accept a list of pointers (expected to be static function variables) + * and new them once in a thrad-safe manner. + * Implementation aims for minimal overhead when initialization is done. + */ +#define QI_THREADSAFE_NEW(...) \ + QI_ONCE(QI_VAARGS_APPLY(_QI_INSTANCIATE, _, __VA_ARGS__);) + +/// Execute code once, parallel calls are blocked until code finishes. +#define QI_ONCE(code) \ + static qi::AtomicBase QI_UNIQ_DEF(atomic_guard_a) = {0}; \ + static qi::AtomicBase QI_UNIQ_DEF(atomic_guard_b) = {0}; \ + while (!QI_UNIQ_DEF(atomic_guard_a).setIfEquals(1, 1)) \ + { \ + bool tok = QI_UNIQ_DEF(atomic_guard_b).setIfEquals(0,1); \ + if (tok) \ + { \ + code; \ + ++QI_UNIQ_DEF(atomic_guard_a); \ + } \ + } + + +#endif // _QI_ATOMIC_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/buffer.hpp b/naoModule/libnaoqi_files/include/qi/buffer.hpp new file mode 100755 index 0000000..42dab1e --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/buffer.hpp @@ -0,0 +1,84 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_BUFFER_HPP_ +#define _QI_BUFFER_HPP_ + +# include +# include +# include +# include +# include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi +{ + class BufferPrivate; + + /// Class to store buffer. + class QI_API Buffer + { + public: + /// Default constructor. + Buffer(); + /// Copy constructor. + Buffer(const Buffer& b); + /// Assignment operator. + Buffer& operator = (const Buffer& b); + + /// Write data in the buffer. + bool write(const void *data, size_t size); + + /// Add a sub-buffer to the main buffer. + size_t addSubBuffer(const Buffer& buffer); + /// Check if there is a sub-buffer at given offset. + bool hasSubBuffer(size_t offset) const; + /// Return the sub-buffer at given offset. + const Buffer& subBuffer(size_t offset) const; + + /// Return the content size of this buffer not counting sub-buffers. + size_t size() const; + /// Return the content size of this buffer and of all its sub-buffers. + size_t totalSize() const; + + /// Return a vector of sub-buffers of the current buffer. + const std::vector >& subBuffers() const; + + /// Reserve bytes at the end of current buffer. + void* reserve(size_t size); + /// Erase content of buffer and remove sub-buffers whithout clearing them. + void clear(); + + /// Return a pointer to the raw data storage of this buffer. + void* data(); + /// Return a const pointer to the raw data in this buffer. + const void* data() const; + + /// Read some data from the buffer. + const void* read(size_t offset = 0, size_t length = 0) const; + /// Read some data in the buffer and store it in a new pre-allocated buffer. + size_t read(void* buffer, size_t offset = 0, size_t length = 0) const; + + private: + friend class BufferReader; + // CS4251 + boost::shared_ptr _p; + }; + + namespace details { + QI_API void printBuffer(std::ostream& stream, const Buffer& buffer); + } +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QI_BUFFER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/bufferreader.hpp b/naoModule/libnaoqi_files/include/qi/bufferreader.hpp new file mode 100755 index 0000000..52284ce --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/bufferreader.hpp @@ -0,0 +1,46 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_BUFFERREADER_HPP_ +#define _QI_BUFFERREADER_HPP_ + +#include + +namespace qi { + + /// Class to read const buffer. + class QI_API BufferReader + { + public: + /// Constructor. + explicit BufferReader(const Buffer& buf); + /// Default destructor. + ~BufferReader(); + /// read and store data from the buffer. + size_t read(void *data, size_t length); + + /// read data from buffer. + void *read(size_t offset); + /// Move forward the buffer cursor by the given offset. + bool seek(size_t offset); + /// Check if we can read from the actual position toward \a offset bytes. + void *peek(size_t offset) const; + + /// Check if there is sub-buffer at the actual position. + bool hasSubBuffer() const; + /// return the sub-buffer at the actual position. + const Buffer& subBuffer(); + /// return the actual position in the buffer. + size_t position() const; + + private: + Buffer _buffer; + size_t _cursor; + size_t _subCursor; // position in sub-buffers + }; +} + +#endif // _QI_BUFFERREADER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/clock.hpp b/naoModule/libnaoqi_files/include/qi/clock.hpp new file mode 100755 index 0000000..4aa4c66 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/clock.hpp @@ -0,0 +1,156 @@ +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#pragma once +#ifndef _QI_CLOCK_HPP_ +#define _QI_CLOCK_HPP_ + +#include +#include +#include + +namespace qi +{ + + + typedef boost::chrono::duration Duration; + typedef boost::chrono::duration NanoSeconds; + typedef boost::chrono::duration MicroSeconds; + typedef boost::chrono::duration MilliSeconds; + typedef boost::chrono::duration Seconds; + typedef boost::chrono::duration > Minutes; + typedef boost::chrono::duration > Hours; + + + class QI_API SteadyClock + { + public: + typedef int64_t rep; + typedef boost::nano period; // clock counts nanoseconds + typedef boost::chrono::duration duration; + typedef boost::chrono::time_point time_point; + BOOST_STATIC_CONSTEXPR bool is_steady = boost::chrono::steady_clock::is_steady; + + public: + typedef boost::chrono::time_point SteadyClockTimePoint; + + enum Expect { + Expect_SoonerOrLater, + Expect_Later, + Expect_Sooner + }; + + + // Returns a time_point representing the current value of the clock. + static SteadyClockTimePoint now(); + + // Convert the time point to a number of milliseconds on 32 bits. + // Since the 32 bits number overflows every 2^32 ms ~ 50 days, + // this is a lossy operation. + static uint32_t toUint32ms(const SteadyClockTimePoint &t) throw(); + static int32_t toInt32ms(const SteadyClockTimePoint &t) throw(); + + // Get a time point from a number of milliseconds on 32 bits. + // + // Since the 32 bits number overflows every ~50 days, an infinity of + // time points match a given 32 bits number (all modulo ~50 days). + // This function picks the result near the guess timepoint depending on + // the expect argument: + // + // if expect == LATER, result is expected to be later than guess: + // + // guess <= result < guess + period + // + // if expect == SOONER, result is expected to be sooner than guess: + // + // guess - period < result <= guess + // + // if expect == SOONER_OR_LATER, pick the nearest result: + // + // guess - period/2 < result <= guess + period/2 + // + // where period == 2^32 ms ~ 50 days + static time_point fromUint32ms(uint32_t t_ms, SteadyClockTimePoint guess, + Expect expect=Expect_SoonerOrLater) throw(); + static time_point fromInt32ms(int32_t t_ms, SteadyClockTimePoint guess, + Expect expect=Expect_SoonerOrLater) throw(); + }; + + class QI_API WallClock + { + public: + typedef int64_t rep; + typedef boost::nano period; // clock counts nanoseconds + typedef boost::chrono::duration duration; + typedef boost::chrono::time_point time_point; + BOOST_STATIC_CONSTEXPR bool is_steady = false; + + public: + typedef boost::chrono::time_point WallClockTimePoint; + + // Returns a time_point representing the current value of the clock. + static WallClockTimePoint now(); + + // Converts a system clock time point to std::time_t + static std::time_t to_time_t(const WallClockTimePoint& t) throw(); + + // Converts std::time_t to a system clock time point + static WallClockTimePoint from_time_t(const std::time_t &t) throw(); + }; + + + + typedef SteadyClock::SteadyClockTimePoint SteadyClockTimePoint; + typedef WallClock::WallClockTimePoint WallClockTimePoint; + + inline SteadyClockTimePoint steadyClockNow() { + return SteadyClock::now(); + } + + inline WallClockTimePoint wallClockNow() { + return WallClock::now(); + } + + + // Blocks the execution of the current thread for at least d. + QI_API void sleepFor(const qi::Duration& d); + template + inline void sleepFor(const boost::chrono::duration& d); + + // Blocks the execution of the current thread until t has been + // reached. + // + // This is equivalent to sleep_for(t-steady_clock::now()) + QI_API void sleepUntil(const SteadyClockTimePoint &t); + template + inline void sleepUntil(const boost::chrono::time_point& t); + + // Blocks the execution of the current thread until t has been + // reached. + // Adjustments of the clock are taken into account. + // Thus the duration of the block might, but might not, be less + // or more than t - system_clock::now() + QI_API void sleepUntil(const WallClockTimePoint& t); + template + inline void sleepUntil(const boost::chrono::time_point& t); + +} + +#ifdef __APPLE__ + //export template instanciation for RTTI issues across libraries. (mostly for OSX) + template class QI_API boost::chrono::duration; + template class QI_API boost::chrono::duration; + template class QI_API boost::chrono::duration; + template class QI_API boost::chrono::duration; + template class QI_API boost::chrono::duration >; + template class QI_API boost::chrono::duration >; + template class QI_API boost::chrono::time_point; + template class QI_API boost::chrono::time_point; +#endif + +#include + +#endif // _QI_OS_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/clock.hxx b/naoModule/libnaoqi_files/include/qi/clock.hxx new file mode 100755 index 0000000..5860089 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/clock.hxx @@ -0,0 +1,59 @@ +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#pragma once +#ifndef _QI_CLOCK_HXX_ +#define _QI_CLOCK_HXX_ + +#include + +namespace qi { + + template + void sleepFor(const boost::chrono::duration& d) + { + sleepFor(boost::chrono::ceil(d)); + } + + template + void sleepUntil(const boost::chrono::time_point& t) + { + sleepFor(t - SteadyClock::now()); + } + + template + void sleepUntil(const boost::chrono::time_point& t) + { + sleepFor(t - WallClock::now()); + } + +} + +namespace boost +{ + namespace chrono + { + template + struct clock_string + { + static std::basic_string name() {return "qi::steady_clock";} + static std::basic_string since() { + return clock_string::since(); + } + }; + + template + struct clock_string + { + static std::basic_string name() {return "qi::system_clock";} + static std::basic_string since() { + return clock_string::since(); + } + }; + } +} + +#endif // _QI_CLOCK_HXX_ diff --git a/naoModule/libnaoqi_files/include/qi/config.hpp b/naoModule/libnaoqi_files/include/qi/config.hpp new file mode 100755 index 0000000..c1d959a --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/config.hpp @@ -0,0 +1 @@ +/* #undef qi_STATIC_BUILD */ diff --git a/naoModule/libnaoqi_files/include/qi/details/eventloop.hxx b/naoModule/libnaoqi_files/include/qi/details/eventloop.hxx new file mode 100755 index 0000000..1f9c724 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/eventloop.hxx @@ -0,0 +1,64 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_DETAILS_EVENTLOOP_HXX_ +#define _QI_DETAILS_EVENTLOOP_HXX_ + +#include + +namespace qi +{ + + namespace detail + { + template + class DelayedPromise: public Promise + { + public: + DelayedPromise() {} + void setup(boost::function)> cancelCallback, FutureCallbackType async = FutureCallbackType_Async) + { + Promise::setup(cancelCallback, async); + } + }; + + template void call_and_set(qi::Promise p, boost::function f) + { + try + { + p.setValue(f()); + } + catch (const std::exception& e) + { + p.setError(e.what()); + } + catch(...) + { + p.setError("unknown exception"); + } + } + template void check_canceled(qi::Future f, qi::Promise p) + { + if (f.wait() == FutureState_Canceled) + p.setCanceled(); + // Nothing to do for other states. + } + } + template void nullConverter(void*, R&) {} + template Future EventLoop::async(boost::function callback, uint64_t usDelay) + { + detail::DelayedPromise promise; + qi::Future f = async((boost::function)boost::bind(detail::call_and_set, promise, callback), usDelay); + promise.setup(boost::bind(&detail::futureCancelAdapter, + boost::weak_ptr >(f.impl())), FutureCallbackType_Sync); + f.connect(boost::bind(&detail::check_canceled,_1, promise)); + return promise.future(); + } + +} + + +#endif diff --git a/naoModule/libnaoqi_files/include/qi/details/future.hxx b/naoModule/libnaoqi_files/include/qi/details/future.hxx new file mode 100755 index 0000000..f11425d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/future.hxx @@ -0,0 +1,335 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_DETAILS_FUTURE_HXX_ +#define _QI_DETAILS_FUTURE_HXX_ + +#include +#include // pair +#include +#include + +#include + +namespace qi { + + namespace detail { + + class FutureBasePrivate; + class QI_API FutureBase { + public: + FutureBase(); + ~FutureBase(); + + FutureState wait(int msecs) const; + FutureState state() const; + bool isRunning() const; + bool isFinished() const; + bool isCanceled() const; + bool hasError(int msecs) const; + bool hasValue(int msecs) const; + const std::string &error(int msecs) const; + void reportStart(); + void reset(); + + protected: + void reportValue(); + void reportError(const std::string &message); + void reportCanceled(); + boost::recursive_mutex& mutex(); + void notifyFinish(); + + public: + FutureBasePrivate *_p; + }; + + + //common state shared between a Promise and multiple Futures + template + class FutureBaseTyped : public FutureBase { + public: + typedef typename FutureType::type ValueType; + FutureBaseTyped() + : _value() + , _async(FutureCallbackType_Async) + { + } + + bool isCancelable() const + { + return _onCancel; + } + + void cancel(qi::Future& future) + { + if (isFinished()) + return; + if (!_onCancel) + throw FutureException(FutureException::ExceptionState_FutureNotCancelable); + _onCancel(Promise(future)); + } + + void setOnCancel(boost::function)> onCancel) + { + _onCancel = onCancel; + } + + + void callCbNotify(qi::Future& future) + { + for(unsigned i = 0; i<_onResult.size(); ++i) + { + try { + if (_async == FutureCallbackType_Async) + getEventLoop()->post(boost::bind(_onResult[i], future)); + else + _onResult[i](future); + } catch(const qi::PointerLockException&) { // do nothing + } catch(const std::exception& e) { + qiLogError("qi.future") << "Exception caught in future callback " + << e.what(); + } catch (...) { + qiLogError("qi.future") + << "Unknown exception caught in future callback"; + } + } + notifyFinish(); + } + + void setValue(qi::Future& future, const ValueType &value) + { + // report-ready + onResult() must be Atomic to avoid + // missing callbacks/double calls in case connect() is invoked at + // the same time + boost::recursive_mutex::scoped_lock lock(mutex()); + if (!isRunning()) + throw FutureException(FutureException::ExceptionState_PromiseAlreadySet); + + _value = value; + reportValue(); + callCbNotify(future); + } + + /* + * inplace api for promise + */ + void set(qi::Future& future) + { + // report-ready + onResult() must be Atomic to avoid + // missing callbacks/double calls in case connect() is invoked at + // the same time + boost::recursive_mutex::scoped_lock lock(mutex()); + if (!isRunning()) + throw FutureException(FutureException::ExceptionState_PromiseAlreadySet); + + reportValue(); + callCbNotify(future); + } + + void setError(qi::Future& future, const std::string &message) + { + boost::recursive_mutex::scoped_lock lock(mutex()); + if (!isRunning()) + throw FutureException(FutureException::ExceptionState_PromiseAlreadySet); + + reportError(message); + callCbNotify(future); + } + + void setCanceled(qi::Future& future) { + boost::recursive_mutex::scoped_lock lock(mutex()); + if (!isRunning()) + throw FutureException(FutureException::ExceptionState_PromiseAlreadySet); + + reportCanceled(); + callCbNotify(future); + } + + + void connect(qi::Future future, + const boost::function)> &s, + FutureCallbackType type) + { + bool ready; + { + boost::recursive_mutex::scoped_lock lock(mutex()); + _onResult.push_back(s); + ready = isFinished(); + } + //result already ready, notify the callback + if (ready) { + if (type == FutureCallbackType_Async) + getEventLoop()->post(boost::bind(s, future)); + else + { + try { + s(future); + } catch(const ::qi::PointerLockException&) + {/*do nothing*/} + } + } + } + + const ValueType &value(int msecs) const { + FutureState state = wait(msecs); + if (state == FutureState_Running) + throw FutureException(FutureException::ExceptionState_FutureTimeout); + if (state == FutureState_Canceled) + throw FutureException(FutureException::ExceptionState_FutureCanceled); + if (state == FutureState_FinishedWithError) + throw FutureUserException(error(FutureTimeout_None)); + return _value; + } + + private: + friend class Promise; + typedef std::vector)> > Callbacks; + Callbacks _onResult; + ValueType _value; + boost::function)> _onCancel; + FutureCallbackType _async; + }; + + template + void waitForFirstHelper(qi::Promise< qi::Future >& prom, + qi::Future& fut, + qi::Atomic* count) { + if (!prom.future().isFinished() && !fut.hasError()) + { + // An other future can trigger at the same time. + // Don't bother to lock, just catch the FutureAlreadySet exception + try + { + prom.setValue(fut); + } + catch(const FutureException&) + {} + } + if (! --*count) + { + // I'm the last + if (!prom.future().isFinished()) + { + // same 'race' as above. between two setError, not between a value and + // an error. + try + { + prom.setValue(makeFutureError("No future returned successfully.")); + } + catch(const FutureException&) + {} + } + delete count; + } + } + } // namespace detail + + template + qi::Future makeFutureError(const std::string &error, FutureCallbackType async) { + qi::Promise prom(async); + prom.setError(error); + return prom.future(); + } + + template + void waitForAll(std::vector >& vect) { + typename std::vector< Future >::iterator it; + qi::FutureBarrier barrier; + + for (it = vect.begin(); it != vect.end(); ++it) { + barrier.addFuture(*it); + } + barrier.future().wait(); + } + + template + qi::FutureSync< qi::Future > waitForFirst(std::vector< Future >& vect) { + typename std::vector< Future >::iterator it; + qi::Promise< qi::Future > prom; + qi::Atomic* count = new qi::Atomic(); + count->swap((int)vect.size()); + for (it = vect.begin(); it != vect.end(); ++it) { + it->connect(boost::bind(&detail::waitForFirstHelper, prom, *it, count)); + } + return prom.future(); + } + + namespace detail + { + template + void futureAdapter(Future f, Promise p, CONV converter) + { + if (f.hasError()) + p.setError(f.error()); + else if (f.isCanceled()) + p.setCanceled(); + else + { + try { + converter(f.value(), p.value()); + } + catch (const std::exception& e) + { + p.setError(std::string("futureAdapter conversion error: ") + e.what()); + return; + } + p.trigger(); + } + } + + template + void futureCancelAdapter(boost::weak_ptr > wf) + { + if (boost::shared_ptr > f = wf.lock()) + Future(f).cancel(); + } + } + + template <> + struct FutureValueConverter + { + void operator()(void* in, void* out) + { + } + }; + + template + struct FutureValueConverter + { + void operator()(const T& in, void* out) + { + } + }; + + template + struct FutureValueConverter + { + void operator()(void* in, const T& out) + { + } + }; + + template + void adaptFuture(const Future& f, Promise& p) + { + if (f.isCancelable()) + p.setup(boost::bind(&detail::futureCancelAdapter, + boost::weak_ptr >(f._p))); + const_cast&>(f).connect(boost::bind(detail::futureAdapter >, _1, p, + FutureValueConverter())); + } + + template + void adaptFuture(const Future& f, Promise& p, CONV converter) + { + if (f.isCancelable()) + p.setup(boost::bind(&detail::futureCancelAdapter, + boost::weak_ptr >(f._p))); + const_cast&>(f).connect(boost::bind(detail::futureAdapter, _1, p, converter)); + } +} + +#endif // _QI_DETAILS_FUTURE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qi/details/log.hxx b/naoModule/libnaoqi_files/include/qi/details/log.hxx new file mode 100755 index 0000000..716da29 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/log.hxx @@ -0,0 +1,283 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_DETAILS_LOG_HXX_ +#define _QI_DETAILS_LOG_HXX_ + + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogDebug(...) qi::log::LogStream(qi::LogLevel_Debug, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogDebug(...) qi::log::LogStream(qi::LogLevel_Debug, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogVerbose(...) qi::log::LogStream(qi::LogLevel_Verbose, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogVerbose(...) qi::log::LogStream(qi::LogLevel_Verbose, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogInfo(...) qi::log::LogStream(qi::LogLevel_Info, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogInfo(...) qi::log::LogStream(qi::LogLevel_Info, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogWarning(...) qi::log::LogStream(qi::LogLevel_Warning, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogWarning(...) qi::log::LogStream(qi::LogLevel_Warning, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogError(...) qi::log::LogStream(qi::LogLevel_Error, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogError(...) qi::log::LogStream(qi::LogLevel_Error, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _qiLogFatal(...) qi::log::LogStream(qi::LogLevel_Fatal, "", __FUNCTION__, 0, __VA_ARGS__).self() +#else +# define _qiLogFatal(...) qi::log::LogStream(qi::LogLevel_Fatal, __FILE__, __FUNCTION__, __LINE__, __VA_ARGS__).self() +#endif + + +# define _QI_FORMAT_ELEM(_, a, elem) % (elem) + +# define _QI_LOG_FORMAT(Msg, ...) \ + QI_CAT(_QI_LOG_FORMAT_HASARG_, _QI_LOG_ISEMPTY(__VA_ARGS__))(Msg, __VA_ARGS__) + +#define _QI_LOG_FORMAT_HASARG_0(Msg, ...) \ + boost::str(::qi::log::detail::getFormat(Msg) QI_VAARGS_APPLY(_QI_FORMAT_ELEM, _, __VA_ARGS__ /**/)) + +#define _QI_LOG_FORMAT_HASARG_1(Msg, ...) Msg + +#define _QI_SECOND(a, ...) __VA_ARGS__ + +/* For fast category access, we use lookup to a fixed name symbol. + * The user is required to call qiLogCategory somewhere in scope. + */ + +# define _QI_LOG_CATEGORY_GET() _qi_log_category + +#if defined(NO_QI_LOG_DETAILED_CONTEXT) || defined(NDEBUG) +# define _QI_LOG_MESSAGE(Type, Message) \ + do \ + { \ + if (::qi::log::detail::isVisible(_QI_LOG_CATEGORY_GET(), ::qi::Type)) \ + ::qi::log::log(::qi::Type, \ + _QI_LOG_CATEGORY_GET(), \ + Message, \ + "", __FUNCTION__, 0); \ + } \ + while (false) +#else +# define _QI_LOG_MESSAGE(Type, Message) \ + do \ + { \ + if (::qi::log::detail::isVisible(_QI_LOG_CATEGORY_GET(), ::qi::Type)) \ + ::qi::log::log(::qi::Type, \ + _QI_LOG_CATEGORY_GET(), \ + Message, \ + __FILE__, __FUNCTION__, __LINE__); \ + } \ + while (false) +#endif + +/* Tricky, we do not want to hit category_get if a category is specified +* Usual glitch of off-by-one list size: put argument 'TypeCased' in the vaargs +* Basically we want variadic macro, but it does not exist, so emulate it using _QI_LOG_EMPTY. +*/ +# define _QI_LOG_MESSAGE_STREAM(Type, TypeCased, ...) \ + QI_CAT(_QI_LOG_MESSAGE_STREAM_HASCAT_, _QI_LOG_ISEMPTY( __VA_ARGS__))(Type, TypeCased, __VA_ARGS__) + +// no extra argument +#define _QI_LOG_MESSAGE_STREAM_HASCAT_1(Type, TypeCased, ...) \ + ::qi::log::detail::isVisible(_QI_LOG_CATEGORY_GET(), ::qi::Type) \ + && BOOST_PP_CAT(_qiLog, TypeCased)(_QI_LOG_CATEGORY_GET()) + +// Visual bouncer for macro evalution order glitch. +#ifdef _MSC_VER +#define _QI_LOG_MESSAGE_STREAM_HASCAT_0(...) QI_DELAY(_QI_LOG_MESSAGE_STREAM_HASCAT_0) ## _BOUNCE(__VA_ARGS__) +#else +#define _QI_LOG_MESSAGE_STREAM_HASCAT_0(...) _QI_LOG_MESSAGE_STREAM_HASCAT_0_BOUNCE(__VA_ARGS__) +#endif + +// At leas one argument: category. Check for a format argument +#define _QI_LOG_MESSAGE_STREAM_HASCAT_0_BOUNCE(Type, TypeCased, cat, ...) \ + QI_CAT(_QI_LOG_MESSAGE_STREAM_HASCAT_HASFORMAT_, _QI_LOG_ISEMPTY( __VA_ARGS__))(Type, TypeCased, cat, __VA_ARGS__) + + +// No format argument +#define _QI_LOG_MESSAGE_STREAM_HASCAT_HASFORMAT_1(Type, TypeCased, cat, ...) \ + BOOST_PP_CAT(_qiLog,TypeCased)(cat) + +// Format argument +#define _QI_LOG_MESSAGE_STREAM_HASCAT_HASFORMAT_0(Type, TypeCased, cat, ...) \ + BOOST_PP_CAT(_qiLog, TypeCased)(cat, _QI_LOG_FORMAT(__VA_ARGS__)) + + +/* Detecting empty arg is tricky. + * Trick 1 below does not work with gcc, because x ## "foo" produces a preprocessor error. + * Trick 2 rely on ##__VA_ARGS__ +*/ +#ifdef _MSC_VER + +#define _WQI_IS_EMPTY_HELPER___ a,b +#define WQI_IS_EMPTY(a,...) QI_CAT_20(QI_LIST_VASIZE,((QI_CAT_22(_WQI_IS_EMPTY_HELPER, QI_CAT_24(QI_CAT_26(_, a), _))))) + +#define _QI_FIRST_ARG(a, ...) a +#define _QI_LOG_ISEMPTY(...) WQI_IS_EMPTY(QI_CAT_18(_, _QI_FIRST_ARG(__VA_ARGS__, 12))) + +#else + +#define _QI_LOG_REVERSE 9, 8, 7, 6, 5, 4, 3, 2, 1, 0, 0, 0 +#define _QI_LOG_REVERSEEMPTY 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1 +#define _QI_LOG_ARGN(a, b, c, d, e, f, g, h, i, N, ...) N +#define _QI_LOG_NARG_(dummy, ...) _QI_LOG_ARGN(__VA_ARGS__) +#define _QI_LOG_NARG(...) _QI_LOG_NARG_(dummy, ##__VA_ARGS__, _QI_LOG_REVERSE) +#define _QI_LOG_ISEMPTY(...) _QI_LOG_NARG_(dummy, ##__VA_ARGS__, _QI_LOG_REVERSEEMPTY) + +#endif + +namespace qi { + namespace log{ + namespace detail { + + // Used to remove warning "statement has no effect" + inline bool qiFalse() {return false;} + + class NullStream { + public: + NullStream(...) + { + } + + NullStream &self() + { + return *this; + } + template + NullStream& operator<<(const T &QI_UNUSED(val)) + { + return self(); + } + + NullStream& operator<<(std::ostream& (*QI_UNUSED(f))(std::ostream&)) + { + return self(); + } + }; + + // Hack required to silence spurious warning in compile-time disabled macros + // We need an operator with priority below << and above && + inline bool operator<(bool b, const NullStream& ns) + { + return false; + } + + struct Category + { + Category() + : maxLevel(qi::LogLevel_Silent) + {} + + Category(const std::string &name) + : name(name) + , maxLevel(qi::LogLevel_Silent) + {} + + std::string name; + qi::LogLevel maxLevel; //max level among all subscribers + std::vector levels; //level by subscribers + + void setLevel(SubscriberId sub, qi::LogLevel level); + }; + + QI_API boost::format getFormat(const std::string& s); + + //inlined for perf + inline bool isVisible(Category* category, qi::LogLevel level) + { + return category && level <= category->maxLevel; + } + } + + typedef detail::Category* CategoryType; + class LogStream: public std::stringstream + { + public: + LogStream(const qi::LogLevel level, + const char *file, + const char *function, + const int line, + const char *category) + : _logLevel(level) + , _category(category) + , _categoryType(0) + , _file(file) + , _function(function) + , _line(line) + { + } + LogStream(const qi::LogLevel level, + const char *file, + const char *function, + const int line, + CategoryType category) + : _logLevel(level) + , _category(0) + , _categoryType(category) + , _file(file) + , _function(function) + , _line(line) + { + } + LogStream(const qi::LogLevel level, + const char *file, + const char *function, + const int line, + const char *category, + const std::string& message) + : _logLevel(level) + , _category(category) + , _categoryType(0) + , _file(file) + , _function(function) + , _line(line) + { + *this << message; + } + + ~LogStream() + { + if (_category) + qi::log::log(_logLevel, _category, this->str().c_str(), _file, _function, _line); + else + qi::log::log(_logLevel, _categoryType, this->str(), _file, _function, _line); + } + + LogStream& self() { + return *this; + } + + private: + qi::LogLevel _logLevel; + const char *_category; + CategoryType _categoryType; + const char *_file; + const char *_function; + int _line; + + //avoid copy + LogStream(const LogStream &rhs); + LogStream &operator=(const LogStream &rhs); + }; + } +} + +#endif // _QI_DETAILS_LOG_HXX_ diff --git a/naoModule/libnaoqi_files/include/qi/details/trackable.hxx b/naoModule/libnaoqi_files/include/qi/details/trackable.hxx new file mode 100755 index 0000000..66d739f --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/trackable.hxx @@ -0,0 +1,207 @@ +#pragma once +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_DETAILS_TRACKABLE_HXX_ +#define _QI_DETAILS_TRACKABLE_HXX_ + +#include +#include +#include +#include +#include +#include + +namespace qi +{ + template + inline Trackable::Trackable(T* ptr) + : _wasDestroyed(false) + { + _ptr = boost::shared_ptr(ptr, boost::bind(&Trackable::_destroyed, _1)); + } + + template + inline void Trackable::destroy() + { + _ptr.reset(); + wait(); + } + + template + inline void Trackable::wait() + { + boost::mutex::scoped_lock lock(_mutex); + while (!_wasDestroyed) + { + _cond.wait(lock); + } + } + + template + inline void Trackable::_destroyed() + { + // unblock + boost::mutex::scoped_lock lock(_mutex); + _wasDestroyed = true; + _cond.notify_all(); + } + + template + inline Trackable::~Trackable() + { + // We expect destroy() to have been called from parent destructor, so from + // this thread. + if (!_wasDestroyed) + { + qiLogError("qi.Trackable") << "Trackable destroyed without calling destroy()"; + // do it to mitigate the effect, but it's too late + destroy(); + } + } + + template + inline boost::shared_ptr Trackable::lock() + { + return _ptr; + } + + template + inline boost::weak_ptr Trackable::weakPtr() + { + return boost::weak_ptr(_ptr); + } + + namespace detail + { + // Functor that locks a weak ptr and make a call if successful + // Generalize on shared_ptr and weak_ptr types in case we ever have + // other types with their semantics + template + class LockAndCall + { + public: + typedef typename boost::function_types::result_type::type Result; + LockAndCall(const WT& arg, boost::function func, boost::function onFail) + : _wptr(arg) + , _f(func) + , _onFail(onFail) + {} + +#define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + QI_GEN_MAYBE_TEMPLATE_OPEN(comma) \ + ATYPEDECL \ + QI_GEN_MAYBE_TEMPLATE_CLOSE(comma) \ + Result operator()(ADECL) { \ + ST s = _wptr.lock(); \ + if (s) \ + return _f(AUSE); \ + else \ + if (_onFail) \ + _onFail(); \ + else \ + return Result(); \ + } + QI_GEN(genCall) +#undef genCall + WT _wptr; + boost::function _f; + boost::function _onFail; + }; + + template struct BindTransform + { + typedef const T& type; + static type transform(const T& arg) + { + return arg; + } + template + static boost::function wrap(const T& arg, boost::function func, boost::function onFail) + { + return func; + } + }; + + template struct BindTransform, false > + { + typedef T* type; + static T* transform(const boost::weak_ptr& arg) + { + // Note that we assume that lock if successful always return the same pointer + // And that if lock fails once, it will fail forever from that point + return arg.lock().get(); + } + template + static boost::function wrap(const boost::weak_ptr& arg, boost::function func, boost::function onFail) + { + return LockAndCall, boost::shared_ptr, F>(arg, func, onFail); + } + }; + + template struct BindTransform + { + typedef T* type; + static T* transform(T* const & arg) + { + // Note that we assume that lock if successful always return the same pointer + return arg; + } + template + static boost::function wrap(T*const & arg, boost::function func, boost::function onFail) + { + return LockAndCall, boost::shared_ptr, F>(arg->weakPtr(), func, onFail); + } + }; + + inline void throwPointerLockException() + { + throw PointerLockException(); + } + } + +#ifndef DOXYGEN + template + boost::function bind(const AF& fun) + { + return fun; + } +#define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + boost::function bind(const AF& fun, const ARG0& arg0 comma ADECL) \ + { \ + typedef typename detail::BindTransform::type>::value> Transform; \ + typename Transform::type transformed = Transform::transform(arg0); \ + boost::function f = boost::bind(fun, transformed comma AUSE); \ + return Transform::wrap(arg0, f, detail::throwPointerLockException); \ + } \ + template \ + boost::function bindWithFallback(const boost::function onFail, const AF& fun, const ARG0& arg0 comma ADECL) \ + { \ + typedef typename detail::BindTransform::type>::value> Transform; \ + typename Transform::type transformed = Transform::transform(arg0); \ + boost::function f = boost::bind(fun, transformed comma AUSE); \ + return Transform::wrap(arg0, f, onFail); \ + } + QI_GEN(genCall) +#undef genCall +#endif // DOXYGEN + template + boost::function track(const boost::function& f, const ARG0& arg0) + { + typedef typename detail::BindTransform::type>::value> Transform; + return Transform::wrap(arg0, f, detail::throwPointerLockException); + } + template + boost::function trackWithFallback(boost::function onFail, + const boost::function& f, const ARG0& arg0) + { + typedef typename detail::BindTransform::type>::value> Transform; + return Transform::wrap(arg0, f, onFail); + } +} + +#endif // _QI_DETAILS_TRACKABLE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qi/details/warn_pop_ignore_deprecated.hpp b/naoModule/libnaoqi_files/include/qi/details/warn_pop_ignore_deprecated.hpp new file mode 100755 index 0000000..480fca3 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/warn_pop_ignore_deprecated.hpp @@ -0,0 +1,13 @@ +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +// clang and GCC +#if defined(__GNUC__) +# if defined(__clang__) || (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +# pragma GCC diagnostic pop +# endif +#elif defined(_MSC_VER) +# pragma warning(pop) +#endif diff --git a/naoModule/libnaoqi_files/include/qi/details/warn_push_ignore_deprecated.hpp b/naoModule/libnaoqi_files/include/qi/details/warn_push_ignore_deprecated.hpp new file mode 100755 index 0000000..a73f095 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/details/warn_push_ignore_deprecated.hpp @@ -0,0 +1,27 @@ +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +/* + * this allow removing spurious warning when a deprecated declaration use another deprecated declaration. + * + * QI_API_DEPRECATED class Foo; + * + * #include + * //Would emit a spurious deprecated warning about Foo otherwise + * QI_API_DEPRECATED void bar(Foo foo); + * #include + */ + + +// clang and GCC +#if defined(__GNUC__) +# if defined(__clang__) || (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +# pragma GCC diagnostic push +# endif +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#elif defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable : 4996) +#endif diff --git a/naoModule/libnaoqi_files/include/qi/error.hpp b/naoModule/libnaoqi_files/include/qi/error.hpp new file mode 100755 index 0000000..8eae392 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/error.hpp @@ -0,0 +1,69 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/** @file + * @brief + */ + +#ifndef _QI_ERROR_HPP_ +#define _QI_ERROR_HPP_ + +# include + +# include +# include + +namespace qi { + namespace os { + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable : 4251 ) +// non dll-interface std::runtime_error used as base for dll-interface calss +// qi::os::QiException +# pragma warning( disable : 4275 ) +#endif + + /** \class QiException error.hpp "qi/error.hpp" + * \brief Custom exception that may be thrown by QI methods. + * \deprecated since 1.14, there is no more exception in libqi. + */ + class QI_API QI_API_DEPRECATED QiException : public std::runtime_error + { + public: + + /** + * \brief Constructor + * + * Create a message exception. + * + * \param message Exception message. + */ + explicit QiException(const std::string &message) + : std::runtime_error(message) + {} + + /** + * \brief Copy constructor. + * \param[in] e message Exception message. + */ + QiException(const QiException &e) + : std::runtime_error(e.what()) + {} + + /** \brief Destructor */ + virtual ~QiException() throw() + {} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + }; + } +} + +#endif // _QI_ERROR_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/eventloop.hpp b/naoModule/libnaoqi_files/include/qi/eventloop.hpp new file mode 100755 index 0000000..b6a2804 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/eventloop.hpp @@ -0,0 +1,121 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_EVENTLOOP_HPP_ +#define _QI_EVENTLOOP_HPP_ + +#ifdef _MSC_VER +# pragma warning( disable: 4503 ) // decorated name length +#endif + +#include +#include + +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace boost { + namespace asio { + class io_service; +}} + +namespace qi +{ + template class Future; + + class EventLoopPrivate; + class QI_API EventLoop + { + public: + /** Create a new eventLoop. + * You must then call either start(), run() or startThreadPool() to start event processing. + */ + EventLoop(const std::string& name = "eventloop"); + ~EventLoop(); + /// Return true if current thread is the event loop thread. + bool isInEventLoopThread(); + /// Start in threaded mode + void start(int nthreads = 0); + /// Start in thread-pool mode: each asyncCall() will be run in parallel + void startThreadPool(int minWorkers=-1, int maxWorkers=-1, int minIdleWorkers=-1, int maxIdleWorkers=-1); + /// Wait for run thread to terminate + void join(); + /// Ask main loop to terminate + void stop(); + /// Run main loop in current thread. + void run(); + /// Set callback to be called in case of a deadlock detection + void setEmergencyCallback(boost::function cb); + + /// Set the maximum number of threads in the pool + void setMaxThreads(unsigned int max); + + // Internal function + void *nativeHandle(); + + /// @{ + /** Call given function once after given delay in microseconds. + * @return a canceleable future + */ + + template + Future async(boost::function callback, uint64_t usDelay=0); + Future async(boost::function callback, uint64_t usDelay=0); + + /// @} + + /// Similar to async() but without cancelation or notification + void post(const boost::function& callback, uint64_t usDelay=0); + + /** Monitor event loop to detect deadlocks. + @param helper an other event loop used for monitoring + @param maxUsDelay maximum expected delay between an async() and its execution + @return a canceleable future. Invoke cancel() to terminate monitoring. + In case an async() call does not execute in time, the + future's error will be set. + */ + Future monitorEventLoop(EventLoop* helper, uint64_t maxUsDelay); + + EventLoopPrivate *_p; + std::string _name; + }; + + /// Return the global eventloop, created on demand on first call. + QI_API EventLoop* getEventLoop(); + + /// Start the eventloop with nthread threads. No-op if already started. + QI_API void startEventLoop(int nthread); + + /// Return the io_service used by the global event loop + QI_API boost::asio::io_service& getIoService(); + + /// Compat + /// Return a default event loop for network operations. + QI_API QI_API_DEPRECATED EventLoop* getDefaultNetworkEventLoop(); + /// Return a default context for other uses. + QI_API QI_API_DEPRECATED EventLoop* getDefaultObjectEventLoop(); + /// Return a default thread pool context + QI_API QI_API_DEPRECATED EventLoop* getDefaultThreadPoolEventLoop(); + + namespace detail { + /* when throw this thread will stop a thread of the eventloop + */ + class TerminateThread { + }; + }; +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#include +#endif // _QI_EVENTLOOP_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/future.hpp b/naoModule/libnaoqi_files/include/qi/future.hpp new file mode 100755 index 0000000..22bc8ba --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/future.hpp @@ -0,0 +1,607 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_FUTURE_HPP_ +#define _QI_FUTURE_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +# pragma warning( disable: 4275 ) //std::runtime_error: no dll interface +#endif + +namespace qi { + + template + struct FutureType + { + typedef T type; + typedef T typecast; + }; + + struct FutureHasNoValue {}; + // Hold a void* for Future + template<> + struct FutureType + { + typedef void* type; + typedef FutureHasNoValue typecast; + }; + + template class FutureInterface; + template class Future; + template class FutureSync; + template class Promise; + + namespace detail { + template class FutureBaseTyped; + + template + void futureCancelAdapter( + boost::weak_ptr > wf); + } + + /** State of the future. + */ + enum FutureState { + FutureState_None, /// Future is not tied to a promise + FutureState_Running, /// Operation pending + FutureState_Canceled, /// The future has been canceled + FutureState_FinishedWithError, /// The operation is finished with an error + FutureState_FinishedWithValue, /// The operation is finished with a value + }; + + enum FutureCallbackType { + FutureCallbackType_Sync = 0, + FutureCallbackType_Async = 1 + }; + + enum FutureTimeout { + FutureTimeout_Infinite = ((int) 0x7fffffff), + FutureTimeout_None = 0, + }; + + /** base exception raised for all future error. + */ + class QI_API FutureException : public std::runtime_error { + public: + enum ExceptionState { + //No result ready + ExceptionState_FutureTimeout, + //The future has been canceled + ExceptionState_FutureCanceled, + //The future is not cancelable + ExceptionState_FutureNotCancelable, + //asked for error, but there is no error + ExceptionState_FutureHasNoError, + //real future error + ExceptionState_FutureUserError, + //when the promise is already set. + ExceptionState_PromiseAlreadySet, + }; + + explicit FutureException(const ExceptionState &es, const std::string &str = std::string()) + : std::runtime_error(stateToString(es) + str) + , _state(es) + {} + + inline ExceptionState state() const { return _state; } + + std::string stateToString(const ExceptionState &es); + + virtual ~FutureException() throw() + {} + + private: + ExceptionState _state; + }; + + /** Exception inherited from FutureException + * This exception represent an error reported by the operation. + */ + class QI_API FutureUserException : public FutureException { + public: + + explicit FutureUserException(const std::string &str = std::string()) + : FutureException(ExceptionState_FutureUserError, str) + {} + + virtual ~FutureUserException() throw() + {} + }; + + template + class Future { + public: + typedef typename FutureType::type ValueType; + typedef typename FutureType::typecast ValueTypeCast; + + public: + Future() + : _p(boost::make_shared >()) + { + } + + Future(const Future& b) + : _p(b._p) + {} + + bool operator==(const Future &other) + { + return _p.get() == other._p.get(); + } + + inline Future& operator=(const Future& b) + { + _p = b._p; + return *this; + } + + bool operator < (const Future& b) const + { + return _p.get() < b._p.get(); + } + explicit Future(const ValueType& v, FutureCallbackType async = FutureCallbackType_Async) + { + Promise promise(async); + promise.setValue(v); + *this = promise.future(); + } + + /** + * @brief Return the value associated to a Future. + * @param msecs timeout + * @return the value + * + * This function can throw for many reason: + * - wait timeout + * - user error + * - future canceled + * + * if an error is set, then value throw a FutureUserException, others errors are FutureException. + */ + inline const ValueType &value(int msecs = FutureTimeout_Infinite) const { return _p->value(msecs); } + + /** same as value() with an infinite timeout. + */ + inline operator const ValueTypeCast&() const { return _p->value(FutureTimeout_Infinite); } + + /** Wait for future to contain a value or an error + @param msecs: Maximum time to wait in milliseconds, 0 means return immediately. + @return a FutureState corresponding to the state of the future. + */ + inline FutureState wait(int msecs = FutureTimeout_Infinite) const { return _p->wait(msecs); } + + /** + * @brief isFinished + * @return true if finished + * do not throw + */ + inline bool isFinished() const { return _p->isFinished(); } + + /** + * @brief isRunning + * @return + * do not throw + */ + inline bool isRunning() const { return _p->isRunning(); } + + /** + * @brief isCanceled + * @return + * do not throw + */ + inline bool isCanceled() const { return _p->isCanceled(); } + + /** + * @brief hasError + * @param msecs timeout + * @return true if the future has an error. + * throw in the following case: + * - timeout + */ + inline bool hasError(int msecs = FutureTimeout_Infinite) const { return _p->hasError(msecs); } + /** + * @brief hasValue + * @param msecs timeout + * @return + * true if the future has a value. + * throw in the following case: + * - timeout + */ + inline bool hasValue(int msecs = FutureTimeout_Infinite) const { return _p->hasValue(msecs); } + + /** + * @brief error + * @param msecs + * @return the error + * throw on timeout + * throw if the future do not have an actual error. + */ + inline const std::string &error(int msecs = FutureTimeout_Infinite) const { return _p->error(msecs); } + + + inline FutureSync sync() + { + return FutureSync(*this); + }; + + /** cancel() the asynchronous operation if possible + * Exact effect is controlled by the cancel implementation, but it is + * expected to set a value or an error to the Future as fast as possible. + * Note that cancelation may be asynchronous. + * @throw ExceptionState_FutureNotCancelable if isCancelable() is false. + */ + void cancel() + { + _p->cancel(*this); + } + + /** return true if the future can be canceled. This does not mean that cancel will succeed. + */ + bool isCancelable() const + { + return _p->isCancelable(); + } + public: //Signals + typedef boost::function) > Connection; + + /** Connect a callback function that will be called once when the Future + * finishes (that is, switches from running to an other state). + * + * If type is sync, connect may block and call the callback synchronously if + * the future is already set. + */ + template + inline void connect(const AF& fun, + FutureCallbackType type = FutureCallbackType_Async) + { + _p->connect(*this, fun, type); + } +#ifdef DOXYGEN + /** Connect a callback with binding and tracking support. + * + * If the first argument is a weak_ptr or a pointer inheriting from + * qi::Trackable, the callback will not be called if tracked object was + * destroyed. + */ + template + void connect(FUNCTYPE fun, ARG0 tracked, ..., + FutureCallbackType type = FutureCallbackType_Async); +#else +#define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + inline void connect(const AF& fun, const ARG0& arg0 comma ADECL, \ + FutureCallbackType type = FutureCallbackType_Async) \ + { \ + _p->connect(*this, ::qi::bind)>(fun, arg0 comma AUSE), \ + type); \ + } + QI_GEN(genCall) +#undef genCall +#endif + + // Our companion library libqitype requires a connect with same signature for all instantiations + inline void _connect(const boost::function& s) { connect(boost::bind(s));} + + boost::shared_ptr > impl() { return _p;} + Future(boost::shared_ptr > p) : + _p(p) + { + assert(_p); + } + protected: + // C4251 needs to have dll-interface to be used by clients of class 'qi::Future' + boost::shared_ptr< detail::FutureBaseTyped > _p; + friend class Promise; + friend class FutureSync; + + template + friend void adaptFuture(const Future& f, Promise& p); + template + friend void adaptFuture(const Future& f, Promise& p, + CONV converter); + template + friend void detail::futureCancelAdapter( + boost::weak_ptr > wf); + }; + + + + /** this class allow throwing on error and being synchronous + * when the future is not handled by the client. + */ + template + class FutureSync + { + public: + typedef typename Future::ValueType ValueType; + typedef typename Future::ValueTypeCast ValueTypeCast; + typedef typename Future::Connection Connection; + // This future cannot be set, so sync starts at false + FutureSync() : _sync(false) {} + + FutureSync(const Future& b) + : _sync(true) + { + _future = b; + } + + FutureSync(const FutureSync& b) + : _sync(true) + { + _future = b._future; + b._sync = false; + } + + explicit FutureSync(const ValueType& v) + : _sync(false) + { + Promise promise; + promise.setValue(v); + _future = promise.future(); + } + + inline FutureSync& operator=(const FutureSync& b) + { + _future = b; + _sync = true; + b._sync = false; + return *this; + } + + inline FutureSync& operator=(const Future& b) + { + _future = b; + _sync = true; + return *this; + } + + ~FutureSync() + { + if (_sync) + _future.value(); + } + + operator Future() + { + return async(); + } + + bool operator < (const FutureSync& b) const + { + return _future._p.get() < b._future._p.get(); + } + + const ValueType &value(int msecs = FutureTimeout_Infinite) const { _sync = false; return _future.value(msecs); } + operator const typename Future::ValueTypeCast&() const { _sync = false; return _future.value(); } + FutureState wait(int msecs = FutureTimeout_Infinite) const { _sync = false; return _future.wait(msecs); } + bool isRunning() const { _sync = false; return _future.isRunning(); } + bool isFinished() const { _sync = false; return _future.isFinished(); } + bool isCanceled() const { _sync = false; return _future.isCanceled(); } + bool hasError(int msecs = FutureTimeout_Infinite) const { _sync = false; return _future.hasError(msecs); } + bool hasValue(int msecs = FutureTimeout_Infinite) const { _sync = false; return _future.hasValue(msecs); } + const std::string &error(int msecs = FutureTimeout_Infinite) const { _sync = false; return _future.error(msecs); } + void cancel() { _sync = false; _future.cancel(); } + bool isCancelable() const { _sync = false; return _future.isCancelable(); } + void connect(const Connection& s) { _sync = false; _future.connect(s);} + void _connect(const boost::function& s) { _sync = false; _future._connect(s);} + +#ifdef DOXYGEN + /** Connect a callback with binding and tracking support. + * + * If the first argument is a weak_ptr or a pointer inheriting from + * qi::Trackable, the callback will not be called if tracked object was + * destroyed. + */ + template + void connect(FUNCTYPE fun, ARG0 tracked, ...); +#else +#define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + inline void connect(const AF& fun, const ARG0& arg0 comma ADECL) \ + { \ + _sync = false; \ + connect(::qi::bind)>(fun, arg0 comma AUSE)); \ + } + QI_GEN(genCall) +#undef genCall +#endif + + Future async() + { + _sync = false; + return _future; + } + + protected: + mutable bool _sync; + Future _future; + friend class Future; + }; + + + /** A Promise is used to create and satisfy a Future. + */ + template + class Promise { + public: + typedef typename FutureType::type ValueType; + + /** Create a standard promise. + * @param async specify how callbacks registered with Future::connect + * are called: synchronously from the Promise setter, or + * asynchronously from a thread pool. + */ + explicit Promise(FutureCallbackType async = FutureCallbackType_Async) { + _f._p->reportStart(); + _f._p->_async = async; + } + + /** Create a canceleable promise. If Future::cancel is invoked, + * onCancel() will be called. It is expected to call setValue(), + * setError() or setCanceled() as quickly as possible, but can do so + * in an asynchronous way. + */ + explicit Promise(boost::function)> cancelCallback, FutureCallbackType async = FutureCallbackType_Async) + { + setup(cancelCallback, async); + } + + /** notify all future that a value has been set. + * throw if state != running + */ + void setValue(const ValueType &value) { + _f._p->setValue(_f, value); + } + + /** set the error, and notify all futures + * throw if state != running + */ + void setError(const std::string &msg) { + _f._p->setError(_f, msg); + } + + /** set the cancel state, and notify all futures + * throw if state != running + */ + void setCanceled() { + _f._p->setCanceled(_f); + } + + /* reset the promise and the future */ + void reset() { + _f._p->reset(); + } + + /// Get a future linked to this promise. Can be called multiple times. + Future future() const { return _f; } + + /** Gives access to the underlying value for in-place modification. + * trigger() must be called after the value is written to trigger the promise. + */ + ValueType& value() { return _f._p->_value;} + /** Trigger the promise with the current value. + */ + void trigger() { _f._p->set(_f);} + protected: + void setup(boost::function)> cancelCallback, FutureCallbackType async = FutureCallbackType_Async) + { + this->_f._p->reportStart(); + this->_f._p->setOnCancel(cancelCallback); + this->_f._p->_async = async; + } + explicit Promise(Future& f) : _f(f) {} + template friend class ::qi::detail::FutureBaseTyped; + Future _f; + + template + friend void adaptFuture(const Future& f, Promise& p); + template + friend void adaptFuture(const Future& f, Promise& p, + CONV converter); + }; + + template + class FutureBarrier { + public: + /// FutureBarrier constructor taking no argument. + FutureBarrier(FutureCallbackType async = FutureCallbackType_Async) + : _closed(false) + , _count(0) + , _futures() + , _promise(async) + {} + + /// Adds the future to the barrier. + bool addFuture(qi::Future fut) { + // Can't add future from closed qi::FutureBarrier. + if (this->_closed) + return false; + + ++(this->_count); + fut.connect(boost::bind(&FutureBarrier::onFutureFinish, this)); + this->_futures.push_back(fut); + return true; + } + + /// Gets the future result for the barrier. + Future< std::vector< Future > > future() { + this->close(); + return this->_promise.future(); + } + + protected: + bool _closed; + Atomic _count; + std::vector< Future > _futures; + Promise< std::vector< Future > > _promise; + + private: + void onFutureFinish() { + if (--(this->_count) == 0 && this->_closed) { + this->_promise.setValue(this->_futures); + } + } + + void close() { + this->_closed = true; + if (*(this->_count) == 0) { + this->_promise.setValue(this->_futures); + } + } + }; + + template + qi::Future makeFutureError(const std::string &value, FutureCallbackType async = FutureCallbackType_Async); + + /// Helper function to wait on a vector of futures. + template + void waitForAll(std::vector< Future >& vect); + + /// Helper function to wait for the first valid future. + template + qi::FutureSync< qi::Future > waitForFirst(std::vector< Future >& vect); + + /// Specialize this struct to provide conversion between future values + template + struct FutureValueConverter + { + void operator()(const FT& vIn, PT& vOut) { vOut = vIn;} + }; + + /** Feed a promise from a future of possibly different type. + * Will monitor \p f, and bounce its state to \p p. + * Error and canceled state are bounced as is. + * Valued state is bounced through FutureValueConverter::convert() + */ + template + void adaptFuture(const Future& f, Promise& p); + + /// Similar to adaptFuture(f, p) but with a custom converter + template + void adaptFuture(const Future& f, Promise& p, CONV converter); +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#include + +#endif // _QI_FUTURE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/iocolor.hpp b/naoModule/libnaoqi_files/include/qi/iocolor.hpp new file mode 100755 index 0000000..e5dfb07 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/iocolor.hpp @@ -0,0 +1,56 @@ +/* +** Author(s): +** - Cedric GESTES +** +** Copyright (C) 2013 Aldebaran Robotics +*/ + +#ifndef _QI_IOCOLOR_HPP_ +#define _QI_IOCOLOR_HPP_ + +#include +#include + +namespace qi { + + enum StreamColor { + //no color + StreamColor_None = 0, + + //attributes control + StreamColor_Reset = 1, + StreamColor_Bold = 2, + StreamColor_Faint = 3, + StreamColor_Standout = 4, + StreamColor_Underline = 5, + StreamColor_Blink = 6, + StreamColor_Overline = 7, + + //light colors + StreamColor_Black = 8, + StreamColor_DarkRed = 9, + StreamColor_DarkGreen = 10, + StreamColor_Brown = 11, + StreamColor_DarkBlue = 12, + StreamColor_Purple = 13, + StreamColor_Teal = 14, + StreamColor_LightGray = 15, + + //dark colors + StreamColor_DarkGray = 16, + StreamColor_Red = 17, + StreamColor_Green = 18, + StreamColor_Yellow = 19, + StreamColor_Blue = 20, + StreamColor_Fuchsia = 21, + StreamColor_Turquoise = 22, + StreamColor_White = 23, + }; +} + +namespace std { + QI_API std::ostream& operator<<(std::ostream& os, qi::StreamColor col); +} + +#endif // _QI_IOCOLOR_HPP_ + diff --git a/naoModule/libnaoqi_files/include/qi/log.hpp b/naoModule/libnaoqi_files/include/qi/log.hpp new file mode 100755 index 0000000..6e45866 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/log.hpp @@ -0,0 +1,246 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/** @file qi/log.hpp + * @brief Convenient log macro + */ + + +#ifndef _QI_LOG_HPP_ +#define _QI_LOG_HPP_ + +# include +# include +# include +# include +# include + +#include +#include + +#include + + +# define qiLogCategory(Cat) \ + static ::qi::log::CategoryType _QI_LOG_CATEGORY_GET() QI_ATTR_UNUSED = \ + ::qi::log::addCategory(Cat) + + + +#if defined(NO_QI_DEBUG) || defined(NDEBUG) +# define qiLogDebug(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogDebugF(Msg, ...) +#else +# define qiLogDebug(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Debug, Debug , __VA_ARGS__) +# define qiLogDebugF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Debug, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +#if defined(NO_QI_VERBOSE) +# define qiLogVerbose(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogVerboseF(Msg, ...) +#else +# define qiLogVerbose(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Verbose, Verbose, __VA_ARGS__) +# define qiLogVerboseF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Verbose, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +#if defined(NO_QI_INFO) +# define qiLogInfo(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogInfoF(Msg, ...) +#else +# define qiLogInfo(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Info, Info, __VA_ARGS__) +# define qiLogInfoF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Info, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +#if defined(NO_QI_WARNING) +# define qiLogWarning(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogWarningF(Msg, ...) +#else +# define qiLogWarning(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Warning, Warning, __VA_ARGS__) +# define qiLogWarningF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Warning, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +#if defined(NO_QI_ERROR) +# define qiLogError(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogErrorF(Msg, ...) +#else +# define qiLogError(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Error, Error, __VA_ARGS__) +# define qiLogErrorF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Error, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +#if defined(NO_QI_FATAL) +# define qiLogFatal(...) ::qi::log::detail::qiFalse() && false < qi::log::detail::NullStream().self() +# define qiLogFatalF(Msg, ...) +#else +# define qiLogFatal(...) _QI_LOG_MESSAGE_STREAM(LogLevel_Fatal, Fatal, __VA_ARGS__) +# define qiLogFatalF(Msg, ...) _QI_LOG_MESSAGE(LogLevel_Fatal, _QI_LOG_FORMAT(Msg, __VA_ARGS__)) +#endif + +namespace qi { + + enum LogLevel { + LogLevel_Silent = 0, + LogLevel_Fatal, + LogLevel_Error, + LogLevel_Warning, + LogLevel_Info, + LogLevel_Verbose, + LogLevel_Debug + }; + + enum LogColor { + LogColor_Never, + LogColor_Auto, + LogColor_Always, + }; + + enum LogContextAttr { + LogContextAttr_None = 0, + LogContextAttr_Verbosity = 1 << 0, + LogContextAttr_ShortVerbosity = 1 << 1, + LogContextAttr_Date = 1 << 2, + LogContextAttr_Tid = 1 << 3, + LogContextAttr_Category = 1 << 4, + LogContextAttr_File = 1 << 5, + LogContextAttr_Function = 1 << 6, + LogContextAttr_Return = 1 << 7 + }; + + typedef int LogContext; + + namespace log { + + //deprecated 1.22 + QI_API_DEPRECATED static const qi::LogLevel silent = LogLevel_Silent; + QI_API_DEPRECATED static const qi::LogLevel fatal = LogLevel_Fatal; + QI_API_DEPRECATED static const qi::LogLevel error = LogLevel_Error; + QI_API_DEPRECATED static const qi::LogLevel warning = LogLevel_Warning; + QI_API_DEPRECATED static const qi::LogLevel info = LogLevel_Info; + QI_API_DEPRECATED static const qi::LogLevel verbose = LogLevel_Verbose; + QI_API_DEPRECATED static const qi::LogLevel debug = LogLevel_Debug; + + //deprecated 1.22 + QI_API_DEPRECATED typedef qi::LogLevel LogLevel; + } +} + +namespace qi { + namespace log { + namespace detail { + struct Category; + } + + typedef unsigned int SubscriberId; + typedef detail::Category* CategoryType; + + //Deprecated 1.22 + QI_API_DEPRECATED typedef unsigned int Subscriber; + + typedef boost::function7 logFuncHandler; + + QI_API void init(qi::LogLevel verb = qi::LogLevel_Info, + qi::LogContext context = qi::LogContextAttr_ShortVerbosity | qi::LogContextAttr_Tid | qi::LogContextAttr_Category, + bool synchronous = true); + + QI_API void destroy(); + + QI_API void log(const qi::LogLevel verb, + const char* category, + const char* msg, + const char* file = "", + const char* fct = "", + const int line = 0); + + QI_API void log(const qi::LogLevel verb, + CategoryType category, + const std::string& msg, + const char* file = "", + const char* fct = "", + const int line = 0); + + + QI_API const char* logLevelToString(const qi::LogLevel verb, bool verbose = true); + + QI_API qi::LogLevel stringToLogLevel(const char* verb); + + QI_API qi::LogLevel verbosity(SubscriberId sub = 0); + + /// @return the list of existing categories + QI_API std::vector categories(); + + /** Parse and execute a set of verbosity rules + * Colon separated of rules. + * Each rule can be: + * - (+)?CAT : enable category CAT + * - -CAT : disable category CAT + * - CAT=level : set category CAT to level + * + * Each category can include a '*' for globbing. + */ + QI_API void setVerbosity(const std::string& rules, SubscriberId sub = 0); + QI_API void setVerbosity(const qi::LogLevel lv, SubscriberId sub = 0); + + + /// Add/get a category + QI_API CategoryType addCategory(const std::string& name); + /// Set \param cat to current verbosity level. Globbing is supported. + QI_API void enableCategory(const std::string& cat, SubscriberId sub = 0); + /// Set \param cat to silent log level. Globbing is supported. + QI_API void disableCategory(const std::string& cat, SubscriberId sub = 0); + /// Set per-subscriber \param cat to level \param level. Globbing is supported. + QI_API void setCategory(const std::string& cat, qi::LogLevel level, SubscriberId sub = 0); + + + /// \return true if given combination of category and level is enabled. + QI_API bool isVisible(CategoryType category, qi::LogLevel level); + /// \return true if given combination of category and level is enabled. + QI_API bool isVisible(const std::string& category, qi::LogLevel level); + + QI_API void setContext(int ctx); + + QI_API int context(); + + QI_API void setColor(LogColor color); + + QI_API LogColor color(); + + /** Set logs synchronicity + * + * When setting to async, this function must be called after main has + * started. + */ + QI_API void setSynchronousLog(bool sync); + + QI_API SubscriberId addLogHandler(const std::string& name, + qi::log::logFuncHandler fct, + qi::LogLevel defaultLevel = LogLevel_Info); + + QI_API void removeLogHandler(const std::string& name); + + QI_API void flush(); + + + #include + // Deprecated 1.22 + QI_API_DEPRECATED inline void setVerbosity(SubscriberId sub, const qi::log::LogLevel lv) { setVerbosity((qi::LogLevel)lv, sub); } + // Deprecated 1.22 + QI_API_DEPRECATED inline void setCategory(SubscriberId sub, const std::string& cat, qi::log::LogLevel level) { setCategory(cat, (qi::LogLevel)level, sub); } + #include + + } +} + +#include + + +#endif // _QI_LOG_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/log/consoleloghandler.hpp b/naoModule/libnaoqi_files/include/qi/log/consoleloghandler.hpp new file mode 100755 index 0000000..680df3a --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/log/consoleloghandler.hpp @@ -0,0 +1,51 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#ifndef _QI_LOG_CONSOLELOGHANDLER_HPP_ +#define _QI_LOG_CONSOLELOGHANDLER_HPP_ + +# include +# include + +namespace qi { + namespace log { + + class PrivateConsoleLogHandler; + + /// Print colored logs to the console. + class QI_API ConsoleLogHandler : private boost::noncopyable + { + public: + /// Initialize everything the console log handler needs to print on the + /// console with colors. + ConsoleLogHandler(); + + /// Unloads any data managed by ConsoleLogHandler. Destructor is not + /// virtual. + ~ConsoleLogHandler(); + + /// Prints a log message on the console. + void log(const qi::LogLevel verb, + const qi::os::timeval date, + const char *category, + const char *msg, + const char *file, + const char *fct, + const int line); + + void updateColor(); + + + protected: + PrivateConsoleLogHandler* _p; + }; + } +} + + +#endif // _QI_LOG_CONSOLELOGHANDLER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/log/fileloghandler.hpp b/naoModule/libnaoqi_files/include/qi/log/fileloghandler.hpp new file mode 100755 index 0000000..ea61ce1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/log/fileloghandler.hpp @@ -0,0 +1,45 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_LOG_FILELOGHANDLER_HPP_ +#define _QI_LOG_FILELOGHANDLER_HPP_ + +# include +# include + +namespace qi { + namespace log { + class PrivateFileLogHandler; + + /// Log messages to a file. + class QI_API FileLogHandler : private boost::noncopyable + { + public: + /// \brief Initialize the file handler on the file. File is opened + /// directly on construction. + explicit FileLogHandler(const std::string& filePath); + + /// Closes the file. + virtual ~FileLogHandler(); + + /// Writes a log message to the file. + void log(const qi::LogLevel verb, + const qi::os::timeval date, + const char *category, + const char *msg, + const char *file, + const char *fct, + const int line); + + private: + PrivateFileLogHandler* _p; + }; // !FileLogHandler + + }; // !log +}; // !qi + +#endif // _QI_LOG_FILELOGHANDLER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/log/headfileloghandler.hpp b/naoModule/libnaoqi_files/include/qi/log/headfileloghandler.hpp new file mode 100755 index 0000000..875ec80 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/log/headfileloghandler.hpp @@ -0,0 +1,47 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_LOG_HEADFILELOGHANDLER_HPP_ +#define _QI_LOG_HEADFILELOGHANDLER_HPP_ + +# include +# include +# include + +namespace qi { + namespace log { + class PrivateHeadFileLogHandler; + + /// Log the first length lines to a file. + class QI_API HeadFileLogHandler : private boost::noncopyable + { + public: + /// \brief Initialize the head file handler on the file. File is opened + /// directly on construction. + HeadFileLogHandler(const std::string &filePath, + int length = 2000); + /// Closes the file. + virtual ~HeadFileLogHandler(); + + /// \brief Writes a log message to the file if it is part of the first + /// length lines. + void log(const qi::LogLevel verb, + const qi::os::timeval date, + const char *category, + const char *msg, + const char *file, + const char *fct, + const int line); + + private: + PrivateHeadFileLogHandler* _p; + }; // !HeadFileLogHandler + + }; // !log +}; // !qi + +#endif // _QI_LOG_HEADFILELOGHANDLER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/log/tailfileloghandler.hpp b/naoModule/libnaoqi_files/include/qi/log/tailfileloghandler.hpp new file mode 100755 index 0000000..660618d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/log/tailfileloghandler.hpp @@ -0,0 +1,44 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_LOG_TAILFILELOGHANDLER_HPP_ +#define _QI_LOG_TAILFILELOGHANDLER_HPP_ + +# include +# include +# include + +namespace qi { + namespace log { + class PrivateTailFileLogHandler; + + /// Keeps at most 2 MiB of logs. + class QI_API TailFileLogHandler : private boost::noncopyable + { + public: + /// Initialize the tail file log handler. File is opened on construction. + TailFileLogHandler(const std::string &filePath); + /// Closes the file. + virtual ~TailFileLogHandler(); + + /// Writes the log message to the file. + void log(const qi::LogLevel verb, + const qi::os::timeval date, + const char *category, + const char *msg, + const char *file, + const char *fct, + const int line); + + private: + PrivateTailFileLogHandler* _p; + }; // !TailFileLogHandler + + }; // !log +}; // !qi + +#endif // _QI_LOG_TAILFILELOGHANDLER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/macro.hpp b/naoModule/libnaoqi_files/include/qi/macro.hpp new file mode 100755 index 0000000..8a2b250 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/macro.hpp @@ -0,0 +1,167 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/** @file + * @brief dll import/export and compiler message + */ + +#ifndef _QI_MACRO_HPP_ +#define _QI_MACRO_HPP_ + + + +#include + +// Deprecated +#if defined(__GNUC__) && !defined(QI_NO_API_DEPRECATED) +# define QI_API_DEPRECATED __attribute__((deprecated)) +#elif defined(_MSC_VER) && !defined(QI_NO_API_DEPRECATED) +# define QI_API_DEPRECATED __declspec(deprecated) +#else +# define QI_API_DEPRECATED +#endif + + +#if defined(__GNUC__) +/// Portable noreturn attribute, used to declare that a function does not return +# define QI_NORETURN __attribute__((noreturn)) +#elif defined(_MSC_VER) +/// Portable noreturn attribute, used to declare that a function does not return +# define QI_NORETURN __declspec(noreturn) +#else +# define QI_NORETURN +#endif + +// Mark compilers supporting variable length array (VLA) +#if defined(__GNUC__) && !defined(__clang__) +# define QI_HAS_VARIABLE_LENGTH_ARRAY 1 +#else +# define QI_HAS_VARIABLE_LENGTH_ARRAY 0 +#endif + +// For shared library + + +/** @return the proper type specification for import/export + * @param libname the name of your library. + * This macro will use two preprocessor defines: + * libname_EXPORTS (cmake convention) and libname_STATIC_BUILD. + * Those macro can be unset or set to 0 to mean false, or set to empty or 1 to + * mean true. + * The first one must be true if the current compilation unit is within the library. + * The second must be true if the library was built as a static archive. + * The proper way to use this macro is to: + * - Have your buildsystem set mylib_EXPORTS when building MYLIB + * - Have your buildsystem produce a config.h file that + \#define mylib_STATIC_BUILD to 1 or empty if it is a static build, and + not define mylib_STATIC_BUILD or define it to 0 otherwise + * In one header, write + * \#include + * \#define MYLIB_API QI_LIB_API(mylib) + */ +#define QI_LIB_API(libname) _QI_LIB_API(BOOST_PP_CAT(libname, _EXPORTS), BOOST_PP_CAT(libname, _STATIC_BUILD)) + +#define _QI_LIB_API(IS_BUILDING_LIB, IS_LIB_STATIC_BUILD) \ + QI_LIB_API_NORMALIZED(_QI_IS_ONE_OR_EMPTY(BOOST_PP_CAT(_ , IS_BUILDING_LIB)), _QI_IS_ONE_OR_EMPTY(BOOST_PP_CAT(_, IS_LIB_STATIC_BUILD))) + +// Each platform must provide a QI_LIB_API_NORMALIZED(isBuilding, isStatic) +#if defined _WIN32 || defined __CYGWIN__ +# define QI_EXPORT_API __declspec(dllexport) +# define QI_IMPORT_API __declspec(dllimport) +# define QI_LIB_API_NORMALIZED(exporting, isstatic) BOOST_PP_CAT(BOOST_PP_CAT(_QI_LIB_API_NORMALIZED_, exporting), isstatic) +# define _QI_LIB_API_NORMALIZED_00 QI_IMPORT_API +# define _QI_LIB_API_NORMALIZED_10 QI_EXPORT_API +# define _QI_LIB_API_NORMALIZED_11 +# define _QI_LIB_API_NORMALIZED_01 +#elif __GNUC__ >= 4 +# define QI_EXPORT_API __attribute__ ((visibility("default"))) +# define QI_IMPORT_API QI_EXPORT_API +# define QI_LIB_API_NORMALIZED(a, b) QI_EXPORT_API +#else +# define QI_IMPORT_API +# define QI_EXPORT_API +# define QI_LIB_API_NORMALIZED(a, b) +#endif + + +//! \cond internal +// Macros adapted from opencv2.2 +#if defined(_MSC_VER) + #define QI_DO_PRAGMA(x) __pragma(x) + #define __ALSTR2__(x) #x + #define __ALSTR1__(x) __ALSTR2__(x) + #define _ALMSVCLOC_ __FILE__ "("__ALSTR1__(__LINE__)") : " + #define QI_MSG_PRAGMA(_msg) QI_DO_PRAGMA(message (_ALMSVCLOC_ _msg)) +#elif defined(__GNUC__) + #define QI_DO_PRAGMA(x) _Pragma (#x) + #define QI_MSG_PRAGMA(_msg) QI_DO_PRAGMA(message (_msg)) +#else + #define QI_DO_PRAGMA(x) + #define QI_MSG_PRAGMA(_msg) +#endif +//! \endcond + + +// Use this macro to generate compiler warnings. +#if defined(QI_NO_COMPILER_WARNING) +# define QI_COMPILER_WARNING(x) +#else +# define QI_COMPILER_WARNING(x) QI_MSG_PRAGMA("Warning: " #x) +#endif + +// Deprecate a header, add a message to explain what user should do +#if !defined(WITH_DEPRECATED) || defined(QI_NO_DEPRECATED_HEADER) +# define QI_DEPRECATED_HEADER(x) +#else +# define QI_DEPRECATED_HEADER(x) QI_MSG_PRAGMA("\ +This file includes at least one deprecated or antiquated ALDEBARAN header \ +which may be removed without further notice in the next version. \ +Please consult the changelog for details. " #x) +#endif + + +#ifdef __cplusplus +namespace qi { + template + struct IsClonable; +}; +#endif + +#define QI_DEPRECATE_MACRO(name) \ + QI_COMPILER_WARNING(name macro is deprecated.) + +// This macro is deprecated, use boost::noncopyable instead +#define QI_DISALLOW_COPY_AND_ASSIGN(type) \ + QI_DEPRECATE_MACRO(QI_DISALLOW_COPY_AND_ASSIGN) \ + type(type const &); \ + void operator=(type const &); \ + typedef int _qi_not_clonable; \ + template friend struct ::qi::IsClonable + + +#if defined(__GNUC__) +# define QI_WARN_UNUSED_RESULT __attribute__((warn_unused_result)) +#else +# define QI_WARN_UNUSED_RESULT +#endif + +#if defined(__GNUC__) +# define QI_ATTR_UNUSED __attribute__((unused)) +#else +# define QI_ATTR_UNUSED +#endif + +#define QI_UNUSED(x) + +// A macro to append the line number of the parent macro usage, to define a +// function in or a variable and avoid name collision. +#define _QI_UNIQ_DEF_LEVEL2(A, B) A ## __uniq__ ## B +#define _QI_UNIQ_DEF_LEVEL1(A, B) _QI_UNIQ_DEF_LEVEL2(A, B) +#define QI_UNIQ_DEF(A) _QI_UNIQ_DEF_LEVEL1(A, __LINE__) + + +#endif // _QI_MACRO_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/os.hpp b/naoModule/libnaoqi_files/include/qi/os.hpp new file mode 100755 index 0000000..86a95dc --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/os.hpp @@ -0,0 +1,100 @@ +#pragma once +/* + * Copyright (c) 2012, 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_OS_HPP_ +#define _QI_OS_HPP_ + +# include +# include +# include +# include +# include +# include + +struct stat; + +namespace qi { + + namespace os { + + QI_API FILE* fopen(const char *filename, const char *mode); + QI_API int stat(const char *filename, struct stat *pstat); + QI_API int checkdbg(); + QI_API std::string home(); + QI_API std::string mktmpdir(const char *prefix = ""); + QI_API std::string tmp(); + QI_API std::string gethostname(); + QI_API int isatty(int fd = 1); + + /** + * handles * and ? wilcards + */ + QI_API bool fnmatch(const std::string &pattern, const std::string &string); + + // lib C + QI_API char* strdup(const char *src); + QI_API int snprintf(char *str, size_t size, const char *format, ...); + + // env + QI_API std::string getenv(const char *var); + QI_API int setenv(const char *var, const char *value); + QI_API std::string timezone(); + + // time + QI_API void sleep(unsigned int seconds); + QI_API void msleep(unsigned int milliseconds); + struct QI_API timeval { + qi::int64_t tv_sec; + qi::int64_t tv_usec; + }; + QI_API int gettimeofday(qi::os::timeval *tp); + QI_API qi::int64_t ustime(); + QI_API std::pair cputime(); + + QI_API qi::os::timeval operator+(const qi::os::timeval &lhs, + const qi::os::timeval &rhs); + QI_API qi::os::timeval operator+(const qi::os::timeval &lhs, + long us); + QI_API qi::os::timeval operator-(const qi::os::timeval &lhs, + const qi::os::timeval &rhs); + QI_API qi::os::timeval operator-(const qi::os::timeval &lhs, + long us); + + // shared library + QI_API void *dlopen(const char *filename, int flag = -1); + QI_API int dlclose(void *handle); + QI_API void *dlsym(void *handle, const char *symbol); + QI_API const char *dlerror(void); + + // process management + QI_API int spawnvp(char *const argv[]); + QI_API int spawnlp(const char* argv, ...); + QI_API int system(const char *command); + QI_API int getpid(); + QI_API int gettid(); + QI_API int waitpid(int pid, int* status); + QI_API int kill(int pid, int sig); + + QI_API unsigned short findAvailablePort(unsigned short port); + QI_API std::map > hostIPAddrs(bool ipv6Addr = false); + + QI_API void setCurrentThreadName(const std::string &name); + QI_API std::string currentThreadName(); + QI_API bool setCurrentThreadCPUAffinity(const std::vector &cpus); + QI_API long numberOfCPUs(); + QI_API std::string getMachineId(); + QI_API std::string generateUuid(); + // in kB + QI_API size_t memoryUsage(unsigned int pid); + + //since 1.12.1 + QI_API_DEPRECATED QI_API std::string tmpdir(const char *prefix = ""); + } +} + + +#endif // _QI_OS_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/path.hpp b/naoModule/libnaoqi_files/include/qi/path.hpp new file mode 100755 index 0000000..5337f3d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/path.hpp @@ -0,0 +1,148 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +/** @file + * @brief find bin/lib/data/conf for the current application + */ + +#ifndef _QI_PATH_HPP_ +#define _QI_PATH_HPP_ + +# include +# include +# include +# include + +namespace qi +{ + + class PrivatePath; + class Path; + typedef std::vector PathVector; + class QI_API Path { + public: + Path(const std::string& unicodePath = std::string()); + + bool isEmpty() const; + bool isDir() const; + bool isRegularFile() const; + + std::string filename() const; + std::string extension() const; + + Path parent(); + Path absolute(); + + PathVector files(); + PathVector dirs(); + + operator std::string() const; + + Path operator/(const qi::Path& rhs) const; + const Path& operator/=(const qi::Path& rhs) const; + + private: + Path(const boost::shared_ptr &p);; + boost::shared_ptr _p; + }; + + /// Set of tools to handle SDK layouts. + namespace path + { + + /// Return the default SDK prefix path. + QI_API std::string sdkPrefix(); + + // not thread-safe, must be kept internal + namespace detail { + + /** + * \brief Return the SDK prefixes list. + * It's always complete, native paths. + */ + QI_API std::vector getSdkPrefixes(); + + /** \brief Add a new SDK prefix to the list of searchable prefixes. + * + * A default SDK prefix is computed using argc, argv when calling + * qi::init(). + * + * After calling this function, the new SDK prefix will be taken + * into account by the other methods. + * \param prefix The new prefix to add (in UTF-8). + */ + QI_API void addOptionalSdkPrefix(const char* prefix); + + /** \brief Reset the list of additional SDK prefixes. + * + * Reset all the SDK added with qi::path::addOptionalSdkPrefix. + * The list of SDK prefixes will only contain the default SDK + * prefix. + */ + QI_API void clearOptionalSdkPrefix(); + + } + + /// Look for a binary. + QI_API std::string findBin(const std::string& name); + + /// Look for a library. + QI_API std::string findLib(const std::string& name); + + /// Look for a configuration file. + QI_API std::string findConf(const std::string& applicationName, + const std::string& filename); + + /// Look for a file in all dataPaths(applicationName) directories, + /// return the first match. + QI_API std::string findData(const std::string& applicationName, + const std::string& filename); + + /// List data files matching the given pattern in all + /// dataPaths(applicationName) directories. For each match, return the + /// occurence from the first dataPaths prefix. + /// Directories are discarded. + QI_API std::vector listData(const std::string& applicationName, + const std::string& pattern="*"); + + /// Get the list of directories used when searching for configuration files for the given application name. + QI_API std::vector confPaths(const std::string& applicationName=""); + + /// Get the list of directories used when searching for data files for the given application name. + QI_API std::vector dataPaths(const std::string& applicationName=""); + + /// Get the list of directories used when searching for binaries. + QI_API std::vector binPaths(); + + /// Get the list of directories used when searching for libraries. + QI_API std::vector libPaths(); + + + /// Set the writable files path for users. + QI_API void setWritablePath(const std::string &path); + + /// Get the writable data files path for users. + QI_API std::string userWritableDataPath(const std::string& applicationName, + const std::string& filename); + + /// Get the writable configuration files path for users. + QI_API std::string userWritableConfPath(const std::string& applicationName, + const std::string& filename=""); + + /** Convert given path into DOS 8.3 path if it exists, else returns empty string (Windows only). + * To use some API that doesn't support unicode on Windows, it is + * possible to convert a unicode path to an existing file into a DOS + * path without any accentuated characters. + * (for ex. "C:\test àé\" becomes "C:\TEST~1\" if it already exists) + * + * On other platforms, simply return pathString. + */ + QI_API std::string convertToDosPath(const std::string &pathString); + } +} + +#endif // _QI_PATH_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/periodictask.hpp b/naoModule/libnaoqi_files/include/qi/periodictask.hpp new file mode 100755 index 0000000..d00abff --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/periodictask.hpp @@ -0,0 +1,106 @@ +#pragma once +/* +* Copyright (c) Aldebaran Robotics 2013 All Rights Reserved +*/ +#ifndef _QI_PERIODICTASK_HPP_ +#define _QI_PERIODICTASK_HPP_ + +#include + +#include +#include + +#include +#include +#include +#include + +namespace qi +{ + struct PeriodicTaskPrivate; + /** Control a task executed periodically and asynchronously. + */ + class QI_API PeriodicTask: public boost::noncopyable + { + public: + typedef boost::function Callback; + + PeriodicTask(); + + ~PeriodicTask(); + + /// @{ + /** One of the setCallback() functions below must be called before + * any other operation. Once set the callback cannot be changed. + * If the callback throws, async task will be stopped + */ + void setCallback(const Callback& cb); +#ifdef DOXYGEN + template PeriodicTask& setCallback(const T& callable, ARG0 tracked, ...); +#else + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + inline void setCallback(const AF& fun, const ARG0& arg0 comma ADECL) \ + { \ + setCallback(::qi::bind(fun, arg0 comma AUSE)); \ + } + QI_GEN(genCall) +#undef genCall +#endif + + /** Set the call interval in microseconds. + * This call will wait until next callback invocation to apply the change. + * Use: + * task.stop(); + * task.setUsPeriod() + * task.start() + * to apply the change immediately. + */ + void setUsPeriod(qi::int64_t usPeriod); + + /** Start the periodic task at specified period. No effect if already running. + * @param immediate if true, first schedule of the task will happen with no delay. + * @warning concurrent calls to start() and stop() will result in undefined behavior. + */ + void start(bool immediate = true); + + /** Trigger a started periodic task to run right now. + * Does nothing if the periodic task just ran, is running, starting, + * stopping or stopped. + */ + void trigger(); + + /** Stop the periodic task. When this function returns, the callback will + * not be called anymore. + * Can be called from within the callback function. + * @warning concurrent calls to start() and stop() will result in undefined behavior. + */ + void stop(); + + /** Request for periodic task to stop asynchronously. + * Can be safely called from within the callback. + */ + void asyncStop(); + + /** If argument is true, call interval will take into account call duration + * to maintain the period. + */ + void compensateCallbackTime(bool compensate); + + /// Set name for debugging and tracking purpose + void setName(const std::string& name); + + /// @return true if task is running + bool isRunning() const; + + /** @return whether state is stopping or stopped + * Can be called from within the callback to know if stop() or asyncStop() + * was called. + */ + bool isStopping() const; + private: + boost::shared_ptr _p; + }; + +} +#endif diff --git a/naoModule/libnaoqi_files/include/qi/preproc.hpp b/naoModule/libnaoqi_files/include/qi/preproc.hpp new file mode 100755 index 0000000..906b909 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/preproc.hpp @@ -0,0 +1,607 @@ +#pragma once +/* + * Copyright (C) 2009-2012, Aldebaran Robotics. + * Imported from urbi-sdk's libport. + * + */ + +#ifndef _QI_PREPROC_HPP_ +#define _QI_PREPROC_HPP_ + +# include +# include +# include + +# define QI_MAP_HELPER(R, Macro, Elt) (Macro(Elt)) +/// Return \a Seq, with \a Macro applied on every element. +# define QI_MAP(Macro, Seq) \ + BOOST_PP_SEQ_FOR_EACH(QI_MAP_HELPER, Macro, Seq) + +# define QI_APPLY_HELPER(R, Macro, Elt) Macro(Elt) +/// Apply \a Macro applied on every element of \a Seq. +# define QI_APPLY(Macro, Seq) \ + BOOST_PP_SEQ_FOR_EACH(QI_APPLY_HELPER, Macro, Seq) + + +# define QI_SEPARATE_HELPER(Elt) , Elt +/// Separate \a Seq with commas +# define QI_SEPARATE(Seq) \ + BOOST_PP_SEQ_HEAD(Seq) \ + QI_APPLY(QI_SEPARATE_HELPER, BOOST_PP_SEQ_TAIL(Seq)) + +/// Separate \a Seq with \a Sep +# define QI_ENUM(Seq, Sep) \ + BOOST_PP_SEQ_HEAD(Seq) \ + BOOST_PP_SEQ_FOR_EACH(QI_ENUM_HELPER, Sep, BOOST_PP_SEQ_TAIL(Seq)) +# define QI_ENUM_HELPER(Data, Sep, Elt) Sep Elt + +/// Separate \a Seq with \a LSep for the last separator and \a Sep everywhere else. +/// Typically: "a, b, c, d and e". +# define QI_ENUM_PRETTY(Seq, Sep, LSep) \ + BOOST_PP_CAT( \ + QI_ENUM_PRETTY_, \ + BOOST_PP_IF(BOOST_PP_DEC(BOOST_PP_SEQ_SIZE(Seq)), SEVERAL, ONE)) \ + (Seq, Sep, LSep) +# define QI_ENUM_PRETTY_ONE(Seq, Sep, LSep) \ + BOOST_PP_SEQ_HEAD(Seq) +# define QI_ENUM_PRETTY_SEVERAL(Seq, Sep, LSep) \ + QI_ENUM(QI_RTAIL(Seq), Sep) LSep QI_RHEAD(Seq) + +/// The last element element of the sequence (reverse head) +# define QI_RHEAD(Seq) BOOST_PP_SEQ_ELEM(BOOST_PP_DEC(BOOST_PP_SEQ_SIZE(Seq)), Seq) +/// The sequence minus the last element (reverse tail) +# define QI_RTAIL(Seq) BOOST_PP_SEQ_REMOVE(Seq, BOOST_PP_DEC(BOOST_PP_SEQ_SIZE(Seq))) + +/// Concatenate the two arguments. +# ifdef _MSC_VER + +# define QI_CAT(A, B) QI_CAT_0(A, B) +/* +#!/usr/bin/python + +for i in range(0, 32): + print '# define QI_CAT_%s(A, B) QI_CAT_%s(A, B)' % (i, i + 1) +*/ +# define QI_CAT_0(A, B) QI_CAT_1(A, B) +# define QI_CAT_1(A, B) QI_CAT_2(A, B) +# define QI_CAT_2(A, B) QI_CAT_3(A, B) +# define QI_CAT_3(A, B) QI_CAT_4(A, B) +# define QI_CAT_4(A, B) QI_CAT_5(A, B) +# define QI_CAT_5(A, B) QI_CAT_6(A, B) +# define QI_CAT_6(A, B) QI_CAT_7(A, B) +# define QI_CAT_7(A, B) QI_CAT_8(A, B) +# define QI_CAT_8(A, B) QI_CAT_9(A, B) +# define QI_CAT_9(A, B) QI_CAT_10(A, B) +# define QI_CAT_10(A, B) QI_CAT_11(A, B) +# define QI_CAT_11(A, B) QI_CAT_12(A, B) +# define QI_CAT_12(A, B) QI_CAT_13(A, B) +# define QI_CAT_13(A, B) QI_CAT_14(A, B) +# define QI_CAT_14(A, B) QI_CAT_15(A, B) +# define QI_CAT_15(A, B) QI_CAT_16(A, B) +# define QI_CAT_16(A, B) QI_CAT_17(A, B) +# define QI_CAT_17(A, B) QI_CAT_18(A, B) +# define QI_CAT_18(A, B) QI_CAT_19(A, B) +# define QI_CAT_19(A, B) QI_CAT_20(A, B) +# define QI_CAT_20(A, B) QI_CAT_21(A, B) +# define QI_CAT_21(A, B) QI_CAT_22(A, B) +# define QI_CAT_22(A, B) QI_CAT_23(A, B) +# define QI_CAT_23(A, B) QI_CAT_24(A, B) +# define QI_CAT_24(A, B) QI_CAT_25(A, B) +# define QI_CAT_25(A, B) QI_CAT_26(A, B) +# define QI_CAT_26(A, B) QI_CAT_27(A, B) +# define QI_CAT_27(A, B) QI_CAT_28(A, B) +# define QI_CAT_28(A, B) QI_CAT_29(A, B) +# define QI_CAT_29(A, B) QI_CAT_30(A, B) +# define QI_CAT_30(A, B) QI_CAT_31(A, B) +# define QI_CAT_31(A, B) A ## B +# else +# define QI_CAT(A, B) QI_CAT_(A, B) +# define QI_CAT_(A, B) A ## B +# endif + +/// __FILE__:__LINE__ as a string. +# define __HERE \ + __FILE__ ":" BOOST_PP_STRINGIZE(__LINE__) + +# define QI_ID(...) __VA_ARGS__ + +# define QI_DELAY(X) X + +# define QI_COMMA , + +# define QI_WRAP(...) (__VA_ARGS__) + +# define QI_UNWRAP(...) QI_ID __VA_ARGS__ + + +/* +#!/usr/bin/python + +def gen(n): + print '#define QI_LIST_BUILD_%(max)s(%(formals)s IGNORED) %(list)s' % { + 'formals' : ''.join(map(lambda i: 'A%s,' % i, range(n))), + 'list' : ''.join(map(lambda i: '(A%s)' % i, range(n))), + 'max' : n, + } + +for i in range(10): + gen(i) +*/ + +#define QI_LIST_BUILD_0( IGNORED) +#define QI_LIST_BUILD_1(A0, IGNORED) \ + (A0) +#define QI_LIST_BUILD_2(A0,A1, IGNORED) \ + (A0)(A1) +#define QI_LIST_BUILD_3(A0,A1,A2, IGNORED) \ + (A0)(A1)(A2) +#define QI_LIST_BUILD_4(A0,A1,A2,A3, IGNORED) \ + (A0)(A1)(A2)(A3) +#define QI_LIST_BUILD_5(A0,A1,A2,A3,A4, IGNORED) \ + (A0)(A1)(A2)(A3)(A4) +#define QI_LIST_BUILD_6(A0,A1,A2,A3,A4,A5, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5) +#define QI_LIST_BUILD_7(A0,A1,A2,A3,A4,A5,A6, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6) +#define QI_LIST_BUILD_8(A0,A1,A2,A3,A4,A5,A6,A7, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7) +#define QI_LIST_BUILD_9(A0,A1,A2,A3,A4,A5,A6,A7,A8, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8) +#define QI_LIST_BUILD_10(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9) +#define QI_LIST_BUILD_11(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10) +#define QI_LIST_BUILD_12(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11) +#define QI_LIST_BUILD_13(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12) +#define QI_LIST_BUILD_14(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13) +#define QI_LIST_BUILD_15(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14) +#define QI_LIST_BUILD_16(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15) +#define QI_LIST_BUILD_17(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16) +#define QI_LIST_BUILD_18(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17) +#define QI_LIST_BUILD_19(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18) +#define QI_LIST_BUILD_20(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19) +#define QI_LIST_BUILD_21(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20) +#define QI_LIST_BUILD_22(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21) +#define QI_LIST_BUILD_23(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22) +#define QI_LIST_BUILD_24(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23) +#define QI_LIST_BUILD_25(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24) +#define QI_LIST_BUILD_26(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25) +#define QI_LIST_BUILD_27(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25,A26, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25)(A26) +#define QI_LIST_BUILD_28(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25,A26,A27, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25)(A26)(A27) +#define QI_LIST_BUILD_29(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25,A26,A27,A28, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25)(A26)(A27)(A28) +#define QI_LIST_BUILD_30(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25,A26,A27,A28,A29, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25)(A26)(A27)(A28)(A29) +#define QI_LIST_BUILD_31(A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15,A16,A17,A18,A19,A20,A21,A22,A23,A24,A25,A26,A27,A28,A29,A30, IGNORED) \ + (A0)(A1)(A2)(A3)(A4)(A5)(A6)(A7)(A8)(A9)(A10)(A11)(A12)(A13)(A14)(A15)(A16)(A17)(A18)(A19)(A20)(A21)(A22)(A23)(A24)(A25)(A26)(A27)(A28)(A29)(A30) + +# ifdef _MSC_VER +# define QI_LIST_VASIZE_HELPER1(...) \ + QI_DELAY(QI_LIST_VASIZE_HELPER)##2(__VA_ARGS__, 31, 30, 29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0) +# else +# define QI_LIST_VASIZE_HELPER1(...) \ + QI_LIST_VASIZE_HELPER2(__VA_ARGS__, 31, 30, 29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0) +# endif +# define QI_LIST_VASIZE_HELPER2(A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, A10, A11, A12, A13, A14, A15, A16, A17, A18, A19, A20, A21, A22, A23, A24, A25, A26, A27, A28, A29, A30, A31, A32, ...) \ + A32 + +# define QI_LIST_VASIZE(List) \ + QI_LIST_VASIZE_HELPER1 List + +#define QI_LIST_HELPER(M, A) M A + +#define QI_LIST(...) \ + QI_LIST_HELPER( \ + QI_CAT(QI_LIST_BUILD_, QI_LIST_VASIZE((__VA_ARGS__))), \ + (__VA_ARGS__)) + +# define QI_LIST_SIZE(List) BOOST_PP_SEQ_SIZE(List) + +# define QI_LIST_EMPTY_0 QI_TRUE +# define QI_LIST_EMPTY_1 QI_FALSE +# define QI_LIST_EMPTY_2 QI_FALSE +# define QI_LIST_EMPTY_3 QI_FALSE +# define QI_LIST_EMPTY_4 QI_FALSE +# define QI_LIST_EMPTY_5 QI_FALSE +# define QI_LIST_EMPTY_6 QI_FALSE +# define QI_LIST_EMPTY_7 QI_FALSE +# define QI_LIST_EMPTY_8 QI_FALSE +# define QI_LIST_EMPTY_9 QI_FALSE +# define QI_LIST_EMPTY_10 QI_FALSE +# define QI_LIST_EMPTY_11 QI_FALSE +# define QI_LIST_EMPTY_12 QI_FALSE +# define QI_LIST_EMPTY_13 QI_FALSE +# define QI_LIST_EMPTY_14 QI_FALSE +# define QI_LIST_EMPTY_15 QI_FALSE +# define QI_LIST_EMPTY_16 QI_FALSE +# define QI_LIST_EMPTY_17 QI_FALSE +# define QI_LIST_EMPTY_18 QI_FALSE +# define QI_LIST_EMPTY_19 QI_FALSE +# define QI_LIST_EMPTY_20 QI_FALSE +# define QI_LIST_EMPTY_21 QI_FALSE +# define QI_LIST_EMPTY_22 QI_FALSE +# define QI_LIST_EMPTY_23 QI_FALSE +# define QI_LIST_EMPTY_24 QI_FALSE +# define QI_LIST_EMPTY_25 QI_FALSE +# define QI_LIST_EMPTY_26 QI_FALSE +# define QI_LIST_EMPTY_27 QI_FALSE +# define QI_LIST_EMPTY_28 QI_FALSE +# define QI_LIST_EMPTY_29 QI_FALSE +# define QI_LIST_EMPTY_30 QI_FALSE +# define QI_LIST_EMPTY_31 QI_FALSE +# define QI_LIST_EMPTY(List) QI_CAT(QI_LIST_EMPTY_, QI_LIST_SIZE(List)) + +# define QI_LIST_HEAD(List) BOOST_PP_SEQ_HEAD(List) + +# define QI_LIST_TAIL(List) BOOST_PP_SEQ_TAIL(List) + +# define QI_LIST_MAP_HELPER(Unused, Macro, Elt) \ + Macro(Elt) +# define QI_LIST_MAP(Macro, List) \ + BOOST_PP_SEQ_TRANSFORM(QI_LIST_MAP_HELPER, Macro, List) + +# define QI_LIST_MAP_AUX_HELPER(Unused, Aux, Elt) \ + BOOST_PP_TUPLE_ELEM(2, 0, Aux)(Elt, BOOST_PP_TUPLE_ELEM(2, 1, Aux)) +# define QI_LIST_MAP_AUX(Macro, List, Aux) \ + BOOST_PP_SEQ_TRANSFORM(QI_LIST_MAP_AUX_HELPER, (Macro, Aux), List) + +# define QI_LIST_APPLY_HELPER(Unused, Macro, Elt) \ + Macro(Elt) +# define QI_LIST_APPLY(Macro, List) \ + BOOST_PP_SEQ_FOR_EACH(QI_LIST_APPLY_HELPER, Macro, List) + +# define QI_LIST_APPLY_ARGS_HELPER(Unused, Macro, Elt) \ + Macro Elt +# define QI_LIST_APPLY_ARGS(Macro, List) \ + BOOST_PP_SEQ_FOR_EACH(QI_LIST_APPLY_ARGS_HELPER, Macro, List) + +# define QI_LIST_APPLY_AUX_HELPER(Unused, Aux, Elt) \ + BOOST_PP_TUPLE_ELEM(2, 0, Aux)(Elt, BOOST_PP_TUPLE_ELEM(2, 1, Aux)) +# define QI_LIST_APPLY_AUX(Macro, List, Aux) \ + BOOST_PP_SEQ_FOR_EACH(QI_LIST_APPLY_AUX_HELPER, (Macro, Aux), List) + +/* +#!/usr/bin/python + +def gen(n): + args = {'n': n, 'n_1': n - 1,} + print '# define QI_LIST_NTH_%(n)s(List) BOOST_PP_CAT(QI_LIST_NTH_%(n)s_, QI_LIST_EMPTY(List))(List)' % args + print '# define QI_LIST_NTH_%(n)s_QI_TRUE(List)' % args + if n != 0: + print '# define QI_LIST_NTH_%(n)s_QI_FALSE(List) QI_LIST_NTH_%(n_1)s(QI_LIST_TAIL(List))' %args + +for i in range(0, 10): + gen(i) +*/ + +# define QI_LIST_NTH_0(List) BOOST_PP_CAT(QI_LIST_NTH_0_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_0_QI_TRUE(List) +# define QI_LIST_NTH_1(List) BOOST_PP_CAT(QI_LIST_NTH_1_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_1_QI_TRUE(List) +# define QI_LIST_NTH_1_QI_FALSE(List) QI_LIST_NTH_0(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_2(List) BOOST_PP_CAT(QI_LIST_NTH_2_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_2_QI_TRUE(List) +# define QI_LIST_NTH_2_QI_FALSE(List) QI_LIST_NTH_1(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_3(List) BOOST_PP_CAT(QI_LIST_NTH_3_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_3_QI_TRUE(List) +# define QI_LIST_NTH_3_QI_FALSE(List) QI_LIST_NTH_2(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_4(List) BOOST_PP_CAT(QI_LIST_NTH_4_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_4_QI_TRUE(List) +# define QI_LIST_NTH_4_QI_FALSE(List) QI_LIST_NTH_3(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_5(List) BOOST_PP_CAT(QI_LIST_NTH_5_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_5_QI_TRUE(List) +# define QI_LIST_NTH_5_QI_FALSE(List) QI_LIST_NTH_4(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_6(List) BOOST_PP_CAT(QI_LIST_NTH_6_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_6_QI_TRUE(List) +# define QI_LIST_NTH_6_QI_FALSE(List) QI_LIST_NTH_5(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_7(List) BOOST_PP_CAT(QI_LIST_NTH_7_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_7_QI_TRUE(List) +# define QI_LIST_NTH_7_QI_FALSE(List) QI_LIST_NTH_6(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_8(List) BOOST_PP_CAT(QI_LIST_NTH_8_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_8_QI_TRUE(List) +# define QI_LIST_NTH_8_QI_FALSE(List) QI_LIST_NTH_7(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_9(List) BOOST_PP_CAT(QI_LIST_NTH_9_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_9_QI_TRUE(List) +# define QI_LIST_NTH_9_QI_FALSE(List) QI_LIST_NTH_8(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_10(List) BOOST_PP_CAT(QI_LIST_NTH_10_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_10_QI_TRUE(List) +# define QI_LIST_NTH_10_QI_FALSE(List) QI_LIST_NTH_9(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_11(List) BOOST_PP_CAT(QI_LIST_NTH_11_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_11_QI_TRUE(List) +# define QI_LIST_NTH_11_QI_FALSE(List) QI_LIST_NTH_10(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_12(List) BOOST_PP_CAT(QI_LIST_NTH_12_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_12_QI_TRUE(List) +# define QI_LIST_NTH_12_QI_FALSE(List) QI_LIST_NTH_11(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_13(List) BOOST_PP_CAT(QI_LIST_NTH_13_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_13_QI_TRUE(List) +# define QI_LIST_NTH_13_QI_FALSE(List) QI_LIST_NTH_12(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_14(List) BOOST_PP_CAT(QI_LIST_NTH_14_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_14_QI_TRUE(List) +# define QI_LIST_NTH_14_QI_FALSE(List) QI_LIST_NTH_13(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_15(List) BOOST_PP_CAT(QI_LIST_NTH_15_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_15_QI_TRUE(List) +# define QI_LIST_NTH_15_QI_FALSE(List) QI_LIST_NTH_14(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_16(List) BOOST_PP_CAT(QI_LIST_NTH_16_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_16_QI_TRUE(List) +# define QI_LIST_NTH_16_QI_FALSE(List) QI_LIST_NTH_15(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_17(List) BOOST_PP_CAT(QI_LIST_NTH_17_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_17_QI_TRUE(List) +# define QI_LIST_NTH_17_QI_FALSE(List) QI_LIST_NTH_16(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_18(List) BOOST_PP_CAT(QI_LIST_NTH_18_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_18_QI_TRUE(List) +# define QI_LIST_NTH_18_QI_FALSE(List) QI_LIST_NTH_17(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_19(List) BOOST_PP_CAT(QI_LIST_NTH_19_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_19_QI_TRUE(List) +# define QI_LIST_NTH_19_QI_FALSE(List) QI_LIST_NTH_18(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_20(List) BOOST_PP_CAT(QI_LIST_NTH_20_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_20_QI_TRUE(List) +# define QI_LIST_NTH_20_QI_FALSE(List) QI_LIST_NTH_19(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_21(List) BOOST_PP_CAT(QI_LIST_NTH_21_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_21_QI_TRUE(List) +# define QI_LIST_NTH_21_QI_FALSE(List) QI_LIST_NTH_20(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_22(List) BOOST_PP_CAT(QI_LIST_NTH_22_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_22_QI_TRUE(List) +# define QI_LIST_NTH_22_QI_FALSE(List) QI_LIST_NTH_21(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_23(List) BOOST_PP_CAT(QI_LIST_NTH_23_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_23_QI_TRUE(List) +# define QI_LIST_NTH_23_QI_FALSE(List) QI_LIST_NTH_22(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_24(List) BOOST_PP_CAT(QI_LIST_NTH_24_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_24_QI_TRUE(List) +# define QI_LIST_NTH_24_QI_FALSE(List) QI_LIST_NTH_23(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_25(List) BOOST_PP_CAT(QI_LIST_NTH_25_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_25_QI_TRUE(List) +# define QI_LIST_NTH_25_QI_FALSE(List) QI_LIST_NTH_24(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_26(List) BOOST_PP_CAT(QI_LIST_NTH_26_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_26_QI_TRUE(List) +# define QI_LIST_NTH_26_QI_FALSE(List) QI_LIST_NTH_25(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_27(List) BOOST_PP_CAT(QI_LIST_NTH_27_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_27_QI_TRUE(List) +# define QI_LIST_NTH_27_QI_FALSE(List) QI_LIST_NTH_26(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_28(List) BOOST_PP_CAT(QI_LIST_NTH_28_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_28_QI_TRUE(List) +# define QI_LIST_NTH_28_QI_FALSE(List) QI_LIST_NTH_27(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_29(List) BOOST_PP_CAT(QI_LIST_NTH_29_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_29_QI_TRUE(List) +# define QI_LIST_NTH_29_QI_FALSE(List) QI_LIST_NTH_28(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_30(List) BOOST_PP_CAT(QI_LIST_NTH_30_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_30_QI_TRUE(List) +# define QI_LIST_NTH_30_QI_FALSE(List) QI_LIST_NTH_29(QI_LIST_TAIL(List)) +# define QI_LIST_NTH_31(List) BOOST_PP_CAT(QI_LIST_NTH_31_, QI_LIST_EMPTY(List))(List) +# define QI_LIST_NTH_31_QI_TRUE(List) +# define QI_LIST_NTH_31_QI_FALSE(List) QI_LIST_NTH_30(QI_LIST_TAIL(List)) + +# define QI_LIST_NTH_0_QI_FALSE(List) QI_LIST_HEAD(List) +# define QI_LIST_NTH(Nth, List) BOOST_PP_CAT(QI_LIST_NTH_, Nth)(List) + +# define QI_LIST_FLATTEN(List) QI_LIST_SEP(List, ) + +# define QI_LIST_SEP_HELPER(Elt, Sep) \ + QI_UNWRAP(Sep) Elt +# define QI_LIST_SEP_QI_FALSE(List, Sep) \ + QI_LIST_HEAD(List) \ + QI_LIST_APPLY_AUX(QI_LIST_SEP_HELPER, QI_LIST_TAIL(List), Sep) +# define QI_LIST_SEP_QI_TRUE(List, Sep) +# define QI_LIST_SEP(List, Sep) \ + QI_CAT(QI_LIST_SEP_, \ + QI_LIST_EMPTY(List))(List, QI_WRAP(Sep)) + +# define QI_LIST_ARG_HELPER(Macro, Args) \ + Macro Args +# define QI_LIST_ARG(Macro, List) \ + QI_LIST_ARG_HELPER(Macro, (QI_LIST_SEP(List, QI_COMMA))) + +/// Call Macro(useless, Arg, elem) for each elem (extra argument). +#define QI_VAARGS_APPLY(Macro, Arg, ...) \ + BOOST_PP_SEQ_FOR_EACH(Macro, Arg, \ + QI_LIST(__VA_ARGS__,)) + +#define _QI_OR_00 0 +#define _QI_OR_01 1 +#define _QI_OR_10 1 +#define _QI_OR_11 1 +#define _QI_OR_I1(a, b) BOOST_PP_CAT(BOOST_PP_CAT(_QI_OR_, a), b) +#define _QI_OR_I2(a, b) _QI_OR_I1(a, b) +#define _QI_OR_I3(a, b) _QI_OR_I2(a, b) +#define _QI_OR_I4(a, b) _QI_OR_I3(a, b) +#define QI_OR(a, b) _QI_OR_I4(a, b) + +#define _QI_IS_EMPTY_HELPER__ a,b +#define _QI_IS_ONE_HELPER__1 a,b + +// To suppress a VCXX warning, the two macro below must be called with CAT(_, arg) +// otherwise due to evaluation ordering, code ends up calling QI_IS_ONE() which +// triggers a warning + +//@return 1 if a is defined to 1, 0 otherwise. Must be called with CAT(_, a) +#define _QI_IS_ONE(a) QI_LIST_VASIZE((BOOST_PP_CAT(_QI_IS_ONE_HELPER_, a))) +//@return 1 if a is defined to empty, 0 otherwise. Must be called with CAT(_, a) +#define _QI_IS_EMPTY(a) QI_LIST_VASIZE((BOOST_PP_CAT(_QI_IS_EMPTY_HELPER, BOOST_PP_CAT(_, a)))) + + +//@return 1 if a is defined to empty or 1. Return 0 otherwise. Must be called with CAT(_, a) +#define _QI_IS_ONE_OR_EMPTY(a) \ + QI_OR(_QI_IS_EMPTY(a), _QI_IS_ONE(a)) + + +#define _QI_GEN_ARGTYPE(z,n,_) BOOST_PP_COMMA_IF(n) P ## n +#define _QI_GEN_ARGDECL(z,n,_) BOOST_PP_COMMA_IF(n) P ## n p##n +#define _QI_GEN_ARGDECLSAMETYPE(z,n,t) BOOST_PP_COMMA_IF(n) t p##n +#define _QI_GEN_ARGUSE(z,n,_) BOOST_PP_COMMA_IF(n) p##n +#define _QI_GEN_ARGTYPEDECL(z, n, _) BOOST_PP_COMMA_IF(n) typename P##n + +#define _QI_GEN_PREPOST(z, n, prepost) BOOST_PP_CAT(BOOST_PP_SEQ_ELEM(0, prepost), n) BOOST_PP_SEQ_ELEM(1, prepost) +#define _QI_GEN_PREPOST2(z, n, prepost) BOOST_PP_CAT(BOOST_PP_SEQ_ELEM(0, prepost), n) BOOST_PP_CAT(BOOST_PP_SEQ_ELEM(1, prepost), n) BOOST_PP_SEQ_ELEM(2, prepost) + +// pre 0 post pre 1 post pre 2 post... +#define QI_GEN_PREPOST(n, pre, post) BOOST_PP_REPEAT(n, _QI_GEN_PREPOST, (pre)(post)) +// pre 0 mid 0 post pre 1 mid 1 post ... +#define QI_GEN_PREPOST2(n, pre, mid, post) BOOST_PP_REPEAT(n, _QI_GEN_PREPOST2, (pre)(mid)(post)) +// P0, P1, ... +#define QI_GEN_ARGSTYPE(n) BOOST_PP_REPEAT(n, _QI_GEN_ARGTYPE, _) +// P0 p0, P1 p1, ... +#define QI_GEN_ARGSDECL(n) BOOST_PP_REPEAT(n, _QI_GEN_ARGDECL, _) +// p0, p1, p2 ... +#define QI_GEN_ARGSUSE(n) BOOST_PP_REPEAT(n, _QI_GEN_ARGUSE, _) +// typename P0, typename P1... +#define QI_GEN_ARGSTYPEDECL(n) BOOST_PP_REPEAT(n, _QI_GEN_ARGTYPEDECL, _) +// t p0, t p1... +#define QI_GEN_ARGSDECLSAMETYPE(n, t) BOOST_PP_REPEAT(n, _QI_GEN_ARGDECLSAMETYPE, t) + + +#define _QI_GEN(z, n, f) f(n, QI_GEN_ARGSTYPEDECL(n), QI_GEN_ARGSTYPE(n), QI_GEN_ARGSDECL(n), QI_GEN_ARGSUSE(n), BOOST_PP_COMMA_IF(n)) + +// invoke f(n, argtypedecl, argstype, argsdecl, argsuses, comma_or_empty) for n in [0, 10] +#define QI_GEN(f) BOOST_PP_REPEAT(10, _QI_GEN, f) +#define QI_GEN_RANGE(f, max) BOOST_PP_REPEAT(max, _QI_GEN, f) + +// Evaluate to empty or 'template<' depending on wheter args is empty or a comma. +#define QI_GEN_MAYBE_TEMPLATE_OPEN(...) \ + QI_CAT(_QI_GEN_MAYBE_TEMPLATE_OPEN_, QI_LIST_VASIZE((__VA_ARGS__))) +#define QI_GEN_MAYBE_TEMPLATE_CLOSE(...) \ + QI_CAT(_QI_GEN_MAYBE_TEMPLATE_CLOSE_, QI_LIST_VASIZE((__VA_ARGS__))) + +#define QI_PAIR_FIRST(x) QI_DELAY(_QI_PAIR_FIRST)x +#define QI_PAIR_SECOND(x) QI_DELAY(_QI_PAIR_SECOND)x +#define _QI_PAIR_FIRST(x, ...) x +#define _QI_PAIR_SECOND(x, y) y +#define _QI_GEN_MAYBE_TEMPLATE_OPEN_1 template< +#define _QI_GEN_MAYBE_TEMPLATE_OPEN_0 +#define _QI_GEN_MAYBE_TEMPLATE_CLOSE_1 > +#define _QI_GEN_MAYBE_TEMPLATE_CLOSE_0 +// Return i+1 as a symbol +#define QI_GEN_SYMINC(i) BOOST_PP_CAT(_QI_GEN_SYMINC_, i) +#define _QI_GEN_SYMINC_9 10 +#define _QI_GEN_SYMINC_8 9 +#define _QI_GEN_SYMINC_7 8 +#define _QI_GEN_SYMINC_6 7 +#define _QI_GEN_SYMINC_5 6 +#define _QI_GEN_SYMINC_4 5 +#define _QI_GEN_SYMINC_3 4 +#define _QI_GEN_SYMINC_2 3 +#define _QI_GEN_SYMINC_1 2 +#define _QI_GEN_SYMINC_0 1 + +#define _QI_IF_QI_TRUE(a) a +#define _QI_IF_QI_FALSE(a) +#define _QI_NIF_QI_TRUE(a) +#define _QI_NIF_QI_FALSE(a) a + + + +#define QI_01_TO_TRUEFALSE(v) BOOST_PP_CAT(_QI_01_TO_TRUEFALSE_,v) +#define _QI_01_TO_TRUEFALSE_0 QI_FALSE +#define _QI_01_TO_TRUEFALSE_1 QI_TRUE + +# ifdef _MSC_VER +/* Sometimes when bouncing __VA_ARGS__ around you end up with all args in the same, so use a delay-trick +*/ +#define __QI_VAARGS_MAP_0(Macro, Arg, elem, ...) Macro(0, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##1(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_1(Macro, Arg, elem, ...) , Macro(1, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##2(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_2(Macro, Arg, elem, ...) , Macro(2, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##3(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_3(Macro, Arg, elem, ...) , Macro(3, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##4(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_4(Macro, Arg, elem, ...) , Macro(4, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##5(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_5(Macro, Arg, elem, ...) , Macro(5, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##6(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_6(Macro, Arg, elem, ...) , Macro(6, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##7(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_7(Macro, Arg, elem, ...) , Macro(7, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##8(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_8(Macro, Arg, elem, ...) , Macro(8, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##9(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_9(Macro, Arg, elem, ...) , Macro(9, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##10(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_10(Macro, Arg, elem, ...) , Macro(10, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##11(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_11(Macro, Arg, elem, ...) , Macro(11, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##12(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_12(Macro, Arg, elem, ...) , Macro(12, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##13(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_13(Macro, Arg, elem, ...) , Macro(13, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##14(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_14(Macro, Arg, elem, ...) , Macro(14, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##15(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_15(Macro, Arg, elem, ...) , Macro(15, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##16(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_16(Macro, Arg, elem, ...) , Macro(16, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##17(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_17(Macro, Arg, elem, ...) , Macro(17, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##18(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_18(Macro, Arg, elem, ...) , Macro(18, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##19(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_19(Macro, Arg, elem, ...) , Macro(19, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##20(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_20(Macro, Arg, elem, ...) , Macro(20, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##21(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_21(Macro, Arg, elem, ...) , Macro(21, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##22(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_22(Macro, Arg, elem, ...) , Macro(22, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##23(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_23(Macro, Arg, elem, ...) , Macro(23, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##24(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_24(Macro, Arg, elem, ...) , Macro(24, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##25(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_25(Macro, Arg, elem, ...) , Macro(25, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##26(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_26(Macro, Arg, elem, ...) , Macro(26, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##27(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_27(Macro, Arg, elem, ...) , Macro(27, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##28(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_28(Macro, Arg, elem, ...) , Macro(28, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##29(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_29(Macro, Arg, elem, ...) , Macro(29, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##30(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_30(Macro, Arg, elem, ...) , Macro(30, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##31(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_31(Macro, Arg, elem, ...) , Macro(31, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##32(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_32(Macro, Arg, elem, ...) , Macro(32, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(QI_DELAY(__QI_VAARGS_MAP_)##33(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_33(Macro, Arg, elem, ...) , Macro(33, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(TOO_MANY_ARGUMENTS) + +#define __QI_VAARGS_EMPTY(p1, p2, p3, p4, p5, p6, p7, p8, p9, p10, p11, p12, p13, p14, p15, p16, p17, p18, p19, p20, ...) QI_01_TO_TRUEFALSE(p20) + +// QI_TRUE if __VA_ARGS__ has *no comma*, QI_FALSE else +#define QI_VAARGS_EMPTY(...) QI_DELAY(__QI_VAARGS_)##EMPTY(__VA_ARGS__, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0, 0,1,1) +// expand to Macro(0, Arg, p0), Macro(1, Arg, p1), ... , Macro(N, Arg, pN) +#define QI_VAARGS_MAP(Macro, Arg, ...) \ + QI_DELAY(__QI_VAARGS_MAP_)##0(Macro, Arg, __VA_ARGS__,) + +#else + +#define __QI_VAARGS_MAP_0(Macro, Arg, elem, ...) Macro(0, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_1(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_1(Macro, Arg, elem, ...) , Macro(1, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_2(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_2(Macro, Arg, elem, ...) , Macro(2, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_3(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_3(Macro, Arg, elem, ...) , Macro(3, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_4(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_4(Macro, Arg, elem, ...) , Macro(4, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_5(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_5(Macro, Arg, elem, ...) , Macro(5, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_6(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_6(Macro, Arg, elem, ...) , Macro(6, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_7(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_7(Macro, Arg, elem, ...) , Macro(7, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_8(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_8(Macro, Arg, elem, ...) , Macro(8, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_9(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_9(Macro, Arg, elem, ...) , Macro(9, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_10(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_10(Macro, Arg, elem, ...) , Macro(10, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_11(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_11(Macro, Arg, elem, ...) , Macro(11, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_12(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_12(Macro, Arg, elem, ...) , Macro(12, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_13(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_13(Macro, Arg, elem, ...) , Macro(13, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_14(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_14(Macro, Arg, elem, ...) , Macro(14, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_15(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_15(Macro, Arg, elem, ...) , Macro(15, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_16(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_16(Macro, Arg, elem, ...) , Macro(16, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_17(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_17(Macro, Arg, elem, ...) , Macro(17, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_18(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_18(Macro, Arg, elem, ...) , Macro(18, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_19(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_19(Macro, Arg, elem, ...) , Macro(19, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_20(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_20(Macro, Arg, elem, ...) , Macro(20, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_21(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_21(Macro, Arg, elem, ...) , Macro(21, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_22(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_22(Macro, Arg, elem, ...) , Macro(22, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_23(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_23(Macro, Arg, elem, ...) , Macro(23, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_24(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_24(Macro, Arg, elem, ...) , Macro(24, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_25(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_25(Macro, Arg, elem, ...) , Macro(25, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_26(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_26(Macro, Arg, elem, ...) , Macro(26, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_27(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_27(Macro, Arg, elem, ...) , Macro(27, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_28(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_28(Macro, Arg, elem, ...) , Macro(28, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_29(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_29(Macro, Arg, elem, ...) , Macro(29, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_30(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_30(Macro, Arg, elem, ...) , Macro(30, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_31(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_31(Macro, Arg, elem, ...) , Macro(31, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_32(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_32(Macro, Arg, elem, ...) , Macro(32, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(__QI_VAARGS_MAP_33(Macro, Arg, __VA_ARGS__)) +#define __QI_VAARGS_MAP_33(Macro, Arg, elem, ...) , Macro(33, Arg, elem) QI_CAT(_QI_NIF_,QI_VAARGS_EMPTY(__VA_ARGS__))(TOO_MANY_ARGUMENTS) + +#define __QI_VAARGS_EMPTY(p1, p2, p3, p4, p5, p6, p7, p8, p9, p10, p11, p12, p13, p14, p15, p16, p17, p18, p19, p20, ...) QI_01_TO_TRUEFALSE(p20) + +/// QI_TRUE if __VA_ARGS__ has *no comma*, QI_FALSE else +#define QI_VAARGS_EMPTY(...) __QI_VAARGS_EMPTY(__VA_ARGS__, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0, 0,1,1) +/// expand to Macro(0, Arg, p0), Macro(1, Arg, p1), ... , Macro(N, Arg, pN) +#define QI_VAARGS_MAP(Macro, Arg, ...) \ + __QI_VAARGS_MAP_0(Macro, Arg, __VA_ARGS__,) + +#endif + + + +#endif // _QI_PREPROC_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/qi.hpp b/naoModule/libnaoqi_files/include/qi/qi.hpp new file mode 100755 index 0000000..3ac3c5d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/qi.hpp @@ -0,0 +1,25 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_QI_HPP_ +#define _QI_QI_HPP_ + +#include +#include + +namespace qi { + + QI_API QI_API_DEPRECATED void init(int& argc, char **& argv); + QI_API QI_API_DEPRECATED int argc(); + QI_API QI_API_DEPRECATED const char** argv(); + QI_API QI_API_DEPRECATED const char *program(); + + typedef std::codecvt codecvt_type; + QI_API const codecvt_type &unicodeFacet(); +} + +#endif // _QI_QI_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/shared_ptr.hpp b/naoModule/libnaoqi_files/include/qi/shared_ptr.hpp new file mode 100755 index 0000000..ae4e119 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/shared_ptr.hpp @@ -0,0 +1,106 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#ifndef _QI_SHARED_PTR_HPP_ +#define _QI_SHARED_PTR_HPP_ + +#include +#include + +namespace qi +{ + /// Lightweight implementation of shared pointers. + template + class SharedPtr + { + public: + /// Initialization of the SharedPtr with the pointer it will manage. + SharedPtr(T *ptr) + : _ptr(ptr) + , _refcount(new qi::Atomic(1)) + { + } + + /// \brief Destruct the shared pointer and the pointer if current SharedPtr + /// is the last one to hold the pointer. + ~SharedPtr() + { + if (--(*_refcount) == 0) + { + delete _ptr; + delete _refcount; + } + } + + /// Copy shared pointer. + SharedPtr(const SharedPtr &sp) + { + /* + * Note that this line is racy. + * If someone is deleting _refcount, + * it cannot be used below. + */ + if (++(*sp._refcount) != 1) + { + _ptr = sp._ptr; + _refcount = sp._refcount; + } + else + { + + _ptr = 0; + _refcount = 0; + qiLogDebug("qi.log.shared_ptr") + << "tried to copy a shared pointer targeted for deletion" + << std::endl; + } + } + + /// \brief Link current SharedPtr to a new pointer. If old pointer was + /// only held by the current SharedPtr, it is freed. + SharedPtr& operator=(SharedPtr &sp) + { + // release the current pointer + if (--(*_refcount) == 0) + { + delete _ptr; + delete _refcount; + } + if (++(*sp._refcount) != 1) + { + _ptr = sp._ptr; + _refcount = sp._refcount; + } + else + { + qiLogDebug("qi.log.shared_ptr") + << "tried to copy a shared pointer targeted for deletion" + << std::endl; + } + return *this; + } + + /// Value accessor. + T &operator*() const + { + return *_ptr; + } + + /// Pointer accessor. + T *operator->() const + { + return _ptr; + } + + private: + T *_ptr; + qi::Atomic *_refcount; + }; +} + +#endif // _QI_SHARED_PTR_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/stats.hpp b/naoModule/libnaoqi_files/include/qi/stats.hpp new file mode 100755 index 0000000..20b1ae4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/stats.hpp @@ -0,0 +1,88 @@ +#pragma once +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + #ifndef _QI_STATS_HPP_ + #define _QI_STATS_HPP_ + + #include + + namespace qi + { + /// Stores min, max and sum of values fed to it + class MinMaxSum + { + public: + MinMaxSum() : _minValue(0), _maxValue(0), _cumulatedValue(0) {} + MinMaxSum(float minValue, float maxValue, float cumulatedValue) + : _minValue(minValue), _maxValue(maxValue), _cumulatedValue(cumulatedValue) + {} + + const float& minValue() const { return _minValue;} + const float& maxValue() const { return _maxValue;} + const float& cumulatedValue() const { return _cumulatedValue;} + void push(float val, bool init = false) + { + if (init) + _minValue = _maxValue = _cumulatedValue = val; + else + { + _cumulatedValue += val; + _minValue = (std::min)(_minValue, val); + _maxValue = (std::max)(_maxValue, val); + } + } + void reset() + { + _minValue = _maxValue = _cumulatedValue = 0; + } + std::string asString(unsigned int count) const + { + std::stringstream s; + s << (_cumulatedValue / (float)count) << ' ' << _minValue << ' ' << _maxValue; + return s.str(); + } + private: + float _minValue; + float _maxValue; + float _cumulatedValue; + }; + + /// Store statistics about method calls. + class MethodStatistics + { + public: + MethodStatistics() + : _count(0) {} + MethodStatistics(unsigned count, MinMaxSum wall, MinMaxSum user, MinMaxSum system) + : _count(count), _wall(wall), _user(user), _system(system) + {} + void push(float wall, float user, float system) + { + _wall.push(wall, _count==0); + _user.push(user, _count==0); + _system.push(system, _count==0); + ++_count; + } + const MinMaxSum& wall() const { return _wall;} + const MinMaxSum& user() const { return _user;} + const MinMaxSum& system() const { return _system;} + const unsigned int& count() const { return _count;} + void reset() + { + _count = 0; + _wall.reset(); + _user.reset(); + _system.reset(); + } + private: + unsigned int _count; + MinMaxSum _wall; + MinMaxSum _user; + MinMaxSum _system; + }; + } + #endif diff --git a/naoModule/libnaoqi_files/include/qi/threadpool.hpp b/naoModule/libnaoqi_files/include/qi/threadpool.hpp new file mode 100755 index 0000000..74cfda5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/threadpool.hpp @@ -0,0 +1,68 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#ifndef _QI_THREADPOOL_HPP_ +#define _QI_THREADPOOL_HPP_ + +# include +# include + +namespace qi +{ + class ThreadPoolPrivate; + + /// Pool of workers + class QI_API ThreadPool + { + public: + /// ThreadPool constructor. + ThreadPool(unsigned int minWorkers = 2, unsigned int maxWorkers = 100, + unsigned int minIdleWorkers = 1, unsigned int maxIdleWorkers = 0); + /// ThreadPool destructor. + ~ThreadPool(); + + /// Returns the number of workers in the pool. + unsigned int size() const; + /// Returns the number of active workers in the pool. + unsigned int active() const; + + /// Resizes the pool. + void setMaxWorkers(unsigned int n); + /// Sets minimum number of workers in the pool. + unsigned int getMaxWorkers() const; + /// Sets max idle workers. + void setMinWorkers(unsigned int n); + /// Sets min idle workers. + unsigned int getMinWorkers() const; + /// Returns maximum number of workers in the pool. + void setMinIdleWorkers(unsigned int n); + /// Returns minimum number of workers in the pool. + unsigned int getMinIdleWorkers() const; + /// Returns maximum number of inactive workers in the pool. + void setMaxIdleWorkers(unsigned int n); + /// Returns minimum number of inactive workers in the pool. + unsigned int getMaxIdleWorkers() const; + + /// Stop the threadpool, no more will be accepted + void stop(); + + /// Put the threadpool back in a state where it accept request + void reset(); + + /// Sleeps until all tasks are completed + void waitForAll(); + + /// Adds a task to the pool. + bool schedule(const boost::function& f); + + private: + ThreadPoolPrivate* _p; + }; +} + +#endif // _QI_THREADPOOL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/trackable.hpp b/naoModule/libnaoqi_files/include/qi/trackable.hpp new file mode 100755 index 0000000..91097ad --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/trackable.hpp @@ -0,0 +1,107 @@ +#pragma once +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + + +#ifndef _QI_TRACKABLE_HPP_ +#define _QI_TRACKABLE_HPP_ + +#include +#include +#include +#include + +#include + +namespace qi +{ + + /// Common base class to templates Trackable for compile-time detection. + class TrackableBase {}; + + /** Object tracking by blocking destruction while shared pointers are present. + * + * Inherit from Trackable to allow a form of tracking that blocks destruction + * while shared pointers are held. This allows using your class without a + * shared_ptr wrapper. + * + * @warning when inheriting from this class, you *must* invoke the destroy() + * method from your destructor, before any operation that puts your object in + * an invalid state. + * + * @warning since destroy() blocks until all shared pointers are destroyed, + * deadlocks may occur if used improperly. + * + */ + template + class Trackable: public TrackableBase + { + public: + Trackable(T* ptr); + ~Trackable(); + + /** @return a shared_ptr that will block destruction (call to destroy() until + * it is released, or an empty shared_ptr if destroy was already called. + */ + boost::shared_ptr lock(); + + /** @return a weak_ptr from this. While a shared_ptr exists from this weak_ptr, + * a call to destroy will block() + * + */ + boost::weak_ptr weakPtr(); + + /** Blocks until destroy() is called and all shared_ptr built from weak_ptr() + * are deleted. + */ + void wait(); + protected: + /** *Must* be called by parent class destructor, first thing. + * Can block until lock holders terminate + */ + void destroy(); + private: + void _destroyed(); + + boost::shared_ptr _ptr; + boost::condition_variable _cond; + boost::mutex _mutex; + bool _wasDestroyed; + }; + + class QI_API PointerLockException: public std::exception + { + public: + virtual const char* what() const throw() + { + return "Pointer Lock failed"; + } + }; + +#ifdef DOXYGEN + /** Bind a set of arguments or placeholders to a function. + * + * Handles first function argument of kind boost::weak_ptr and qi::Trackable: + * will try to lock and throw qi::PointerLockException in case of failure + */ + template boost::function bind(const AF& fun, ...); +#endif + + /** Wrap given function \p f with a tracking check on \p arg0, which must + * be a weak pointer or a Trackable instance. + * @return a function that, when called: + * - If lock can be acquired, calls \p f + * - Else throws qi::PointerLockException + */ + template + boost::function track(const boost::function& f, const ARG0& arg0); + template + boost::function trackWithFallback(boost::function onFail, + const boost::function& f, const ARG0& arg0); +} + +#include +#endif // _QI_TRACKABLE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/traits.hpp b/naoModule/libnaoqi_files/include/qi/traits.hpp new file mode 100755 index 0000000..7cc803a --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/traits.hpp @@ -0,0 +1,56 @@ +#pragma once +/* + * Copyright (c) 2012 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _LIBQI_TRAITS_HPP_ +# define _LIBQI_TRAITS_HPP_ + +#include + +namespace boost +{ + // forward-declare the trait to avoid an include + template struct is_base_of; +} +namespace qi +{ + /// Detect if a type is using boost::noncopyable or QI_DISALLOW_COPY_AND_ASSIGN + template struct IsClonable + { + typedef char yes[1]; + typedef char no[2]; + template + static no& test(typename C::_qi_not_clonable*); + + template + static yes& test(...); + + static const bool value = sizeof(test(0)) == sizeof(yes) + && ! boost::is_base_of::value; + }; + + ///@return true if T inherits from boost::noncopyable or uses QI_DISALLOW_COPY_AND_ASSIGN + template bool isClonable() + { + return IsClonable::value; + } + + template bool isClonable(T*) + { + return IsClonable::value; + } + + namespace details + { + template void newAndAssign(T** ptr) + { + *ptr = new T(); + } + } +} + + +#endif diff --git a/naoModule/libnaoqi_files/include/qi/translator.hpp b/naoModule/libnaoqi_files/include/qi/translator.hpp new file mode 100755 index 0000000..8654c11 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/translator.hpp @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef _QI_TRANSLATOR_HPP_ +#define _QI_TRANSLATOR_HPP_ + +# include +# include +# include + +namespace qi +{ + class TranslatorPrivate; + class QI_API Translator : private boost::noncopyable + { + public: + Translator(const std::string &name); + ~Translator(); + + std::string translate(const std::string &msg, + const std::string &domain = "", + const std::string &locale = ""); + + void setCurrentLocale(const std::string &locale); + void setDefaultDomain(const std::string &domain); + void addDomain(const std::string &domain); + + private: + TranslatorPrivate *_p; + }; + + QI_API qi::Translator &defaultTranslator(const std::string &name); + + QI_API std::string tr(const std::string &msg, + const std::string &domain = "", + const std::string &locale = ""); + + namespace detail + { + QI_API void addDomainPath(const std::string &path); + QI_API void removeDomainPath(const std::string &path); + } + +} + +#endif // _QI_TRANSLATOR_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/types.hpp b/naoModule/libnaoqi_files/include/qi/types.hpp new file mode 100755 index 0000000..6c5b11a --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/types.hpp @@ -0,0 +1,42 @@ +#pragma once +/* +** Author(s): +** - Cuche Herve +** +** Copyright (C) 2012 Aldebaran Robotics +*/ + +#ifndef _QI_TYPES_HPP_ +#define _QI_TYPES_HPP_ + +// visual studio 2008 and lower version +# if defined(_MSC_VER) && (_MSC_VER <= 1500) +namespace qi +{ + typedef signed __int8 int8_t; + typedef signed __int16 int16_t; + typedef signed __int32 int32_t; + typedef signed __int64 int64_t; + + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + typedef unsigned __int64 uint64_t; +} +# else +# include +namespace qi +{ + typedef int8_t int8_t; + typedef int16_t int16_t; + typedef int32_t int32_t; + typedef int64_t int64_t; + + typedef uint8_t uint8_t; + typedef uint16_t uint16_t; + typedef uint32_t uint32_t; + typedef uint64_t uint64_t; +} +# endif + +#endif // _QI_TYPES_HPP_ diff --git a/naoModule/libnaoqi_files/include/qi/version.hpp b/naoModule/libnaoqi_files/include/qi/version.hpp new file mode 100755 index 0000000..6b17235 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qi/version.hpp @@ -0,0 +1,67 @@ +#pragma once +/* +** Author(s): +** - Cedric GESTES +** +** Copyright (C) 2010 Aldebaran Robotics +*/ + +#ifndef _QI_VERSION_HPP_ +#define _QI_VERSION_HPP_ + +//scoped_ptr needs to have dll-interface to be used +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +# include +# include +# include +# include + +namespace qi { + namespace version { + + class VersionPrivate; + class QI_API Version + { + public: + // these constructors are implicit by design + Version(); + Version(const Version &other); + Version(const std::string &version); + Version(const char *version); + ~Version(); + + Version &operator= (const Version& rhs); + + operator const std::string&() const; + + bool operator< (const Version& pi) const; + bool operator> (const Version& pi) const; + bool operator==(const Version& pi) const; + bool operator!=(const Version& pi) const; + bool operator<=(const Version& pi) const; + bool operator>=(const Version& pi) const; + + private: + boost::scoped_ptr _p; + }; + + //convert a version's string into a vector with each comparable part + QI_API std::vector explode(const std::string &version); + + //compare two version's strings. a < b return -1 + QI_API int compare(const std::string &versionA, + const std::string &versionB); + + QI_API std::string extract(const std::string &version); + } +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QI_VERSION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qimessaging/api.hpp b/naoModule/libnaoqi_files/include/qimessaging/api.hpp new file mode 100755 index 0000000..16a2670 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/api.hpp @@ -0,0 +1,16 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIMESSAGING_API_HPP_ +#define _QIMESSAGING_API_HPP_ + +#include + +#define QIMESSAGING_API QI_LIB_API(qimessaging) + + +#endif // _QIMESSAGING_API_HPP_ + diff --git a/naoModule/libnaoqi_files/include/qimessaging/applicationsession.hpp b/naoModule/libnaoqi_files/include/qimessaging/applicationsession.hpp new file mode 100755 index 0000000..93e392d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/applicationsession.hpp @@ -0,0 +1,86 @@ +#pragma once +/* + * Copyright (c) 2013 Aldebaran Robotics. All rights reserved. + * Use of this source code is governed by a BSD-style license that can be + * found in the COPYING file. + */ + +#ifndef QIMESSAGING_APPLICATIONSESSION_HPP_ +#define QIMESSAGING_APPLICATIONSESSION_HPP_ +#include +#include +#include + +namespace qi +{ + class ApplicationSessionPrivate; + typedef qi::uint32_t ApplicationSessionOptions; + + /** ApplicationSession is an application with an embedded session. + * The constructor has to be the first method called of the class to initialize the class. + * Be careful with the scope of the object, once the destructor is called, + * the session is destroyed as well. + */ + class QIMESSAGING_API ApplicationSession : public Application, private boost::noncopyable + { + public: + /** By default, ApplicationSession will automatically call qi::Application::stop() + * when the session is over. If you want a different behaviour you have to + * call the constructor with the desired option below. + * + * Ex: qi::ApplicationSession app(argc, argv, qi::ApplicationSession::Option_NoAutoExit) + */ + enum Option + { + Option_None = 0, //!< No option, this is the default behavior. + Option_NoAutoExit = 1, //!< With this option the application won't stop once the session is disconnected. + }; + + /** ApplicationSession will check first if there is a --qi-url given in argv, + * if not it will take the url in the constructor instead setting its url. + * If --qi-listen-url is set the session will listen on the provided url. + * @param argc The number of arguments. + * @param argv The array containing all the arguments given to the program. + * @param opt Either ApplicationSession::Option_None or + * ApplicationSession::Option_NoAutoExit. The default behavior of + * ApplicationSession is to call stop() once the session gets disconnected. + * @see qi::ApplicationSession::Option + * @param url The default url used if no --qi-url was found in the options. + */ + ApplicationSession(int& argc, char**& argv, ApplicationSessionOptions opt = Option_None, const Url& url = "tcp://127.0.0.1:9559"); + ApplicationSession(const std::string& name, int& argc, char**& argv, ApplicationSessionOptions opt = Option_None, const Url& url = "tcp://127.0.0.1:9559"); + virtual ~ApplicationSession(); + + /** + * @return The embedded session used by ApplicationSession. + */ + SessionPtr session(); + + /** + * @return The url used by ApplicationSession parsed on the command line by + * --qi-url if specified, otherwise the default url given in the constructor. + * @see qi::ApplicationSession::ApplicationSession for parsing information. + */ + Url url(); + + /** + * @return The url used by ApplicationSession parsed on the command line by + * --qi-listen-url, or an empty string if the option wasn't given. + * @see qi::ApplicationSession::ApplicationSession for parsing information. + */ + Url listenUrl(); + + /** Establishes the session's connection and moreover starts listening if + * --qi-listen-url was given. + */ + void start(); + + /** Runs the application and automatically calls start() if it hasn't been done yet. + */ + void run(); + private: + ApplicationSessionPrivate* _p; + }; +} + +#endif // QIMESSAGING_APPLICATIONSESSION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qimessaging/autoservice.hpp b/naoModule/libnaoqi_files/include/qimessaging/autoservice.hpp new file mode 100755 index 0000000..1ab6955 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/autoservice.hpp @@ -0,0 +1,110 @@ + +#pragma once + +/* + ** Copyright (C) 2013 Aldebaran Robotics + ** See COPYING for the licence +*/ + +#ifndef _QIMESSAGING_AUTOSERVICE_HPP_ +#define _QIMESSAGING_AUTOSERVICE_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace qi +{ + + namespace detail + { + template + class Keeper; + } + + /** + * Service remote that automatically reconnect + * + * Wrapper around qi::Object that automatically tries to reacquire + * the object from the session in case of disconnection. Throws if + * dereferenced while the service is unavailable. + * The class is templated and should be used with a remote class + * that will call the methods of the service. (see also the test_autoservice.cpp file) + */ + template + class AutoService : public qi::Trackable >, public qi::detail::GenericObjectBounce > + { + public: + /** + * Constuctor of AutoService + * + * Automatically provides a connection to the service + * + * @param name the name of the service to use + * @param session a ref to the session that will be used to find the service. + */ + AutoService(const std::string& name, qi::SessionPtr session); + + ~AutoService(); + + /** + * Provides an access to the service + * + * Use this operator to call any method of the variable stored in the AutoService. + * For exemple if you have a remote class called PingRemote that have a method called ping + * that call the matching service, you can create an \b AutoService \b autoService and write + * \b autoService->ping(); + * + * @throws If the connection to the Service is unavailable, throws a runtime_exception + */ + qi::detail::Keeper operator->(); + qi::detail::Keeper operator->() const; + /** + * Provides an access to the var stored in the AutoService + * + * @throws If the connection to the Service is unavailable, throws a runtime_exception + */ + T& operator*(); + T* get(); + const T* get() const; + + /** + * Notify when the service is available. + * + * @return a Future that will be set when the service is available (or immediately if the service is available at the time of the call). + */ + qi::FutureSync waitForReady(); + + /** + * This signal is triggered when your service register. + */ + qi::Signal serviceAdded; + + /** + * This signal is triggered when your service is lost. + */ + qi::Signal serviceRemoved; + + qi::GenericObject* asGenericObject() const; + + private: + void onServiceModified(const qi::Future& future); + void onServiceAdded(const std::string& name); + void onServiceRemoved(const std::string& name); + + mutable boost::mutex _mutex; + SessionPtr _session; + qi::Object _object; + std::string _name; + qi::Promise _promise; + }; + + typedef AutoService AnyAutoService; +} + +#include "details/autoservice.hxx" + +#endif diff --git a/naoModule/libnaoqi_files/include/qimessaging/details/autoservice.hxx b/naoModule/libnaoqi_files/include/qimessaging/details/autoservice.hxx new file mode 100755 index 0000000..fcb8f24 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/details/autoservice.hxx @@ -0,0 +1,175 @@ +#include + +namespace qi +{ + template + AutoService::AutoService(const std::string& name, SessionPtr session) + : qi::Trackable > (this) + , _session(session) + , _name(name) + { + Future fut = session->service(name); + fut.connect(&AutoService::onServiceModified, this, fut); + + _session->serviceRegistered.connect(&AutoService::onServiceAdded, this, _2); + _session->serviceUnregistered.connect(&AutoService::onServiceRemoved, this, _2); + } + + template + AutoService::~AutoService() + { + this->destroy(); + } + + template + void AutoService::onServiceRemoved(const std::string& name) + { + if (name == _name) + { + { + boost::mutex::scoped_lock scoped_lock(_mutex); + _object = qi::Object(); + _promise.reset(); + } + serviceRemoved(); + } + } + + template + void AutoService::onServiceModified(const qi::Future& future) + { + if (!future.hasError()) + { + { + boost::mutex::scoped_lock scoped_lock(_mutex); + _object = qi::Object(future.value()); + if (!_promise.future().isFinished()) + _promise.setValue(0); + } + serviceAdded(); + } + else + { // A Service has been added, but it has been impossible to get it; so we delete it. + { + boost::mutex::scoped_lock scoped_lock(_mutex); + _object = qi::Object(); + _promise.reset(); + } + serviceRemoved(); + } + } + + template + void AutoService::onServiceAdded(const std::string& name) + { + if (name == _name) + { + boost::mutex::scoped_lock scoped_lock(_mutex); + qi::Future future = _session->service(name); + future.connect(&AutoService::onServiceModified, this, future); + } + } + + /** + * The compiler will recursively call operator-> on each returned object until he get a pointer + * We return an qi::details::Keeper to keep T* alive during the call + * (Object will be temporary stored on stack while the call is pending) + */ + template + qi::detail::Keeper AutoService::operator->() + { + boost::mutex::scoped_lock scoped_lock(_mutex); + qi::detail::Keeper keeper = qi::detail::Keeper(_object); + if (keeper._obj) + return keeper; + else + throw std::runtime_error("Service " + _name + " unavailable"); + } + + template + qi::detail::Keeper AutoService::operator->() const + { + boost::mutex::scoped_lock scoped_lock(_mutex); + qi::detail::Keeper keeper = qi::detail::Keeper(_object); + if (keeper._obj) + return keeper; + else + throw std::runtime_error("Service " + _name + " unavailable"); + } + + template + const T* AutoService::get() const + { + boost::mutex::scoped_lock scoped_lock(_mutex); + if (_object) + return &(*_object); + else + throw std::runtime_error("Service " + _name + " unavailable"); + } + + template + T* AutoService::get() + { + boost::mutex::scoped_lock scoped_lock(_mutex); + if (_object) + return &(*_object); + else + throw std::runtime_error("Service " + _name + " unavailable"); + } + + template + T& AutoService::operator*() + { + return *get(); + } + + + template + qi::FutureSync AutoService::waitForReady() + { + return _promise.future(); + } + + template + qi::GenericObject* AutoService::asGenericObject() const + { + boost::mutex::scoped_lock scoped_lock(_mutex); + if (_object) + return _object.asGenericObject(); + else + throw std::runtime_error("Service " + _name + " unavailable"); + } + + /** + * Warning: AutoService is invalid. + * + * Prefere use AnyAutoService instead. + */ + template <> + class AutoService + { + private: + virtual void forbiden() = 0; + }; + + + namespace detail + { + template + class Keeper + { + public: + Keeper(qi::Object& obj) + : _obj(obj) + { + } + + T* operator->() + { + return &(*_obj); + } + + qi::Object _obj; + }; + } +} diff --git a/naoModule/libnaoqi_files/include/qimessaging/gateway.hpp b/naoModule/libnaoqi_files/include/qimessaging/gateway.hpp new file mode 100755 index 0000000..90b7ec4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/gateway.hpp @@ -0,0 +1,58 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIMESSAGING_GATEWAY_HPP_ +#define _QIMESSAGING_GATEWAY_HPP_ + +# include + +namespace qi +{ + class GatewayPrivate; + + class QIMESSAGING_API Gateway + { + public: + Gateway(); + ~Gateway(); + + bool attachToServiceDirectory(const qi::Url &address); + bool listen(const qi::Url &address); + std::vector endpoints() const; + + private: + GatewayPrivate *_p; + }; + + class QIMESSAGING_API RemoteGateway + { + public: + RemoteGateway(); + ~RemoteGateway(); + + bool listen(const qi::Url &address); + void join(); + + private: + GatewayPrivate *_p; + }; + + class QIMESSAGING_API ReverseGateway + { + public: + ReverseGateway(); + ~ReverseGateway(); + + bool attachToServiceDirectory(const qi::Url &address); + bool connect(const qi::Url &address); + void join(); + + private: + GatewayPrivate *_p; + }; +} + +#endif // _QIMESSAGING_GATEWAY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qimessaging/serviceinfo.hpp b/naoModule/libnaoqi_files/include/qimessaging/serviceinfo.hpp new file mode 100755 index 0000000..dd3d995 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/serviceinfo.hpp @@ -0,0 +1,53 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIMESSAGING_SERVICEINFO_HPP_ +#define _QIMESSAGING_SERVICEINFO_HPP_ + +#include +#include + +#include +#include +#include + +namespace qi +{ + class ServiceInfoPrivate; + class QIMESSAGING_API ServiceInfo { + public: + ServiceInfo(); + ServiceInfo(const ServiceInfo& svcinfo); + + ~ServiceInfo(); + + ServiceInfo& operator= (const ServiceInfo& svcinfo); + + void setName(const std::string& name); + void setServiceId(unsigned int serviceId); + void setMachineId(const std::string& machineId); + void setProcessId(unsigned int processId); + void setEndpoints(const qi::UrlVector& endpoints); + void addEndpoint(const qi::Url& endpoint); + void setSessionId(const std::string& sessionId); + + const std::string& name() const; + unsigned int serviceId() const; + const std::string& machineId() const; + unsigned int processId() const; + const qi::UrlVector& endpoints() const; + const std::string& sessionId() const; + + ServiceInfoPrivate* _p; + + protected: + friend class TypeImpl; + }; + + typedef std::vector ServiceInfoVector; +} // !qi + +#endif // _QIMESSAGING_SERVICEINFO_HPP_ diff --git a/naoModule/libnaoqi_files/include/qimessaging/session.hpp b/naoModule/libnaoqi_files/include/qimessaging/session.hpp new file mode 100755 index 0000000..ce44f52 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/session.hpp @@ -0,0 +1,89 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIMESSAGING_SESSION_HPP_ +#define _QIMESSAGING_SESSION_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + class SessionPrivate; + class QIMESSAGING_API Session : boost::noncopyable { + public: + Session(); + virtual ~Session(); + + enum ServiceLocality { + ServiceLocality_All = 0, + ServiceLocality_Local = 1, + ServiceLocality_Remote = 2 + }; + + //Client + qi::FutureSync connect(const char* serviceDirectoryURL); + qi::FutureSync connect(const std::string &serviceDirectoryURL); + qi::FutureSync connect(const qi::Url &serviceDirectoryURL); + bool isConnected() const; + qi::Url url() const; + + qi::FutureSync< std::vector > services(ServiceLocality locality = ServiceLocality_All); + + qi::FutureSync< qi::AnyObject > service(const std::string &service, + const std::string &protocol = ""); + + //Server + qi::FutureSync listen(const qi::Url &address); + std::vector endpoints() const; + bool setIdentity(const std::string& key, const std::string& crt); + + //close both client and server side + qi::FutureSync close(); + + //this create a listen and create a service directory + qi::FutureSync listenStandalone(const qi::Url &address); + + qi::FutureSync registerService(const std::string &name, AnyObject object); + qi::FutureSync unregisterService(unsigned int serviceId); + + + /// Load a module and register an instance of each declared object as a service. + std::vector loadService(const std::string& name, int flags = -1); + + public: + qi::Signal serviceRegistered; + qi::Signal serviceUnregistered; + // C4251 + qi::Signal<> connected; + // C4251 + qi::Signal disconnected; + + protected: + friend class SessionPrivate; + boost::shared_ptr _p; + }; + + typedef boost::shared_ptr SessionPtr; + + inline SessionPtr makeSession() { return boost::make_shared(); } +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QIMESSAGING_SESSION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qimessaging/url.hpp b/naoModule/libnaoqi_files/include/qimessaging/url.hpp new file mode 100755 index 0000000..2a299da --- /dev/null +++ b/naoModule/libnaoqi_files/include/qimessaging/url.hpp @@ -0,0 +1,132 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIMESSAGING_URL_HPP_ +#define _QIMESSAGING_URL_HPP_ + +#include +#include + +#include + +namespace qi { + class UrlPrivate; + + /** qi::Url is an address represented by a protocol, a host and a port. + * @warning The class isn't compliant with RFC 3986. + * + * qi::Url can parse the following formats : + * - protocol://host:port + * - protocol://host + * - host:port + * - host + * - protocol://:port + * - protocol:// + * - :port + * - *empty string* + * + * @note This class is copyable. + */ + class QIMESSAGING_API Url + { + public: + /** Creates an empty url. + */ + Url(); + + /** + * @param url The url string, the port and the protocol will be extracted + * if they're present. + */ + Url(const std::string &url); + + /** + * @param url The url string, the port and the protocol will be extracted + * if they're present. + * @param defaultPort The port that will be used if no port had been found + * in the url string. + */ + Url(const std::string &url, unsigned short defaultPort); + + /** + * @param url The url string, the port and the protocol will be extracted + * if they're present. + * @param defaultProtocol The protocol that will be used if no protocol had + * been found in the url string. + */ + Url(const std::string &url, const std::string &defaultProtocol); + + /** + * @param url The url string, the port and the protocol will be extracted + * if they're present. + * @param defaultProtocol The protocol that will be used if no protocol had + * been found in the url string. + * @param defaultPort The port that will be used if no port had been found + * in the url string. + */ + Url(const std::string &url, const std::string &defaultProtocol, unsigned short defaultPort); + + /** + * @cond + */ + Url(const char *url); + /** + * @endcond + */ + + /** Compares the url strings. + */ + bool operator ==(const Url& url); + + virtual ~Url(); + + /** + * @cond + */ + Url(const qi::Url& url); + Url& operator= (const Url& rhs); + bool operator< (const Url& rhs) const; + /** + * @endcond + */ + + /** + * @return True if the port and the protocol had been set. + */ + bool isValid() const; + + /** + * @return The url string used by the Url class, the port and/or the + * protocol may have been appended if they had been given in the + * constructor. + */ + const std::string& str() const; + + /** + * @return The protocol of the url or an empty string if no protocol was + * set. + */ + const std::string& protocol() const; + + /** + * @return The host part of the url or an empty string if no host part was + * found. + */ + const std::string& host() const; + + /** + * @return The port of the url, 0 if no port were given. + */ + unsigned short port() const; + + private: + UrlPrivate* _p; + }; + + typedef std::vector UrlVector; +} + +#endif // _QIMESSAGING_URL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qiperf/api.hpp b/naoModule/libnaoqi_files/include/qiperf/api.hpp new file mode 100755 index 0000000..4a1ba0e --- /dev/null +++ b/naoModule/libnaoqi_files/include/qiperf/api.hpp @@ -0,0 +1,23 @@ +/** @file + * @brief dll import/export and compiler message + */ + +#pragma once +#ifndef _LIBQI_QI_PERF_CONFIG_HPP_ +#define _LIBQI_QI_PERF_CONFIG_HPP_ + +#include + +// qiperf controls which symbols are exported when libqiperf +// is compiled as a SHARED lib. +// DO NOT USE OUTSIDE LIBQIPERF +#ifdef qiperf_EXPORTS +# define QIPERF_API QI_EXPORT_API +#elif defined(qiperf_IMPORTS) +# define QIPERF_API QI_IMPORT_API +#else +# define QIPERF_API +#endif + + +#endif // _LIBQI_QI_PERF_CONFIG_HPP_ diff --git a/naoModule/libnaoqi_files/include/qiperf/dataperf.hpp b/naoModule/libnaoqi_files/include/qiperf/dataperf.hpp new file mode 100755 index 0000000..4ce1416 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qiperf/dataperf.hpp @@ -0,0 +1,54 @@ +/* +** Author(s): +** - Nicolas Cornu +** +** Copyright (C) 2012-2013 Aldebaran Robotics +*/ + +#pragma once +#ifndef _QI_PERF_DATAPERF_HPP_ +#define _QI_PERF_DATAPERF_HPP_ + +#include +#include + +namespace qi +{ + class DataPerfPrivate; + + /// Class to compute and store a benchmark time. + class QIPERF_API DataPerf + { + public: + /// Default constructor. + DataPerf(); + /// Default destructor. + ~DataPerf(); + + /// Start measuring time + void start(const std::string& benchmarkName, unsigned long loopCount = 1, unsigned long msgSize = 0, const std::string& variable = ""); + /// Stop measuring time + void stop(); + + /// Return the name of the benchmark. + std::string getBenchmarkName() const; + /// Return the variable of the benchmark + std::string getVariable() const; + /// Return the size of message transmitted. + unsigned long getMsgSize() const; + /// Return the average time taken by a single execution of the benchmarked code. + double getPeriod() const; + /// Return the time take by the CPU against the total time. + double getCpu() const; + /// Return the number of messages transmitted in a single second. + double getMsgPerSecond() const; + /// Return the MB transmitted in a single second. + double getMegaBytePerSecond() const; + + private: + DataPerfPrivate *_p; + }; +} + + +#endif // _QIPERF_DETAILS_DATAPERF_HPP_ diff --git a/naoModule/libnaoqi_files/include/qiperf/dataperfsuite.hpp b/naoModule/libnaoqi_files/include/qiperf/dataperfsuite.hpp new file mode 100755 index 0000000..9cf8af6 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qiperf/dataperfsuite.hpp @@ -0,0 +1,55 @@ +/* +** Author(s): +** - Nicolas Cornu +** +** Copyright (C) 2012-2013 Aldebaran Robotics +*/ + +#pragma once +#ifndef _QI_PERF_DATAPERFSUITE_HPP_ +#define _QI_PERF_DATAPERFSUITE_HPP_ + +#include + +#include +#include + +namespace qi +{ + class DataPerfSuitePrivate; + + /// A class to perform benchmarks. + class QIPERF_API DataPerfSuite + { + public: + + enum OutputData { + OutputData_None = 0, + OutputData_Cpu = 1, + OutputData_Period = 2, + OutputData_MsgPerSecond = 3, + OutputData_MsgMBPerSecond = 4 + }; + + /// Constructor + DataPerfSuite(const std::string& projectName, const std::string& executableName, OutputData outputData = OutputData_None, const std::string& filename = ""); + + /// Destructor + ~DataPerfSuite(); + + /// Overloading used to print data out. + DataPerfSuite& operator<<(const DataPerf& data); + + /// Print end of file and close it. + void close(); + + void flush(); + + private: + DataPerfSuitePrivate *_p; + }; +} + +#include + +#endif // _QI_PERF_DATAPERFSUITE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qiperf/details/dataperfsuite.hxx b/naoModule/libnaoqi_files/include/qiperf/details/dataperfsuite.hxx new file mode 100755 index 0000000..175e155 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qiperf/details/dataperfsuite.hxx @@ -0,0 +1,33 @@ +#pragma once +/* +** Copyright (C) 2012 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QI_PERF_DETAILS_DATAPERFSUITE_HXX_ +#define _QI_PERF_DETAILS_DATAPERFSUITE_HXX_ + +#include + +namespace po = boost::program_options; + +namespace qi { + + namespace details { + + inline po::options_description getPerfOptions() + { + po::options_description desc(std::string("Options for perf")); + + desc.add_options() + ("output,o", po::value()->default_value(""), + "Output file (If not specified, set to standard output)."); + + return desc; + } + + } + +} + +#endif /* _QI_PERF_DETAILS_DATAPERFSUITE_HXX_ */ diff --git a/naoModule/libnaoqi_files/include/qiperf/measure.hpp b/naoModule/libnaoqi_files/include/qiperf/measure.hpp new file mode 100755 index 0000000..a24e4ae --- /dev/null +++ b/naoModule/libnaoqi_files/include/qiperf/measure.hpp @@ -0,0 +1,23 @@ +/* +** Author(s): +** - Nicolas Cornu +** +** Copyright (C) 2013 Aldebaran Robotics +*/ + +#pragma once +#ifndef _QI_PERF_UTILS_HPP_ +#define _QI_PERF_UTILS_HPP_ + +#include + +namespace qi +{ + namespace measure + { + // Get the number of fd currently open. Works only for linux. + QIPERF_API int getNumFD(); + } +} + +#endif diff --git a/naoModule/libnaoqi_files/include/qipython/api.hpp b/naoModule/libnaoqi_files/include/qipython/api.hpp new file mode 100755 index 0000000..72f1ad8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/api.hpp @@ -0,0 +1,14 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_API_HPP_ +#define _QIPYTHON_API_HPP_ + +#include + +#define QIPYTHON_API QI_LIB_API(qipython) + +#endif // _QIPYTHON_PYEXPORT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/error.hpp b/naoModule/libnaoqi_files/include/qipython/error.hpp new file mode 100755 index 0000000..27e751c --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/error.hpp @@ -0,0 +1,27 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_ERROR_HPP_ +#define _QIPYTHON_ERROR_HPP_ + +#include +#include +#include + +//this allow displaying error raised in the python world +#define PY_CATCH_ERROR(DO) \ + try \ + { \ + DO; \ + } \ + catch (const boost::python::error_already_set &) \ + { \ + qiLogError("python") << PyFormatError(); \ + } + +QIPYTHON_API std::string PyFormatError(); + +#endif // _QIPYTHON_ERROR_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/gil.hpp b/naoModule/libnaoqi_files/include/qipython/gil.hpp new file mode 100755 index 0000000..958e2bb --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/gil.hpp @@ -0,0 +1,76 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_GIL_HPP_ +#define _QIPYTHON_GIL_HPP_ + +#include +#include + +namespace qi { + namespace py { + + //Acquire the GIL if needed + //and setup the thread in the python world if needed + // + //Use that before calling python (even from an unknown thread) + //Can be nested + class GILScopedLock : private boost::noncopyable + { + public: + GILScopedLock() { + qiLogCategory("qi.py.gil"); + qiLogDebug() << "ScopedLockEnter(Begin)"; + _state = PyGILState_Ensure(); + qiLogDebug() << "ScopedLockEnter(End)"; + } + + ~GILScopedLock() { + qiLogCategory("qi.py.gil"); + qiLogDebug() << "ScopedLockQuit(Begin)"; + PyGILState_Release(_state); + qiLogDebug() << "ScopedLockQuit(End)"; + } + + private: + PyGILState_STATE _state; + }; + + //Unlock the GIL, allow python to process other python threads + //Use that while doing C++ computation (sleep, IO, whatever). + // + //This can be called from a thread not previously managed by python. + //Can be nested + class GILScopedUnlock : private boost::noncopyable + { + public: + GILScopedUnlock() + { + qiLogCategory("qi.py.gil"); + qiLogDebug() << "ScopedUnlockEnter(Begin)"; + _save = PyEval_SaveThread(); + qiLogDebug() << "ScopedUnlockEnter(End)"; + } + ~GILScopedUnlock() + { + qiLogCategory("qi.py.gil"); + qiLogDebug() << "ScopedUnlockQuit(Begin)"; + PyEval_RestoreThread(_save); + qiLogDebug() << "ScopedUnlockQuit(End)"; + } + + private: + // It is not allowed to call PyEval_SaveThread if the GIL is not owned, + // so we ensure we have the gil before unlocking, this allows one to nest + // multiple ScopedUnlock + GILScopedLock _l; + PyThreadState* _save; + }; + } +} + + +#endif // _QIPYTHON_GIL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyapplication.hpp b/naoModule/libnaoqi_files/include/qipython/pyapplication.hpp new file mode 100755 index 0000000..72eaf92 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyapplication.hpp @@ -0,0 +1,17 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYAPPLICATION_HPP_ +#define _QIPYTHON_PYAPPLICATION_HPP_ + +namespace qi { + namespace py { + void export_pyapplication(); + void export_pyapplicationsession(); + } +} + +#endif // _QIPYTHON_PYAPPLICATION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyasync.hpp b/naoModule/libnaoqi_files/include/qipython/pyasync.hpp new file mode 100755 index 0000000..9f70177 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyasync.hpp @@ -0,0 +1,16 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYASYNC_HPP_ +#define _QIPYTHON_PYASYNC_HPP_ + +namespace qi { + namespace py { + void export_pyasync(); + } +} + +#endif // _QIPYTHON_PYASYNC_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyexport.hpp b/naoModule/libnaoqi_files/include/qipython/pyexport.hpp new file mode 100755 index 0000000..3993b28 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyexport.hpp @@ -0,0 +1,18 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYEXPORT_HPP_ +#define _QIPYTHON_PYEXPORT_HPP_ + +#include + +namespace qi { + namespace py { + QIPYTHON_API void export_all(); + } +} + +#endif // _QIPYTHON_PYEXPORT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyfuture.hpp b/naoModule/libnaoqi_files/include/qipython/pyfuture.hpp new file mode 100755 index 0000000..a9b2aa0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyfuture.hpp @@ -0,0 +1,99 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYFUTURE_HPP_ +#define _QIPYTHON_PYFUTURE_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace qi { + namespace py { + + class PyPromise; + class PyThreadSafeObject; + + class PyFuture : public qi::Future { + protected: + PyFuture(); + PyFuture(const qi::Future& fut); + friend class PyPromise; + friend void pyFutureCb(const qi::Future& fut, const PyThreadSafeObject& callable); + + public: + boost::python::object value(int msecs = qi::FutureTimeout_Infinite) const; + std::string error(int msecs = qi::FutureTimeout_Infinite) const; + void addCallback(const boost::python::object &callable); + FutureState wait(int msecs) const; + bool hasError(int msecs) const; + bool hasValue(int msecs) const; + }; + + + class PyPromise: public qi::Promise { + public: + PyPromise(); + PyPromise(const qi::Promise &ref); + PyPromise(boost::python::object callable); + void setValue(const boost::python::object &pyval); + PyFuture future(); + }; + + + //convert from Future to PyFuture + template + PyFuture toPyFuture(qi::Future fut) { + PyPromise gprom; + qi::adaptFuture(fut, gprom); + return gprom.future(); + } + + //convert from FutureSync to PyFuture + template + PyFuture toPyFuture(qi::FutureSync fut) { + return toPyFuture(fut.async()); + } + + //async == true => convert to PyFuture + //async == false => convert to PyObject or throw on error + template + boost::python::object toPyFutureAsync(qi::Future fut, bool async) { + if (async) + return boost::python::object(toPyFuture(fut)); + { + GILScopedUnlock _; + fut.wait(); + } + return qi::AnyReference::from(fut.value()).template to(); //throw on error + } + + template <> + inline boost::python::object toPyFutureAsync(qi::Future fut, bool async) { + if (async) + return boost::python::object(toPyFuture(fut)); + { + GILScopedUnlock _; + fut.value(); //wait for the result + } + return boost::python::object(); //throw on error + } + + template + boost::python::object toPyFutureAsync(qi::FutureSync fut, bool async) { + return toPyFutureAsync(fut.async(), async); + } + + void export_pyfuture(); + + } +} + + +#endif // _QIPYTHON_PYFUTURE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyinit.hpp b/naoModule/libnaoqi_files/include/qipython/pyinit.hpp new file mode 100755 index 0000000..8909c39 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyinit.hpp @@ -0,0 +1,24 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYINIT_HPP_ +#define _QIPYTHON_PYINIT_HPP_ + +#include + +namespace qi { + namespace py { + /// Initialise Python and release the lock. This method is *not* + /// threadsafe. Initialising multiple time is safe, but this must not be + /// called if initialisation has already been done somewhere else. + QIPYTHON_API void initialise(); + /// Deinitialise Python. This method is automatically called when + /// qi::Application exits. + QIPYTHON_API void uninitialise(); + } +} + +#endif // _QIPYTHON_PYINIT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pylog.hpp b/naoModule/libnaoqi_files/include/qipython/pylog.hpp new file mode 100755 index 0000000..5eff5d9 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pylog.hpp @@ -0,0 +1,16 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYLOG_HPP_ +# define _QIPYTHON_PYLOG_HPP_ + +namespace qi { + namespace py { + void export_pylog(); + } +} + +#endif // !_QIPYTHON_PYLOG_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyobject.hpp b/naoModule/libnaoqi_files/include/qipython/pyobject.hpp new file mode 100755 index 0000000..d020ce4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyobject.hpp @@ -0,0 +1,23 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYOBJECT_HPP_ +#define _QIPYTHON_PYOBJECT_HPP_ + +#include +#include +#include + +namespace qi { + namespace py { + QIPYTHON_API boost::python::object makePyQiObject(qi::AnyObject obj, const std::string &name = std::string()); + QIPYTHON_API qi::AnyObject makeQiAnyObject(boost::python::object obj); + void export_pyobject(); + } +} + + +#endif // _QIPYTHON_PYOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pyobjectfactory.hpp b/naoModule/libnaoqi_files/include/qipython/pyobjectfactory.hpp new file mode 100755 index 0000000..310330d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyobjectfactory.hpp @@ -0,0 +1,16 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYOBJECTFACTORY_HPP_ +#define _QIPYTHON_PYOBJECTFACTORY_HPP_ + +namespace qi { + namespace py { + void export_pyobjectfactory(); + } +} + +#endif // _QIPYTHON_PYOBJECTFACTORY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pypath.hpp b/naoModule/libnaoqi_files/include/qipython/pypath.hpp new file mode 100755 index 0000000..6d2edff --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pypath.hpp @@ -0,0 +1,19 @@ +#pragma once +/* +** Copyright (C) 2014 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _PYTHON_SRC_PYPATH_HPP_ +# define _PYTHON_SRC_PYPATH_HPP_ + +namespace qi { + namespace py { + + void export_pypath(); + + } +} + + +#endif diff --git a/naoModule/libnaoqi_files/include/qipython/pyproperty.hpp b/naoModule/libnaoqi_files/include/qipython/pyproperty.hpp new file mode 100755 index 0000000..5d694fc --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pyproperty.hpp @@ -0,0 +1,25 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYPROPERTY_HPP_ +#define _QIPYTHON_PYPROPERTY_HPP_ + +#include +#include +#include +#include + +namespace qi { + class PropertyBase; + namespace py { + QIPYTHON_API boost::python::object makePyProperty(const std::string &signature); + QIPYTHON_API qi::PropertyBase *getProperty(boost::python::object obj); + QIPYTHON_API boost::python::object makePyProxyProperty(const qi::AnyObject &obj, const qi::MetaProperty &prop); + void export_pyproperty(); + } +} + +#endif // _QIPYTHON_PYPROPERTY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pysession.hpp b/naoModule/libnaoqi_files/include/qipython/pysession.hpp new file mode 100755 index 0000000..99bd758 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pysession.hpp @@ -0,0 +1,21 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYSESSION_HPP_ +#define _QIPYTHON_PYSESSION_HPP_ + +#include +#include +#include + +namespace qi { + namespace py { + QIPYTHON_API boost::python::object makePySession(const SessionPtr& ses); + void export_pysession(); + } +} + +#endif // _QIPYTHON_PYSESSION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pysignal.hpp b/naoModule/libnaoqi_files/include/qipython/pysignal.hpp new file mode 100755 index 0000000..ea4380c --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pysignal.hpp @@ -0,0 +1,27 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYSIGNAL_HPP_ +#define _QIPYTHON_PYSIGNAL_HPP_ + +#include +#include +#include +#include +#include + +namespace qi { + class SignalBase; + namespace py { + QIPYTHON_API boost::python::object makePySignal(const std::string &signature = "m"); + QIPYTHON_API boost::python::object makePySignalFromBase(boost::shared_ptr sb); + QIPYTHON_API boost::python::object makePyProxySignal(const qi::AnyObject &obj, const qi::MetaSignal &signal); + QIPYTHON_API qi::SignalBase *getSignal(boost::python::object obj); + void export_pysignal(); + } +} + +#endif // _QIPYTHON_PYSIGNAL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pythreadsafeobject.hpp b/naoModule/libnaoqi_files/include/qipython/pythreadsafeobject.hpp new file mode 100755 index 0000000..c4974e4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pythreadsafeobject.hpp @@ -0,0 +1,65 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_PYTHREADSAFEOBJECT_HPP_ +#define _QIPYTHON_PYTHREADSAFEOBJECT_HPP_ + +#include + +namespace qi { + namespace py { + + // This class ensure boost::python::object are copied in a threadsafe + // manner. + // because PyObject inc/dec ref should be done with the GIL held. + class PyThreadSafeObject { + public: + PyThreadSafeObject(const boost::python::object &obj) + { + GILScopedLock _lock; + _obj = new boost::python::object(obj); + } + + PyThreadSafeObject(const PyThreadSafeObject &rhs) + { + GILScopedLock _lock; + _obj = new boost::python::object(*rhs._obj); + } + + ~PyThreadSafeObject() + { + GILScopedLock _lock; + delete _obj; + } + + PyThreadSafeObject& operator=(const PyThreadSafeObject& rhs) + { + GILScopedLock _lock; + *_obj = *rhs._obj; + return *this; + } + + // /!\ Should be called with the GIL locked + boost::python::object &object() + { + return *_obj; + } + + // /!\ Should be called with the GIL locked + const boost::python::object &object() const + { + return *_obj; + } + + private: + boost::python::object* _obj; + }; + + } +} + + +#endif // _QIPYTHON_PYTHREADSAFEOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qipython/pytranslator.hpp b/naoModule/libnaoqi_files/include/qipython/pytranslator.hpp new file mode 100755 index 0000000..53922da --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/pytranslator.hpp @@ -0,0 +1,26 @@ +#pragma once +/* +** Copyright (C) 2014 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _PYTHON_SRC_PYTRANSLATOR_HPP_ +#define _PYTHON_SRC_PYTRANSLATOR_HPP_ + +#include + +namespace qi { + namespace py { + class PyTranslator: public qi::Translator { + public: + PyTranslator(const std::string &name); + + std::string translate1(const std::string &msg); + std::string translate2(const std::string &msg, const std::string &domain); + }; + + void export_pytranslator(); + } +} + +#endif diff --git a/naoModule/libnaoqi_files/include/qipython/trace.hpp b/naoModule/libnaoqi_files/include/qipython/trace.hpp new file mode 100755 index 0000000..c4e2157 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qipython/trace.hpp @@ -0,0 +1,19 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QIPYTHON_TRACE_HPP_ +#define _QIPYTHON_TRACE_HPP_ + +#include +#include + +namespace qi { + namespace py { + QIPYTHON_API std::string thread_traces(); + } +} + +#endif // _QIPYTHON_TRACE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/anyfunction.hpp b/naoModule/libnaoqi_files/include/qitype/anyfunction.hpp new file mode 100755 index 0000000..cc19a96 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/anyfunction.hpp @@ -0,0 +1,234 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_ANYFUNCTION_HPP_ +#define _QITYPE_ANYFUNCTION_HPP_ + +#include +#include +#include + +namespace qi { + class AnyValue; + class AutoAnyReference; + + template + class VarArguments { + public: + VarArguments() {}; + VarArguments(const T& t) { _args.push_back(t); } + VarArguments& operator()(const T& t) { _args.push_back(t); return *this; } + + typedef std::vector VectorType; + + VectorType &args() { return _args; } + const VectorType &args() const { return _args; } + + private: + VectorType _args; + }; + + template <> + class VarArguments { + public: + VarArguments() {}; + VarArguments(const AutoAnyReference& t); + VarArguments& operator()(const AutoAnyReference& t); + + typedef std::vector VectorType; + + VectorType &args() { return _args; } + const VectorType &args() const { return _args; } + + private: + VectorType _args; + }; + + typedef VarArguments<> AnyVarArguments; +} + +#include + + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + inline VarArguments::VarArguments(const AutoAnyReference& t) { + _args.push_back(qi::AnyValue(t)); + } + + inline VarArguments& VarArguments::operator()(const AutoAnyReference& t) { + _args.push_back(qi::AnyValue(t)); + return *this; + } + + + /// Signature information for both callable types FunctionTypeInterface and MethodType + class QITYPE_API CallableTypeInterface + { + public: + CallableTypeInterface(); + TypeInterface* resultType(); + const std::vector& argumentsType(); + qi::Signature parametersSignature() const; + qi::Signature returnSignature() const; + protected: + TypeInterface* _resultType; + // C4251 + std::vector _argumentsType; + }; + + class QITYPE_API FunctionTypeInterface: public TypeInterface, public CallableTypeInterface + { + public: + /** Call the function func with argument args that must be of the correct type. + * @return the return value of type resultType(). This value is allocated and must be destroyed. + */ + virtual void* call(void* storage, void** args, unsigned int argc) = 0; + }; + + template FunctionTypeInterface* makeFunctionTypeInterface(); + + struct ArgumentTransformation + { + public: + // Drop first argument + bool dropFirst; + // Prepend boundValue to argument list + bool prependValue; + + // So if both dropFirst and prependValue are set, first argument is + // replaced with boundValue. + ArgumentTransformation(bool dropFirst = false, bool prependValue=false, void* value = 0) + : dropFirst(dropFirst) + , prependValue(prependValue) + , boundValue(value) + {} + + void* boundValue; + }; + + template + class QITYPE_API KeywordArguments { + public: + KeywordArguments& operator()(const std::string& name, const T& t) { values[name] = t; return *this; } + + std::map values; + }; + + /// A function with AnyArguments as its sole argument will behave as if AnyFunction::fromDynamicFunction was called. + // This is going to be deprecated in profit of VarArgument and AnyVarArgument + class QITYPE_API AnyArguments + { + public: + AnyArguments() {}; + AnyArguments(const AnyValueVector& args) + : _args(args) {} + operator const AnyValueVector&() const { return _args;} + AnyValueVector &args() { return _args; } + const AnyValueVector &args() const { return _args; } + + private: + AnyValueVector _args; + }; + + typedef boost::function DynamicFunction; + + /** Represents a generic callable function. + * This class has value semantic. + * + */ + class QITYPE_API AnyFunction + { + public: + AnyFunction(); + ~AnyFunction(); + AnyFunction(const AnyFunction& b); + AnyFunction(FunctionTypeInterface* type, void* value); + AnyFunction& operator = (const AnyFunction& b); + AnyReference call(const AnyReferenceVector& args); + AnyReference call(AnyReference arg1, const AnyReferenceVector& args); + AnyReference operator()(const AnyReferenceVector& args); + + /// Change signature, drop the first argument passed to call. + const AnyFunction& dropFirstArgument() const; + /// Replace first argument by \p value which must be storage for correct type. + const AnyFunction& replaceFirstArgument(void* value) const; + /// Prepend extra argument \p value to argument list + const AnyFunction& prependArgument(void* value) const; + + /// Return expected argument types, taking transform into account + std::vector argumentsType() const; + TypeInterface* resultType() const; + //dropfirst is useful when you want the parameters signature of a method. + Signature parametersSignature(bool dropFirst=false) const; + Signature returnSignature() const; + + void swap(AnyFunction& b); + + operator bool() const; + FunctionTypeInterface* functionType() const; + + /*** @return an AnyFunction wrapping func. + * func can be: + * - a boost::bind object + * - a boost::function + * - a function pointer + * - a member function pointer + * + */ + template + static AnyFunction from(F func); + /// @return a AnyFunction binding \p instance to member function \p func + template + static AnyFunction from(F func, C instance); + + + /// @return a AnyFunction that takes arguments as a list of unconverted AnyReference. + static AnyFunction fromDynamicFunction(DynamicFunction f); + + private: + FunctionTypeInterface* type; + void* value; //type-dependant storage + mutable ArgumentTransformation transform; + }; + + + /** Store function parameters as a list of AnyReference. + * Storage can be on the stack or allocated + * Memory management is the responsibility of the user. + * If GenericFunctionParameters is obtained throug copy(), convert() or + * fromBuffer(), it must be cleared by destroy() + */ + class QITYPE_API GenericFunctionParameters: public AnyReferenceVector + { + public: + GenericFunctionParameters(); + GenericFunctionParameters(const AnyReferenceVector&); + /// Copy arguments. destroy() must be called on the result + GenericFunctionParameters copy(bool notFirst=false) const; + /// Convert the arguments to given signature. destroy() must be called on the result. + GenericFunctionParameters convert(const Signature& sig) const; + qi::Signature signature(bool dyn) const; + void destroy(bool notFirst = false); + }; + + /// @return the type used by dynamic functions + QITYPE_API FunctionTypeInterface* dynamicFunctionTypeInterface(); +} + +#include +#include + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_ANYFUNCTION_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/anyobject.hpp b/naoModule/libnaoqi_files/include/qitype/anyobject.hpp new file mode 100755 index 0000000..54c0722 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/anyobject.hpp @@ -0,0 +1,392 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_ANYOBJECT_HPP_ +#define _QITYPE_ANYOBJECT_HPP_ + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +# pragma warning( disable: 4231 ) +#endif + +namespace qi { + + //all methods ID lesser than this constant are considered special. + //they are reserved for internal use by qitype/qimessaging. + //(see boundobject.cpp for details) + static const unsigned int qiObjectSpecialMemberMaxUid = 100; + + /* We need shared typeid on Future + * If we do not export, typeids do not compare equals under some gcc-macos + * Furthermore we get: + * - macos: compiler warning and incorrect code if the template implementation is + * used before the extern declaration + * - macos: compiler error if the extern is seen before a non-extern forced + * instantiation + * - linux: linker error: if the symbol is marked hidden in some .o files, + * and not hidden in others, hidden has precedence, and the extern prevents + * the usage of the inlined code version. + * - win32: if the whole template is exported, then no new instanciations + * besides the one in the defining module can be created. + */ + + class SignalSubscriber; + class SignalBase; + + class GenericObject; + + class Empty {}; + + /* ObjectValue + * static version wrapping class C: Type + * dynamic version: Type + * + * All the methods are convenience wrappers that bounce to the ObjectTypeInterface, + * except Event Loop management + * This class has pointer semantic. Do not use directly, use AnyObject, + * obtained through Session, DynamicObjectBuilder or ObjectTypeBuilder. + */ + class QITYPE_API GenericObject + : public Manageable + , public boost::enable_shared_from_this + { + public: + GenericObject(ObjectTypeInterface *type, void *value); + ~GenericObject(); + const MetaObject &metaObject(); + +#ifdef DOXYGEN + // Help doxygen and the header reader a bit. + template + qi::FutureSync call( + const std::string& eventName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); + template + qi::FutureSync call( + qi::MetaCallType callType, + const std::string& eventName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); + + template + qi::Future async( + const std::string& eventName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); +#else + // Declare genCall, using overloads for all argument count instead of default values. + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::FutureSync call( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::FutureSync call( \ + qi::MetaCallType callType, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); + QI_GEN(genCall) + #undef genCall +#endif // DOXYGEN + + qi::Future metaCall(unsigned int method, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSignature = Signature()); + /** Find method named \p named callable with arguments \p parameters + */ + int findMethod(const std::string& name, const GenericFunctionParameters& parameters); + /** Resolve the method Id and bounces to metaCall + * @param signature method name or method signature 'name::(args)' + * if signature is given, an exact match is required + */ + qi::Future metaCall(const std::string &nameWithOptionalSignature, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSignature = Signature()); + + void post(const std::string& eventName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); + + void metaPost(unsigned int event, const GenericFunctionParameters& params); + void metaPost(const std::string &nameWithOptionalSignature, const GenericFunctionParameters &in); + + /** Connect an event to an arbitrary callback. + * + * If you are within a service, it is recommended that you connect the + * event to one of your Slots instead of using this method. + */ + template + qi::FutureSync connect(const std::string& eventName, FUNCTOR_TYPE callback, + MetaCallType threadingModel = MetaCallType_Direct); + + + qi::FutureSync connect(const std::string &name, const SignalSubscriber& functor); + + /// Calls given functor when event is fired. Takes ownership of functor. + qi::FutureSync connect(unsigned int signal, const SignalSubscriber& subscriber); + + /** Connect an event to a method. + * Recommended use is when target is not a proxy. + * If target is a proxy and this is server-side, the event will be + * registered localy and the call will be forwarded. + * If target and this are proxies, the message will be routed through + * the current process. + */ + qi::FutureSync connect(unsigned int signal, AnyObject target, unsigned int slot); + + /// Disconnect an event link. Returns if disconnection was successful. + qi::FutureSync disconnect(SignalLink linkId); + + template + qi::FutureSync property(const std::string& name); + + template + qi::FutureSync setProperty(const std::string& name, const T& val); + + //Low Level Properties + qi::FutureSync property(unsigned int id); + qi::FutureSync setProperty(unsigned int id, const AnyValue &val); + + + //bool isValid() { return type && value;} + ObjectTypeInterface* type; + void* value; + }; + + // C4251 + template + qi::FutureSync GenericObject::connect(const std::string& eventName, + FUNCTION_TYPE callback, + MetaCallType model) + { + return connect(eventName, + SignalSubscriber(AnyFunction::from(callback), model)); + } + + + /** Make a call honoring ThreadingModel requirements + * + * Check the following rules in order: + * - If \p el is set, force call in it overriding all rules. + * - If method type is not auto, honor it, overriding callType + * - If callType is set (not auto), honor it. + * - Be synchronous. + * + * @param callerId: thread id of caller, for tracing purposes + * + * When the call is finally made, if ObjectThreadingModel + * is SingleThread, acquire the object lock. + */ + QITYPE_API qi::Future metaCall(EventLoop* el, + ObjectThreadingModel objectThreadingModel, + MetaCallType methodThreadingModel, + MetaCallType callType, + AnyObject manageable, + unsigned int methodId, + AnyFunction func, const GenericFunctionParameters& params, bool noCloneFirst=false, + unsigned int callerId = 0, + qi::os::timeval postTimestamp = qi::os::timeval()); + + namespace detail + { + // Storage type used by Object, and Proxy. + typedef boost::shared_ptr ManagedObjectPtr; + } + + class QITYPE_API Proxy; + +#ifdef DOXYGEN + /** Perform an asynchronous call on a method. + * @param instance a pointer or shared-pointer to an instance of a class known to type system. + */ + template + qi::Future async(T instancePointerOrSharedPointer, + const std::string& methodName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); +#else +#define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + T* instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); \ + template qi::Future async( \ + boost::shared_ptr instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); \ + template qi::Future async( \ + qi::Object instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)); + QI_GEN(genCall) +#undef genCall +#endif + + /** Register \p Proxy as a proxy class. + * Required for bound methods to accept a ProxyPtr as argument + * Proxy must be constructible with an AnyObject as argument + * @return unused value, present to ease registration at static initialisation + */ + template + bool registerProxy(); + + /** Register \p Proxy as a proxy class for interface \p Interface. + * Required to allow the typesystem to construct an + * Object from an AnyObject. + * Proxy must be constructible with an AnyObject as argument + * @return unused value, present to ease registration at static initialisation + */ + template + bool registerProxyInterface(); + + #define QI_REGISTER_PROXY(Proxy) \ + namespace { \ + static bool BOOST_PP_CAT(_qi_register_proxy_, Proxy) = ::qi::registerProxy(); \ + } + + #define QI_REGISTER_PROXY_INTERFACE(Proxy, Interface) \ + namespace { \ + static bool BOOST_PP_CAT(_qi_register_proxy_, Proxy) = ::qi::registerProxyInterface(); \ + } +} + +#define __QI_REGISTER_ELEMENT(_, name, field) \ + b.advertise(BOOST_PP_STRINGIZE(field), & name::field); // do not remove the space + +/** Register an object to the typesystem + * @param name the class name, without any namespace + * @param ARGS the names of the methods, signals and properties of the class + * + * @warning must be called from an unique compilation unit (not a header), from + * within the namespace of the class + */ +#define QI_REGISTER_OBJECT(name, ...) \ +static bool _qiregister##name() { \ + ::qi::ObjectTypeBuilder b; \ + QI_VAARGS_APPLY(__QI_REGISTER_ELEMENT, name, __VA_ARGS__) \ + b.registerType(); \ + return true; \ +} \ +static bool BOOST_PP_CAT(__qi_registration, __LINE__) = _qiregister##name(); + +#define QI_REGISTER_MT_OBJECT(name, ...) \ +static bool _qiregister##name() { \ + ::qi::ObjectTypeBuilder b; \ + b.setThreadingModel(qi::ObjectThreadingModel_MultiThread); \ + QI_VAARGS_APPLY(__QI_REGISTER_ELEMENT, name, __VA_ARGS__) \ + b.registerType(); \ + return true; \ +} \ +static bool BOOST_PP_CAT(__qi_registration, __LINE__) = _qiregister##name(); + + /** Register object \p name as implementation of \p parent + * FIXME: support inheritance with offset. + * This implementation just bounces to parent's TypeInterfac. + * If that doesn't fit your need, you can always re-register + * everything from the interface on your class. + */ +#define QI_REGISTER_IMPLEMENTATION(parent, name) \ +static bool _qiregister##name() { \ + qi::registerType(typeid(name), qi::typeOf()); \ + name* ptr = (name*)(void*)0x10000; \ + parent* pptr = ptr; \ + int offset = (intptr_t)(void*)pptr - (intptr_t)(void*) ptr; \ + if (offset) \ + qiLogError("qitype.register") << "non-zero offset for implementation " \ + << #name <<" of " << #parent << ", call will fail at runtime"; \ + return true; \ + } \ + static bool BOOST_PP_CAT(__qi_registration, __LINE__) = _qiregister##name(); + + + +/** Register name as a template object type + * Remaining arguments are the methods, signals and properties of the object. + * Use QI_TEMPLATE_TYPE_GET() to access the TemplateTypeInterface from a Type. + */ +#define QI_REGISTER_TEMPLATE_OBJECT(name, ...) \ + namespace qi { \ + template class TypeOfTemplateImpl: public TypeOfTemplateDefaultImpl \ + { \ + public: \ + TypeOfTemplateImpl(): _next(0) {} \ + virtual TypeInterface* next() \ + { \ + if (!_next) \ + { \ + ObjectTypeBuilder > b(false); \ + QI_VAARGS_APPLY(__QI_REGISTER_ELEMENT, name , __VA_ARGS__) \ + _next = b.type(); \ + } \ + return _next; \ + } \ + TypeInterface* _next; \ + }; \ + } \ + QI_TEMPLATE_TYPE_DECLARE(name) + + + +#include + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_ANYOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/anyreference.hpp b/naoModule/libnaoqi_files/include/qitype/anyreference.hpp new file mode 100755 index 0000000..80821eb --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/anyreference.hpp @@ -0,0 +1,22 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_ANYREFERENCE_HPP_ +#define _QITYPE_ANYREFERENCE_HPP_ + +//AnyReference/AnyIterator are declared in their own files to avoid +//include dependencies cycles... +#include +//when using AnyReference you need type. so include it! +#include +#include + +/* Since AnyReference does not handle its memory, it cannot be used +* inside a AnyReference. use AnyValue instead. +*/ +QI_NO_TYPE(qi::AnyReference); + +#endif // _QITYPE_ANYREFERENCE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/anyvalue.hpp b/naoModule/libnaoqi_files/include/qitype/anyvalue.hpp new file mode 100755 index 0000000..5e398cf --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/anyvalue.hpp @@ -0,0 +1,16 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_ANYVALUE_HPP_ +#define _QITYPE_ANYVALUE_HPP_ + +//AnyValue are declared in their own files to avoid +//include dependencies cycles... +#include +//when using AnyReference you need type. so include it! +#include + +#endif // _QITYPE_ANYVALUE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/api.hpp b/naoModule/libnaoqi_files/include/qitype/api.hpp new file mode 100755 index 0000000..760e7a1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/api.hpp @@ -0,0 +1,27 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_API_HPP_ +#define _QITYPE_API_HPP_ + +#include +#include + +#define QITYPE_API QI_LIB_API(qitype) + +/* dynamic_casting template partial specializations + * between shared objects poses problems with + * clang under macos. + * This macro is a workaround that seems to work + * for now. + */ +#ifdef __clang__ +# define QITYPE_TEMPLATE_API QITYPE_API +#else +# define QITYPE_TEMPLATE_API +#endif + +#endif // _QITYPE_API_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/binarycodec.hpp b/naoModule/libnaoqi_files/include/qitype/binarycodec.hpp new file mode 100755 index 0000000..ddc4400 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/binarycodec.hpp @@ -0,0 +1,163 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_BINARYCODEC_HPP_ +#define _QITYPE_BINARYCODEC_HPP_ + +#include + +#include +#include +#include +#include +#include +#include + +namespace qi { + + /// Informations passed when serializing an object + struct ObjectSerializationInfo + { + ObjectSerializationInfo() : transmitMetaObject(true), metaObjectCachedId(notCached) {} + MetaObject metaObject; + bool transmitMetaObject; + qi::uint32_t metaObjectCachedId; + qi::uint32_t serviceId; + qi::uint32_t objectId; + static const qi::uint32_t notCached = 0xFFFFFFFF; + }; + + typedef std::map CapabilityMap; + + /** Store contextual data associated to one point-to-point point transport. + * + * Currently handles: + * - A map of local and remote capabilities. Overload advertiseCapabilities() to + * perform the actual sending of local capabilities to the remote endpoint. + * - A MetaObject cache so that any given MetaObject is sent in full only once + * for each transport stream. + */ + class QITYPE_API StreamContext + { + public: + StreamContext(); + virtual ~StreamContext(); + /// Set or update a local capability, and immediately advertise to the other end + virtual void advertiseCapability(const std::string& key, const AnyValue& value); + /** Set or update and advertise a set of local capabilities. + * Implementer must either update _localCapabilityMap or overload localCapability(). + * + */ + virtual void advertiseCapabilities(const CapabilityMap& map) = 0; + + /// Fetch remote capability (default: from local cache). + virtual boost::optional remoteCapability(const std::string& key); + template T remoteCapability(const std::string& key, const T& defaultValue); + + /// Fetch back what we advertised to the other end (default: local cache) + virtual boost::optional localCapability(const std::string& key); + template T localCapability(const std::string& key, const T& defaultValue); + + /** Return a value based on shared capability. + * If not present on one side, returns void. + * If present on both sides with same type, return the lesser of both values. + * Otherwise, throws. + */ + boost::optional sharedCapability(const std::string& key); + /// Similar to above, but replace error conditions by default value. + template T sharedCapability(const std::string& key, const T& defaultValue); + + /// Return (cacheUid, wasInserted) + std::pair sendCacheSet(const MetaObject& mo); + void receiveCacheSet(unsigned int uid, const MetaObject& mo); + MetaObject receiveCacheGet(unsigned int uid); + /// Default capabilities injected on all transports upon connection + static const CapabilityMap& defaultCapabilities(); + protected: + qi::Atomic _cacheNextId; + // Protects all storage + boost::mutex _contextMutex; + + CapabilityMap _remoteCapabilityMap; // remote capabilities we received + CapabilityMap _localCapabilityMap; // memory of what we advertisedk + + typedef std::map SendMetaObjectCache; + typedef std::map ReceiveMetaObjectCache; + SendMetaObjectCache _sendMetaObjectCache; + ReceiveMetaObjectCache _receiveMetaObjectCache; + }; + + /// Type of callback invoked by sdeerializer when it encounters an object + typedef boost::function DeserializeObjectCallback; + + /// Type of callback invoked by serializer when it encounters an object. + typedef boost::function SerializeObjectCallback; + + template + void decodeBinary(qi::BufferReader *buf, T* value, + DeserializeObjectCallback onObject=DeserializeObjectCallback(), + StreamContext* streamContext = 0 + ); + + /** Encode content of \p gvp into \p buf. + * @param onObject callback invoked each time an object is encountered. + * @throw std::runtime_error when the encoding fail + */ + QITYPE_API void encodeBinary(qi::Buffer *buf, const AutoAnyReference &gvp, SerializeObjectCallback onObject=SerializeObjectCallback(), StreamContext* ctx=0); + + + /** Decode content of \p buf into \p gvp. + * @param buf buffer with serialized data + * @param gvp initialized AnyReference of correct type. Will be filled in. + * @param onObject callback invoked each time an object is encountered. + * + * @throw std::runtime_error when the decoding fail + */ + QITYPE_API void decodeBinary(qi::BufferReader *buf, AnyReference gvp, DeserializeObjectCallback onObject=DeserializeObjectCallback(), StreamContext* ctx = 0); + + template + void decodeBinary(qi::BufferReader *buf, T* value, DeserializeObjectCallback onObject, StreamContext* ctx) { + decodeBinary(buf, AnyReference::fromPtr(value), onObject, ctx); + } + + template T StreamContext::remoteCapability(const std::string& key, const T& defaultValue) + { + boost::optional v = remoteCapability(key); + if (v) + return v->to(); + else + return defaultValue; + } + + template T StreamContext::localCapability(const std::string& key, const T& defaultValue) + { + boost::optional v = localCapability(key); + if (v) + return v->to(); + else + return defaultValue; + } + + + template T StreamContext::sharedCapability(const std::string& key, const T& defaultValue) + { + try + { + T v1 = localCapability(key, defaultValue); + T v2 = remoteCapability(key, defaultValue); + qiLogDebug("qitype.capability") << "Share check compare: " << v1 <<' ' << v2; + return std::min (v1, v2); + } + catch(const std::exception& e) + { + qiLogDebug("qitype.capability") << "Share check exception: " << e.what(); + return defaultValue; + } + } + +} + +#endif // _QITYPE_BINARYCODEC_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/config.hpp b/naoModule/libnaoqi_files/include/qitype/config.hpp new file mode 100755 index 0000000..ab25623 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/config.hpp @@ -0,0 +1,2 @@ + +/* #undef qitype_STATIC_BUILD */ diff --git a/naoModule/libnaoqi_files/include/qitype/details/accessor.hxx b/naoModule/libnaoqi_files/include/qitype/details/accessor.hxx new file mode 100755 index 0000000..1ce2295 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/accessor.hxx @@ -0,0 +1,73 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ACCESSOR_HXX_ +#define _QITYPE_DETAILS_ACCESSOR_HXX_ + +#include +#include + +namespace qi +{ + /** Traits and functions to factor code taking any accessor as argument. + * Supports member function, member object, and free-function + */ + namespace detail + { + template struct Accessor + { + typedef boost::false_type is_accessor; + }; + template struct AccessorBase + { + typedef boost::true_type is_accessor; + typedef typename boost::remove_const::type value_type; + typedef C class_type; + }; + // we must explicitely check for is_member_object_pointer because T C::* + // can match functions also even if it may not make sense + template struct Accessor >::type > + : public AccessorBase + { + typedef T C::* type; + static T& access(C* instance, type acc) + { + return *instance.*acc; + } + }; + template struct Accessor + : public AccessorBase + { + typedef T& (C::*type)(); + static T& access(C* instance, type acc) + { + return (*instance.*acc)(); + } + }; + template struct Accessor + : public AccessorBase + { + typedef T& (C::*type)() const; + static T& access(C* instance, type acc) + { + return (*instance.*acc)(); + } + }; + template struct Accessor + : public AccessorBase + { + typedef T& (*type)(C*); + static T& access(C* instance, type acc) + { + return acc(instance); + } + }; + } +} + +#endif // _QITYPE_DETAILS_ACCESSOR_HXX_ + + diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyfunction.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyfunction.hxx new file mode 100755 index 0000000..bd4fbd7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyfunction.hxx @@ -0,0 +1,95 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYFUNCTION_HXX_ +#define _QITYPE_DETAILS_ANYFUNCTION_HXX_ + +#include +#include + +namespace qi +{ + inline CallableTypeInterface::CallableTypeInterface() + : _resultType(0) + { + } + + inline TypeInterface* CallableTypeInterface::resultType() + { + return _resultType; + } + + inline const std::vector& CallableTypeInterface::argumentsType() + { + return _argumentsType; + } + + inline AnyReference AnyFunction::operator()(const AnyReferenceVector& args) + { + return call(args); + } + + inline AnyFunction::AnyFunction() + : type(0), value(0) + {} + + inline AnyFunction::AnyFunction(const AnyFunction& b) + { + type = b.type; + value = type?type->clone(b.value):0; + transform = b.transform; + } + + inline AnyFunction::AnyFunction(FunctionTypeInterface* type, void* value) + : type(type) + , value(value) + { + } + + inline AnyFunction& AnyFunction::operator=(const AnyFunction& b) + { + this->~AnyFunction(); + type = b.type; + value = type?type->clone(b.value):0; + transform = b.transform; + return *this; + } + + inline AnyFunction::~AnyFunction() + { + if (type) + type->destroy(value); + } + + inline void AnyFunction::swap(AnyFunction& b) + { + std::swap(value, b.value); + std::swap(type, b.type); + std::swap(transform, b.transform); + } + + inline AnyFunction::operator bool() const + { + return type != 0; + } + + inline FunctionTypeInterface* AnyFunction::functionType() const + { + return type; + } + + +} // namespace qi + +namespace std +{ + template<> inline void swap(::qi::AnyFunction& a, ::qi::AnyFunction & b) + { + a.swap(b); + } +} + +#endif // _QITYPE_DETAILS_ANYFUNCTION_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyfunctionfactory.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyfunctionfactory.hxx new file mode 100755 index 0000000..1cc104c --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyfunctionfactory.hxx @@ -0,0 +1,657 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYFUNCTIONFACTORY_HXX_ +#define _QITYPE_DETAILS_ANYFUNCTIONFACTORY_HXX_ + +#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 + +namespace qi +{ + namespace detail + { + /* General idea: code generated to make a function call taking a + * void*, long, or long& is the same. + * So we reduce the function types for which we effectively implement + * call, and bounce the equivalent functions to it. + */ + + /* ASSERTS + * We make some asumptions for this code to work. Failure on any of + * those asumptions will *not* be detected and will cause undefined behavior. + * - typesystem Storage for pointer types is by-value, and by-pointer for everything else + * - compiler-generated code is the same when calling a function: + * - with argument T and EqType::type + * - with return type T and EqType::rType + * - with all pointer types and all reference types for argument/return type + */ + + class Class{}; // dummy class placeholder + + /* For each type, get equivalent type, and if it is a reference + * Equivalent type is a type for which when types are substituted in a + * function call, compiler-generated code is the same. + * *WARNING* some magic occurs for return type, so have a separate rule + * which matches less stuffs for it. + */ + template + struct EqTypeBase + { + typedef T type; + typedef T rType; + typedef typename boost::is_reference::type isReference; + static const int dbgTag = 0; + }; + + template + struct EqTypeBase + { + typedef typename boost::mpl::if_::type, void*, T>::type type; + typedef typename boost::mpl::if_::type, void*, T>::type rType; + typedef typename boost::is_reference::type isReference; + static const int dbgTag = 1; + }; + + template + struct EqType: public EqTypeBase + { + }; + + template <> struct EqType + { + typedef void type; + typedef void* rType; + typedef boost::false_type isReference; + }; + + template<> struct EqType + { + typedef double type; + typedef double rType; + typedef boost::false_type isReference; + }; + + template<> struct EqType + { + typedef float type; + typedef float rType; + typedef boost::false_type isReference; + }; + + template<> struct EqType + { + typedef void* type; + typedef void* rType; + typedef boost::false_type isReference; + }; + + template struct EqType + { + typedef void* type; + typedef void* rType; + typedef boost::true_type isReference; + static const int dbgTag = 2; + }; + + template struct EqType + { + typedef void* type; + typedef void* rType; + typedef boost::true_type isReference; + static const int dbgTag = 3; + }; + + // HACK: mark pointer as references, because typesystem transmit them + // by-value + template + struct EqType + { + typedef void* type; + typedef void* rType; + typedef boost::true_type isReference; + static const int dbgTag = 4; + }; + + // helper to compute a reference mask iterating through a mpl sequence + template + struct RefMasqBuilderHelper + { + typedef typename boost::mpl::deref::type type; + static const unsigned int isRef = EqType::isReference::value; + static const unsigned long vSelf = isRef << p; + static const unsigned long val = vSelf + RefMasqBuilderHelper::type, p+1>::val; + }; + + template + struct RefMasqBuilderHelper::type, p> + { + static const unsigned long val = 0; + }; + + /* Equivalent function info for function type F + * + */ + template struct EqFunctionBare + { + typedef typename boost::function_types::components::type Components; + + typedef typename boost::function_types::parameter_types::type Arguments; + typedef typename boost::function_types::result_type::type Result; + + // need to handle result type separately + typedef typename boost::mpl::transform >::type EqArguments; + typedef typename EqType::rType EqResult; + typedef typename boost::mpl::push_front::type EqComponents; + + // Bit b is set if argument index b+1 (0=return type) is a reference. + static const unsigned long refMask = RefMasqBuilderHelper::type, 0>::val; + typedef typename boost::function_types::function_type::type type; + }; + + template struct EqMemberFunction + { + typedef typename boost::function_types::components::type Components; + // we need to handle object type and return type separately + // arguments with object + typedef typename boost::function_types::parameter_types::type MethodArguments; + // arguments without object + typedef typename boost::mpl::pop_front::type Arguments; + // return type + typedef typename boost::function_types::result_type::type Result; + typedef typename boost::mpl::transform >::type EqArguments; + typedef typename EqType::rType EqResult; + // push equivalent object type + typedef typename boost::mpl::push_front::type EqComponentsInt; + typedef typename boost::mpl::push_front::type EqComponents; + typedef typename boost::function_types::member_function_pointer::type type; + static const unsigned long refMask = RefMasqBuilderHelper::type, 0>::val; + }; + + template + struct EqFunction: + public boost::mpl::if_::type, + EqMemberFunction, + EqFunctionBare >::type + {}; + /* args[i] is a pointer to an element of expected type DROPPING ref + * we will make the call by dereferencing all args, so we must add + * one layer of pointer to effective refs + * + */ + inline void transformRef(void** args, void** out, unsigned int sz, unsigned long refMask) + { + for (unsigned i=0; i::type *)args[n] +#define makeCall(n, argstypedecl, argstype, argsdecl, argsues, comma) \ + template \ + void* makeCall(R(*f)(argstype), void** args) \ + { \ + detail::AnyReferenceCopy val; \ + val(), f( \ + BOOST_PP_REPEAT(n, callArg, _) \ + ); \ + return val.rawValue(); \ + } + QI_GEN(makeCall) +#undef makeCall + +#ifdef _WIN32 +#define STATIC_IF_SAFE +#else +#define STATIC_IF_SAFE static +#endif + + // hacks are disabled for boost::function (refMask forced to 0) + // so use ptrFromStorage. +#define declType(z, n, _) \ + STATIC_IF_SAFE TypeInterface* type_ ## n = typeOf::type>(); +#define callArgBF(z, n, _) \ + BOOST_PP_COMMA_IF(n) *(typename boost::remove_reference

::type *)type_##n -> ptrFromStorage(&args[n]) + +#define makeCall(n, argstypedecl, argstype, argsdecl, argsues, comma) \ + template \ + void* makeCall(boost::function f, void** args) \ + { \ + BOOST_PP_REPEAT(n, declType, _) \ + detail::AnyReferenceCopy val; \ + val(), f( \ + BOOST_PP_REPEAT(n, callArgBF, _) \ + ); \ + return val.rawValue(); \ + } + QI_GEN(makeCall) +#undef makeCall + +#define makeCall(n, argstypedecl, argstype, argsdecl, argsues, comma) \ + template \ + void* makeCall(R(Class::*f)(argstype), void* instance, void** args) \ + { \ + detail::AnyReferenceCopy val; \ + Class* cptr = *(Class**)instance; \ + val(), ((*cptr).*f)( \ + BOOST_PP_REPEAT(n, callArg, _) \ + ); \ + return val.rawValue(); \ + } + QI_GEN(makeCall) +#undef makeCall + +#define makeCall_(n, argstypedecl, argstype, argsdecl, argsues, comma) \ + template \ + void* makeCall(R(Class::*f)(argstype), void** args) \ + { \ + return makeCall(f, args[0], args + 1); \ + } + + QI_GEN(makeCall_) +#undef callArg +#undef makeCall_ + +#ifdef QITYPE_TRACK_FUNCTIONTYPE_INSTANCES + // debug-tool to monitor function type usage + void QITYPE_API functionTypeTrack(const std::string& functionName); + void QITYPE_API functionTypeDump(); +#endif + } + + struct InfosKeyMask: public std::vector + { + public: + InfosKeyMask(const std::vector& b, unsigned long mask) + : std::vector(b), _mask(mask) {} + bool operator < (const InfosKeyMask& b) const + { + if (size() != b.size()) + return size() < b.size(); + for (unsigned i=0; iinfo() != b[i]->info()) + return (*this)[i]->info() < b[i]->info(); + } + return _mask < b._mask; + } + unsigned long _mask; + }; + + /* T is the *reducted* function type + * S is the storage type of the function + * So each instance must know the refMask, and the real return type + * + * categories of S in use: + * boost::function: no reduction performed + * bare function pointer + * member function pointer: T is the linearized signature + */ + template + class FunctionTypeInterfaceEq: public FunctionTypeInterface + { + public: + typedef typename boost::function_types::result_type::type ReturnType; + FunctionTypeInterfaceEq(unsigned long refMask) + : refMask(refMask) + { +#ifdef QITYPE_TRACK_FUNCTIONTYPE_INSTANCES + detail::functionTypeTrack(typeid(S).name()); +#endif + } + virtual void* call(void* storage, void** args, unsigned int argc) + { +#if QI_HAS_VARIABLE_LENGTH_ARRAY + void* out[argc]; +#else + void* outStatic[8]; + void** out; + if (argc <= 8) + out = outStatic; + else + out = new void*[argc]; +#endif + detail::transformRef(args, out, argc, refMask); + void* v = detail::makeCall(*(S*)ptrFromStorage(&storage), (void**)out); + // v is storage for type ReturnType we claimed we were + // adapt return value if needed + if (boost::is_pointer::value + && _resultType->kind() != TypeKind_Pointer) + { + // if refMask&1, real return type is some Foo& and v is Foo* + // else, return type is Foo with sizeof(Foo) == sizeof(void*) and v is a Foo + void* vstorage = _resultType->initializeStorage( + (refMask&1)? v: &v); + vstorage = _resultType->clone(vstorage); + //qiLogWarning("ft") << "Ret deref " << (unsigned long)v <<' ' << vstorage + // << ' ' << *(unsigned long*)vstorage; + v = vstorage; + } +#if ! QI_HAS_VARIABLE_LENGTH_ARRAY + if (argc > 8) + delete[] out; +#endif + return v; + } + unsigned long refMask; + static FunctionTypeInterfaceEq* make(unsigned long refMask, std::vector argsType, + TypeInterface* returnType) + { // we need to hash/compare on all the arguments + std::vector key(argsType); + key.push_back(returnType); + typedef std::map* > FTMap; + static FTMap* ftMap = 0; + static boost::mutex* mutex = 0; + QI_THREADSAFE_NEW(ftMap, mutex); + boost::mutex::scoped_lock lock(*mutex); + FunctionTypeInterfaceEq* & fptr = (*ftMap)[InfosKeyMask(key, refMask)]; + if (!fptr) + { + fptr = new FunctionTypeInterfaceEq(refMask); + fptr->_resultType = returnType; + fptr->_argumentsType = argsType; + } + return fptr; + } + _QI_BOUNCE_TYPE_METHODS(DefaultTypeImplMethods); + }; + + namespace detail + { + + // Trick used to avoid instanciating a T + template struct Ident + { + }; + + struct checkForNonConstRef + { + template void operator()(Ident) + { + qiLogCategory("qitype.functiontypefactory"); + if (boost::is_reference::value && !boost::is_const< + typename boost::remove_reference::type>::value) + qiLogWarning() << "Function argument is a non-const reference: " << typeid(T).name(); + } + }; + template struct remove_constptr + { + typedef T type; + }; + template struct remove_constptr + { + typedef T* type; + }; + // Fill a vector from a T* + struct fill_arguments + { + inline fill_arguments(std::vector* target) + : target(target) {} + + template void operator()(T*) const + { + TypeInterface* result = typeOf< + typename remove_constptr< + typename boost::remove_const< + typename boost::remove_reference::type + >::type>::type>(); + target->push_back(result); + } + std::vector* target; + }; + + // build a function pointer or member function pointer type + template struct FunctionPointerSynthetizer + { + typedef typename boost::function_types::member_function_pointer::type type; + }; + template struct FunctionPointerSynthetizer + { + typedef typename boost::function_types::function_pointer::type type; + }; + // Accept a function pointer or member function pointer + template + AnyFunction makeAnyFunctionBare(F func) + { + typedef typename boost::function_types::parameter_types::type ArgsType; + typedef typename boost::function_types::result_type::type ResType; + TypeInterface* resultType = typeOf(); + std::vector argumentsType; + // Generate and store a TypeInterface* for each argument + boost::mpl::for_each< + boost::mpl::transform_view > > > >(detail::fill_arguments(&argumentsType)); + typedef typename EqFunction::type MapedF; + // regenerate eq function pointer type + typedef typename boost::function_types::components::type EqComponents; + // would have used mpl::if_ but it has laziness issues it seems + typedef typename FunctionPointerSynthetizer::value>::type EqFunPtr; + unsigned long mask = EqFunction::refMask; + FunctionTypeInterface* ftype = FunctionTypeInterfaceEq::make(mask, argumentsType, resultType); + + qiLogDebug("qitype.makeAnyFunction") << "bare mask " << (unsigned long)EqFunction::refMask; + return AnyFunction(ftype, ftype->clone(ftype->initializeStorage(&func))); + } + + template + AnyReference bouncer(const AnyReferenceVector& vargs, + R (C::*fun)(const AnyArguments&) + ) + { + // Pack arguments, call, wrap return value in AnyValue + AnyArguments nargs; + nargs.args().resize(vargs.size()-1); + for (unsigned i=0; i + AnyReference bouncerBF(const AnyReferenceVector& vargs, + boost::function f + ) + { + AnyArguments nargs; + if(!vargs.empty()) + { + nargs.args().resize(vargs.size()); + for (unsigned i=0; i + AnyFunction makeAnyFunctionBare(R (C::*fun)(const AnyArguments&)) + { + AnyFunction res = AnyFunction::fromDynamicFunction(boost::bind(&bouncer, _1, fun)); + // The signature storage in GO will drop first argument, and bug if none is present + const_cast &>(res.functionType()->argumentsType()).push_back(typeOf()); + return res; + } + + template + AnyFunction makeAnyFunctionBare(R (*fun)(const AnyArguments&)) + { + boost::function fu = fun; + AnyFunction res = AnyFunction::fromDynamicFunction(boost::bind(&bouncerBF, _1, fun)); + // The signature storage in GO will drop first argument, and bug if none is present + const_cast &>(res.functionType()->argumentsType()).push_back(typeOf()); + return res; + } + + template AnyFunction makeAnyFunctionBare(boost::function fun) + { + AnyFunction res = AnyFunction::fromDynamicFunction(boost::bind(&bouncerBF, _1, fun)); + // The signature storage in GO will drop first argument, and bug if none is present + const_cast &>(res.functionType()->argumentsType()).push_back(typeOf()); + return res; + } + + template AnyFunction makeAnyFunctionBare(boost::function func) + { + /* Do not try to reduce anything on a boost::function. + * It will bounce to an internal template backend anyway + */ + typedef typename boost::function_types::parameter_types::type ArgsType; + typedef typename boost::function_types::result_type::type ResType; + TypeInterface* resultType = typeOf(); + std::vector argumentsType; + boost::mpl::for_each< + boost::mpl::transform_view > > > >(detail::fill_arguments(&argumentsType)); + FunctionTypeInterface* ftype = FunctionTypeInterfaceEq >::make(0, argumentsType, resultType); + return AnyFunction(ftype, new boost::function(func)); + } + + // Use helper structures for which template partial specialisation is possible + template struct AnyFunctionMaker + { + static AnyFunction make(T func) + { + return makeAnyFunctionBare(func); + } + }; + template struct AnyFunctionMaker + { + static AnyFunction make(T* func) + { + return makeAnyFunctionBare(func); + } + }; + template + struct AnyFunctionMaker > + { + static AnyFunction make(boost::_bi::bind_t v) + { + typedef typename boost::function >::type> CompatType; + CompatType f = v; + return AnyFunction::from(f); + } + }; + template struct AnyFunctionMaker > + { + static AnyFunction make(boost::function func) + { + assert(sizeof(boost::function) == sizeof(boost::function)); + AnyFunction res = detail::makeAnyFunctionBare(func); + return res; + } + }; + template struct AnyFunctionMaker + : public AnyFunctionMaker {}; + template<> struct AnyFunctionMaker + { + static AnyFunction make(AnyFunction func) + { + return func; + } + }; + } + + template + AnyFunction AnyFunction::from(T f) + { + return detail::AnyFunctionMaker::make(f); + } + + namespace detail + { + template struct Pointer + { + static T* pointer(T& t) + { + return &t; + } + }; + template struct Pointer + { + static T* pointer(T* & t) + { + return t; + } + }; + } + + template + AnyFunction AnyFunction::from(F func, C instance) + { + /* Taking a AnyFunction of F will likely imply a typeOf which is + * unnecessary. So use a fake class in signature. + */ + typedef typename boost::function_types::result_type::type Result; + typedef typename boost::function_types::parameter_types >::type Args; + typedef typename boost::mpl::pop_front::type ArgsNoClass; + typedef typename boost::mpl::push_front::type ArgsFakeClass; + typedef typename boost::mpl::push_front::type ComponentsFaked; + typedef typename boost::function_types::member_function_pointer::type MethodTypeFaked; + MethodTypeFaked newFunk = *(MethodTypeFaked*)(void*)&func; + AnyFunction res = AnyFunction::from(newFunk); + + // Dynamic-cast instance to expected pointer type. + typedef typename boost::mpl::at_c::type FirstArg; + // Get expected + FirstArg* ptr = dynamic_cast(detail::Pointer::pointer(instance)); + if (!ptr && instance) + throw std::runtime_error("makeAnyFunction: failed to dynamic_cast bound value to expected type"); + res.prependArgument((void*)(const void*)ptr); + return res; + } + +} +#endif // _QITYPE_DETAILS_ANYFUNCTIONFACTORY_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hpp b/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hpp new file mode 100755 index 0000000..20781c2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hpp @@ -0,0 +1,48 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYITERATOR_HPP_ +#define _QITYPE_DETAILS_ANYITERATOR_HPP_ + +#include +#include + +namespace qi { + + /** AnyValue with Iterator kind, behaving as a STL-compatible iterator + */ + class QITYPE_API AnyIterator: public AnyValue + { + public: + typedef AnyReference value_type; + typedef AnyReference* pointer; + typedef AnyReference& reference; + typedef ptrdiff_t difference_type; + typedef std::forward_iterator_tag iterator_category; + + AnyIterator(); + AnyIterator(const AnyReference& p); + AnyIterator(const AnyValue& v); + + template + AnyIterator(const T& ref); + + /// Iterator pre-increment + AnyIterator& operator++(); + /// Iterator post-increment + AnyIterator operator++(int); + /// Dereference + AnyReference operator*(); + }; + + QITYPE_API bool operator==(const AnyIterator& a, const AnyIterator& b); + QITYPE_API bool operator!=(const AnyIterator& a, const AnyIterator& b); +} + +#include + +#endif // _QITYPE_DETAILS_ANYITERATOR_HPP_ + diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hxx new file mode 100755 index 0000000..1219dd1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyiterator.hxx @@ -0,0 +1,63 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYITERATOR_HXX_ +#define _QITYPE_DETAILS_ANYITERATOR_HXX_ + +#include + +namespace qi { + + inline AnyReference AnyIterator::operator*() + { + if (kind() == TypeKind_Iterator) + return static_cast(_type)->dereference(_value); + else + throw std::runtime_error("Expected iterator"); + } + + template + AnyIterator::AnyIterator(const T& ref) + : AnyValue(AnyReference::from(ref)) + {} + + inline AnyIterator::AnyIterator() + {} + + inline AnyIterator::AnyIterator(const AnyReference& p) + : AnyValue(p) + {} + + inline AnyIterator::AnyIterator(const AnyValue& v) + : AnyValue(v) + {} + + inline AnyIterator& AnyIterator::operator++() + { + if (kind() != TypeKind_Iterator) + throw std::runtime_error("Expected an iterator"); + static_cast(_type)->next(&_value); + return *this; + } + + inline AnyIterator AnyIterator::operator++(int) + { + if (kind() != TypeKind_Iterator) + throw std::runtime_error("Expected an iterator"); + AnyIterator it2 = *this; + static_cast(_type)->next(&_value); + return it2; + } + + inline bool operator!=(const AnyIterator& a, const AnyIterator& b) + { + return !(a==b); + } + +} + + +#endif // _QITYPE_DETAILS_ANYITERATOR_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyobject.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyobject.hxx new file mode 100755 index 0000000..afe47fa --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyobject.hxx @@ -0,0 +1,1065 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_GENERICOBJECT_HXX_ +#define _QITYPE_DETAILS_GENERICOBJECT_HXX_ + +#include + +#include +#include +#include +#include + +// Visual defines interface... +#ifdef interface +#undef interface +#endif + +namespace qi { + + namespace detail { + typedef std::map > ProxyGeneratorMap; + QITYPE_API ProxyGeneratorMap& proxyGeneratorMap(); + + // bounce to a genericobject obtained by (O*)this->asAnyObject() + /* Everything need to be const: + * anyobj.call bounces to anyobj.asObject().call, and the + * second would work on const object + */ + template class GenericObjectBounce + { + public: + const MetaObject &metaObject() const { return go()->metaObject();} + inline qi::Future metaCall(unsigned int method, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSignature=Signature()) const + { + return go()->metaCall(method, params, callType, returnSignature); + } + inline int findMethod(const std::string& name, const GenericFunctionParameters& parameters) const + { + return go()->findMethod(name, parameters); + } + inline qi::Future metaCall(const std::string &nameWithOptionalSignature, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSignature=Signature()) const + { + return go()->metaCall(nameWithOptionalSignature, params, callType, returnSignature); + } + inline void metaPost(unsigned int event, const GenericFunctionParameters& params) const + { + return go()->metaPost(event, params); + } + inline void metaPost(const std::string &nameWithOptionalSignature, const GenericFunctionParameters &in) const + { + return go()->metaPost(nameWithOptionalSignature, in); + } + inline void post(const std::string& eventName, + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()) const + { + return go()->post(eventName, p1, p2, p3, p4, p5, p6, p7, p8); + } + template + inline qi::FutureSync connect(const std::string& eventName, FUNCTOR_TYPE callback, + MetaCallType threadingModel = MetaCallType_Direct) const + { + return go()->connect(eventName, callback, threadingModel); + } + inline qi::FutureSync connect(const std::string &name, const SignalSubscriber& functor) const + { + return go()->connect(name, functor); + } + inline qi::FutureSync connect(unsigned int signal, const SignalSubscriber& subscriber) const + { + return go()->connect(signal, subscriber); + } + // Cannot inline here, AnyObject not fully declared + qi::FutureSync connect(unsigned int signal, AnyObject target, unsigned int slot) const; + inline qi::FutureSync disconnect(SignalLink linkId) const + { + return go()->disconnect(linkId); + } + template + inline qi::FutureSync property(const std::string& name) const + { + return go()->template property(name); + } + template + inline qi::FutureSync setProperty(const std::string& name, const T& val) const + { + return go()->setProperty(name, val); + } + inline qi::FutureSync property(unsigned int id) const + { + return go()->property(id); + } + inline qi::FutureSync setProperty(unsigned int id, const AnyValue &val) const + { + return go()->setProperty(id, val); + } + inline EventLoop* eventLoop() const + { + return go()->eventLoop(); + } + inline bool isStatsEnabled() const + { + return go()->isStatsEnabled(); + } + inline void enableStats(bool enable) const + { + return go()->enableStats(enable); + } + inline ObjectStatistics stats() const + { + return go()->stats(); + } + inline void clearStats() const + { + return go()->clearStats(); + } + inline bool isTraceEnabled() const + { + return go()->isTraceEnabled(); + } + inline void enableTrace(bool enable) + { + return go()->enableTrace(enable); + } + inline void forceEventLoop(qi::EventLoop* el) + { + return go()->forceEventLoop(el); + } + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) const { \ + return go()->template async(methodName comma AUSE); \ + } \ + template qi::FutureSync call( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) const { \ + return go()->template call(methodName comma AUSE); \ + } \ + template qi::FutureSync call( \ + qi::MetaCallType callType, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) const { \ + return go()->template call(callType, methodName comma AUSE);\ + } + QI_GEN(genCall) + #undef genCall + private: + inline GenericObject* go() const + { + GenericObject* g = static_cast(this)->asGenericObject(); + if (!g) + throw std::runtime_error("This object is null"); + return g; + } + }; + } + + template class Object + : public detail::GenericObjectBounce > + { + public: + Object(); + + template Object(const Object& o); + template void operator=(const Object& o); + // Templates above do not replace default ctor or copy operator + Object(const Object& o); + void operator=(const Object& o); + // Disable the ctor taking future if T is Empty, as it would conflict with + // Future cast operator + typedef typename boost::mpl::if_::type, Empty, Object >::type MaybeAnyObject; + Object(const qi::Future& fobj); + Object(const qi::FutureSync& fobj); + + /// @{ + + /** This constructors take ownership of the underlying pointers. + * If a callback is given, it will be called instead of the default + * behavior of deleting the stored GenericObject and the underlying T object. + */ + + Object(GenericObject* go); + Object(T* ptr); + Object(GenericObject* go, boost::function deleter); + Object(T* ptr, boost::function deleter); + /// @} + + /// Shares ref counter with \p other, which much handle the destrutiong of \p go. + template Object(GenericObject* go, boost::shared_ptr other); + template Object(boost::shared_ptr other); + bool operator <(const Object& b) const; + template bool operator !=(const Object& b) const; + template bool operator ==(const Object& b) const; + operator bool() const; + operator Object() const; + + boost::shared_ptr asSharedPtr(); + + T& asT(); + const T& asT() const; + T* operator ->(); + const T* operator->() const; + + T& operator *(); + const T& operator *() const; + bool unique() const; + GenericObject* asGenericObject() const; + void reset(); + unsigned use_count() const { return _obj.use_count();} + + ObjectTypeInterface* interface(); + // Check or obtain T interface, or throw + void checkT(); + // no-op deletor callback + static void keepManagedObjectPtr(detail::ManagedObjectPtr ptr) {} + template + static void keepReference(GenericObject* obj, boost::shared_ptr ptr) {qiLogDebug("qi.object") << "AnyObject ptr holder deleter"; delete obj;} + static void noDeleteT(T*) {qiLogDebug("qi.object") << "AnyObject noop T deleter";} + static void noDelete(GenericObject*) {qiLogDebug("qi.object") << "AnyObject noop deleter";} + // deletor callback that deletes only the GenericObject and not the content + static void deleteGenericObjectOnly(GenericObject* obj) { qiLogDebug("qi.object") << "AnyObject GO deleter"; delete obj;} + template + static void deleteGenericObjectOnlyAndKeep(GenericObject* obj, U) { qiLogDebug("qi.object") << "AnyObject GO-keep deleter";delete obj;} + static void deleteCustomDeleter(GenericObject* obj, boost::function deleter) + { + qiLogDebug("qi.object") << "custom deleter"; + deleter((T*)obj->value); + delete obj; + } + detail::ManagedObjectPtr managedObjectPtr() { return _obj;} + private: + friend class GenericObject; + template friend class Object; + template friend class WeakObject; + Object(detail::ManagedObjectPtr obj) + { + init(obj); + } + void init(detail::ManagedObjectPtr obj); + static void deleteObject(GenericObject* obj) + { + qiLogCategory("qi.object"); + qiLogDebug() << "deleteObject " << obj << " " << obj->value << " " << obj->type->infoString(); + obj->type->destroy(obj->value); + delete obj; + } + /* Do not change this, Object must be binary-equivalent to ManagedObjectPtr. + */ + detail::ManagedObjectPtr _obj; + }; + + template class WeakObject + { + public: + WeakObject() {} + template WeakObject(const Object& o) + : _ptr(o._obj) {} + Object lock() { return Object(_ptr.lock());} + boost::weak_ptr _ptr; + }; + typedef WeakObject AnyWeakObject; + + template inline ObjectTypeInterface* Object::interface() + { + TypeInterface* type = typeOf(); + if (type->kind() != TypeKind_Object) + { + // Try template + TemplateTypeInterface* t = dynamic_cast(type); + if (t) + type = t->next(); + if (type->kind() != TypeKind_Object) + { + std::stringstream err; + err << "Object can only be used on registered object types. (" + << type->infoString() << ")(" << type->kind() << ')'; + throw std::runtime_error(err.str()); + } + } + ObjectTypeInterface* otype = static_cast(type); + return otype; + } + + template inline Object::Object() {} + template templateinline Object::Object(const Object& o) + { + /* An Object created by convert may be in fact an object that does + * not implement the T interface. + * Checking and converting on first access to T& is not enough: + * Object o = obj.call("fetchOne"); // this one might be incorrect + * someVector.push_back(o); // pushes the incorrect one + * o->someIfaceOperation(); // will upgrade o, but not the one in someVector + * + * So we check as early as we can, in all copy pathes, and back-propagate + * the upgrade to the source of the copy + */ + const_cast&>(o).checkT(); + init(o._obj); + } + template templateinline void Object::operator=(const Object& o) + { + const_cast&>(o).checkT(); + init(o._obj); + } + template inline Object::Object(const Object& o) + { + const_cast&>(o).checkT(); + init(o._obj); + } + templateinline void Object::operator=(const Object& o) + { + const_cast&>(o).checkT(); + init(o._obj); + } + template inline Object::Object(GenericObject* go) + { + init(detail::ManagedObjectPtr(go, &deleteObject)); + } + template inline Object::Object(GenericObject* go, boost::function deleter) + { + init(detail::ManagedObjectPtr(go, deleter)); + } + template template Object::Object(GenericObject* go, boost::shared_ptr other) + { + init(detail::ManagedObjectPtr(other, go)); + // Notify the shared_from_this of GenericObject + _obj->_internal_accept_owner(&other, go); + } + namespace detail + { + template ManagedObjectPtr fromSharedPtr(Object& dst, boost::shared_ptr& other, boost::false_type) + { + ObjectTypeInterface* otype = dst.interface(); + T* ptr = static_cast(other.get()); + return ManagedObjectPtr(new GenericObject(otype, ptr), + boost::bind(&Object::template keepReference, _1, other)); + } + template ManagedObjectPtr fromSharedPtr(AnyObject& dst, boost::shared_ptr& other, boost::true_type) + { + return Object(other).managedObjectPtr(); + } + } + + template template Object::Object(boost::shared_ptr other) + { // bounce depending on T==Empty + _obj = detail::fromSharedPtr(*this, other, typename boost::is_same::type()); + } + + template inline Object::Object(T* ptr) + { + ObjectTypeInterface* otype = interface(); + _obj = detail::ManagedObjectPtr(new GenericObject(otype, ptr), &deleteObject); + } + template inline Object::Object(T* ptr, boost::function deleter) + { + ObjectTypeInterface* otype = interface(); + if (deleter) + _obj = detail::ManagedObjectPtr(new GenericObject(otype, ptr), + boost::bind(&Object::deleteCustomDeleter, _1, deleter)); + else + _obj = detail::ManagedObjectPtr(new GenericObject(otype, ptr), &deleteObject); + } + template inline Object::Object(const qi::Future& fobj) + { + init(fobj.value()._obj); + } + template inline Object::Object(const qi::FutureSync& fobj) + { + init(fobj.value()._obj); + } + + template inline boost::shared_ptr Object::asSharedPtr() + { + checkT(); + return boost::shared_ptr(&asT(), boost::bind(&keepManagedObjectPtr, _obj)); + } + + template inline void Object::init(detail::ManagedObjectPtr obj) + { + _obj = obj; + if (!boost::is_same::value && obj) + checkT(); + _obj = obj; + } + + template inline bool Object::operator <(const Object& b) const { return _obj < b._obj;} + template template bool Object::operator !=(const Object& b) const + { + return !(*this ==b); + } + template template bool Object::operator ==(const Object& b) const + { + return asGenericObject() == b.asGenericObject(); + } + template Object::operator bool() const { return _obj && _obj->type;} + + template Object::operator Object() const { return Object(_obj);} + /// Check tha value actually has the T interface + template void Object::checkT() + { + if (boost::is_same::value || !_obj) + return; + if (_obj->type->info() != typeOf()->info() + && _obj->type->inherits(typeOf())==-1) + { // No T interface, try upgrading _obj + detail::ProxyGeneratorMap& map = detail::proxyGeneratorMap(); + detail::ProxyGeneratorMap::iterator it = map.find(typeOf()->info()); + if (it != map.end()) + { + qiLogDebug("qitype.anyobject") << "Upgrading Object to specialized proxy."; + AnyReference ref = it->second(AnyObject(_obj)); + _obj = ref.to(); + ref.destroy(); + return; + } + throw std::runtime_error(std::string() + "Object does not have interface " + typeOf()->infoString()); + } + } + template T& Object::asT() + { + checkT(); + return *reinterpret_cast(_obj->value); + } + template const T& Object::asT() const + { + const_cast* >(this)->checkT(); + return *reinterpret_cast(_obj->value); + } + template T* Object::operator ->() + { + return &asT(); + } + template const T* Object::operator->() const + { + return &asT(); + } + template T& Object::operator *() + { + return asT(); + } + template const T& Object::operator *() const + { + return asT(); + } + template bool Object::unique() const + { + return _obj.unique(); + } + template GenericObject* Object::asGenericObject() const + { + return _obj.get(); + } + template void Object::reset() + { + _obj.reset(); + } + + /** A Proxy is the base class used by bouncer implementations of all + * interfaces. + */ + class QITYPE_API Proxy : public boost::noncopyable + { + public: + Proxy(AnyObject obj) : _obj(obj) {qiLogDebug("qitype.proxy") << "Initializing " << this;} + Proxy() {} + ~Proxy() { qiLogDebug("qitype.proxy") << "Finalizing on " << this;} + Object asObject() const; + protected: + Object _obj; + }; + + + + namespace detail + { + + template void hold(T data) {} + + template void setPromise(qi::Promise& promise, AnyValue& v) + { + try + { + qiLogDebug("qi.adapter") << "converting value"; + T val = v.to(); + qiLogDebug("qi.adapter") << "setting promise"; + promise.setValue(val); + qiLogDebug("qi.adapter") << "done"; + } + catch(const std::exception& e) + { + qiLogError("qi.adapter") << e.what(); + promise.setError(e.what()); + } + } + template<> inline void setPromise(qi::Promise& promise, AnyValue&) + { + promise.setValue(0); + } + template + void futureAdapterGeneric(AnyReference val, qi::Promise promise) + { + qiLogDebug("qi.adapter") << "futureAdapter trigger"; + TemplateTypeInterface* ft1 = QI_TEMPLATE_TYPE_GET(val.type(), Future); + TemplateTypeInterface* ft2 = QI_TEMPLATE_TYPE_GET(val.type(), FutureSync); + TemplateTypeInterface* futureType = ft1 ? ft1 : ft2; + ObjectTypeInterface* onext = dynamic_cast(futureType->next()); + GenericObject gfut(onext, val.rawValue()); + // Need a live shared_ptr for shared_from_this() to work. + boost::shared_ptr ao(&gfut, hold); + if (gfut.call(MetaCallType_Direct, "hasError", 0)) + { + qiLogDebug("qi.adapter") << "futureAdapter: future in error"; + std::string s = gfut.call("error", 0); + qiLogDebug("qi.adapter") << "futureAdapter: got error: " << s; + promise.setError(s); + return; + } + qiLogDebug("qi.adapter") << "futureAdapter: future has value"; + AnyValue v = gfut.call(MetaCallType_Direct, "value", 0); + // For a Future, value() gave us a void* + if (futureType->templateArgument()->kind() == TypeKind_Void) + v = AnyValue(qi::typeOf()); + qiLogDebug("qi.adapter") << v.type()->infoString(); + setPromise(promise, v); + qiLogDebug("qi.adapter") << "Promise set"; + val.destroy(); + } + + // futureAdapter helper that detects and handles value of kind future + // return true if value was a future and was handled + template + inline bool handleFuture(AnyReference val, Promise promise) + { + TemplateTypeInterface* ft1 = QI_TEMPLATE_TYPE_GET(val.type(), Future); + TemplateTypeInterface* ft2 = QI_TEMPLATE_TYPE_GET(val.type(), FutureSync); + TemplateTypeInterface* futureType = ft1 ? ft1 : ft2; + qiLogDebug("qi.object") << "isFuture " << val.type()->infoString() << ' ' << !!ft1 << ' ' << !!ft2; + if (!futureType) + return false; + + TypeInterface* next = futureType->next(); + ObjectTypeInterface* onext = dynamic_cast(next); + GenericObject gfut(onext, val.rawValue()); + // Need a live shared_ptr for shared_from_this() to work. + boost::shared_ptr ao(&gfut, &hold); + boost::function cb = boost::bind(futureAdapterGeneric, val, promise); + // Careful, gfut will die at the end of this block, but it is + // stored in call data. So call must finish before we exit this block, + // and thus must be synchronous. + qi::Future waitResult = gfut.call(MetaCallType_Direct, "_connect", cb); + waitResult.wait(); + qiLogDebug("qi.adapter") << "future connected " << !waitResult.hasError(); + if (waitResult.hasError()) + qiLogWarning("qi.object") << waitResult.error(); + return true; + } + + template + inline void futureAdapter(qi::Future metaFut, qi::Promise promise) + { + qiLogDebug("qi.object") << "futureAdapter " << qi::typeOf()->infoString()<< ' ' << metaFut.hasError(); + //error handling + if (metaFut.hasError()) { + promise.setError(metaFut.error()); + return; + } + + AnyReference val = metaFut.value(); + if (handleFuture(val, promise)) + return; + + static TypeInterface* targetType = typeOf(); + try + { + std::pair conv = val.convert(targetType); + if (!conv.first.type()) + promise.setError(std::string("Unable to convert call result to target type: from ") + + val.signature(true).toPrettySignature() + " to " + targetType->signature().toPrettySignature() ); + else + { + promise.setValue(*conv.first.ptr(false)); + } + if (conv.second) + conv.first.destroy(); + } + catch(const std::exception& e) + { + promise.setError(std::string("Return argument conversion error: ") + e.what()); + } + val.destroy(); + } + + template <> + inline void futureAdapter(qi::Future metaFut, qi::Promise promise) + { + //error handling + if (metaFut.hasError()) { + promise.setError(metaFut.error()); + return; + } + AnyReference val = metaFut.value(); + if (!handleFuture(val, promise)) + promise.setValue(0); + } + + template + inline void futureAdapterVal(qi::Future metaFut, qi::Promise promise) + { + //error handling + if (metaFut.hasError()) { + promise.setError(metaFut.error()); + return; + } + const AnyValue& val = metaFut.value(); + try + { + promise.setValue(val.to()); + } + catch (const std::exception& e) + { + promise.setError(std::string("Return argument conversion error: ") + e.what()); + } + } + + template<> + inline void futureAdapterVal(qi::Future metaFut, qi::Promise promise) + { + if (metaFut.hasError()) + promise.setError(metaFut.error()); + else + promise.setValue(metaFut.value()); + } + } + + + /* Generate qi::FutureSync GenericObject::call(methodname, args...) + * for all argument counts + * The function packs arguments in a vector, computes the + * signature and bounce those to metaCall. + */ + #define pushi(z, n,_) params.push_back(p ## n); + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::FutureSync GenericObject::call( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + if (!value || !type) { \ + return makeFutureError("Invalid GenericObject"); \ + } \ + std::vector params; \ + params.reserve(n); \ + BOOST_PP_REPEAT(n, pushi, _) \ + std::string sigret; \ + qi::Promise res; \ + qi::Future fmeta = metaCall(methodName, params, \ + MetaCallType_Auto, typeOf()->signature()); \ + fmeta.connect(boost::bind(&detail::futureAdapter, _1, res), \ + FutureCallbackType_Sync); \ + return res.future(); \ + } + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future GenericObject::async( \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + if (!value || !type) { \ + return makeFutureError("Invalid GenericObject"); \ + } \ + std::vector params; \ + params.reserve(n); \ + BOOST_PP_REPEAT(n, pushi, _) \ + std::string sigret; \ + qi::Promise res; \ + qi::Future fmeta = metaCall(methodName, params, \ + MetaCallType_Queued, typeOf()->signature()); \ + fmeta.connect(boost::bind(&detail::futureAdapter, _1, res), \ + FutureCallbackType_Sync); \ + return res.future(); \ + } + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::FutureSync GenericObject::call( \ + MetaCallType callType, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + if (!value || !type) { \ + return makeFutureError("Invalid GenericObject"); \ + } \ + std::vector params; \ + params.reserve(n); \ + BOOST_PP_REPEAT(n, pushi, _) \ + std::string sigret; \ + qi::Promise res; \ + qi::Future fmeta = metaCall(methodName, params, callType, \ + typeOf()->signature()); \ + fmeta.connect(boost::bind(&detail::futureAdapter, _1, res), \ + FutureCallbackType_Sync); \ + return res.future(); \ + } + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + T* instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + AnyObject obj = AnyReference::from(instance).toObject(); \ + qi::Future res = obj.template call(MetaCallType_Queued, \ + methodName comma AUSE); \ + res.connect(boost::bind(&detail::hold, obj)); \ + return res; \ + } + QI_GEN(genCall) + #undef genCall + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + boost::shared_ptr instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + AnyObject obj = AnyReference::from(instance).toObject(); \ + qi::Future res = obj.call(MetaCallType_Queued, \ + methodName comma AUSE); \ + res.connect(boost::bind(&detail::hold, obj)); \ + return res; \ + } + QI_GEN(genCall) + #undef genCall + #undef pushi + + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template qi::Future async( \ + Object instance, \ + const std::string& methodName comma \ + QI_GEN_ARGSDECLSAMETYPE(n, qi::AutoAnyReference)) \ + { \ + AnyObject obj = instance; \ + qi::Future res = obj.call(MetaCallType_Queued, \ + methodName comma AUSE); \ + res.connect(boost::bind(&detail::hold, obj)); \ + return res; \ + } + QI_GEN(genCall) + #undef genCall + #undef pushi + + template + qi::FutureSync GenericObject::property(const std::string& name) + { + int pid = metaObject().propertyId(name); + if (pid < 0) + return makeFutureError("Property not found"); + qi::Future f = type->property(value, pid); + qi::Promise p; + f.connect(boost::bind(&detail::futureAdapterVal,_1, p), + FutureCallbackType_Sync); + return p.future(); + } + + template + qi::FutureSync GenericObject::setProperty(const std::string& name, const T& val) + { + int pid = metaObject().propertyId(name); + if (pid < 0) + return makeFutureError("Property not found"); + return type->setProperty(value, pid, AnyValue::from(val)); + } + + /* An AnyObject is actually of a Dynamic type: The underlying TypeInterface* + * is not allways the same. + * Override backend shared_ptr + */ + template<> class QITYPE_API TypeImpl >: public DynamicTypeInterface + { + public: + virtual AnyReference get(void* storage) + { + detail::ManagedObjectPtr* val = (detail::ManagedObjectPtr*)ptrFromStorage(&storage); + AnyReference result; + if (!*val) + { + return AnyReference(); + } + return AnyReference((*val)->type, (*val)->value); + } + + virtual void set(void** storage, AnyReference source) + { + qiLogCategory("qitype.object"); + detail::ManagedObjectPtr* val = (detail::ManagedObjectPtr*)ptrFromStorage(storage); + TemplateTypeInterface* templ = dynamic_cast(source.type()); + if (templ) + source = AnyReference(templ->next(), source.rawValue()); + if (source.type()->info() == info()) + { // source is objectptr + detail::ManagedObjectPtr* src = source.ptr(false); + if (!*src) + qiLogWarning() << "NULL Object"; + *val = *src; + } + else if (source.kind() == TypeKind_Dynamic) + { // try to dereference dynamic type in case it contains an object + set(storage, source.content()); + } + else if (source.kind() == TypeKind_Object) + { // wrap object in objectptr: we do not keep it alive, + // but source type offers no tracking capability + detail::ManagedObjectPtr op(new GenericObject(static_cast(source.type()), source.rawValue())); + *val = op; + } + else if (source.kind() == TypeKind_Pointer) + { + PointerTypeInterface* ptype = static_cast(source.type()); + // FIXME: find a way! + if (ptype->pointerKind() == PointerTypeInterface::Shared) + qiLogInfo() << "Object will *not* track original shared pointer"; + set(storage, *source); + } + else + throw std::runtime_error((std::string)"Cannot assign non-object " + source.type()->infoString() + " to Object"); + + } + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + + /* Pretend that Object is exactly shared_ptr + * Which it is in terms of memory layout. + * But as a consequence, convert will happily create Object for any T + * without checking it. + * Object is handling this through the checkT() method. + */ + template class QITYPE_API TypeImpl >: public TypeImpl > + { + }; + + + namespace detail + { + /* Factory helper functions + */ + + // create a T, wrap in a AnyObject + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + Object constructObject(ADECL) \ + { \ + return Object(new T(AUSE)); \ + } + QI_GEN(genCall) + #undef genCall + } + + + /* A proxy instance can have members: signals and properties, inherited from interface. + * So it need a type of its own, we cannot pretend it's a AnyObject. + */ + class TypeProxy: public ObjectTypeInterface + { + public: + /* We need a per-instance offset from effective type to Proxy. + * Avoid code explosion by putting it per-instance + */ + typedef boost::function ToProxy; + TypeProxy(ToProxy toProxy) + : toProxy(toProxy) + { + } + virtual const MetaObject& metaObject(void* instance) + { + Proxy* ptr = toProxy(instance); + return ptr->asObject().metaObject(); + } + virtual qi::Future metaCall(void* instance, AnyObject context, unsigned int method, const GenericFunctionParameters& params, MetaCallType callType, Signature returnSignature) + { + Proxy* ptr = toProxy(instance); + return ptr->asObject().metaCall(method, params, callType, returnSignature); + } + virtual void metaPost(void* instance, AnyObject context, unsigned int signal, const GenericFunctionParameters& params) + { + Proxy* ptr = toProxy(instance); + ptr->asObject().metaPost(signal, params); + } + virtual qi::Future connect(void* instance, AnyObject context, unsigned int event, const SignalSubscriber& subscriber) + { + Proxy* ptr = toProxy(instance); + return ptr->asObject().connect(event, subscriber); + } + virtual qi::Future disconnect(void* instance, AnyObject context, SignalLink linkId) + { + Proxy* ptr = toProxy(instance); + return ptr->asObject().disconnect(linkId); + } + virtual const std::vector >& parentTypes() + { + static std::vector > empty; + return empty; + } + virtual qi::Future property(void* instance, unsigned int id) + { + Proxy* ptr = toProxy(instance); + GenericObject* obj = ptr->asObject().asGenericObject(); + return obj->type->property(obj->value, id); + } + virtual qi::Future setProperty(void* instance, unsigned int id, AnyValue value) + { + Proxy* ptr = toProxy(instance); + GenericObject* obj = ptr->asObject().asGenericObject(); + return obj->type->setProperty(obj->value, id, value); + } + typedef DefaultTypeImplMethods Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + ToProxy toProxy; + }; + + /* We limit usage of per-class type for generated proxies + *to non-interface mode + * where it is needed. + */ + template struct TypeProxyWrapper: public TypeProxy + { + typedef boost::function ToProxy; + TypeProxyWrapper(ToProxy toProxy) + : TypeProxy(toProxy) + { + } + typedef DefaultTypeImplMethods Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + // Needed for legacy code + //template<> struct TypeImpl: public TypeProxy {}; + + namespace detail + { + // FIXME: inline that in QI_REGISTER_PROXY_INTERFACE maybe + template Proxy* static_proxy_cast(void* storage) + { + return static_cast((ProxyImpl*)storage); + } + + template + TypeProxy* makeProxyInterfaceWrapper() + { + static TypeProxy * result = 0; + if (!result) + result = new TypeProxyWrapper(&static_proxy_cast); + return result; + } + + template + TypeProxy* makeProxyInterface() + { + static TypeProxy * result = 0; + if (!result) + result = new TypeProxy(&static_proxy_cast); + return result; + } + + template + AnyReference makeProxy(AnyObject ptr) + { + boost::shared_ptr sp(new ProxyImpl(ptr)); + return AnyReference::from(sp).clone(); + } + } + + template + bool registerProxyInterface() + { + qiLogVerbose("qitype.type") << "ProxyInterface registration " << typeOf()->infoString(); + // Runtime-register TypeInterface for Proxy, using ProxyInterface with + // proper static_cast (from Proxy template to qi::Proxy) helper. + registerType(typeid(Proxy), detail::makeProxyInterface()); + detail::ProxyGeneratorMap& map = detail::proxyGeneratorMap(); + map[typeOf()->info()] = &detail::makeProxy; + return true; + } + + template + bool registerProxy() + { + /* In non-interface mode, we need one different registered type + * per Proxy class, otherwise they will all land in the same + * bucket of proxyGeneratorMap. + * In interface mode this problem is absent because the TypeInfo + * of the interface is used (not the one of the proxy). + */ + registerType(typeid(ProxyType), detail::makeProxyInterfaceWrapper()); + detail::ProxyGeneratorMap& map = detail::proxyGeneratorMap(); + map[typeOf()->info()] = &detail::makeProxy; + return true; + } + + namespace detail + { + // in dynamicobjectbuilder.hxx + template AnyObject makeObject(const std::string& fname, T func); + + // Create a factory function for an object with one method functionName bouncing to func + template boost::function + makeObjectFactory(const std::string functionName, T func) + { + return boost::bind(&makeObject, functionName, func); + } + + template + inline qi::FutureSync GenericObjectBounce::connect(unsigned int signal, AnyObject target, unsigned int slot) const + { + return go()->connect(signal, target, slot); + } + } + + inline AnyObject Proxy::asObject() const + { + qiLogDebug("qitype.proxy") << "asObject " << this << ' ' << &_obj.asT(); + return AnyObject(_obj); + } +} + + +QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(qi::MinMaxSum, + ("minValue", minValue), + ("maxValue", maxValue), + ("cumulatedValue", cumulatedValue)); + +QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(qi::MethodStatistics, + ("count", count), + ("wall", wall), + ("user", user), + ("system", system)); + +QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(qi::EventTrace, + ("id", id), + ("kind", kind), + ("slotId", slotId), + ("arguments", arguments), + ("timestamp", timestamp), + ("userUsTime", userUsTime), + ("systemUsTime", systemUsTime), + ("callerContext", callerContext), + ("calleeContext", calleeContext)); + +QI_TYPE_STRUCT(qi::os::timeval, tv_sec, tv_usec); + +#endif // _QITYPE_DETAILS_GENERICOBJECT_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyreference.hpp b/naoModule/libnaoqi_files/include/qitype/details/anyreference.hpp new file mode 100755 index 0000000..d53f7b4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyreference.hpp @@ -0,0 +1,375 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYREFERENCE_HPP_ +#define _QITYPE_DETAILS_ANYREFERENCE_HPP_ + +#include +#include +#include +#include +#include +#include + +namespace qi { + + + class AnyReference; + typedef std::vector AnyReferenceVector; + + /** Class that holds any value, with informations to manipulate it. + * operator=() makes a shallow copy. + * + * \warning AnyReference should not be used directly as call arguments. + * Use qi::AnyValue which has value semantics instead. + * + */ + class QITYPE_API AnyReferenceBase + { + protected: + + AnyReferenceBase(); + + ///@{ + /// Low level Internal API + + /** Store type and allocate storage of value. + * @param type use this type for initialization + */ + explicit AnyReferenceBase(TypeInterface* type); + + /** Create a generic value with type and a value who should have + * already been allocated. + * @param type type of this generic value + * @param value an already alloc place to store value + */ + AnyReferenceBase(TypeInterface* type, void* value) + : _type(type) + , _value(value) + {} + + public: + + /// @return the pair (convertedValue, trueIfCopiedAndNeedsDestroy) + std::pair convert(TypeInterface* targetType) const; + std::pair convert(ListTypeInterface* targetType) const; + std::pair convert(StructTypeInterface* targetType) const; + std::pair convert(MapTypeInterface* targetType) const; + std::pair convert(IntTypeInterface* targetType) const; + std::pair convert(FloatTypeInterface* targetType) const; + std::pair convert(RawTypeInterface* targetType) const; + std::pair convert(StringTypeInterface* targetType) const; + std::pair convert(PointerTypeInterface* targetType) const; + std::pair convert(DynamicTypeInterface* targetType) const; + + + + + /** Return the typed pointer behind a AnyReference. T *must* be the type + * of the value. + * @return a pointer to the value as a T or 0 if value is not a T. + * @param check if false, does not validate type before converting + */ + template + T* ptr(bool check = true); + + bool isValid() const; + /// @return true if value is valid and not void + bool isValue() const; + + /// Helper function that converts and always clone + AnyReference convertCopy(TypeInterface* targetType) const; + + // get item with key/ïndex 'key'. Return empty GVP or throw in case of failure + AnyReference _element(const AnyReference& key, bool throwOnFailure); + void _append(const AnyReference& element); + void _insert(const AnyReference& key, const AnyReference& val); + ///@} + + ///@{ + /** Construction and assign. + */ + + /** Construct a AnyValue with storage pointing to ptr. + * @warning the AnyReference will become invalid if ptr + * is destroyed (if it gets deleted or points to the stack and goes + * out of scope). + */ + template + static AnyReference from(const T& ref); + + template + static AnyReference fromPtr(const T* ptr); + + + /** Assignment operator. + * Previous content is lost, and will leak if not deleted outside or + * with destroy(). + */ + //TODO: DROP THAT FUNCTION. that is dangerous + //AnyReferenceBase& operator=(const AutoAnyReference& b); + + AnyReference clone() const; + /// Deletes storage. + void destroy(); + ///@} + + + ///@{ + /** The following methods return a typed copy of the stored value, + * converting if necessary. + * They throw in case of conversion failure. + */ + + /// Convert to anything or throw trying. + template + T to() const; + + /// Similar to previous method, but uses a dummy value to get the target type + template + T to(const T&) const; + + int64_t toInt() const; + uint64_t toUInt() const; + float toFloat() const; + double toDouble() const; + std::string toString() const; + + template + std::vector toList() const; + + template + std::map toMap() const; + + AnyObject toObject() const; + + /** Convert the value to a tuple. + * If value is currently a tuple, it will be returned. + * If value is a list its elements will become the tuple components. + * @param homogeneous if true, all tuple elements will be of the type + * of the list element type. If false, the effective type of elements + * of kind dynamic will be used. + */ + AnyValue toTuple(bool homogeneous) const; + ///@} + + qi::Signature signature(bool resolveDynamic = false) const; + TypeKind kind() const; + + ///@{ + /** Read and update functions + * The following functions access or modify the existing value. + * They never change the storage location or type. + * They will fail by throwing an exception if the requested operation + * is incompatible with the current value type. + * + * @warning a AnyReference refering to a container element will + * become invalid as soon as the container is modified. + * + */ + + /** @return a typed reference to the underlying value + * @warning This method will only succeed if T exactly matches + * the type of the value stored. No conversion will be performed. + * So if you only want a value and not a reference, use to() instead. + */ + template + T& as(); + + int64_t& asInt64() { return as();} + uint64_t& asUInt64() { return as();} + int32_t& asInt32() { return as();} + uint32_t& asUInt32() { return as();} + int16_t& asInt16() { return as();} + uint16_t& asUInt16() { return as();} + int8_t& asInt8() { return as();} + uint8_t& asUInt8() { return as();} + double& asDouble() { return as();} + float& asFloat() { return as();} + std::string& asString() { return as();} + + /// @return a pair of (char*, size) corresponding to the raw buffer. No copy made. + std::pair asRaw() const; + + + /** @return contained AnyValue or throw if type is not dynamic. + * @note Returned AnyReference might be empty. + */ + AnyReference content() const; + + /// @{ + /** Container partial unboxing. + * The following functions unbox the container-part of the value. + * The values in the contairer are exposed as AnyReference. + * The values can be modified using the set and as function families, + * But the container itself is a copy. + * @warning for better performances use the begin() and end() iterator API + */ + AnyReferenceVector asTupleValuePtr(); + AnyReferenceVector asListValuePtr(); + std::map asMapValuePtr(); + /// @} + + + ///TODO: update == set (remove one) + /// Update the value with the one in b + void update(const AutoAnyReference& b); + + /// Update the value to val, which will be converted if required. + template + void set(const T& val); + + void set(int64_t v) { setInt(v);} + void set(int32_t v) { setInt(v);} + void set(uint64_t v) { setUInt(v);} + void set(uint32_t v) { setUInt(v);} + void set(float v) { setFloat(v);} + void set(double v) { setDouble(v);} + void set(const std::string& v) { setString(v);} + + void setInt(int64_t v); + void setUInt(uint64_t v); + void setFloat(float v); + void setDouble(double v); + void setString(const std::string& v); + void setDynamic(const AnyReference &value); + + /// set the value of the raw buffer, a copy will be made. + /// @throw std::runtime_error when kind is not Raw + void setRaw(const char *buffer, size_t size); + + /// set the values of the tuple. A copy will be made. + /// @throw std::runtime_error when kind is not Tuple + void setTuple(const AnyReferenceVector& values); + + ///@{ + /// In-place container manipulation. + + /** Return a reference to container element at index or key idx. + * Use set methods on the result for inplace modification. + * Behavior depends on the container kind: + * - List or tuple: The key must be of integral type. Boundary checks + * are performed. + * - Map: The key must be of a convertible type to the container key type. + * If the key is not found in the container, a new default-valued + * Element will be created, inserted. and returned. + * @warning the returned value is only valid until owning container + * is changed. + */ + template + AnyReference operator[](const K& key); + + /// Call operator[](key).as, element type must match E + template + E& element(const K& key); + + size_t size() const; + + //TODO: use AutoAnyReference + template + void append(const T& element); + + template + void insert(const K& key, const V& val); + + /** Similar to operator[](), but return an empty AnyValue + * If the key is not present. + */ + template + AnyReference find(const K& key); + + /// Return an iterator on the beginning of the container + AnyIterator begin() const; //we lie on const but GV does not honor it yet + /// Return an iterator on the end of the container + AnyIterator end() const; + + /// Dereference pointer, iterator or dynamic + AnyReference operator*() const; + ///@} + + ///@} + + TypeInterface* type() const { return _type; } + /// @return list of tuple elements type, or throw if not a tuple + std::vector membersType() const; + void* rawValue() const { return _value; } + + protected: + TypeInterface* _type; + void* _value; + }; + + class QITYPE_API AnyReference : public AnyReferenceBase { + public: + AnyReference() + : AnyReferenceBase() + {} + + AnyReference(const AnyReferenceBase& rhs) + : AnyReferenceBase(rhs) + {} + + explicit AnyReference(TypeInterface* type) + : AnyReferenceBase(type) + {} + + AnyReference(TypeInterface* type, void* value) + : AnyReferenceBase(type, value) + {} + + private: + //block the dangerous automatic cast from AnyValue to AnyRef + //use AnyValue::asReference() to take a ref on the content of a value. + //use AnyValue::from(value) to take a ref on the value. + AnyReference(const AnyValue& val) { throw std::runtime_error("invalid internal operation."); }; + + }; + + typedef std::vector AnyReferenceVector; + QITYPE_API bool operator< (const AnyReference& a, const AnyReference& b); + QITYPE_API bool operator==(const AnyReference& a, const AnyReference& b); + QITYPE_API bool operator!=(const AnyReference& a, const AnyReference& b); + + + ///@return an allocated Tuple made from copies of \param values + QITYPE_API AnyReference makeGenericTuple(const AnyReferenceVector& values); + + ///@return a Tuple pointing to \param values as its storage + QITYPE_API AnyReference makeGenericTuplePtr(const std::vector&types, + const std::vector&values); + + /** Generates AnyReference from everything transparently. + * To be used as type of meta-function call argument + * + * Example: + * void metaCall(ValueGen arg1, ValueGen arg2); + * can be called with any argument type: + * metaCall("foo", 12); + */ + class QITYPE_API AutoAnyReference: public AnyReference + { + public: + AutoAnyReference (); + AutoAnyReference(const AutoAnyReference & b); + + AutoAnyReference(const AnyReference &self) + : AnyReference(self) + {} + + + AutoAnyReference(const AnyReferenceBase &self) + : AnyReference(self) + {} + + template + AutoAnyReference(const T& ptr); + }; + +} + +#include + +#endif // _QITYPE_DETAILS_ANYREFERENCE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyreference.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyreference.hxx new file mode 100755 index 0000000..d09cfe0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyreference.hxx @@ -0,0 +1,374 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYREFERENCE_HXX_ +#define _QITYPE_DETAILS_ANYREFERENCE_HXX_ + +#include +#include +#include +#include +#include +#include +#include + +namespace qi { + + inline AutoAnyReference::AutoAnyReference() + { + } + + inline AutoAnyReference::AutoAnyReference(const AutoAnyReference& b) + { + _value = b._value; + _type = b._type; + } + + template + AutoAnyReference::AutoAnyReference(const T& ptr) + { + *(AnyReference*)this = AnyReference::from(ptr); + } + +// inline +// AnyReferenceBase& AnyReferenceBase::operator=(const AutoAnyReference& b) +// { +// update(b); +// return *this; +// } + + inline + AnyReference AnyReferenceBase::clone() const + { + AnyReference res; + res._type = _type; + res._value = _type ? res._type->clone(_value) : 0; + return res; + } + + inline qi::Signature AnyReferenceBase::signature(bool resolveDynamic) const + { + if (!_type) + return qi::Signature(); + else + return _type->signature(_value, resolveDynamic); + } + + inline void AnyReferenceBase::destroy() + { + if (_type) + _type->destroy(_value); + _value = _type = 0; + } + + inline AnyReferenceBase::AnyReferenceBase() + : _type(0) + , _value(0) + { + } + + inline AnyReferenceBase::AnyReferenceBase(TypeInterface* type) + : _type(type) + , _value(type->initializeStorage()) + { + } + + template + AnyReference AnyReferenceBase::fromPtr(const T* ptr) + { + static TypeInterface* t = 0; + if (!t) + t = typeOf::type>(); + void *value = t->initializeStorage(const_cast((const void*)ptr)); + return AnyReference(t, value); + } + + template + AnyReference AnyReferenceBase::from(const T& ptr) + { + AnyReference ref; + static TypeInterface* t = 0; + QI_ONCE( t = typeOf::type>()); + return AnyReference(t, t->initializeStorage(const_cast((const void*)&ptr))); + } + + inline TypeKind AnyReferenceBase::kind() const + { + if (!_type) + throw std::runtime_error("Can't take the kind of an invalid value"); + else + return _type->kind(); + } + + + // Kind -> handler Type (IntTypeInterface, ListTypeInterface...) accessor + + class KindNotConvertible; + + template struct TypeOfKind + { + typedef KindNotConvertible type; + }; + +#define TYPE_OF_KIND(k, t) template<> struct TypeOfKind { typedef t type;} + + + TYPE_OF_KIND(TypeKind_Int, IntTypeInterface); + TYPE_OF_KIND(TypeKind_Float, FloatTypeInterface); + TYPE_OF_KIND(TypeKind_String, StringTypeInterface); + +#undef TYPE_OF_KIND + + + // Type -> Kind accessor + + namespace detail + { + struct Nothing {}; + template struct MakeKind + { + static const TypeKind value = k; + }; + + template struct IfElse + { + }; + + template struct IfElse + { + typedef T type; + }; + + template struct IfElse + { + typedef F type; + }; + + } + +#define IF(cond, type) \ + public detail::IfElse, detail::Nothing>::type + + template struct KindOfType + : IF(typename boost::is_integral::type, TypeKind_Int) + , IF(typename boost::is_floating_point::type, TypeKind_Float) + { + }; + +#undef IF + + namespace detail { + + // Optimized AnyReferenceBase::as for direct access to a subType getter + template + inline T valueAs(const AnyReferenceBase& v) + { + if (v.kind() == k) + return static_cast( + static_cast::type* const>(v.type())->get(v.rawValue())); + // Fallback to default which will attempt a full conversion. + return v.to(); + } + } + + template + inline T* AnyReferenceBase::ptr(bool check) + { + if (!_type || (check && typeOf()->info() != _type->info())) + return 0; + else + return (T*)_type->ptrFromStorage(&_value); + } + + template + inline T& AnyReferenceBase::as() + { + T* p = ptr(true); + if (!p) + throw std::runtime_error("Type mismatch"); + return *p; + } + + template + inline T AnyReferenceBase::to(const T&) const + { + return to(); + } + + namespace detail + { + QI_NORETURN QITYPE_API void throwConversionFailure(TypeInterface* from, TypeInterface* to); + } + + template + inline T AnyReferenceBase::to() const + { + TypeInterface* targetType = typeOf(); + std::pair conv = convert(targetType); + if (!conv.first._type) + { + detail::throwConversionFailure(_type, targetType); + } + T result = *conv.first.ptr(false); + if (conv.second) + conv.first.destroy(); + return result; + } + + template<> + inline void AnyReferenceBase::to() const + { + return; + } + + inline bool AnyReferenceBase::isValid() const { + return _type != 0; + } + + inline bool AnyReferenceBase::isValue() const { + return _type != 0 && _type->info() != typeOf()->info(); + } + + inline int64_t AnyReferenceBase::toInt() const + { + return detail::valueAs(*this); + } + + inline uint64_t AnyReferenceBase::toUInt() const + { + return detail::valueAs(*this); + } + + inline float AnyReferenceBase::toFloat() const + { + return detail::valueAs(*this); + } + + inline double AnyReferenceBase::toDouble() const + { + return detail::valueAs(*this); + } + + + inline std::string AnyReferenceBase::toString() const + { + return to(); + } + + template + std::vector + AnyReferenceBase::toList() const + { + return to >(); + } + + template + std::map + AnyReferenceBase::toMap() const + { + return to >(); + } + + + inline AnyReferenceVector + AnyReferenceBase::asListValuePtr() + { + return asTupleValuePtr(); + } + + + namespace detail + { + /** This class can be used to convert the return value of an arbitrary function + * into a AnyReference. It handles functions returning void. + * + * Usage: + * ValueCopy val; + * val(), functionCall(arg); + * + * in val(), parenthesis are useful to avoid compiler warning "val not used" when handling void. + */ + class AnyReferenceCopy: public AnyReference + { + public: + AnyReferenceCopy &operator()() { return *this; } + }; + + template void operator,(AnyReferenceCopy& g, const T& any) + { + *(AnyReference*)&g = AnyReference::from(any).clone(); + } + } + + template + void AnyReferenceBase::set(const T& v) + { + update(AnyReferenceBase::from(v)); + } + + inline void AnyReferenceBase::setFloat(float v) + { + setDouble(static_cast(v)); + } + + template + E& AnyReferenceBase::element(const K& key) + { + return (*this)[key].template as(); + } + + template + AnyReference AnyReferenceBase::operator[](const K& key) + { + return _element(AnyReferenceBase::from(key), true); + } + + template + void AnyReferenceBase::append(const T& element) + { + _append(AnyReference::from(element)); + } + + template + void AnyReferenceBase::insert(const K& key, const V& val) + { + _insert(AnyReference::from(key), AnyReference::from(val)); + } + + template + AnyReference AnyReferenceBase::find(const K& key) + { + return _element(AnyReference::from(key), false); + } + + inline bool operator != (const AnyReference& a, const AnyReference& b) + { + return !(a==b); + } + + /// FutureValueConverter implementation for AnyReference -> T + /// that destroys the value + template + struct FutureValueConverterTakeAnyReference + { + void operator()(const AnyReference& in, T& out) + { + try { + out = in.to(); + } + catch (const std::exception& e) + { + const_cast(in).destroy(); + throw e; + } + const_cast(in).destroy(); + } + }; + +} + +#endif // _QITYPE_DETAILS_ANYREFERENCE_HXX_ + diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hpp b/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hpp new file mode 100755 index 0000000..6c447b8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hpp @@ -0,0 +1,119 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYVALUE_HPP_ +#define _QITYPE_DETAILS_ANYVALUE_HPP_ + +#include +#include +#include + +namespace qi { + + + /** Represent any value supported by the typesystem. + * when constructed or set the value is copied. + * as a pointer to the real value. + * to convert the value if needed and copy to the required type. + */ + class QITYPE_API AnyValue: public AnyReferenceBase + { + public: + + AnyValue(); + AnyValue(const AnyValue& b); + explicit AnyValue(const AnyReference& b, bool copy, bool free); + explicit AnyValue(const AutoAnyReference& b); + explicit AnyValue(qi::TypeInterface *type); + /// Create and return a AnyValue of type T + template static AnyValue make(); + + /// @return the contained value, and reset the AnyValue. + /// @warning you should destroy the returned value or no, depending on how the AnyValue was initialized. + AnyReference release() { + AnyReference ref = AnyReference(_type, _value); + _allocated = false; + _value = 0; + _type = 0; + return ref; + } + + /// @{ + /** The following functions construct a AnyValue from containers of + * AnyReference. + */ + static AnyValue makeTuple(const AnyReferenceVector& values); + static AnyValue makeTupleFromValue(const AutoAnyReference& v0, + const AutoAnyReference& v1, + const AutoAnyReference& v2, + const AutoAnyReference& v3, + const AutoAnyReference& v4, + const AutoAnyReference& v5, + const AutoAnyReference& v6, + const AutoAnyReference& v7, + const AutoAnyReference& v8, + const AutoAnyReference& v9); + + template + static AnyValue makeList(const AnyReferenceVector& values); + static AnyValue makeGenericList(const AnyReferenceVector& values); + template + static AnyValue makeMap(const std::map& values); + static AnyValue makeGenericMap(const std::map& values); + /// @} + + ~AnyValue(); + void operator=(const AnyReference& b); + void operator=(const AnyValue& b); + + void reset(); + void reset(qi::TypeInterface *type); + + template + void set(const T& t) { AnyReferenceBase::set(t); } + + void reset(const AnyReference& src); + void reset(const AnyReference& src, bool copy, bool free); + + void swap(AnyValue& b); + + AnyReference asReference() const { + //AnyRef == AnyRefBase + return *reinterpret_cast(static_cast(this)); + } + + template + static AnyValue from(const T& r) { + //explicit AutoAnyReference to avoid ambiguous call for object implementing cast to AnyValue + return AnyValue(AutoAnyReference(r)); + } + + private: + //hide AnyReference::destroy + //simply assign an empty AnyValue. + void destroy() { return AnyReferenceBase::destroy(); } + + //we dont accept GVP here. (block set with T=GVP) + void set(const AnyReference& t); + bool _allocated; + }; + + /// Less than operator. Will compare the values within the AnyValue. + QITYPE_API bool operator<(const AnyValue& a, const AnyValue& b); + + /// Value equality operator. Will compare the values within. + QITYPE_API bool operator==(const AnyValue& a, const AnyValue& b); + QITYPE_API bool operator!=(const AnyValue& a, const AnyValue& b); + + typedef std::vector AnyValueVector; + + inline AnyReferenceVector asAnyReferenceVector(const AnyValueVector& vect); + +} + +#include + +#endif // _QITYPE_DETAILS_ANYVALUE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hxx b/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hxx new file mode 100755 index 0000000..a79baa2 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/anyvalue.hxx @@ -0,0 +1,247 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_ANYVALUE_HXX_ +#define _QITYPE_DETAILS_ANYVALUE_HXX_ + +#include + +#include +#include +#include +#include + +namespace qi { + + template<> + class TypeImpl: public DynamicTypeInterface + { + public: + virtual AnyReference get(void* storage) + { + AnyValue* ptr = (AnyValue*)ptrFromStorage(&storage); + return ptr->asReference(); + } + + virtual void set(void** storage, AnyReference src) + { + AnyValue* val = (AnyValue*)ptrFromStorage(storage); + val->reset(src, true, true); + } + + // Default cloner will do just right since AnyValue is by-value. + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + + inline AnyValue + AnyValue::makeTuple(const AnyReferenceVector& values) + { + return AnyValue(makeGenericTuple(values), false, true); + } + + inline AnyValue + AnyValue::makeTupleFromValue(const AutoAnyReference& v0, + const AutoAnyReference& v1, + const AutoAnyReference& v2, + const AutoAnyReference& v3, + const AutoAnyReference& v4, + const AutoAnyReference& v5, + const AutoAnyReference& v6, + const AutoAnyReference& v7, + const AutoAnyReference& v8, + const AutoAnyReference& v9) + { + const AnyReference* vect[10] = { &v0, &v1, &v2, &v3, &v4, &v5, &v6, &v7, &v8, &v9 }; + AnyReferenceVector arv; + + for (unsigned int i = 0; i < 10; ++i) { + if (!vect[i]->isValid()) + break; + arv.push_back(*vect[i]); + } + return AnyValue(makeGenericTuple(arv), false, true); + } + + + template + AnyValue AnyValue::makeList(const AnyReferenceVector& values) + { + AnyValue res = make >(); + for (unsigned i=0; i()); + return res; + } + inline + AnyValue AnyValue::makeGenericList(const AnyReferenceVector& values) + { + return makeList(values); + } + template + AnyValue AnyValue::makeMap(const std::map& values) + { + AnyValue res = make >(); + std::map::const_iterator it; + for(it = values.begin(); it != values.end(); ++it) + res.insert(it->first.to(), it->second.to()); + return res; + } + + inline + AnyValue AnyValue::makeGenericMap(const std::map& values) + { + return makeMap(values); + } + + inline AnyValue::AnyValue() + : _allocated(false) + {} + + + inline AnyValue::AnyValue(const AnyValue& b) + : _allocated(false) + { + *this = b; + } + + inline AnyValue::AnyValue(qi::TypeInterface *type) + : AnyReferenceBase(type) + , _allocated(true) + { + } + + inline AnyValue::AnyValue(const AnyReference& b, bool copy, bool free) + : _allocated(false) + { + reset(b, copy, free); + } + + inline AnyValue::AnyValue(const AutoAnyReference& b) + : _allocated(false) + { + reset(b); + } + + template + AnyValue AnyValue::make() + { + return AnyValue(AnyReference(typeOf()), false, true); + } + + inline void AnyValue::operator=(const AnyValue& b) + { + reset(b.asReference(), true, true); + } + + inline void AnyValue::operator=(const AnyReference& b) + { + reset(b, true, true); + } + + inline void AnyValue::reset(const AnyReference& b) + { + reset(b, true, true); + } + + inline void AnyValue::reset(const AnyReference& b, bool copy, bool free) + { + reset(); + *(AnyReferenceBase*)this = b; + _allocated = free; + if (copy) + *(AnyReferenceBase*)this = clone(); + } + + inline void AnyValue::reset() + { + if (_allocated) + AnyReferenceBase::destroy(); + _type = 0; + _value = 0; + } + + inline void AnyValue::reset(qi::TypeInterface *ttype) + { + reset(); + _allocated = true; + _type = ttype; + _value = _type->initializeStorage(); + } + + inline AnyValue::~AnyValue() + { + reset(); + } + + inline void AnyValue::swap(AnyValue& b) + { + std::swap((::qi::AnyReference&)*this, (::qi::AnyReference&)b); + std::swap(_allocated, b._allocated); + } + + + inline bool operator != (const AnyValue& a, const AnyValue& b) + { + return !(a==b); + } + + + + /// FutureValueConverter implementation for AnyReference -> T + /// that destroys the value + template<> + struct FutureValueConverterTakeAnyReference + { + void operator()(const AnyReference& in, AnyValue& out) + { + out.reset(in, false, true); + } + }; + + template + struct FutureValueConverter; + + template + struct FutureValueConverter + { + void operator()(const T& in, qi::AnyValue &out) + { + out = qi::AnyValue::from(in); + } + }; + + template <> + struct FutureValueConverter + { + void operator()(void *in, qi::AnyValue &out) + { + out = qi::AnyValue::make(); + } + }; + + inline AnyReferenceVector asAnyReferenceVector(const AnyValueVector& vect) { + AnyReferenceVector result; + result.resize(vect.size()); + for (unsigned int i = 0; i < vect.size(); ++i) { + result[i] = vect[i].asReference(); + } + return result; + } + +} + +namespace std +{ + inline void swap(::qi::AnyValue& a, ::qi::AnyValue& b) + { + a.swap(b); + } +} + + +#endif // _QITYPE_DETAILS_ANYVALUE_HXX_ + + diff --git a/naoModule/libnaoqi_files/include/qitype/details/bindtype.hxx b/naoModule/libnaoqi_files/include/qitype/details/bindtype.hxx new file mode 100755 index 0000000..2d0791d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/bindtype.hxx @@ -0,0 +1,263 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_BINDTYPE_HXX_ +#define _QITYPE_DETAILS_BINDTYPE_HXX_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace qi +{ + namespace detail + { + // Support stuff for boost_bind_function_type + + class ignore{}; + + // Just store an int and a type + template struct MappingItem {}; + + // IntFromMappingItem: Extract int from MappingItem or something else + + template struct IntFromMappingItem + { + static const long value = 0; + }; + + template + struct IntFromMappingItem > + { + static const long value = I; + }; + + + // ArgResolver: Take a function, an index, and a boost::_bi::list element + // return ignore, or a MappingItem + + template + struct ArgResolver + { + }; + + template + struct ArgResolver > + { + typedef ignore type; + }; + + template + struct ArgResolver > + { + typedef MappingItem::type, + P + >::type + > type; + }; + + + // ArgLess: Index comparison between MappingItems + + template struct ArgLess + { + typedef boost::true_type type; + }; + + template + struct ArgLess > + { + typedef boost::true_type type; + }; + + template + struct ArgLess, A> + { + typedef boost::false_type type; + }; + + template + struct ArgLess, MappingItem > + { + typedef typename boost::mpl::less, boost::mpl::long_ >::type type; + }; + + + // MapItemIndexIs: By-index MappingItem find helper + + template + struct MapItemIndexIs + { + typedef typename boost::false_type type; + }; + + template + struct MapItemIndexIs, boost::mpl::long_ > + { + typedef typename boost::true_type type; + }; + + + // ReorderMapping: Reorder a sequence of MappingItems by their id + + template + struct ReorderMapping + { + typedef typename boost::mpl::push_back< + typename ReorderMapping::type, + typename boost::mpl::deref > + >::type + >::type>::type type; + }; + template + struct ReorderMapping<1, Map> + { + typedef boost::mpl::vector< + typename boost::mpl::deref > + >::type>::type> type; + }; + template + struct ReorderMapping<0, Map> + { + typedef boost::mpl::vector<> type; + }; + + + // MappingToType: get type of MappingItem, or boost::any + + template + struct MappingToType + { + typedef boost::any type; + }; + template + struct MappingToType > + { + typedef T type; + }; + + + // MappingBuilder: Invoke ArgResolver on all elements of a sequence + + template + struct MappingBuilder + { + typedef typename boost::mpl::push_back< + typename MappingBuilder::type, + typename ArgResolver::type>::type + >::type type; + }; + + template + struct MappingBuilder<0, F, V> + { + typedef typename boost::mpl::vector< + typename ArgResolver::type>::type + > type; + }; + + template + struct parameter_types_from_bilist_seq + { + typedef typename MappingBuilder::type::value-1, F, S>::type + type; + }; + + template struct BilistToSeq + { + typedef boost::mpl::vector<> type; + }; + template + struct BilistToSeq > + { + typedef typename boost::mpl::vector type; + }; + template + struct BilistToSeq > + { + typedef typename boost::mpl::vector type; + }; + template + struct BilistToSeq > + { + typedef typename boost::mpl::vector type; + }; + template + struct BilistToSeq > + { + typedef typename boost::mpl::vector type; + }; + template + struct BilistToSeq > + { + typedef typename boost::mpl::vector type; + }; + + template + struct parameter_types + { + typedef typename BilistToSeq::type BLSeq; + typedef typename parameter_types_from_bilist_seq::type Mapping; + // Mapping is a vector of nothing or pair + // Get max value + typedef typename boost::mpl::deref >::type>::type MaxArg; + // Reorder it + typedef typename ReorderMapping::value, Mapping>::type Reordered; + //typedef typename Reorder::type Reordered; + // Replace MappingItem with the type, and void with any + typedef typename boost::mpl::transform >::type type; + }; + } + + template struct boost_bind_result_type {}; + template + struct boost_bind_result_type > + { + typedef R type; + }; + + template struct boost_bind_parameter_types {}; + template + struct boost_bind_parameter_types > + { + typedef typename detail::parameter_types::type type; + }; + + /** Take as argument the result of a boost::bind, and return + * A compatible function type + */ + template struct boost_bind_function_type + { + typedef typename boost::function_types::function_type< + typename boost::mpl::push_front< + typename boost_bind_parameter_types::type, + typename boost_bind_result_type::type + >::type + >::type type; + typedef typename boost::function_types::function_pointer< + typename boost::mpl::push_front< + typename boost_bind_parameter_types::type, + typename boost_bind_result_type::type + >::type + >::type pointer_type; + }; +} + +#endif // _QITYPE_DETAILS_BINDTYPE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/buffertypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/buffertypeinterface.hxx new file mode 100755 index 0000000..f62bb99 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/buffertypeinterface.hxx @@ -0,0 +1,35 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEBUFFER_HXX_ +#define _QITYPE_DETAILS_TYPEBUFFER_HXX_ + +#include + +namespace qi +{ + class TypeBufferImpl: public RawTypeInterface + { + public: + virtual std::pair get(void *storage) + { + Buffer* b = (Buffer*)Methods::ptrFromStorage(&storage); + return std::make_pair(const_cast((const char*)b->data()), b->size()); + } + virtual void set(void** storage, const char* ptr, size_t sz) + { + Buffer* b = (Buffer*)ptrFromStorage(storage); + b->clear(); + b->write(ptr, sz); + } + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + +template<> class TypeImpl: public TypeBufferImpl {}; +} + +#endif // _QITYPE_DETAILS_TYPEBUFFER_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/dynamicobjectbuilder.hxx b/naoModule/libnaoqi_files/include/qitype/details/dynamicobjectbuilder.hxx new file mode 100755 index 0000000..7f9def7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/dynamicobjectbuilder.hxx @@ -0,0 +1,111 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_GENERICOBJECTBUILDER_HXX_ +#define _QITYPE_DETAILS_GENERICOBJECTBUILDER_HXX_ + +#include +#include + +namespace qi { + + template + unsigned int DynamicObjectBuilder::advertiseMethod(const std::string& name, + FUNCTION_TYPE function, + const std::string& desc, + MetaCallType threadingModel) + { + MetaMethodBuilder builder; + AnyFunction f = AnyFunction::from(function).dropFirstArgument(); + builder.setName(name); + builder.setSignature(f); + builder.setDescription(desc); + // throw on error + return xAdvertiseMethod(builder, f, threadingModel); + } + + template + inline unsigned int DynamicObjectBuilder::advertiseMethod(const std::string& name, + OBJECT_TYPE object, + METHOD_TYPE method, + const std::string& desc, + MetaCallType threadingModel) + { + MetaMethodBuilder builder; + AnyFunction f = AnyFunction::from(method, object).dropFirstArgument(); + builder.setName(name); + builder.setSignature(f); + builder.setDescription(desc); + // throw on error + return xAdvertiseMethod(builder, f, threadingModel); + } + + template + inline unsigned int DynamicObjectBuilder::advertiseMethod(MetaMethodBuilder& builder, + FUNCTION_TYPE function, + MetaCallType threadingModel) + { + AnyFunction f = AnyFunction::from(function).dropFirstArgument(); + builder.setSignature(f); + // throw on error + return xAdvertiseMethod(builder, f, threadingModel); + } + + template + inline unsigned int DynamicObjectBuilder::advertiseMethod(MetaMethodBuilder& builder, + OBJECT_TYPE object, + METHOD_TYPE method, + MetaCallType threadingModel) + { + AnyFunction f = AnyFunction::from(method, object).dropFirstArgument(); + builder.setSignature(f); + // throw on error + return xAdvertiseMethod(builder, f, threadingModel); + } + + #define gen(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + QI_GEN_MAYBE_TEMPLATE_OPEN(comma) ATYPEDECL QI_GEN_MAYBE_TEMPLATE_CLOSE(comma) \ + inline unsigned int DynamicObjectBuilder::advertiseSignal(const std::string& s) \ + { \ + return advertiseSignalF(s); \ + } + + QI_GEN_RANGE(gen, 8) + #undef gen + + template unsigned int DynamicObjectBuilder::advertiseSignalF(const std::string& name) + { + return xAdvertiseSignal(name, detail::FunctionSignature::signature()); + } + + template unsigned int DynamicObjectBuilder::advertiseProperty(const std::string& name) + { + // we must end up with name event, get_name and set_name methods + unsigned int isig = advertiseSignal(name); + isig = xAdvertiseProperty(name, typeOf()->signature(), isig); + return isig; + } + + template qi::AnyObject DynamicObjectBuilder::object(boost::shared_ptr other) + { + DynamicObject* dobj = bareObject(); + qi::AnyObject ao = makeDynamicAnyObject(dobj, other); + setManageable(dobj, ao.asGenericObject()); + return ao; + } + + namespace detail + { + // create an object with a single method name fname bouncing to func + template AnyObject makeObject(const std::string& fname, T func) + { + DynamicObjectBuilder gob; + gob.advertiseMethod(fname, func); + return gob.object(); + } + } +} +#endif // _QITYPE_DETAILS_GENERICOBJECTBUILDER_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/dynamictypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/dynamictypeinterface.hxx new file mode 100755 index 0000000..9b6ec34 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/dynamictypeinterface.hxx @@ -0,0 +1,34 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEDYNAMIC_HXX_ +#define _QITYPE_DETAILS_TYPEDYNAMIC_HXX_ + +#include + +namespace qi { + //any + template<> + class TypeImpl: public DynamicTypeInterface + { + public: + AnyReference get(void* storage) + { + qiLogVerbose("qitype.impl") << "get on boost::any not implemented"; + return AnyReference(); + }; + + void set(void** storage, AnyReference source) + { + qiLogVerbose("qitype.impl") << "set on boost::any not implemented"; + } + + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; +} + +#endif // _QITYPE_DETAILS_TYPEDYNAMIC_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/functionsignature.hxx b/naoModule/libnaoqi_files/include/qitype/details/functionsignature.hxx new file mode 100755 index 0000000..2dddf4c --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/functionsignature.hxx @@ -0,0 +1,150 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_FUNCTIONSIGNATURE_HXX_ +#define _QITYPE_DETAILS_FUNCTIONSIGNATURE_HXX_ + +#include +#include + +namespace qi { + namespace detail { + struct signature_function_arg_apply { + signature_function_arg_apply(std::string* val) + : val(*val) + {} + + template void operator()(T *x) { + val += qi::typeOf()->signature().toString(); + } + + std::string &val; + }; + + template + struct RawFunctionSignature + { + static qi::Signature makeSigreturn() + { + typedef typename boost::function_types::result_type::type ResultType; + return typeOf()->signature(); + } + static qi::Signature makeSignature() + { + std::string signature; + signature += '('; + typedef typename boost::function_types::parameter_types::type ArgsType; + boost::mpl::for_each< + boost::mpl::transform_view + > + > + > + >(qi::detail::signature_function_arg_apply(&signature)); + signature += ')'; + return qi::Signature(signature); + } + }; + + template + struct RawFunctionSignature > + { + static qi::Signature makeSigreturn() + { + typedef typename qi::boost_bind_result_type >::type ResultType; + return typeOf()->signature(); + } + + static qi::Signature makeSignature() + { + std::string signature; + signature += '('; + typedef typename qi::boost_bind_parameter_types >::type ArgsType; + boost::mpl::for_each< + boost::mpl::transform_view + > + > + > + >(qi::detail::signature_function_arg_apply(&signature)); + signature += ')'; + return Signature(signature); + } + }; + + template + struct MemberFunctionSignature + { + static qi::Signature makeSigreturn() + { + typedef typename boost::function_types::result_type::type ResultType; + return typeOf()->signature(); + } + static qi::Signature makeSignature() + { + // Reconstruct the boost::bind(instance, _1, _2...) signature + typedef typename boost::function_types::result_type::type RetType; + typedef typename boost::function_types::parameter_types::type MemArgsType; + typedef typename boost::mpl::pop_front< MemArgsType >::type ArgsType; + typedef typename boost::mpl::push_front::type EffectiveType; + typedef typename boost::function_types::function_type::type type; + return RawFunctionSignature::makeSignature(); + } + }; + + template + struct FunctionSignature + { + typedef typename boost::mpl::if_< + typename boost::function_types::is_member_pointer, + MemberFunctionSignature, + RawFunctionSignature + >::type Backend; + static qi::Signature signature() + { + static qi::Signature result = Backend::makeSignature(); + return result; + } + static qi::Signature sigreturn() + { + static qi::Signature result = Backend::makeSigreturn(); + return result; + } + }; + + template + struct FunctionSignature >: public FunctionSignature {}; + + template inline + qi::Signature _functionArgumentsSignature() + { + std::string sigs; + sigs += '('; + typedef typename boost::function_types::parameter_types::type ArgsType; + boost::mpl::for_each< + boost::mpl::transform_view > > > > (qi::detail::signature_function_arg_apply(&sigs)); + sigs += ')'; + return Signature(sigs); + } + template inline + qi::Signature functionArgumentsSignature() + { + static Signature* res; + QI_ONCE(res = new Signature(_functionArgumentsSignature())); + return *res; + } + } +} + + +#endif // _QITYPE_DETAILS_FUNCTIONSIGNATURE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/hasless.hxx b/naoModule/libnaoqi_files/include/qitype/details/hasless.hxx new file mode 100755 index 0000000..f7d4f14 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/hasless.hxx @@ -0,0 +1,102 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_HASLESS_HXX_ +#define _QITYPE_DETAILS_HASLESS_HXX_ + +#include + +namespace qi { + namespace detail { + + template + struct HasLessGuard; + + // boost::has_less gives true for a vector even if has_less gives false + template + struct HasLess + { + static const bool value = boost::has_less::value; + }; + + template + struct HasLess > + { + static const bool value = HasLessGuard::value; + }; + + template + struct HasLess > + { + static const bool value = HasLessGuard::value; + }; + + template + struct HasLess > + { + static const bool value = HasLessGuard::value + && HasLessGuard::value; + }; + + template + struct HasLess > + { + static const bool value = HasLessGuard::value + && HasLessGuard::value; + }; + + //boost::has_less fails for member function pointer, gard + template + struct HasLessSwitch + {}; + + template + struct HasLessSwitch + { + static const bool value = false; + }; + + template struct HasLessSwitch + { + static const bool value = HasLess::value; + }; + + template + struct HasLessGuard + { + static const bool switchVal = + boost::is_member_function_pointer::value + || boost::is_function::value + || boost::is_function::type>::value + || boost::is_member_pointer::value; + static const bool value = HasLessSwitch::value; + + }; + + + template + struct LessHelper + {}; + + template + struct LessHelper + { + bool operator()(T* a, T* b) { return *a<*b;} + }; + + template + struct LessHelper + { + bool operator()(T*a, T*b) { return a + struct Less: public LessHelper::value> + {}; + } +} + +#endif // _QITYPE_DETAILS_HASLESS_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/inttypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/inttypeinterface.hxx new file mode 100755 index 0000000..f4e44ce --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/inttypeinterface.hxx @@ -0,0 +1,106 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEINT_HXX_ +#define _QITYPE_DETAILS_TYPEINT_HXX_ +#include + +#include + +namespace qi { + + template + class IntTypeInterfaceImpl: public IntTypeInterface + { + public: + typedef typename detail::TypeImplMethodsBySize::type ImplType; + + virtual int64_t get(void* value) + { + return *(T*)ImplType::Access::ptrFromStorage(&value); + } + + virtual void set(void** storage, int64_t value) + { + *(T*)ImplType::Access::ptrFromStorage(storage) = (T)value; + } + + virtual unsigned int size() + { + return sizeof(T); + } + + virtual bool isSigned() + { + return boost::is_signed::value; + } + + _QI_BOUNCE_TYPE_METHODS(ImplType); + }; + + template class TypeBoolImpl: public IntTypeInterface + { + public: + typedef typename detail::TypeImplMethodsBySize::type ImplType; + + virtual int64_t get(void* value) + { + return *(T*)ImplType::Access::ptrFromStorage(&value); + } + + virtual void set(void** storage, int64_t value) + { + *(T*)ImplType::Access::ptrFromStorage(storage) = (T)(value != 0); + } + + virtual unsigned int size() + { + return 0; + } + + virtual bool isSigned() + { + return 0; + } + + _QI_BOUNCE_TYPE_METHODS(ImplType); + }; + +} + + +namespace qi { + + + template + class FloatTypeInterfaceImpl: public FloatTypeInterface + { + public: + typedef typename detail::TypeImplMethodsBySize::type ImplType; + + virtual double get(void* value) + { + return *(T*)ImplType::Access::ptrFromStorage(&value); + } + + virtual void set(void** storage, double value) + { + *(T*)ImplType::Access::ptrFromStorage(storage) = (T)value; + } + + virtual unsigned int size() + { + return sizeof(T); + } + + _QI_BOUNCE_TYPE_METHODS(ImplType); + }; + +} + + + +#endif // _QITYPE_DETAILS_TYPEINT_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/listtypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/listtypeinterface.hxx new file mode 100755 index 0000000..4c77500 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/listtypeinterface.hxx @@ -0,0 +1,167 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPELIST_HXX_ +#define _QITYPE_DETAILS_TYPELIST_HXX_ + +#include + +#include +#include +#include + +namespace qi +{ + // List container +template +class ListTypeInterfaceImpl: public H +{ +public: + typedef DefaultTypeImplMethods > MethodsImpl; + ListTypeInterfaceImpl(); + virtual size_t size(void* storage); + virtual TypeInterface* elementType(); + virtual AnyIterator begin(void* storage); + virtual AnyIterator end(void* storage); + virtual void pushBack(void** storage, void* valueStorage); + _QI_BOUNCE_TYPE_METHODS(MethodsImpl); + TypeInterface* _elementType; +}; + +// Type impl for any class that behaves as a forward iterator (++, *, ==) +template +class TypeSimpleIteratorImpl: public IteratorTypeInterface +{ +public: + typedef T Storage; + virtual AnyReference dereference(void* storage) + { + T* ptr = (T*)ptrFromStorage(&storage); + return AnyReference::from(*(*ptr)); + } + virtual void next(void** storage) + { + T* ptr = (T*)ptrFromStorage(storage); + ++(*ptr); + } + virtual bool equals(void* s1, void* s2) + { + T* p1 = (T*)ptrFromStorage(&s1); + T* p2 = (T*)ptrFromStorage(&s2); + return *p1 == *p2; + } + typedef DefaultTypeImplMethods > TypeImpl; + _QI_BOUNCE_TYPE_METHODS(TypeImpl); + static AnyIterator make(const T& val) + { + static TypeSimpleIteratorImpl* type = 0; + QI_THREADSAFE_NEW(type); + return AnyValue(AnyReference(type, type->initializeStorage(const_cast((const void*)&val)))); + } +}; + + +template +ListTypeInterfaceImpl::ListTypeInterfaceImpl() +{ + _elementType = typeOf(); +} + +template TypeInterface* +ListTypeInterfaceImpl::elementType() +{ + return _elementType; +} + +template +AnyIterator ListTypeInterfaceImpl::begin(void* storage) +{ + T* ptr = (T*)ptrFromStorage(&storage); + return TypeSimpleIteratorImpl::make(ptr->begin()); +} + +template +AnyIterator ListTypeInterfaceImpl::end(void* storage) +{ + T* ptr = (T*)ptrFromStorage(&storage); + return TypeSimpleIteratorImpl::make(ptr->end()); +} +namespace detail +{ + template + void pushBack(T& container, E* element) + { + container.push_back(*element); + } + template + void pushBack(std::set& container, E* element) + { + container.insert(*element); + } +} +template +void ListTypeInterfaceImpl::pushBack(void **storage, void* valueStorage) +{ + T* ptr = (T*) ptrFromStorage(storage); + detail::pushBack(*ptr, (typename T::value_type*)_elementType->ptrFromStorage(&valueStorage)); +} + +template +size_t ListTypeInterfaceImpl::size(void* storage) +{ + T* ptr = (T*) ptrFromStorage(&storage); + return ptr->size(); +} + +// There is no way to register a template container type :( +template struct TypeImpl >: public ListTypeInterfaceImpl > {}; +template struct TypeImpl >: public ListTypeInterfaceImpl > {}; +template struct TypeImpl >: public ListTypeInterfaceImpl > {}; + + +// varargs container +template +class VarArgsTypeInterfaceImpl: public ListTypeInterfaceImpl +{ +public: + typedef ListTypeInterfaceImpl BaseClass; + + typedef DefaultTypeImplMethods > MethodsImpl; + VarArgsTypeInterfaceImpl() {} + + _QI_BOUNCE_TYPE_METHODS(MethodsImpl); + + void* adaptStorage(void** storage) { + T* ptr = (T*) ptrFromStorage(storage); + //return ptr + typename T::VectorType& v = ptr->args(); + return &v; + } + + virtual size_t size(void* storage) { + return BaseClass::size(adaptStorage(&storage)); + } + virtual AnyIterator begin(void* storage) { + return BaseClass::begin(adaptStorage(&storage)); + } + virtual AnyIterator end(void* storage) { + return BaseClass::end(adaptStorage(&storage)); + } + virtual void pushBack(void** storage, void* valueStorage) { + void* vstor = adaptStorage(storage); + BaseClass::pushBack(&vstor, valueStorage); + } + + //ListTypeInterface* _list; +}; + + +template struct TypeImpl >: public VarArgsTypeInterfaceImpl > {}; + + +} + +#endif // _QITYPE_DETAILS_TYPELIST_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/maptypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/maptypeinterface.hxx new file mode 100755 index 0000000..c7c90ae --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/maptypeinterface.hxx @@ -0,0 +1,115 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEMAP_HXX_ +#define _QITYPE_DETAILS_TYPEMAP_HXX_ + +namespace qi +{ + // List container +template class MapTypeInterfaceImpl: +public MapTypeInterface +{ +public: + typedef DefaultTypeImplMethods + > MethodsImpl; + MapTypeInterfaceImpl(); + virtual TypeInterface* elementType(); + virtual TypeInterface* keyType(); + virtual size_t size(void* storage); + virtual AnyIterator begin(void* storage); + virtual AnyIterator end(void* storage); + virtual void insert(void** storage, void* keyStorage, void* valueStorage); + virtual AnyReference element(void** storage, void* keyStorage, bool autoInsert); + _QI_BOUNCE_TYPE_METHODS(MethodsImpl); + TypeInterface* _keyType; + TypeInterface* _elementType; +}; + +} + +namespace qi { +template +MapTypeInterfaceImpl::MapTypeInterfaceImpl() +{ + this->_keyType = typeOf(); + this->_elementType = typeOf(); +} + + +template TypeInterface* +MapTypeInterfaceImpl::elementType() +{ + return _elementType; +} + +template TypeInterface* +MapTypeInterfaceImpl::keyType() +{ + return _keyType; +} + +template size_t +MapTypeInterfaceImpl::size(void* storage) +{ + M* ptr = (M*)ptrFromStorage(&storage); + return ptr->size(); +} + + +template AnyIterator +MapTypeInterfaceImpl::begin(void* storage) +{ + M* ptr = (M*)ptrFromStorage(&storage); + return TypeSimpleIteratorImpl::make(ptr->begin()); +} + +template AnyIterator +MapTypeInterfaceImpl::end(void* storage) +{ + M* ptr = (M*)ptrFromStorage(&storage); + return TypeSimpleIteratorImpl::make(ptr->end()); +} + +template void +MapTypeInterfaceImpl::insert(void** storage, void* keyStorage, void* valueStorage) +{ + M* ptr = (M*) ptrFromStorage(storage); + typename M::key_type& key = *(typename M::key_type*)_keyType->ptrFromStorage(&keyStorage); + typename M::mapped_type& val = *(typename M::mapped_type*)_elementType->ptrFromStorage(&valueStorage); + typename M::iterator it = ptr->find(key); + if (it == ptr->end()) + ptr->insert(std::make_pair(key, val)); + else + it->second = val; +} + +template AnyReference +MapTypeInterfaceImpl::element(void** storage, void* keyStorage, bool autoInsert) +{ + //static TypeInterface* elemType = typeOf(); + M* ptr = (M*) ptrFromStorage(storage); + typename M::key_type* key = (typename M::key_type*)_keyType->ptrFromStorage(&keyStorage); + typename M::iterator it = ptr->find(*key); + if (it == ptr->end()) + { + if (!autoInsert) + return AnyReference(); + typename M::mapped_type& e = (*ptr)[*key]; + return AnyReference::from(e); + } + else + return AnyReference::from(((typename M::mapped_type&)(it->second))); +} + + + +template +struct TypeImpl >: public MapTypeInterfaceImpl > {}; + +} +#endif // _QITYPE_DETAILS_TYPEMAP_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/objecttypebuilder.hxx b/naoModule/libnaoqi_files/include/qitype/details/objecttypebuilder.hxx new file mode 100755 index 0000000..24eadab --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/objecttypebuilder.hxx @@ -0,0 +1,262 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_OBJECTTYPEBUILDER_HXX_ +#define _QITYPE_DETAILS_OBJECTTYPEBUILDER_HXX_ + +#include +#include +#include +#include + +namespace qi { + + + template void ObjectTypeBuilderBase::buildFor(bool autoRegister) + { + // We are erasing T here: we must pass everything the builder need to know about t: + // - typeid + // - cloner/deleter + // - serializer, ... + // => wee need all TypeInterface* methods, but we do not want another TypeInterface* + // to anwser to typeOf + xBuildFor(new DefaultTypeImpl(), autoRegister); + } + + template + unsigned int ObjectTypeBuilderBase::advertiseMethod(const std::string& name, + FUNCTION_TYPE function, + MetaCallType threadingModel, + int id) + { + MetaMethodBuilder builder; + AnyFunction f = AnyFunction::from(function); + if (! boost::is_member_function_pointer::value) + f.dropFirstArgument(); + builder.setName(name); + builder.setSignature(f); + + // throw on error + return xAdvertiseMethod(builder, f, threadingModel, id); + } + + template + unsigned int ObjectTypeBuilderBase::advertiseMethod(MetaMethodBuilder& builder, + FUNCTION_TYPE function, + MetaCallType threadingModel, + int id) + { + AnyFunction f = AnyFunction::from(function); + if (! boost::is_member_function_pointer::value) + f.dropFirstArgument(); + builder.setSignature(f); + + // throw on error + return xAdvertiseMethod(builder, f, threadingModel, id); + } + + template + void ObjectTypeBuilderBase::inherits(int offset) + { + return inherits(typeOf< + typename boost::remove_reference::type>(), offset); + } + + template + template + void ObjectTypeBuilder::inherits() + { + qiLogCategory("qitype.objectbuilder"); + // Compute the offset between T and U + T* ptr = (T*)(void*)0x10000; + U* pptr = ptr; + int offset = (intptr_t)(void*)pptr - (intptr_t)(void*) ptr; + qiLogDebug() << "Offset check T(" << typeid(ptr).name() << ")= " << pptr << ", U(" << typeid(ptr).name() << ")= " << ptr << ", T-U= " << offset; + return ObjectTypeBuilderBase::inherits(offset); + } + + namespace detail + { + template void checkRegisterParent( + ObjectTypeBuilder& , boost::false_type) {} + template void checkRegisterParent( + ObjectTypeBuilder& builder, boost::true_type) + { + typedef typename boost::function_types::parameter_types::type ArgsType; + typedef typename boost::mpl::front::type DecoratedClassType; + typedef typename boost::remove_reference::type ClassType; + builder.template inherits(); + } + }; + + template + template + unsigned int ObjectTypeBuilder::advertiseMethod(const std::string& name, FUNCTION_TYPE function, MetaCallType threadingModel, int id) + { + // Intercept advertise to auto-register parent type if this is a parent method + // Note: if FUNCTION_TYPE is a grandparent method, we will incorrectly add it + // as a child + detail::checkRegisterParent( + *this, + typename boost::function_types::is_member_function_pointer::type()); + + // throw on error + return ObjectTypeBuilderBase::advertiseMethod(name, function, threadingModel, id); + } + + template + template + unsigned int ObjectTypeBuilder::advertiseMethod(MetaMethodBuilder& name, FUNCTION_TYPE function, MetaCallType threadingModel, int id) + { + // Intercept advertise to auto-register parent type if this is a parent method + // Note: if FUNCTION_TYPE is a grandparent method, we will incorrectly add it + // as a child + detail::checkRegisterParent( + *this, + typename boost::function_types::is_member_function_pointer::type()); + + // throw on error + return ObjectTypeBuilderBase::advertiseMethod(name, function, threadingModel, id); + } + + template + AnyObject ObjectTypeBuilder::object(T* ptr, boost::function onDestroy) + { + return ObjectTypeBuilderBase::object(static_cast(ptr), onDestroy); + } + + + template + void ObjectTypeBuilder::registerType() + { + ::qi::registerType(typeid(T), type()); + } + + template + typename boost::enable_if::is_accessor, SignalBase*>::type + signalAccess(A acc, void* instance) + { + typedef typename detail::Accessor::class_type class_type; + return &detail::Accessor::access((class_type*)instance, acc); + } + + template + typename boost::enable_if::is_accessor, PropertyBase*>::type + propertyAccess(A acc, void* instance) + { + typedef typename detail::Accessor::class_type class_type; + return &detail::Accessor::access((class_type*)instance, acc); + } + + template + unsigned int + ObjectTypeBuilderBase::advertiseSignal(const std::string& eventName, A accessor, int id) + { + SignalMemberGetter fun = boost::bind(&signalAccess, accessor, _1); + typedef typename detail::Accessor::value_type::FunctionType FunctionType; + return xAdvertiseSignal(eventName, + detail::FunctionSignature::signature(), fun, id); + } + + template + unsigned int ObjectTypeBuilderBase::advertiseProperty(const std::string& name, A accessor) + { + unsigned int id = advertiseSignal(name, accessor); + PropertyMemberGetter pg = boost::bind(&propertyAccess, accessor, _1); + typedef typename detail::Accessor::value_type::PropertyType PropertyType; + return xAdvertiseProperty(name, typeOf()->signature(), pg, id); + } + + template unsigned int ObjectTypeBuilderBase::advertiseSignal(const std::string& name, SignalMemberGetter getter, int id) + { + return xAdvertiseSignal(name, detail::FunctionSignature::signature(), getter, id); + } + + template + inline unsigned int ObjectTypeBuilderBase::advertiseProperty(const std::string& eventName, PropertyMemberGetter getter) + { + return xAdvertiseProperty(eventName, typeOf()->signature(), getter); + } + + + namespace detail + { + static const char* interfaceMarker = "_interface_"; + static const unsigned int interfaceMarkerLength = strlen(interfaceMarker); + + // Trait that detect inheritance from PropertyBase SignalBase or none of the above. + + template struct SigPropInheritsSignal + {}; + template struct SigPropInheritsProperty + {}; + + template struct SigProp : public + SigPropInheritsProperty::value> {}; + + template struct SigPropInheritsProperty + { + static const unsigned value = 2; + }; + template struct SigPropInheritsProperty + : public SigPropInheritsSignal::value> {}; + + template struct SigPropInheritsSignal + { + static const unsigned value = 1; + }; + template struct SigPropInheritsSignal + { + static const unsigned value = 0; + }; + + template struct Dummy {}; + template unsigned int advertise(ObjectTypeBuilderBase* builder, const std::string& name, A accessor, Dummy<0>) + { + return builder->advertiseMethod(name, accessor); + } + template unsigned int advertise(ObjectTypeBuilderBase* builder, const std::string& name, A accessor, Dummy<1>) + { + std::string n = name; + if (n.size() > interfaceMarkerLength && n.substr(0, interfaceMarkerLength) == interfaceMarker) + n = name.substr(interfaceMarkerLength); + return builder->advertiseSignal(n, accessor); + } + template unsigned int advertise(ObjectTypeBuilderBase* builder, const std::string& name, A accessor, Dummy<2>) + { + std::string n = name; + if (n.size() > interfaceMarkerLength && n.substr(0, interfaceMarkerLength) == interfaceMarker) + n = name.substr(interfaceMarkerLength); + return builder->advertiseProperty(n, accessor); + } + template unsigned int advertiseBounce(ObjectTypeBuilderBase* builder, const std::string& name, A accessor, boost::true_type) + { + return advertise(builder, name, accessor, + Dummy::value_type>::value>()); + } + template unsigned int advertiseBounce(ObjectTypeBuilderBase* builder, const std::string& name, A accessor, boost::false_type) + { + return builder->advertiseMethod(name, accessor); + } + } + template + unsigned int + ObjectTypeBuilderBase::advertiseId(const std::string& name, T element) + { + return detail::advertiseBounce(this, name, element, typename detail::Accessor::is_accessor()); + } + template + ObjectTypeBuilderBase& + ObjectTypeBuilderBase::advertise(const std::string& name, T element) + { + detail::advertiseBounce(this, name, element, typename detail::Accessor::is_accessor()); + return *this; + } + +} + + +#endif // _QITYPE_DETAILS_OBJECTTYPEBUILDER_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/pointertypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/pointertypeinterface.hxx new file mode 100755 index 0000000..edca525 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/pointertypeinterface.hxx @@ -0,0 +1,69 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEPOINTER_HXX_ +#define _QITYPE_DETAILS_TYPEPOINTER_HXX_ + +#include + +namespace qi +{ + template class PointerTypeInterfaceImpl: public PointerTypeInterface + { + public: + TypeInterface* pointedType() + { + // Caching the result here is dangerous if T uses runtime factory. + return typeOf(); + } + PointerKind pointerKind() { return Raw; } + AnyReference dereference(void* storage) + { + // We are in DirectAccess mode, so storage is a T*. + void* value = pointedType()->initializeStorage(storage); + return AnyReference(pointedType(), value); + } + + void setPointee(void** storage, void* pointer) + { + *storage = pointer; + } + + typedef DefaultTypeImplMethods + > TypeMethodsImpl; + _QI_BOUNCE_TYPE_METHODS(TypeMethodsImpl); + }; + + template class TypeImpl: public PointerTypeInterfaceImpl{}; + + template class TypeSharedPointerImpl: public PointerTypeInterface + { + public: + TypeInterface* pointedType() + { + return typeOf(); + } + PointerKind pointerKind() { return Shared; } + AnyReference dereference(void* storage) + { + T* ptr = (T*)ptrFromStorage(&storage); + void *value = pointedType()->initializeStorage(ptr->get()); + return AnyReference(pointedType(), value); + } + void setPointee(void** storage, void* pointer) + { + T* ptr = (T*)ptrFromStorage(storage); + *ptr = T((typename T::element_type*)pointer); + } + typedef DefaultTypeImplMethods > Impl; + _QI_BOUNCE_TYPE_METHODS(Impl); + }; + + template class TypeImpl >: public TypeSharedPointerImpl >{}; +} + +#endif // _QITYPE_DETAILS_TYPEPOINTER_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/property.hxx b/naoModule/libnaoqi_files/include/qitype/details/property.hxx new file mode 100755 index 0000000..ff82918 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/property.hxx @@ -0,0 +1,60 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_PROPERTY_HXX_ +#define _QITYPE_DETAILS_PROPERTY_HXX_ + + +namespace qi +{ + + inline void GenericProperty::set(const AnyValue& v) + { + std::pair conv = v.convert(_type); + if (!conv.first.type()) + throw std::runtime_error(std::string("Failed converting ") + v.type()->infoString() + " to " + _type->infoString()); + + Property::set(AnyValue(conv.first, false, false)); + if (conv.second) + conv.first.destroy(); + } + + template + PropertyImpl::PropertyImpl(Getter getter, Setter setter, + SignalBase::OnSubscribers onsubscribe) + : SignalF(onsubscribe) + , _getter(getter) + , _setter(setter) + { + } + + template + T PropertyImpl::get() const + { + if (_getter) + return _getter(_value); + else + return _value; + } + template + void PropertyImpl::set(const T& v) + { + qiLogDebug("qitype.property") << "set " << this << " " << (!!_setter); + if (_setter) + { + bool ok = _setter(_value, v); + if (ok) + (*this)(_value); + } + else + { + _value = v; + (*this)(_value); + } + } +} + +#endif // _QITYPE_DETAILS_PROPERTY_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/signal.hxx b/naoModule/libnaoqi_files/include/qitype/details/signal.hxx new file mode 100755 index 0000000..f6e14aa --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/signal.hxx @@ -0,0 +1,158 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_SIGNAL_HXX_ +#define _QITYPE_DETAILS_SIGNAL_HXX_ + +#include +#include +#include +#include + +namespace qi +{ + #define genConnect(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + template \ + SignalSubscriber& SignalF::connect(F func, P p comma ADECL) \ + { \ + int curId; \ + SignalLink* trackLink; \ + createNewTrackLink(curId, trackLink); \ + SignalSubscriber& s = connect(::qi::bindWithFallback( \ + boost::bind(&SignalF::disconnectTrackLink, this, curId), \ + func, p comma AUSE)); \ + *trackLink = s; \ + return s; \ + } + QI_GEN(genConnect) + #undef genConnect + + template + SignalSubscriber& SignalF::connect(AnyFunction f) + { + return SignalBase::connect(SignalSubscriber(f)); + } + template + SignalSubscriber& SignalF::connect(const SignalSubscriber& sub) + { + return SignalBase::connect(sub); + } + template + template + SignalSubscriber& SignalF::connect(SignalF& signal) + { + int curId; + SignalLink* trackLink; + createNewTrackLink(curId, trackLink); + SignalSubscriber& s = connect(qi::trackWithFallback( + boost::bind(&SignalF::disconnectTrackLink, this, curId), + (boost::function&)signal, + boost::weak_ptr(signal._p))); + *trackLink = s; + return s; + } + + template + template + SignalSubscriber& SignalF::connect(Signal& signal) + { + typedef typename detail::VoidFunctionType::type ftype; + int curId; + SignalLink* trackLink; + createNewTrackLink(curId, trackLink); + SignalSubscriber& s = connect(qi::trackWithFallback( + boost::bind(&SignalF::disconnectTrackLink, this, curId), + (boost::function&)signal, + boost::weak_ptr(signal._p))); + *trackLink = s; + return s; + } + + template + SignalSubscriber& SignalF::connect(const boost::function& fun) + { + return connect(AnyFunction::from(fun)); + } + template + SignalSubscriber& SignalBase::connect(const boost::function& fun) + { + return connect(AnyFunction::from(fun)); + } + template + template + SignalSubscriber& SignalF::connect(CALLABLE c) + { + return connect((boost::function)c); + } + template + SignalSubscriber& SignalF::connect(const AnyObject& obj, const std::string& slot) + { + return SignalBase::connect(obj, slot); + } + + template + SignalSubscriber& SignalF::connect(const AnyObject& obj, unsigned int slot) + { + return connect(SignalSubscriber(obj, slot)); + } + + namespace detail + { + + template class BounceToSignalBase + { + // This default should not be instanciated + BOOST_STATIC_ASSERT(sizeof(T) < 0); + public: + BounceToSignalBase(SignalBase& sb) + { + } + }; + #define pushArg(z, n, _) \ + args.push_back(AutoAnyReference(p ##n)); + #define makeBounce(n, argstypedecl, argstype, argsdecl, argsues, comma) \ + template \ + class BounceToSignalBase { \ + public: \ + BounceToSignalBase(SignalBase& signalBase) : signalBase(signalBase) {} \ + R operator()(argsdecl) { \ + AnyReferenceVector args; \ + BOOST_PP_REPEAT(n, pushArg, _); \ + signalBase.trigger(args); \ + } \ + private: \ + SignalBase& signalBase; \ + }; + QI_GEN(makeBounce) + #undef makeBounce + #undef pushArg + + } // detail + + template + SignalF::SignalF(OnSubscribers onSubscribers) + : SignalBase(onSubscribers) + { + * (boost::function*)this = detail::BounceToSignalBase(*this); + _setSignature(detail::functionArgumentsSignature()); + } + + + template + qi::Signature SignalF::signature() const + { + return detail::functionArgumentsSignature(); + } + + inline + SignalSubscriber& SignalSubscriber::setCallType(MetaCallType ct) + { + threadingModel = ct; + return *this; + } +} // qi +#endif // _QITYPE_DETAILS_SIGNAL_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/stringtypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/stringtypeinterface.hxx new file mode 100755 index 0000000..1e014e1 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/stringtypeinterface.hxx @@ -0,0 +1,155 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPESTRING_HXX_ +#define _QITYPE_DETAILS_TYPESTRING_HXX_ +#include +#include + +namespace qi +{ + inline std::string StringTypeInterface::getString(void* storage) + { + ManagedRawString raw = get(storage); + std::string res(raw.first.first, raw.first.second); + if (raw.second) + raw.second(raw.first); + return res; + } + + inline void StringTypeInterface::set(void** storage, const std::string& val) + { + set(storage, val.c_str(), val.size()); + } + + class QITYPE_API StringTypeInterfaceImpl: public StringTypeInterface + { + public: + typedef DefaultTypeImplMethods + > Methods; + virtual ManagedRawString get(void* storage) + { + std::string* ptr = (std::string*)Methods::ptrFromStorage(&storage); + return ManagedRawString(RawString((char*)ptr->c_str(), ptr->size()), + Deleter()); + } + virtual void set(void** storage, const char* value, size_t sz) + { + std::string* ptr = (std::string*)Methods::ptrFromStorage(storage); + ptr->assign(value, sz); + } + + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + + template<> + class TypeImpl: public StringTypeInterfaceImpl + {}; + + class QITYPE_API TypeCStringImpl: public StringTypeInterface + { + public: + virtual ManagedRawString get(void* storage) + { + return ManagedRawString(RawString((char*)storage, strlen((char*)storage)), + Deleter()); + } + virtual void set(void** storage, const char* ptr, size_t sz) + { + *(char**)storage = qi::os::strdup(ptr); + } + virtual void* clone(void* src) + { + return qi::os::strdup((char*)src); + } + virtual void destroy(void* src) + { + free(src); + } + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS_NOCLONE(Methods); + }; + + template<> + class TypeImpl: public TypeCStringImpl + {}; + + + template class TypeImpl: public StringTypeInterface + { + public: + virtual void* clone(void* src) + { + char* res = new char[I]; + memcpy(res, src, I); + return res; + } + virtual void destroy(void* ptr) + { + delete[] (char*)ptr; + } + virtual ManagedRawString get(void* storage) + { + return ManagedRawString(RawString((char*)storage, I-1), + Deleter()); + } + virtual void set(void** storage, const char* ptr, size_t sz) + { + qiLogCategory("qitype.typestring"); + // haha...no + qiLogWarning() << "set on C array not implemented"; + } + + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS_NOCLONE(Methods); + }; + + /** Declare a Type for T of Kind string. + * + * T must be default-constructible, copy-constructible, and + * provide a constructor accepting a string. + * F must be a member function pointer, member object pointer, or free function + * returning a const string&. + */ + template class TypeEquivalentString: public StringTypeInterface + { + public: + TypeEquivalentString(F f): _getter(f) {} + typedef DefaultTypeImplMethods > Impl; + virtual void set(void** storage, const char* ptr, size_t sz) + { + T* inst = (T*)ptrFromStorage(storage); + *inst = T(std::string(ptr, sz)); + } + virtual ManagedRawString get(void* storage) + { + T* ptr = (T*)Impl::ptrFromStorage(&storage); + void* str = detail::fieldStorage(ptr, _getter); + const std::string& s = detail::fieldValue(ptr, _getter, &str); + return ManagedRawString(RawString((char*)s.c_str(), s.size()), + Deleter()); + } + _QI_BOUNCE_TYPE_METHODS(Impl); + F _getter; + }; + + template + StringTypeInterface* makeTypeEquivalentString(T*, F f) + { + return new TypeEquivalentString(f); + } +} + +/** Register type \p type in the type system as string kind, using constructor + * for setter, and function \p func for getter + */ +#define QI_EQUIVALENT_STRING_REGISTER(type, func) \ + static bool BOOST_PP_CAT(__qi_registration, __COUNTER__) \ + = qi::registerType(typeid(type), qi::makeTypeEquivalentString((type*)0, func)) + +#endif // _QITYPE_DETAILS_TYPESTRING_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/structtypeinterface.hxx b/naoModule/libnaoqi_files/include/qitype/details/structtypeinterface.hxx new file mode 100755 index 0000000..ac508d8 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/structtypeinterface.hxx @@ -0,0 +1,497 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPETUPLE_HXX_ +#define _QITYPE_DETAILS_TYPETUPLE_HXX_ + +#include +#include +#include +#include +#include + +namespace qi +{ + namespace detail { + + template struct StructVersioningDelegateDrop + { + static bool canDropFields(void*, const std::vector&) { return false;} + }; + template struct StructVersioningDelegateFill + { + static bool fillMissingFields(StructTypeInterface* type, std::map& fields, const std::vector& missing) { return false;} + }; + bool QITYPE_API fillMissingFieldsWithDefaultValues(StructTypeInterface* type, + std::map& fields, + const std::vector& missing, + const char** which=0, int whichLength=0); + +/** Allow filling given struct field names with the default value, if + * converting from a previous struct version. + * @warning any value set by the default constructor will be overriden + * with the default value for the field type (0 for int). + */ +#define QI_TYPE_STRUCT_EXTENSION_FILL_FIELDS(name, ...) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateFill { \ + static bool fillMissingFields(StructTypeInterface* type, std::map& fields, const std::vector& missing) \ + { \ + const char* which[] = {__VA_ARGS__ }; \ + int count = sizeof(which) / sizeof(char*); \ + return fillMissingFieldsWithDefaultValues(type, fields, missing, which, count); \ + } \ + };}} +/// Allow filling any missing field with default value +#define QI_TYPE_STRUCT_EXTENSION_FILL_ALL(name, ...) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateFill { \ + static bool fillMissingFields(StructTypeInterface* type, std::map& fields, const std::vector& missing) \ + { \ + return fillMissingFieldsWithDefaultValues(type, fields, missing); \ + } \ + };}} +/// Declare struct as extension of previous versions, allowing all fields to be dropped +#define QI_TYPE_STRUCT_EXTENSION_DROP_ALL(name) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateDrop { \ + static bool canDropFields(void*, const std::vector&) { return true;} \ + };}} + +/// Declare struct as extension of previous versions, allowing given fields to be dropped +#define QI_TYPE_STRUCT_EXTENSION_DROP_FIELDS(name, ...) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateDrop { \ + static bool canDropFields(void*, const std::vector& fields) { \ + const char* okFields[] = {__VA_ARGS__ }; \ + int count = sizeof(okFields) / sizeof(char*); \ + for (unsigned i=0; i& fields) + * and must return true to allow the drop, or false to deny the conversion. +*/ +#define QI_TYPE_STRUCT_EXTENSION_DROP_HANDLER(name, f) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateDrop { \ + static bool canDropFields(void* store, const std::vector& fields) { \ + return f((name*)store, fields);} \ + };}} + +/** Define callable \p f as handler when a default value is needed for some + * fields of \p name. Will be invoked as + * f(std::map& content, const vector& missingFields) + * It must return false to indicate a failure, or fill content with a value + * for all the missing fields and return true. + */ +#define QI_TYPE_STRUCT_EXTENSION_FILL_HANDLER(name, f) \ + namespace qi { namespace detail { template<> struct StructVersioningDelegateFill { \ + static bool fillMissingFields(StructTypeInterface* type, std::map& fields, const std::vector& missing) \ + { \ + return f(fields, missing) ; \ + }};}} + +/** Allow converting this struct to/from anything. Dropping unmatched fields, + * and filling non-present ones with the default value for the matching type. + * @warning This will allow conversion between completely unrelated types, + * use with caution. + * + */ +#define QI_TYPE_STRUCT_EXTENSION_ALL(name) \ + QI_TYPE_STRUCT_EXTENSION_DROP_ALL(name); \ + QI_TYPE_STRUCT_EXTENSION_FILL_ALL(name) + +/// Declare a versionned struct that accepts dropping/filling-with-default given fields. +#define QI_TYPE_STRUCT_EXTENSION_FIELDS(name, ...) \ + QI_TYPE_STRUCT_EXTENSION_DROP_FIELDS(name, __VA_ARGS__); \ + QI_TYPE_STRUCT_EXTENSION_FILL_FIELDS(name, __VA_ARGS__) + + //keep only the class name. (remove :: and namespaces) + QITYPE_API std::string normalizeClassName(const std::string &name); + + template void setFromStorage(T& ref, void* storage) + { + ref = *(T*)typeOf()->ptrFromStorage(&storage); + } + + /* Helpers around accessors + */ + template TypeInterface* fieldType(A) + { + static TypeInterface* res = 0; + QI_ONCE(res = qi::typeOf::value_type>()); + return res; + } + + template void* fieldStorage(C* inst, A accessor) + { + return fieldType(accessor)->initializeStorage( + (void*)&detail::Accessor::access(inst, accessor)); + } + + template + typename detail::Accessor::value_type& + fieldValue(C* instance, A accessor, void** data) + { + typedef typename detail::Accessor::value_type T; + return *(T*)fieldType(accessor)->ptrFromStorage(data); + } + } +} + + +#define __QI_TYPE_STRUCT_DECLARE(name, extra) \ +namespace qi { \ + template<> struct TypeImpl: public ::qi::StructTypeInterface \ + { \ + public: \ + typedef name ClassType; \ + TypeImpl(); \ + virtual std::vector< ::qi::TypeInterface*> memberTypes(); \ + virtual std::vector elementsName(); \ + virtual std::string className(); \ + virtual void* get(void* storage, unsigned int index); \ + virtual void set(void** storage, unsigned int index, void* valStorage); \ + virtual bool canDropFields(void* storage, const std::vector& fieldNames); \ + virtual bool fillMissingFields(std::map& fields, const std::vector& missing); \ + extra \ + typedef ::qi::DefaultTypeImplMethods > Impl; \ + _QI_BOUNCE_TYPE_METHODS(Impl); \ + }; } + + +#define __QI_TUPLE_TYPE(_, what, field) res.push_back(::qi::typeOf(ptr->field)); +#define __QI_TUPLE_GET(_, what, field) if (i == index) return ::qi::typeOf(ptr->field)->initializeStorage(&ptr->field); i++; +#define __QI_TUPLE_SET(_, what, field) if (i == index) ::qi::detail::setFromStorage(ptr->field, valueStorage); i++; +#define __QI_TUPLE_FIELD_NAME(_, what, field) res.push_back(BOOST_PP_STRINGIZE(QI_DELAY(field))); +#define __QI_TYPE_STRUCT_IMPLEMENT(name, inl, onSet, ...) \ +namespace qi { \ + inl TypeImpl::TypeImpl() { \ + ::qi::registerStruct(this); \ + } \ + inl std::vector< ::qi::TypeInterface*> TypeImpl::memberTypes() \ + { \ + name* ptr = 0; \ + std::vector< ::qi::TypeInterface*> res; \ + QI_VAARGS_APPLY(__QI_TUPLE_TYPE, _, __VA_ARGS__); \ + return res; \ + } \ + inl void* TypeImpl::get(void* storage, unsigned int index) \ + { \ + unsigned int i = 0; \ + name* ptr = (name*)ptrFromStorage(&storage); \ + QI_VAARGS_APPLY(__QI_TUPLE_GET, _, __VA_ARGS__); \ + return 0; \ + } \ + inl void TypeImpl::set(void** storage, unsigned int index, void* valueStorage)\ + { \ + unsigned int i=0; \ + name* ptr = (name*)ptrFromStorage(storage); \ + QI_VAARGS_APPLY(__QI_TUPLE_SET, _, __VA_ARGS__); \ + onSet \ + }\ + inl std::vector TypeImpl::elementsName() \ + { \ + std::vector res; \ + QI_VAARGS_APPLY(__QI_TUPLE_FIELD_NAME, _, __VA_ARGS__); \ + return res; \ + }\ + inl std::string TypeImpl::className() \ + {\ + return ::qi::detail::normalizeClassName(BOOST_PP_STRINGIZE(name));\ + }\ + inl bool TypeImpl::canDropFields(void* storage, const std::vector& fieldNames) {return ::qi::detail::StructVersioningDelegateDrop::canDropFields(storage, fieldNames);} \ + inl bool TypeImpl::fillMissingFields(std::map& fields, const std::vector& missing) {return ::qi::detail::StructVersioningDelegateFill::fillMissingFields(this, fields, missing);} \ +} + + + +/// Declare a struct field using an helper function +#define QI_STRUCT_HELPER(name, func) (name, func, FUNC) +/// Declare a struct feld that is a member (member value or member accessor function) +#define QI_STRUCT_FIELD(name, field) (name, field, FIELD) + +// construct pointer-to accessor from free-function +#define __QI_STRUCT_ACCESS_FUNC(fname, field) &field +// construct pointer-to-accessor from member function/field +#define __QI_STRUCT_ACCESS_FIELD(fname, field) &ClassType::field + +// invoke the correct __QI_STRUCT_ACCESS_ macro using type +#define __QI_STRUCT_ACCESS_BOUNCE2(name, accessor, type) \ + QI_CAT(__QI_STRUCT_ACCESS_, type)(name, accessor) + +// bounce with default value FIELD for argument 3 +#define __QI_STRUCT_ACCESS_BOUNCE1(x, y) \ + __QI_STRUCT_ACCESS_BOUNCE2(x, y, FIELD) + +// arg-count overload, bounce to __QI_STRUCT_ACCESS_BOUNCE +#define __QI_STRUCT_ACCESS_BOUNCE(...) \ + QI_CAT(__QI_STRUCT_ACCESS_BOUNCE, QI_LIST_VASIZE((__VA_ARGS__)))(__VA_ARGS__) + +// accept (name, accessor, type) and (name, accessor) defaulting type to field +#define __QI_STRUCT_ACCESS(tuple) QI_DELAY(__QI_STRUCT_ACCESS_BOUNCE)tuple + + +#define __QI_ATUPLE_TYPE(_, what, field) res.push_back(::qi::detail::fieldType(__QI_STRUCT_ACCESS(field))); +#define __QI_ATUPLE_GET(_, what, field) if (i == index) return ::qi::detail::fieldStorage(ptr, __QI_STRUCT_ACCESS(field)); i++; +#define __QI_ATUPLE_FIELD_NAME(_, what, field) res.push_back(QI_PAIR_FIRST(field)); +#define __QI_ATUPLE_FROMDATA(idx, what, field) ::qi::detail::fieldValue(ptr, __QI_STRUCT_ACCESS(field), const_cast(&data[idx])) +#define __QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR_IMPLEMENT(name, inl, onSet, ...)\ + namespace qi { \ + inl TypeImpl::TypeImpl() { \ + ::qi::registerStruct(this); \ + } \ + inl std::vector< ::qi::TypeInterface*> TypeImpl::memberTypes() \ + { \ + std::vector< ::qi::TypeInterface*> res; \ + QI_VAARGS_APPLY(__QI_ATUPLE_TYPE, name, __VA_ARGS__); \ + return res; \ + } \ + \ + inl void* TypeImpl::get(void* storage, unsigned int index) \ + { \ + unsigned int i = 0; \ + name* ptr = (name*)ptrFromStorage(&storage); \ + QI_VAARGS_APPLY(__QI_ATUPLE_GET, name, __VA_ARGS__); \ + return 0; \ + } \ + \ + inl void TypeImpl::set(void** storage, unsigned int index, void* valueStorage)\ + {\ + throw std::runtime_error("single-field set not implemented");\ + }\ + \ + inl void TypeImpl::set(void** storage, const std::vector& data) \ + {\ + name* ptr = (name*)ptrFromStorage(storage); \ + *ptr = name(QI_VAARGS_MAP(__QI_ATUPLE_FROMDATA, name, __VA_ARGS__)); \ + }\ + \ + inl std::vector TypeImpl::elementsName() \ + { \ + std::vector res; \ + QI_VAARGS_APPLY(__QI_ATUPLE_FIELD_NAME, _, __VA_ARGS__); \ + return res; \ + }\ + inl std::string TypeImpl::className() \ + \ + { \ + return ::qi::detail::normalizeClassName(BOOST_PP_STRINGIZE(name));\ + } \ + inl bool TypeImpl::canDropFields(void* storage, const std::vector& fieldNames) {return ::qi::detail::StructVersioningDelegateDrop::canDropFields(storage, fieldNames);} \ + inl bool TypeImpl::fillMissingFields(std::map& fields, const std::vector& missing) {return ::qi::detail::StructVersioningDelegateFill::fillMissingFields(this, fields, missing);} \ + } + + +/// Allow the QI_TYPE_STRUCT macro and variants to access private members +#define QI_TYPE_STRUCT_PRIVATE_ACCESS(name) \ +friend class qi::TypeImpl; + +/** Declare a simple struct to the type system. + * First argument is the structure name. Remaining arguments are the structure + * fields. + * This macro must be called outside any namespace. + * This macro should be called in the header file defining the structure 'name', + * or in a header included by all source files using the structure. + * See QI_TYPE_STRUCT_REGISTER for a similar macro that can be called from a + * single source file. + */ +#define QI_TYPE_STRUCT(name, ...) \ + QI_TYPE_STRUCT_DECLARE(name) \ + __QI_TYPE_STRUCT_IMPLEMENT(name, inline, /**/, __VA_ARGS__) + +/** Similar to QI_TYPE_STRUCT, but evaluates 'onSet' after writting to an instance. + * The instance is accessible through the variable 'ptr'. + */ +#define QI_TYPE_STRUCT_EX(name, onSet, ...) \ + QI_TYPE_STRUCT_DECLARE(name) \ + __QI_TYPE_STRUCT_IMPLEMENT(name, inline, onSet, __VA_ARGS__) + +#define QI_TYPE_STRUCT_IMPLEMENT(name, ...) \ + __QI_TYPE_STRUCT_IMPLEMENT(name, /**/, /**/, __VA_ARGS__) + +/** Register a struct with member field/function getters, and constructor setter + * + * Call like that: + * QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(Point, + * ("x", getX), + * ("y", y)) + * + * The first macro argument is the class full name including namespace. + * Remaining arguments can be: + * - (fieldName, accessor): accessor must be: + * - a member function returning a const T& with no argument + * - a member field + * - QI_STRUCT_FIELD(fieldName, accessor): Same thing as above, provided for + * consistency. + * - QI_STRUCT_HELPER(fieldName, function). Function must be a free function + * taking a class pointer, and returning a const T& + * + * The class must provide a constructor that accepts all fields as argument, in + * the order in which they are declared in the macro. + * + * Must be called outside any namespace. + */ +#define QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(name, ...) \ + __QI_TYPE_STRUCT_DECLARE(name, \ + virtual void set(void** storage, const std::vector&);) \ + __QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR_IMPLEMENT(name, inline, /**/, __VA_ARGS__) + +/** Similar to QI_TYPE_STRUCT, but using the runtime factory instead of the + * compile-time template. This macro will register the struct at static + * initialization time, and thus should only be called from one compilation + * unit. To ensure this, the simplest option is to use this macro from a .cpp + * source file. It should *not* be used in a header. + */ +#define QI_TYPE_STRUCT_REGISTER(name, ...) \ +namespace _qi_ { \ + QI_TYPE_STRUCT(name, __VA_ARGS__); \ +} \ +QI_TYPE_REGISTER_CUSTOM(name, _qi_::qi::TypeImpl) + +/** Similar to QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR, + * but using the runtime factory instead of the + * compile-time template. + * + */ +#define QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR_REGISTER(name, ...) \ +namespace _qi_ { \ + QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(name, __VA_ARGS__); \ +} \ +QI_TYPE_REGISTER_CUSTOM(name, _qi_::qi::TypeImpl) + +/** Declares that name is equivalent to type bounceTo, and that instances + * can be converted using the conversion function with signature 'bounceTo* (name*)'. + * This macro should be called in a header included by all code using the 'name' + * class. + * See QI_TYPE_STRUCT_BOUNCE_REGISTER for a similar macro that can be called from a + * single source file. + */ +#define QI_TYPE_STRUCT_BOUNCE(name, bounceTo, conversion) \ +namespace qi { \ +template<> class TypeImpl: public ::qi::StructTypeInterfaceBouncer \ +{ \ +public: \ + void adaptStorage(void** storage, void** adapted) \ + { \ + name* ptr = (name*)ptrFromStorage(storage); \ + bounceTo * tptr = conversion(ptr); \ + *adapted = bounceType()->initializeStorage(tptr); \ + } \ + std::string className() \ + { \ + return ::qi::detail::normalizeClassName(BOOST_PP_STRINGIZE(name)); \ + } \ +};} + +/** Similar to QI_TYPE_STRUCT_BOUNCE, but using the runtime factory instead of the + * compile-time template. + */ +#define QI_TYPE_STRUCT_BOUNCE_REGISTER(name, bounceTo, conversion) \ +namespace _qi_ { \ + QI_TYPE_STRUCT_BOUNCE(name, bounceTo, conversion); \ +} \ +QI_TYPE_REGISTER_CUSTOM(name, _qi_::qi::TypeImpl) + + + +namespace qi { + template + class StructTypeInterfaceBouncer: public StructTypeInterface + { + public: + StructTypeInterface* bounceType() + { + static TypeInterface* result = 0; + if (!result) + result = typeOf(); + return static_cast(result); + } + + virtual void adaptStorage(void** storage, void** adapted) = 0; + + typedef DefaultTypeImplMethods > Methods; + virtual std::vector memberTypes() + { + return bounceType()->memberTypes(); + } + + virtual void* get(void* storage, unsigned int index) + { + void* astorage; + adaptStorage(&storage, &astorage); + return bounceType()->get(astorage, index); + } + + virtual std::vector get(void* storage) + { + void* astorage; + adaptStorage(&storage, &astorage); + return bounceType()->get(astorage); + } + + virtual void set(void** storage, const std::vector& vals) + { + void* astorage; + adaptStorage(storage, &astorage); + bounceType()->set(&astorage, vals); + } + + virtual void set(void** storage, unsigned int index, void* valStorage) + { + void* astorage; + adaptStorage(storage, &astorage); + bounceType()->set(&astorage, index, valStorage); + } + + virtual std::vector elementsName() + { + return bounceType()->elementsName(); + } + + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + + template + class TypeImpl >: public StructTypeInterface + { + public: + typedef DefaultTypeImplMethods, TypeByPointerPOD > > Methods; + typedef typename std::pair BackendType; + TypeImpl() + { + _memberTypes.push_back(typeOf()); + _memberTypes.push_back(typeOf()); + } + std::vector _memberTypes; + + std::vector memberTypes() { return _memberTypes;} + void* get(void* storage, unsigned int index) + { + BackendType* ptr = (BackendType*)ptrFromStorage(&storage); + // Will work if F or S are references + if (!index) + return typeOf()->initializeStorage(const_cast((void*)&ptr->first)); + else + return typeOf()->initializeStorage(const_cast((void*)&ptr->second)); + } + void set(void** storage, unsigned int index, void* valStorage) + { + BackendType* ptr = (BackendType*)ptrFromStorage(storage); + const std::vector& types = _memberTypes; + + + // FIXME cheating, we do not go through TypeInterface of S and F for copy + // because typeerasure does not expose the interface + if (!index) + detail::TypeTraitCopy::type, true>::copy(const_cast((void*)&ptr->first), types[0]->ptrFromStorage(&valStorage)); + else + detail::TypeTraitCopy::type, true>::copy(const_cast((void*)&ptr->second), types[1]->ptrFromStorage(&valStorage)); + } + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + +} +#endif // _QITYPE_DETAILS_TYPETUPLE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/type.hpp b/naoModule/libnaoqi_files/include/qitype/details/type.hpp new file mode 100755 index 0000000..a65433c --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/type.hpp @@ -0,0 +1,121 @@ +/* +** Author(s): +** - Cedric GESTES +** +** Copyright (C) 2014 Aldebaran Robotics +*/ + +#ifndef _QITYPE_TYPE_HPP_ +# define _QITYPE_TYPE_HPP_ + + +#include +#include +#include + + +// THIS INTERFACE IS NOT STABLE. (that's why it belongs to details) +// DO NOT USE. + +namespace qi { + + namespace detail { + + class AnyType; + + struct FieldInfo { + //Type2 type; + std::string name; + qi::uint64_t index; + std::string description; + }; + typedef std::vector FieldInfoVector; + + typedef Signature TypeSignature; + + class AnyType; + typedef std::vector AnyTypeVector; + + QITYPE_API AnyType makeTypeOf(TypeKind kind); + QITYPE_API AnyType makeTypeList(const AnyType& element); + QITYPE_API AnyType makeTypeMap(const AnyType& key, const AnyType& element); + QITYPE_API AnyType makeTypeTuple(const AnyTypeVector& elements); + + class QITYPE_API AnyType { + public: + AnyType(); + AnyType(TypeInterface *typeInterface); + + + AnyType(const AnyType& rhs); + AnyType &operator=(const AnyType& rhs); + + //## General + + TypeKind kind() const; + TypeSignature signature() const; //really? + TypeInterface* type() const { return _type; } + + //convert to a human readable format + //Vector, Map + std::string toString(); + + //unique type identifier + std::string name() const; + + //## Type Specific + + //Struct/Object + std::string className() const; + + AnyTypeVector elements(); + + //Struct/Object + FieldInfoVector members(); + + //Object + FieldInfoVector methods(); + FieldInfo method(const uint32_t id); + FieldInfoVector methodOverloads(const std::string& name); + + FieldInfoVector sigs(); //qt reserve signals + FieldInfo signal(const uint32_t id); + FieldInfo signal(const std::string& id); + + FieldInfoVector properties(); + FieldInfo property(const uint32_t id); + FieldInfo property(const std::string& name); + + //Method/Signal + FieldInfoVector paramsIn(); + //Method + FieldInfoVector paramsOut(); + + //Map + AnyType key(); + + //List/Map/Pointer/Property (not dynamic) + AnyType element(); + + //Float/Int + int bits(); + //Int + int isSigned(); + + //## Operations + bool isConvertible(AnyType type); + //compare kind? + //bool isCompatible(Type2 type); + bool isConstructible(AnyType type); + + //hummm what? + bool operator==(const AnyType& rhs) { return rhs.type() == _type; } + + private: + TypeInterface *_type; + }; + + } +} + +#endif /* !TYPE2_PP_ */ diff --git a/naoModule/libnaoqi_files/include/qitype/details/type.hxx b/naoModule/libnaoqi_files/include/qitype/details/type.hxx new file mode 100755 index 0000000..d99e44d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/type.hxx @@ -0,0 +1,161 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPE_HXX_ +#define _QITYPE_DETAILS_TYPE_HXX_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* This file contains the default-provided Type specialisations + * + */ + + +namespace qi { + + namespace detail { + + // Try to get a nice error message for QI_NO_TYPE + class ForbiddenInTypeSystem: public TypeImpl + { + private: + ForbiddenInTypeSystem(); + }; + + template + inline void initializeType(TypeInterface* &tgt) + { + qiLogDebug("qitype.typeof") << "first typeOf request for unregistered type " << typeid(T).name(); + tgt = new TypeImpl(); + } + + template + inline TypeInterface* typeOfBackend() + { + TypeInterface* result = getType(typeid(T)); + if (!result) + { + + static TypeInterface* defaultResult = 0; + QI_ONCE(initializeType(defaultResult)); + result = defaultResult; + } + return result; + } + + template + struct TypeOfAdapter + { + typedef T type; + }; + + template + struct TypeOfAdapter + { + typedef typename TypeOfAdapter::type type; + }; + + template + struct TypeOfAdapter + { + typedef typename TypeOfAdapter::type type; + }; + + template + struct TypeOfAdapter + { + typedef typename boost::add_pointer::type>::type>::type type; + }; + + } + + template + TypeInterface* typeOf() + { + return detail::typeOfBackend::type>(); + } + + inline TypeKind TypeInterface::kind() + { + return TypeKind_Unknown; + } + + namespace detail { + + // Bouncer to DefaultAccess or DirectAccess based on type size + template + class TypeImplMethodsBySize + { + public: + /* DISABLE. Inplace modification does not work with TypeByValue. + * TODO: be able to switch between ByVal and ByPointer on the + * same type. + */ + typedef DefaultTypeImplMethods type; + /* + typedef typename boost::mpl::if_c< + sizeof(T) <= sizeof(void*), + DefaultTypeImplMethods + >, + DefaultTypeImplMethods + > + >::type type; + */ + }; + } + + // Provide a base class for all templated type impls + class QITYPE_API TemplateTypeInterface: public TypeInterface + { + public: + // Return erased template argument type + virtual TypeInterface* templateArgument() = 0; + // If this type is also an object, return it. + virtual TypeInterface* next() { return 0;} + }; + + // To detect a templated type, make all the Type of its instanciations + // inherit fro a single class + template class T> + class QITYPE_TEMPLATE_API TypeOfTemplate: public TemplateTypeInterface + {}; + + // Default Type for template type T instanciated with type I + template class T, typename I> + class QITYPE_TEMPLATE_API TypeOfTemplateDefaultImpl: public TypeOfTemplate + { + public: + virtual TypeInterface* templateArgument() + { + return typeOf(); + } + typedef DefaultTypeImplMethods > Methods; + _QI_BOUNCE_TYPE_METHODS(Methods); + }; + + template class T, typename I> + class QITYPE_TEMPLATE_API TypeOfTemplateImpl: public TypeOfTemplateDefaultImpl + {}; +} + +#endif // _QITYPE_DETAILS_TYPE_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/typedispatcher.hxx b/naoModule/libnaoqi_files/include/qitype/details/typedispatcher.hxx new file mode 100755 index 0000000..14b87d4 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/typedispatcher.hxx @@ -0,0 +1,121 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#include +#include + +namespace qi { + + template + TypeDispatcher& typeDispatch(const TypeDispatcher &vv, AnyReference value) + { + if (!value.type()) + throw std::runtime_error("NULL type"); + TypeDispatcher& v = const_cast(vv); + switch(value.kind()) + { + case TypeKind_Void: + v.visitVoid(); + break; + case TypeKind_Unknown: + v.visitUnknown(value); + break; + case TypeKind_Int: + { + IntTypeInterface* tint = static_cast(value.type()); + + v.visitInt(value.toInt(), tint->isSigned(), tint->size()); + break; + } + case TypeKind_Float: + { + FloatTypeInterface* tfloat = static_cast(value.type()); + v.visitFloat(value.toDouble(), tfloat->size()); + break; + } + case TypeKind_String: + { + StringTypeInterface* tstring = static_cast(value.type()); + StringTypeInterface::ManagedRawString content = tstring->get(value.rawValue()); + v.visitString(content.first.first, content.first.second); + if (content.second) + content.second(content.first); + break; + } + case TypeKind_List: + { + v.visitList(value.begin(), value.end()); + break; + } + case TypeKind_Map: + { + v.visitMap(value.begin(), value.end()); + break; + } + case TypeKind_Object: + { + v.visitObject(GenericObject(static_cast(value.type()), value.rawValue())); + break; + } + case TypeKind_Pointer: + { + AnyReference pointee = *value; + PointerTypeInterface* type = static_cast(value.type()); + if (type->pointerKind() == PointerTypeInterface::Shared + && pointee.kind() == TypeKind_Object) + { // shared_ptr p with Foo object type. + // Create our own shared_ptr, that holds p and delete it on destruction + qiLogDebug("qitype.typedispatcher") << "Detected object shared ptr"; + AnyReference shared_ptr = value.clone(); + AnyObject ao(new GenericObject(static_cast(pointee.type()), pointee.rawValue()), + boost::bind(&AnyObject::deleteCustomDeleter, _1, (boost::function)boost::bind(&AnyReference::destroy, shared_ptr))); + v.visitAnyObject(ao); + } + else + v.visitPointer(pointee); + break; + } + case TypeKind_Tuple: + { + StructTypeInterface* ttuple = static_cast(value.type()); + AnyReferenceVector tuple = ttuple->values(value.rawValue()); + v.visitTuple(ttuple->className(), tuple, ttuple->elementsName()); + break; + } + case TypeKind_Dynamic: + { + if (value.type()->info() == typeOf()->info()) + { + AnyObject* o = value.ptr(false); + v.visitAnyObject(*o); + } + else + v.visitDynamic(value.content()); + break; + } + case TypeKind_Raw: + { + v.visitRaw(value); + break; + } + case TypeKind_Iterator: + { + v.visitIterator(value); + break; + } + case TypeKind_VarArgs: + v.visitVarArgs(value.begin(), value.end()); + break; + case TypeKind_Function: + case TypeKind_Signal: + case TypeKind_Property: + qiLogError("qitype.typedispatcher") << "Signal and Property not handled"; + + } + return v; + } + +} diff --git a/naoModule/libnaoqi_files/include/qitype/details/typeimpl.hxx b/naoModule/libnaoqi_files/include/qitype/details/typeimpl.hxx new file mode 100755 index 0000000..91fb23d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/typeimpl.hxx @@ -0,0 +1,344 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEIMPL_HXX_ +#define _QITYPE_DETAILS_TYPEIMPL_HXX_ + +#include +#include +#include + + +/* This file contains class to help implementing the Type interface. +*/ +namespace qi +{ + namespace detail { + /// Report a type operation failure + void QITYPE_API typeFail(const char* typeName, const char* operation); + + /* Handle creation (create, createInPlace), copy (copy, clone, cloneInPlace), and + * destruction(destroy) of a given type. + * There is currently no portable way to detect if a given class has + * accesible constructor, destructor and/or copy operators. + * So we provide a reasonable default behavior (through our class/struct + * registration macros) and rely on the user to call the appropriate + * QI_TYPE_NOT_* macro to override. + */ + template + struct TypeTraitCreate + { + static void* create() { return new T();} + static void createInPlace(void* ptr) { new(ptr)T();} + }; + + template + struct TypeTraitCreate + { + static void* create() { typeFail(typeid(T).name(), "default constructor"); return 0;} + static void createInPlace(void* ptr) {typeFail(typeid( T).name(), "default constructor");} + }; + + template + struct TypeTraitCopy + { + static void copy(void* dst, const void* src) { *(T*)dst = *(const T*)src;} + static void* clone(void* src) { return new T(*(T*)src);} + static void cloneInPlace(void* ptr, void* src) { new (ptr)T(*(T*)src);} + }; + + template + struct TypeTraitCopy + { + template + static void copy(const T1& d, const T2&s) {typeFail(typeid(T).name(), "copy operator");} + static void* clone(void* src) { typeFail(typeid(T).name(), "clone"); return 0;} + static void cloneInPlace(void* ptr, void* src) { typeFail(typeid(T).name(), "clone");} + }; + + template + struct TypeTraitDestroy + { + static void destroy(void* ptr) { delete (T*)ptr;} + }; + + template + struct TypeTraitDestroy + { + template + static void destroy(const U& ptr) {typeFail(typeid(T).name(), "destructor");} + }; + + /* Use a two-stage override mechanism. + * That way if a user uses our macro that specializes + * TypeManager on one of the versions below, she can still + * specializes the appropriate TypeManagerDefault{Struct,Class}. + */ + template + struct TypeManagerDefaultStruct + : public TypeTraitCreate + , public TypeTraitCopy + , public TypeTraitDestroy + {}; + + template + struct TypeManagerDefaultInterface + : public TypeTraitCreate + , public TypeTraitCopy + , public TypeTraitDestroy + {}; + + template + struct TypeManagerNull + : public TypeTraitCreate + , public TypeTraitCopy + , public TypeTraitDestroy + {}; + + template + struct TypeManagerNotConstructible // not constructible but copyable + : public TypeTraitCreate + , public TypeTraitCopy + , public TypeTraitDestroy + {}; + + + // TypeManager is accessed by this interface. + // Only things for which we are sure are marked constructible and clonable + template + struct TypeManager + : public boost::mpl::if_c< + boost::is_function::value, + TypeManagerNull, + typename boost::mpl::if_c< boost::is_pod::value, + TypeManagerDefaultStruct, + TypeManagerDefaultInterface > + ::type>::type {}; + + // Except for boost::function which matches is_function and is copyable + template + struct TypeManager >: public TypeManagerDefaultStruct > + {}; + template + struct TypeManager: public TypeManager{}; + + } + + /* To avoid the diamond inheritance problem (interface inheritance between + * for instance Type and IntTypeInterface, and we want to reuse implementations), + * Provide methods in a class that does not inherit from Type, and a macro + * to generate the virtual bouncers. + */ + /// Access API that stores a T* in storage + template > + class TypeByPointer + { + public: + typedef T type; + + static void* ptrFromStorage(void** storage) + { + return *storage; + } + + static void* initializeStorage(void* ptr=0) + { + if (ptr) + return ptr; + //Warning: + // If T is not clonable (no copy constructor or operator=) + // add QI_TYPE_NOT_CLONABLE(T) next to the declaration of T + // in your code. + void* res = Manager::create(); + if (!res) + qiLogError("qitype.bypointer") << "initializeStorage error on " << typeid(T).name(); + return res; + } + + static void* clone(void* src) + { + return Manager::clone(src); + } + + static void destroy(void* src) + { + T* ptr = (T*)ptrFromStorage(&src); + Manager::destroy(ptr); + } + }; + + // const ward + template + class TypeByPointer: public TypeByPointer + {}; + // Helper to mark POD-like + template + class TypeByPointerPOD: public TypeByPointer >{}; + /// Access api that stores a T in storage + /* No longuer used since we have an in-place modification + * of AnyReference, as by-value storage would break reference semantic + */ + template + class TypeByValue + { + public: + typedef T type; + static void* ptrFromStorage(void** storage) + { + return storage; + } + static void* initializeStorage(void* ptr=0) + { + void* result = 0; + T* tresult=(T*)(void*)&result; + detail::TypeManager::createInPlace(tresult); + + if (ptr) + detail::TypeManager::copy(tresult, (T*)ptr); + + return result; + } + static void* clone(void* src) + { + void* res; + detail::TypeManager::cloneInPlace(&res, (T*)&src); + return res; + } + + static void destroy(void* storage) + { + T* ptr = (T*)ptrFromStorage(&storage); + ptr->~T(); + } + }; + + // const ward + template + class TypeByValue: public TypeByValue + {}; + + + /* implementation of Type methods that bounces to the various aspect + * subclasses. + * + */ + template < typename T, typename _Access = TypeByPointer > + class DefaultTypeImplMethods + { + public: + typedef _Access Access; + + static void* initializeStorage(void* ptr=0) + { + return Access::initializeStorage(ptr); + } + + static void* ptrFromStorage(void** storage) + { + return Access::ptrFromStorage(storage); + } + + static const TypeInfo& info() + { + static TypeInfo* result = 0; + if (!result) + result = new TypeInfo(typeid(T)); + return *result; + } + + static void* clone(void* src) + { + return Access::clone(src); + } + + static void destroy(void* ptr) + { + Access::destroy(ptr); + } + + static bool less(void* a, void* b) + { + return ::qi::detail::Less()((T*)ptrFromStorage(&a), (T*)ptrFromStorage(&b)); + } + }; + + ///Implement all methods of Type except clone/destroy as bouncers to Bouncer +#define _QI_BOUNCE_TYPE_METHODS_NOCLONE(Bounce) \ + virtual const ::qi::TypeInfo& info() { return Bounce::info();} \ + virtual void* initializeStorage(void* ptr=0) { return Bounce::initializeStorage(ptr);} \ + virtual void* ptrFromStorage(void**s) { return Bounce::ptrFromStorage(s);} \ + virtual bool less(void* a, void* b) { return Bounce::less(a, b);} + + ///Implement all methods of Type as bouncers to Bouncer +#define _QI_BOUNCE_TYPE_METHODS(Bounce) \ + _QI_BOUNCE_TYPE_METHODS_NOCLONE(Bounce) \ + virtual void* clone(void* ptr) { return Bounce::clone(ptr);} \ + virtual void destroy(void* ptr) { Bounce::destroy(ptr);} + + ///Implement all methods of Type except info() as bouncers to Bouncer. +#define _QI_BOUNCE_TYPE_METHODS_NOINFO(Bounce) \ + virtual void* initializeStorage(void* ptr=0) { return Bounce::initializeStorage(ptr);} \ + virtual void* ptrFromStorage(void**s) { return Bounce::ptrFromStorage(s);} \ + virtual void* clone(void* ptr) { return Bounce::clone(ptr);} \ + virtual void destroy(void* ptr) { Bounce::destroy(ptr);} \ + virtual bool less(void* a, void* b) { return Bounce::less(a, b);} + + template < typename T, typename _Access = TypeByPointer > + class DefaultTypeImpl + : public TypeInterface + { + public: + typedef DefaultTypeImplMethods MethodsImpl; + _QI_BOUNCE_TYPE_METHODS(MethodsImpl); + }; + + /** Compile-time Type "factory", used by typeOf() in case no runtime Type + * was registered. Specialize this class to provide a custom + * Type for a given type, in a header, or use registerType() in a cpp. + */ + template + class TypeImpl: public DefaultTypeImpl + {}; + + // void + template<> + class TypeImpl: public TypeInterface + { + public: + const TypeInfo& info() + { + static TypeInfo result = TypeInfo(typeid(void)); + return result; + } + void* initializeStorage(void*) { return 0;} + void* ptrFromStorage(void** ) { return 0;} + void* clone(void*) { return 0;} + void destroy(void* ptr) {} + TypeKind kind() { return TypeKind_Void;} + bool less(void* a, void* b) { return false;} + }; + + //reference + template + class TypeImpl: public TypeImpl + {}; + + + +} + +namespace _qi_ +{ + namespace qi + { + // Support for QI_TYPE_STRUCT_REGISTER and QI_TYPE_STRUCT_BOUNCE_REGISTER + template + class TypeImpl + {}; + } +} + +#endif // _QITYPE_DETAILS_TYPEIMPL_HXX_ diff --git a/naoModule/libnaoqi_files/include/qitype/details/typeinterface.hpp b/naoModule/libnaoqi_files/include/qitype/details/typeinterface.hpp new file mode 100755 index 0000000..83af821 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/details/typeinterface.hpp @@ -0,0 +1,206 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DETAILS_TYPEINTERFACE_HPP_ +#define _QITYPE_DETAILS_TYPEINTERFACE_HPP_ + +#include +#include +#include +#include + +/* A lot of class are found in this headers... to kill circular dependencies. + Futhermore we need that all "default template" types are registered (included) + when type.hpp is used. (for typeOf to works reliably) +*/ + + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + + /** This class is used to uniquely identify a type. + * + */ + class QITYPE_API TypeInfo + { + public: + TypeInfo(); + /// Construct a TypeInfo from a std::type_info + TypeInfo(const std::type_info& info); + /// Contruct a TypeInfo from a custom string. + TypeInfo(const std::string& ti); + + std::string asString() const; + std::string asDemangledString() const; + + //TODO: DIE + const char* asCString() const; + + bool operator==(const TypeInfo& b) const; + bool operator!=(const TypeInfo& b) const; + bool operator<(const TypeInfo& b) const; + + private: + const std::type_info* stdInfo; + // C4251 + std::string customInfo; + }; + + /** + * TypeInterface base interface. Further interfaces inheriting from + * TypeInterface define operations specific to some type (like lists, + * strings, integral values...). + * + * Type erasure is implemented using the following model. A value or a + * reference is represented by a void* paired with a TypeInterface to + * manipulate the data. + * + * A TypeInterface implements basic operations on values of the type it + * represents. It manipulates said value through an opaque *storage* pointer, + * initialized by clone() or initializeStorage(). Thus, TypeInterface + * instances do not usually hold any data, may exist as singletons inside + * programs and must not be freed. + * + * To obtain a TypeInterface for a known C++ type, use typeOf<>() or + * typeFromSignature(). + * + * Great care must be taken when manipulating storage: depending on the + * circunstances, it can point to a value allocated by the TypeInterface on + * the heap, or to a user-provided value on the heap or on the stack. + * + * As an example, here is a type erased union: + * + * @code + * struct MyUnion { + * enum Type type; + * union Data { + * int i; + * float f; + * } data; + * }; + * + * +-----------------------+ <-- storage of Dynamic + * | Type type | + * | +-------------------+ | <-- storage returned when get() is called + * | | int i / float f | | + * | +-------------------+ | + * +-----------------------+ + * @endcode + * + * DynamicTypeInterface::get() checks the type with the internal Type enum + * and returns a reference with the right TypeInterface to manipulate the + * inner data and a pointer to that inner data. + * + * This base TypeInterface has all the operations we need on any type: + * + * - cloning/destruction in clone() and destroy() + * - Access to value from storage and storage creation in + * ptrFromStorage() and initializeStorage() + * - Type of specialized interface through kind() + * + * Our aim is to transport arbitrary values through: + * + * - synchronous calls: Nothing to do, values are just transported and + * converted. + * - asynchronous call/thread change: Values are copied. + * - process change: Values are serialized. + */ + class QITYPE_API TypeInterface + { + public: + /// Get the TypeInfo corresponding to this type. + virtual const TypeInfo& info() =0; + + /** + * Initialize and return a new storage, from nothing or a T*. + * + * If ptr is not null, it should be used as a storage (the method can + * usually just return ptr in that case). + */ + virtual void* initializeStorage(void* ptr=0)=0; + + /** + * Get pointer to type from pointer to storage. + * + * This allows for storing an integer value (for instance) directily into + * the pointer and avoid an allocation. + * + * This method should be called on storage before casting it to a specific + * type. + */ + // Use a pointer and not a reference to avoid the case where the compiler makes a copy on the stack + virtual void* ptrFromStorage(void**)=0; + + /// Allocate a storage and copy the value given as an argument. + virtual void* clone(void*)=0; + /// Free all resources of a storage + virtual void destroy(void*)=0; + + /** + * Get the kind of the data. + * + * This is used to downcast the TypeInterface object to a specialized + * interface. + */ + virtual TypeKind kind(); + + /** + * Return true if a is less than b + * + * Less must always work: compare pointers if you have to. + */ + virtual bool less(void* a, void* b) = 0; + + //TODO: DIE + inline const char* infoString() { return info().asCString(); } // for easy gdb access + + /** @return the serialization signature corresponding to what the type + * would emit + * @param resolveDynamic: if true, resolve dynamic types as deep as possible + * for example a list that happens to only contain int32 + * will return [i] + * @warning if resolveDynamic is true, a valid storage must be given + */ + qi::Signature signature(void* storage=0, bool resolveDynamic = false); + + ///@return a Type on which signature() returns sig. + static TypeInterface* fromSignature(const qi::Signature& sig); + }; + + /// Runtime Type factory getter. Used by typeOf() + QITYPE_API TypeInterface* getType(const std::type_info& type); + + /// Runtime Type factory setter. + QITYPE_API bool registerType(const std::type_info& typeId, TypeInterface* type); + + /** Get type from a type. Will return a static TypeImpl if T is not registered + */ + template TypeInterface* typeOf(); + + /// Get type from a value. No need to delete the result + template TypeInterface* typeOf(const T& v) + { + return typeOf(); + } + + /** Register type for signature -> TypeInterface factory. + */ + QITYPE_API void registerStruct(TypeInterface* type); + /// @Return matchin TypeInterface registered by registerStruct() or 0. + QITYPE_API TypeInterface* getRegisteredStruct(const qi::Signature& s); +} + + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_DETAILS_TYPEINTERFACE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/dynamicobject.hpp b/naoModule/libnaoqi_files/include/qitype/dynamicobject.hpp new file mode 100755 index 0000000..39c2400 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/dynamicobject.hpp @@ -0,0 +1,94 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DYNAMICOBJECT_HPP_ +#define _QITYPE_DYNAMICOBJECT_HPP_ + +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi +{ + + class DynamicObjectPrivate; + + /** A Dynamic object is an object that handles all signal/method operation + * itself. + * + * Signal handling: + * The default implementation is creating a SignalBase for each MetaSignal in + * the MetaObject, and bounces metaPost(), connect() and disconnect() to it. + * + * Method handling: + * The default implementation holds a method list that the user must populate + * with setMethod() + */ + class QITYPE_API DynamicObject { + public: + DynamicObject(); + + virtual ~DynamicObject(); + + /// You *must* call DynamicObject::setMetaObject() if you overload this method. + virtual void setMetaObject(const MetaObject& mo); + + + MetaObject &metaObject(); + + void setMethod(unsigned int id, AnyFunction callable, MetaCallType threadingModel = MetaCallType_Auto); + void setSignal(unsigned int id, SignalBase* signal); + void setProperty(unsigned int id, PropertyBase* property); + + const AnyFunction& method(unsigned int id) const; + SignalBase* signal(unsigned int id) const; + PropertyBase* property(unsigned int) const; + + virtual qi::Future metaCall(AnyObject context, unsigned int method, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSignature=Signature()); + virtual void metaPost(AnyObject context, unsigned int event, const GenericFunctionParameters& params); + /// Calls given functor when event is fired. Takes ownership of functor. + virtual qi::Future metaConnect(unsigned int event, const SignalSubscriber& subscriber); + /// Disconnect an event link. Returns if disconnection was successful. + virtual qi::Future metaDisconnect(SignalLink linkId); + virtual qi::Future metaProperty(unsigned int id); + virtual qi::Future metaSetProperty(unsigned int id, AnyValue val); + + void setThreadingModel(ObjectThreadingModel model); + ObjectThreadingModel threadingModel() const; + // internal use, call once to update with Manageable methods and signals + void setManageable(Manageable* m); + // C4251 + boost::shared_ptr _p; + }; + + //Make an AnyObject of DynamicObject kind from a DynamicObject + QITYPE_API AnyObject makeDynamicAnyObject(DynamicObject *obj, bool destroyObject = true, + boost::function onDelete = boost::function()); + + QITYPE_API AnyObject makeDynamicSharedAnyObjectImpl(DynamicObject* obj, boost::shared_ptr other); + + /** Make an AnyObject that shares its ref counter with \p other + * Note that \p obj will not be destroyed when the shared counter reaches 0. + */ + template + inline AnyObject makeDynamicSharedAnyObject(DynamicObject *obj, boost::shared_ptr other) + { + return makeDynamicSharedAnyObjectImpl(obj, boost::shared_ptr(other, 0)); + } + + + QITYPE_API ObjectTypeInterface* getDynamicTypeInterface(); +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_DYNAMICOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/dynamicobjectbuilder.hpp b/naoModule/libnaoqi_files/include/qitype/dynamicobjectbuilder.hpp new file mode 100755 index 0000000..354f002 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/dynamicobjectbuilder.hpp @@ -0,0 +1,102 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_DYNAMICOBJECTBUILDER_HPP_ +#define _QITYPE_DYNAMICOBJECTBUILDER_HPP_ + +#include +#include +#include + +namespace qi { + + class DynamicObject; + class DynamicObjectBuilderPrivate; + class QITYPE_API DynamicObjectBuilder : private boost::noncopyable + { + public: + DynamicObjectBuilder(); + DynamicObjectBuilder(DynamicObject *dynobject, bool deleteOnDestroy = true); + + ~DynamicObjectBuilder(); + + // throw on error + template + inline unsigned int advertiseMethod(const std::string& name, + OBJECT_TYPE object, + METHOD_TYPE method, + const std::string& desc = "", + MetaCallType threadingModel = MetaCallType_Auto); + + // throw on error + template + inline unsigned int advertiseMethod(const std::string& name, + FUNCTION_TYPE function, + const std::string& desc = "", + MetaCallType threadingModel = MetaCallType_Auto); + + // throw on error + template + inline unsigned int advertiseMethod(MetaMethodBuilder& builder, + OBJECT_TYPE object, + METHOD_TYPE method, + MetaCallType threadingModel = MetaCallType_Auto); + + // throw on error + template + inline unsigned int advertiseMethod(MetaMethodBuilder& builder, + FUNCTION_TYPE function, + MetaCallType threadingModel = MetaCallType_Auto); + + unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + template unsigned int advertiseSignal(const std::string& name); + + /// Advertise a signal using a function signature + template + unsigned int advertiseSignalF(const std::string& name); + + unsigned int advertiseSignal(const std::string &name, qi::SignalBase *signal); + + template + unsigned int advertiseProperty(const std::string& name); + /// Ownership is transferred to the object + unsigned int advertiseProperty(const std::string &name, qi::PropertyBase *sig); + + void setThreadingModel(ObjectThreadingModel model); + + unsigned int xAdvertiseMethod(const Signature &sigret, + const std::string &name, + const Signature &signature, + AnyFunction func, const std::string& desc = "", + MetaCallType threadingModel = MetaCallType_Auto); + + unsigned int xAdvertiseMethod(MetaMethodBuilder& builder, AnyFunction func, + MetaCallType threadingModel = MetaCallType_Auto); + + unsigned int xAdvertiseSignal(const std::string &name, const Signature &signature); + unsigned int xAdvertiseProperty(const std::string& name, const Signature& sig, int id=-1); + void setDescription(const std::string& desc); + qi::AnyObject object(boost::function onDelete = boost::function()); + /// Return an AnyObject that shares life type with \p other. + template qi::AnyObject object(boost::shared_ptr other); + void markProperty(unsigned int ev, unsigned int getter, unsigned int setter); + private: + DynamicObject* bareObject(); + void setManageable(DynamicObject* obj, Manageable* m); + DynamicObjectBuilderPrivate *_p; + }; +} + +#include + +#endif // _QITYPE_DYNAMICOBJECTBUILDER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/fwd.hpp b/naoModule/libnaoqi_files/include/qitype/fwd.hpp new file mode 100755 index 0000000..58ee7a9 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/fwd.hpp @@ -0,0 +1,76 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_FWD_HPP_ +#define _QITYPE_FWD_HPP_ + +#include +#include +#include + +namespace qi +{ + class TypeInfo; + + class TypeInterface; + class IntTypeInterface; + class FloatTypeInterface; + class StringTypeInterface; + class RawTypeInterface; + class PointerTypeInterface; + class ListTypeInterface; + class MapTypeInterface; + class StructTypeInterface; + class DynamicTypeInterface; + + class AutoAnyReference; + + class AnyReference; + typedef std::vector AnyReferenceVector; + + class AnyValue; + typedef std::vector AnyValueVector; + + class AnyIterator; + + class Manageable; + + class Empty; + class Proxy; + template class Object; + typedef Object AnyObject; + template class WeakObject; + typedef WeakObject AnyWeakObject; + + class GenericObject; + + class Signature; + + //warning update the C enum when updating this one. + enum TypeKind + { + TypeKind_Unknown = 0, + TypeKind_Void = 1, + TypeKind_Int = 2, + TypeKind_Float = 3, + TypeKind_String = 4, + TypeKind_List = 5, + TypeKind_Map = 6, + TypeKind_Object = 7, + TypeKind_Pointer = 8, + TypeKind_Tuple = 9, + TypeKind_Dynamic = 10, + TypeKind_Raw = 11, + TypeKind_Iterator = 13, + TypeKind_Function = 14, + TypeKind_Signal = 15, + TypeKind_Property = 16, + TypeKind_VarArgs = 17, + }; + +} + +#endif // _QITYPE_FWD_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/jsoncodec.hpp b/naoModule/libnaoqi_files/include/qitype/jsoncodec.hpp new file mode 100755 index 0000000..21dcfe6 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/jsoncodec.hpp @@ -0,0 +1,41 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_JSONCODEC_HPP_ +#define _QITYPE_JSONCODEC_HPP_ + +#include +#include + +namespace qi { + + /** @return the value encoded in JSON. + */ + QITYPE_API std::string encodeJSON(const qi::AutoAnyReference &val); + + /** + * creates a GV representing a JSON string or throw on parse error. + * @param JSON string to decode. + * @return a GV representing the JSON string + */ + QITYPE_API qi::AnyValue decodeJSON(const std::string &in); + + /** + * set the input GV to represent the JSON sequence between two string iterators or throw on parse error. + * @param iterator to the beginning of the sequence to decode. + * @param iterator to the end of the sequence to decode. + * @param GV to set. Not modified if an error occured. + * @return an iterator to the last read char + 1 + */ + QITYPE_API std::string::const_iterator decodeJSON(const std::string::const_iterator &begin, + const std::string::const_iterator &end, + AnyValue &target); + + + +} + +#endif // _QITYPE_JSONCODEC_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/manageable.hpp b/naoModule/libnaoqi_files/include/qitype/manageable.hpp new file mode 100755 index 0000000..07fc720 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/manageable.hpp @@ -0,0 +1,170 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_MANAGEABLE_HPP_ +#define _QITYPE_MANAGEABLE_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) // dll interface +#endif + +namespace qi { + + class ManageablePrivate; + class EventLoop; + + /// Possible thread models for an object + enum ObjectThreadingModel + { + /// Object is not thread safe, all method calls must occur in the same thread + ObjectThreadingModel_SingleThread = 0, + /// Object is thread safe, multiple calls can occur in different threads in parallel + ObjectThreadingModel_MultiThread = 1, + + ObjectThreadingModel_Default = ObjectThreadingModel_SingleThread + }; + + + class EventTrace + { + public: + enum EventKind + { + Event_Call = 1, + Event_Result = 2, + Event_Error = 3, + Event_Signal = 4 + }; + EventTrace() {} + EventTrace(unsigned int id, EventKind kind, unsigned int slotId, + const AnyValue& arguments, const qi::os::timeval timestamp, + qi::int64_t userUsTime=0, qi::int64_t systemUsTime=0, + unsigned int callerContext=0, unsigned int calleeContext=0, + qi::os::timeval postTimestamp = qi::os::timeval()) + : _id(id), _kind(kind), _slotId(slotId), _arguments(arguments), + _timestamp(timestamp), _postTimestamp(postTimestamp), _userUsTime(userUsTime), _systemUsTime(systemUsTime), + _callerContext(callerContext), _calleeContext(calleeContext) + {} + + // trace id, used to match call and call result + const unsigned int& id() const { return _id;} + const EventKind& kind() const { return _kind;} + // method or signal id + const unsigned int& slotId() const { return _slotId;} + // call or signal arguments + const AnyValue& arguments() const { return _arguments;} + const qi::os::timeval& timestamp() const { return _timestamp;} + const qi::os::timeval& postTimestamp() const { return _postTimestamp;} + const qi::int64_t& userUsTime() const { return _userUsTime;} + const qi::int64_t& systemUsTime() const { return _systemUsTime;} + const unsigned int& callerContext() const { return _callerContext;} + const unsigned int& calleeContext() const { return _calleeContext;} + + private: + unsigned int _id; // trace id, used to match call and call result + EventKind _kind; + unsigned int _slotId; // method or signal id + AnyValue _arguments; // call or signal arguments + qi::os::timeval _timestamp; + qi::os::timeval _postTimestamp; // timestamp of eventual post call + qi::int64_t _userUsTime; + qi::int64_t _systemUsTime; + unsigned int _callerContext; // context of caller function + unsigned int _calleeContext; // context where method runs + }; + + typedef std::map ObjectStatistics; +/** Per-instance context. + */ + class QITYPE_API Manageable + { + public: + Manageable(); + ~Manageable(); + Manageable(const Manageable& b); + void operator = (const Manageable& b); + + + /// Override all ThreadingModel and force dispatch to given event loop. + void forceEventLoop(EventLoop* eventLoop); + ///@return forced event loop or 0 if not set + EventLoop* eventLoop() const; + + typedef boost::shared_ptr TimedMutexPtr; + ///@return the mutex associated with managed object. + TimedMutexPtr mutex(); // non-recursive of course! + + /// @{ + /** Statistics gathering/retreiving API + * + */ + ///@return if statistics gatehering is enabled + bool isStatsEnabled() const; + /// Set statistics gathering status + void enableStats(bool enable); + /// Push statistics information about \p slotId. + void pushStats(int slotId, float wallTime, float userTime, float systemTime); + ObjectStatistics stats() const; + /// Reset all statistical data + void clearStats(); + + /// Emitted each time a call starts and finishes, and for each signal trigger. + Signal traceObject; + + ///@return if trace mode is enabled + bool isTraceEnabled() const; + /** Set trace mode state. + * + * @warning This function should usually not be called directly. + * Connecting/disconnecting to the traceObject signal automatically + * enables/disables tracing mode. + * + * When enabled, all calls and signal triggers will be reported through the + * "traceObject" signal. + * + */ + void enableTrace(bool enable); + /// @} + + /// Starting id of features handled by Manageable + static const uint32_t startId = 80; + /// Stop id of features handled by Manageable + static const uint32_t endId = 99; + typedef std::map + > MethodMap; + typedef boost::function SignalGetter; + typedef std::map SignalMap; + SignalMap signalMap; + /* Return the methods and signals defined at GenericObject level. + * The 'this' argument must be the Manageable*. + */ + static MethodMap& manageableMmethodMap(); + static SignalMap& manageableSignalMap(); + static MetaObject& manageableMetaObject(); + static void _build(); + int _nextTraceId(); + ManageablePrivate* _p; + }; +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +QI_TYPE_ENUM_REGISTER(qi::EventTrace::EventKind); +#endif // _QITYPE_MANAGEABLE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/metamethod.hpp b/naoModule/libnaoqi_files/include/qitype/metamethod.hpp new file mode 100755 index 0000000..433ff2d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/metamethod.hpp @@ -0,0 +1,99 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_METAMETHOD_HPP_ +#define _QITYPE_METAMETHOD_HPP_ + +# include +# include + +# include +# include + +# ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +# endif + +namespace qi { + class MetaMethodParameterPrivate; + class AnyFunction; + class QITYPE_API MetaMethodParameter { + public: + MetaMethodParameter(); + MetaMethodParameter(const MetaMethodParameter& other); + MetaMethodParameter(const std::string& name, const std::string& doc); + ~MetaMethodParameter(); + + MetaMethodParameter& operator= (const MetaMethodParameter& other); + + std::string name() const; + std::string description() const; + + MetaMethodParameterPrivate* _p; + }; + typedef std::vector MetaMethodParameterVector; + + class MetaMethodPrivate; + /// Representation of a method in an GenericObject. + class QITYPE_API MetaMethod { + public: + MetaMethod(); + MetaMethod(unsigned int newUid, const MetaMethod& other); + + unsigned int uid() const; + const std::string& name() const; + std::string toString() const; //< name::(args) + const Signature& parametersSignature() const; + const Signature& returnSignature() const; + std::string description() const; + MetaMethodParameterVector parameters() const; + std::string returnDescription() const; + + /** return true if method is considered internal, and should not be listed + */ + bool isPrivate() const; + + boost::shared_ptr _p; + + MetaMethod(unsigned int uid, const qi::Signature& returnSignature, + const std::string& name, const qi::Signature& parametersSignature, + const std::string& description, const MetaMethodParameterVector& parameters, + const std::string& returnDescription); + }; + + class MetaMethodBuilderPrivate; + class QITYPE_API MetaMethodBuilder { + public: + MetaMethodBuilder(); + MetaMethodBuilder(const Signature &sigreturn, const std::string& name, const Signature &signature, const std::string& doc = ""); + MetaMethodBuilder(const MetaMethodBuilder& other); + ~MetaMethodBuilder(); + + MetaMethodBuilder& operator= (const MetaMethodBuilder& other); + + std::string name() const; + + void setUid(unsigned int uid); + void setSignature(const AnyFunction& f); + void setReturnSignature(const Signature &sig); + void setName(const std::string& name); + void setParametersSignature(const qi::Signature& sig); + void setReturnDescription(const std::string& doc); + void appendParameter(const std::string& name, const std::string& documentation); + void setDescription(const std::string& documentation); + + qi::MetaMethod metaMethod(); + + MetaMethodBuilderPrivate* _p; + }; +} // namespace qi + +# ifdef _MSC_VER +# pragma warning( pop ) +# endif + +#endif // _QITYPE_METAMETHOD_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/metaobject.hpp b/naoModule/libnaoqi_files/include/qitype/metaobject.hpp new file mode 100755 index 0000000..591515b --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/metaobject.hpp @@ -0,0 +1,179 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_METAOBJECT_HPP_ +#define _QITYPE_METAOBJECT_HPP_ + +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + class MetaObjectPrivate; + class GenericFunctionParameters; + + /// Description of the signals and methods accessible on an ObjectTypeInterface + class QITYPE_API MetaObject { + public: + MetaObject(); + MetaObject(const MetaObject &other); + MetaObject& operator=(const MetaObject &other); + ~MetaObject(); + + /** + * @param name The method's name. + * @return The method's id or -1 if the method wasn't found. + */ + int methodId(const std::string &name) const; + /** + * @param name The name of the signal or its full signature. + * @return The signal's id or -1 if the signal wasn't found. + */ + int signalId(const std::string &name) const; + /** + * @param name The property's name. + * @return The property's id or -1 if the property wasn't found. + */ + int propertyId(const std::string& name) const; + + typedef std::map MethodMap; + /** + * @return The map of all the methods. + */ + MethodMap methodMap() const; + + //not called signals because it conflict with Qt keywords :S + typedef std::map SignalMap; + /** + * @return The map of all the signals. + */ + SignalMap signalMap() const; + + typedef std::map PropertyMap; + /** + * @return The map of all the properties. + */ + PropertyMap propertyMap() const; + + /** + * @param id The method's id. + * @return The desired method or null if the id is invalid. + */ + MetaMethod* method(unsigned int id); + const MetaMethod* method(unsigned int id) const; + + /** + * @param id The signal's id. + * @return The desired signal or null if the id is invalid. + */ + MetaSignal* signal(unsigned int id); + const MetaSignal* signal(unsigned int id) const; + /** + * @param name The name of the signal or its full signature. + * @return The desired signal or null if the signal wasn't found. + */ + const MetaSignal* signal(const std::string &name) const; + + /** + * @param id The property's id. + * @return The desired property of null if the id is invalid. + */ + MetaProperty* property(unsigned int id); + const MetaProperty* property(unsigned int id) const; + + /** Find a method matching @param nameWithOptionalSignature that can be + * called with arguments @param args. + * @return The mathing method id, or -1 if none or an ambiguous set was found. + * @warning This method optimises for speed at the expense of possible false positive: + * It returns a match as soon as there is only one possible candidate + * remaining, even though this candidate can prove later on to be + * incompatible with the arguments. + * @param nameWithOptionalSignature The method's name or its full signature. + * @param args The parameters' type of the method. + * @param canCache If set, will be filled with true if the returned method + * can be cached regardless of the arguments types (but not argument count), + * and false otherwise. + */ + int findMethod(const std::string& nameWithOptionalSignature, const GenericFunctionParameters& args, bool* canCache=0) const; + /** + * @param name The exact method's name. + * @return A vector containing all the overloaded version of the method. + */ + std::vector findMethod(const std::string &name) const; + typedef std::pair CompatibleMethod; + /** Find all the methods compatible with @param nameOrSignature. If no + * signature is specified, the method relies on findMethod. + * @param nameOrSignature Either the name or the signature of the method. + * @return A vector containing all the compatible method and their + * associated compatibility's score. + */ + std::vector findCompatibleMethod(const std::string &nameOrSignature) const; + + /** + * @param name The member's name. + * @param uid The uid's name. + * @return True if the member is considered internal, and should not be + * listed. + */ + static bool isPrivateMember(const std::string &name, unsigned int uid); + + /** Merge two MetaObject. Dest method and signal ids will be incremented by offset. + * @param source The source object. + * @param dest The destination object. + * @return The merge's result of the two objects. + */ + static qi::MetaObject merge(const qi::MetaObject &source, const qi::MetaObject &dest); + + /** + * @return The object's description. + */ + std::string description() const; + + MetaObjectPrivate *_p; + MetaObject(const MethodMap& methodMap, const SignalMap& signalMap, + const PropertyMap& propertyMap, const std::string& description); + }; + + bool QITYPE_API operator < (const MetaObject& a, const MetaObject& b); + + class MetaObjectBuilderPrivate; + class QITYPE_API MetaObjectBuilder { + public: + MetaObjectBuilder(); + + void setDescription(const std::string& desc); + unsigned int addMethod(const qi::Signature &sigret, + const std::string &name, + const qi::Signature &signature, + int id = -1); + unsigned int addMethod(MetaMethodBuilder& builder, int id = -1); + unsigned int addSignal(const std::string &name, const qi::Signature& sig, int id = -1); + unsigned int addProperty(const std::string& name, const qi::Signature& sig, int id = -1); + qi::MetaObject metaObject(); + + private: + // C4251 + boost::shared_ptr _p; + }; + + namespace details { + QITYPE_API void printMetaObject(std::ostream &stream, const qi::MetaObject &metaObject, bool color=true, bool showHidden=false, bool showDoc=false, bool raw=false, bool parseable=false); + } + +} + + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_METAOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/metaproperty.hpp b/naoModule/libnaoqi_files/include/qitype/metaproperty.hpp new file mode 100755 index 0000000..02b6164 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/metaproperty.hpp @@ -0,0 +1,52 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_METAPROPERTY_HPP_ +#define _QITYPE_METAPROPERTY_HPP_ + +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi +{ + class QITYPE_API MetaProperty + { + public: + MetaProperty(unsigned int uid, const std::string& name, const qi::Signature& sig); + MetaProperty(); + const std::string& name() const; + const qi::Signature& signature() const; + std::string toString() const; + unsigned int uid() const; + + /** return true if property is considered internal, and should not be listed + */ + bool isPrivate() const; + + private: + unsigned int _uid; + std::string _name; + qi::Signature _signature; + QI_TYPE_STRUCT_PRIVATE_ACCESS(MetaProperty); + }; +} + + +QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(qi::MetaProperty, + ("uid",_uid), + ("name",_name), + ("signature", _signature)); + + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_METAPROPERTY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/metasignal.hpp b/naoModule/libnaoqi_files/include/qitype/metasignal.hpp new file mode 100755 index 0000000..f992482 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/metasignal.hpp @@ -0,0 +1,54 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_METASIGNAL_HPP_ +#define _QITYPE_METASIGNAL_HPP_ + +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + /// Representation of a Signal in an GenericObject. + class QITYPE_API MetaSignal { + public: + MetaSignal(unsigned int uid, const std::string &name, const qi::Signature &sig); + MetaSignal(); + ~MetaSignal(); + + const std::string &name() const; + std::string toString() const; // name::(sig) + const Signature ¶metersSignature() const; + unsigned int uid() const; + + /** return true if signal is considered internal, and should not be listed + */ + bool isPrivate() const; + + private: + unsigned int _uid; + // C4251 + std::string _name; + qi::Signature _signature; + QI_TYPE_STRUCT_PRIVATE_ACCESS(MetaSignal); + }; + +}; // namespace qi + +QI_TYPE_STRUCT_AGREGATE_CONSTRUCTOR(qi::MetaSignal, + ("uid",_uid), + ("name",_name), + ("signature", _signature)); + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_METASIGNAL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/objectfactory.hpp b/naoModule/libnaoqi_files/include/qitype/objectfactory.hpp new file mode 100755 index 0000000..b35f61d --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/objectfactory.hpp @@ -0,0 +1,109 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_OBJECTFACTORY_HPP_ +#define _QITYPE_OBJECTFACTORY_HPP_ + +#include + +#include + +#include +#include +#include +#include +#include +#include + +namespace qi { + + QITYPE_API bool registerObjectFactory(const std::string& name, AnyFunction factory); + + QITYPE_API qi::AnyObject createObject(const std::string& name, const AnyReferenceVector& args); + + // we need this to be inline to avoid the multiple definition problem for + // createObject(std::string) (no custom argument), we need variadic + // templates... + #define pushi(z, n, _) params.push_back(AnyReference::from(p ## n)); + #define genCall(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + QI_GEN_MAYBE_TEMPLATE_OPEN(comma) ATYPEDECL QI_GEN_MAYBE_TEMPLATE_CLOSE(comma) \ + inline \ + AnyObject createObject(const std::string& name comma ADECL) \ + { \ + std::vector params; \ + params.reserve(n); \ + BOOST_PP_REPEAT(n, pushi, _) \ + return createObject(name, params); \ + } + QI_GEN(genCall) + #undef genCall + #undef pushi + + /// Get all factory names. Order is guaranteed to be the registration order + QITYPE_API std::vector listObjectFactories(); + + /// Load a shared library and return the list of new available factory names. + QITYPE_API std::vector loadObject(const std::string& name, int flags = -1); +} + +/// register \p func as factory for object named \p name +#define QI_REGISTER_OBJECT_FACTORY(name, func) \ + static bool BOOST_PP_CAT(_register_factory_ ,__COUNTER__) = ::qi::registerObjectFactory(name, func) + +/** register \p name's constructor as factory for \p name + * + * @param name class name + * @param args... constructor arguments + * + * @example + * QI_REGISTER_OBJECT_FACTORY_CONSTRUCTOR(MyClass, std::string, int, int); + */ +#define QI_REGISTER_OBJECT_FACTORY_CONSTRUCTOR(...) \ + QI_REGISTER_OBJECT_FACTORY(BOOST_PP_STRINGIZE(QI_LIST_HEAD(QI_LIST(__VA_ARGS__,))), qi::AnyFunction::from(&::qi::detail::constructObject<__VA_ARGS__>)) + +/** register \p cls's default constructor as factory for \p name + * + * @param name factory name + * @param cls class name + * @param args... constructor arguments + * + * @example + * QI_REGISTER_OBJECT_FACTORY_CONSTRUCTOR(ObjectFactory, MyClass, std::string, int, int); + */ +#define QI_REGISTER_OBJECT_FACTORY_CONSTRUCTOR_FOR(name, ...) \ + QI_REGISTER_OBJECT_FACTORY(#name, ::qi::AnyFunction::from(&::qi::detail::constructObject<__VA_ARGS__>)) + +/** Register a factory on \p name that creates an object with a single method + * \p func named \p funcName + */ +#define QI_REGISTER_OBJECT_FACTORY_METHOD(name, funcName, func) \ + QI_REGISTER_OBJECT_FACTORY(name, ::qi::AnyFunction::from(::qi::detail::makeObjectFactory(funcName, func))) + + +/** Register an object as a factory for another object + * + * @param name target class name + * @param args... constructor arguments + * + * Will crate a factory for generated object 'name + "Service"', with a + * create() method * that returns a newly created instance of \p name. + */ +#define QI_REGISTER_OBJECT_FACTORY_BUILDER(...) \ + QI_REGISTER_OBJECT_FACTORY_METHOD(BOOST_PP_STRINGIZE(QI_LIST_HEAD(QI_LIST(__VA_ARGS__,))) "Service", "create", (&::qi::detail::constructObject<__VA_ARGS__>)) + +/** Register an object as a factory for another object with a custom name + * + * @param name factory name + * @param cls target class name + * @param args... constructor arguments + * + * Will crate a factory for generated object 'name + "Service"', with a + * create() method * that returns a newly created instance of \p name. + */ +#define QI_REGISTER_OBJECT_FACTORY_BUILDER_FOR(name, ...) \ + QI_REGISTER_OBJECT_FACTORY_METHOD(#name "Service", "create", (&::qi::detail::constructObject<__VA_ARGS__>)) + +#endif // _QITYPE_OBJECTFACTORY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/objecttypebuilder.hpp b/naoModule/libnaoqi_files/include/qitype/objecttypebuilder.hpp new file mode 100755 index 0000000..937b905 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/objecttypebuilder.hpp @@ -0,0 +1,146 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_OBJECTTYPEBUILDER_HPP_ +#define _QITYPE_OBJECTTYPEBUILDER_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + + +namespace qi { + + class MetaObject; + + class SignalBase; + class ObjectTypeInterface; + class TypeInterface; + template class SignalF; + class ObjectTypeBuilderPrivate; + struct ObjectTypeData; + class QITYPE_API ObjectTypeBuilderBase + { + public: + ObjectTypeBuilderBase(); + ~ObjectTypeBuilderBase(); + + typedef boost::function SignalMemberGetter; + typedef boost::function PropertyMemberGetter; + + // input: template-based + + /// Declare the class type for which this StaticBuilder is. + template void buildFor(bool autoRegister = true); + + template + inline unsigned int advertiseMethod(const std::string& name, FUNCTION_TYPE function, MetaCallType threadingModel = MetaCallType_Auto, int id = -1); + + template + inline unsigned int advertiseMethod(MetaMethodBuilder& name, FUNCTION_TYPE function, MetaCallType threadingModel = MetaCallType_Auto, int id = -1); + + template + unsigned int advertiseSignal(const std::string& eventName, A accessor, int id = -1); + + template + inline unsigned int advertiseSignal(const std::string& name, SignalMemberGetter getter, int id = -1); + + template + inline unsigned int advertiseProperty(const std::string& propertyName, A accessor); + + template + inline unsigned int advertiseProperty(const std::string& eventName, PropertyMemberGetter getter); + + template + void inherits(int offset); + + // Advertise anything, dispatch on {method, event, property} based on T. + template + ObjectTypeBuilderBase& advertise(const std::string& name, T element); + // Like advertise, but return the id + template + unsigned int advertiseId(const std::string& name, T element); + // input: type-erased + + unsigned int xAdvertiseMethod(MetaMethodBuilder& builder, AnyFunction func, MetaCallType threadingModel = MetaCallType_Auto, int id = -1); + unsigned int xAdvertiseSignal(const std::string &name, const qi::Signature& signature, SignalMemberGetter getter, int id = -1); + unsigned int xAdvertiseProperty(const std::string& name, const qi::Signature& signature, PropertyMemberGetter getter, int id = -1); + void xBuildFor(TypeInterface* type, bool autoRegister = true); + void inherits(TypeInterface* parentType, int offset); + + // Configuration + + void setThreadingModel(ObjectThreadingModel model); + + // output + const MetaObject& metaObject(); + AnyObject object(void* ptr, boost::function onDestroy = boost::function()); + ObjectTypeInterface* type(); + + /// Register type to typeof. Called by type() + inline virtual void registerType() {}; + + const ObjectTypeData& typeData(); + private: + ObjectTypeBuilderPrivate* _p; + }; + + template + class ObjectTypeBuilder : public ObjectTypeBuilderBase + { + public: + ObjectTypeBuilder(bool autoRegister=true) + { + buildFor(autoRegister); + } + + /** Declare that T inherits from U. + * + * @warning If type \p U has registered methods,signals, properties, + * then inherits() must be called before registering anything on type T. + */ + template void inherits(); + + template + inline unsigned int advertiseMethod(const std::string& name, + FUNCTION_TYPE function, + MetaCallType threadingModel = MetaCallType_Auto, + int id = -1); + + template + inline unsigned int advertiseMethod(MetaMethodBuilder& name, + FUNCTION_TYPE function, + MetaCallType threadingModel = MetaCallType_Auto, + int id = -1); + + + /// Register type to typeOf, to avoid both TypeImpl and type() being present + inline virtual void registerType(); + + inline AnyObject object(T* ptr, boost::function onDestroy = boost::function()); + }; +} + +#include +// FIXME move this, objecttypebuilder might not be included +QI_REGISTER_TEMPLATE_OBJECT(qi::Future , _connect, isFinished, value, wait, isRunning, isCanceled, hasError, error); +QI_REGISTER_TEMPLATE_OBJECT(qi::FutureSync, _connect, isFinished, value, wait, isRunning, isCanceled, hasError, error, async); +QI_REGISTER_TEMPLATE_OBJECT(qi::Promise, setValue, setError, setCanceled, reset, future, value, trigger); +namespace qi { namespace detail { + template struct TypeManager >: public TypeManagerDefaultStruct > {}; + template struct TypeManager >: public TypeManagerDefaultStruct > {}; + template struct TypeManager >: public TypeManagerDefaultStruct > {}; + +}} + +#endif // _QITYPE_OBJECTTYPEBUILDER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/property.hpp b/naoModule/libnaoqi_files/include/qitype/property.hpp new file mode 100755 index 0000000..c49d747 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/property.hpp @@ -0,0 +1,126 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_PROPERTY_HPP_ +#define _QITYPE_PROPERTY_HPP_ + +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) + // needs to have dll-interface to be used by clients +# pragma warning( disable: 4251 ) + // non dll-interface class * used as base for dll-interface class +# pragma warning( disable: 4275 ) +#endif + +namespace qi +{ + + /** Type-erased virtual interface implemented by all Property classes. + */ + class QITYPE_API PropertyBase + { + public: + virtual ~PropertyBase() {} + virtual SignalBase* signal() = 0; + //TODO: why not AutoAnyReference? + virtual void setValue(AutoAnyReference value) = 0; + virtual AnyValue value() const = 0; + }; + + template + class PropertyImpl: public SignalF, public PropertyBase + { + public: + /** Setter called with storage containing old value, and new value + * Returns true to invoke subscribers, false to 'abort' the update. + */ + typedef boost::function Setter; + typedef boost::function Getter; + typedef SignalF SignalType; + typedef T PropertyType; + /** + * @param getter value getter, default to reading _value + * @param setter value setter, what it returns will be written to + * _value. If it throws AbortUpdate, update operation will + * be silently aborted (subscribers will not be called) + */ + PropertyImpl(Getter getter = Getter(), Setter setter = Setter(), + SignalBase::OnSubscribers onsubscribe = SignalBase::OnSubscribers()); + virtual ~PropertyImpl() {} + T get() const; + void set(const T& v); + void operator = (const T& v) { set(v);} + protected: + Getter _getter; + Setter _setter; + T _value; + }; + + template + class Property: public PropertyImpl + { + public: + typedef PropertyImpl ImplType; + typedef typename ImplType::Getter Getter; + typedef typename ImplType::Setter Setter; + Property(Getter getter = Getter(), Setter setter = Setter(), + SignalBase::OnSubscribers onsubscribe = SignalBase::OnSubscribers()) + : PropertyImpl(getter, setter, onsubscribe) + {} + virtual SignalBase* signal() { return this;} + virtual void setValue(AutoAnyReference value) { PropertyImpl::set(value.to());} + virtual AnyValue value() const { return AnyValue::from(PropertyImpl::get());} + }; + + template<> + class QITYPE_API Property: public PropertyImpl + { + public: + + Property(Getter getter = Getter(), Setter setter = Setter(), + SignalBase::OnSubscribers onsubscribe = SignalBase::OnSubscribers()) + : PropertyImpl(getter, setter, onsubscribe) + { + } + virtual SignalBase* signal() { return this;} + virtual void setValue(AutoAnyReference value) { set(AnyValue(value, false, false));} + virtual AnyValue value() const { return get();} + }; + + /// Type-erased property, simulating a typed property but using AnyValue. + class QITYPE_API GenericProperty: public Property + { + public: + GenericProperty(TypeInterface* type, Getter getter = Getter(), Setter setter = Setter()) + :Property(getter, setter) + , _type(type) + { // Initialize with default value for given type + set(AnyValue(_type)); + std::vector types(&_type, &_type + 1); + _setSignature(makeTupleSignature(types)); + } + virtual void setValue(AutoAnyReference value) { set(AnyValue(value, false, false));} + void set(const AnyValue& v); + virtual qi::Signature signature() const { + return makeTupleSignature(std::vector(&_type, &_type + 1)); + } + private: + TypeInterface* _type; + }; + + +} + +#include + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_PROPERTY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/proxyproperty.hpp b/naoModule/libnaoqi_files/include/qitype/proxyproperty.hpp new file mode 100755 index 0000000..4fe4efe --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/proxyproperty.hpp @@ -0,0 +1,130 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_PROXYPROPERTY_HPP_ +#define _QITYPE_PROXYPROPERTY_HPP_ + +#include +#include +#include + + +namespace qi +{ + /** Property proxy using AnyObject as backend + * @warning reading and writing the property are synchronous operations + * and might take time if backend object is a remote proxy. + */ + template + class ProxyProperty: public Property + { + public: + typedef SignalF SignalType; + ProxyProperty() {} + /* The signal bounce code is completely duplicated from SignalProxy. + * Unfortunately factoring this is not trivial: + * onSubscribe needs to be passed to Signal constructor, and we want to keep + * it that way. + */ + ProxyProperty(AnyObject object, const std::string& propertyName) + { + setup(object, propertyName); + } + void setup(AnyObject object, const std::string& propertyName); + ~ProxyProperty(); + void onSubscribe(bool enable, GenericObject* object, const std::string& propertyName, SignalLink link); + AnyReference bounceEvent(const AnyReferenceVector args); + void triggerOverride(const GenericFunctionParameters& params, MetaCallType, GenericObject* object, const std::string& propertyName); + private: + T getter(GenericObject* object, const std::string& propertyName); + bool setter(T&, const T&, GenericObject* object, const std::string& propertyName); + }; + + template + void makeProxyProperty(Property& target, AnyObject object, const std::string& signalName) + { + ProxyProperty& proxy = static_cast &>(target); + proxy.setup(object, signalName); + } + template + void makeProxyProperty(ProxyProperty& target, AnyObject object, const std::string& signalName) + { + target.setup(object, signalName); + } + + template + ProxyProperty::~ProxyProperty() + { + SignalType::disconnectAll(); + } + + template + void ProxyProperty::setup(AnyObject object, const std::string& propertyName) + { + // signal part + SignalBase::setOnSubscribers(boost::bind(&ProxyProperty::onSubscribe, this, _1, + object.asGenericObject(), propertyName, SignalBase::invalidSignalLink)); + SignalBase::setTriggerOverride(boost::bind(&ProxyProperty::triggerOverride, this, _1, _2, + object.asGenericObject(), propertyName)); + + // property part + this->_getter = boost::bind(&ProxyProperty::getter, this, object.asGenericObject(), propertyName); + this->_setter = boost::bind(&ProxyProperty::setter, this, _1, _2, object.asGenericObject(), propertyName); + } + + template + void ProxyProperty::onSubscribe(bool enable, GenericObject* object, const std::string& propertyName, SignalLink link) + { + if (enable) + { + link = object->connect(propertyName, + SignalSubscriber( + AnyFunction::fromDynamicFunction(boost::bind(&ProxyProperty::bounceEvent, this, _1)) + )); + } + else + { + bool ok = !object->disconnect(link).hasError(); + if (!ok) + qiLogError("qitype.proxysignal") << "Failed to disconnect from parent signal"; + link = SignalBase::invalidSignalLink; + } + // rebind onSubscribe since link changed + SignalBase::setOnSubscribers(boost::bind(&ProxyProperty::onSubscribe, this, _1, + object, propertyName, link)); + } + + template + AnyReference ProxyProperty::bounceEvent(const AnyReferenceVector args) + { + // Receive notify from backend, trigger on our signal, bypassing our trigger overload + SignalType::callSubscribers(args); + return AnyReference(typeOf()); + } + + template + void ProxyProperty::triggerOverride(const GenericFunctionParameters& params, MetaCallType, + GenericObject* object, const std::string& propertyName) + { + // Just forward to backend, which will notify us in bouceEvent(), + // and then we will notify our local Subscribers + object->metaPost(propertyName, params); + } + template + T ProxyProperty::getter(GenericObject* object, const std::string& propertyName) + { + return object->property(propertyName); + } + template + bool ProxyProperty::setter(T& target, const T& v, GenericObject* object, const std::string& propertyName) + { + // no need to fill target it's never used since we have a getter + object->setProperty(propertyName, v).value(); // throw on remote error + // Prevent local subscribers from being called + return false; + } +} +#endif // _QITYPE_PROXYPROPERTY_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/proxysignal.hpp b/naoModule/libnaoqi_files/include/qitype/proxysignal.hpp new file mode 100755 index 0000000..b54464b --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/proxysignal.hpp @@ -0,0 +1,105 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_PROXYSIGNAL_HPP_ +#define _QITYPE_PROXYSIGNAL_HPP_ + +#include +#include + +namespace qi +{ + + /// Signal proxy, using an AnyObject and signal id as backend. + template + class ProxySignal: public SignalF + { + public: + typedef SignalF SignalType; + ProxySignal(AnyObject object, const std::string& signalName) + : SignalType() + { + setup(object, signalName); + } + ProxySignal() {} + ~ProxySignal(); + void setup(AnyObject object, const std::string& signalName) + { + SignalBase::setOnSubscribers(boost::bind(&ProxySignal::onSubscribe, this, _1, + object.asGenericObject(), signalName, SignalBase::invalidSignalLink)); + SignalBase::setTriggerOverride(boost::bind(&ProxySignal::triggerOverride, this, _1, _2, + object.asGenericObject(), signalName)); + } + void onSubscribe(bool enable, GenericObject* object, std::string signalName, SignalLink link); + AnyReference bounceEvent(const AnyReferenceVector args); + void triggerOverride(const GenericFunctionParameters& params, + MetaCallType callType, GenericObject* object, std::string signalName); + }; + + template + void makeProxySignal(SignalF& target, AnyObject object, const std::string& signalName) + { + ProxySignal& proxy = static_cast &>(target); + proxy.setup(object, signalName); + } + + template + void makeProxySignal(ProxySignal& target, AnyObject object, const std::string& signalName) + { + target.setup(object, signalName); + } + + template + ProxySignal::~ProxySignal() + { + SignalType::disconnectAll(); // will invoke onsubscribe + } + + template + void ProxySignal::onSubscribe(bool enable, GenericObject* object, std::string signalName, + SignalLink link) + { + if (enable) + { + link = object->connect(signalName, + SignalSubscriber( + AnyFunction::fromDynamicFunction(boost::bind(&ProxySignal::bounceEvent, this, _1)) + )); + } + else + { + bool ok = !object->disconnect(link).hasError(); + if (!ok) + qiLogError("qitype.proxysignal") << "Failed to disconnect from parent signal"; + link = SignalBase::invalidSignalLink; + } + // link change, rebind ourselve + SignalBase::setOnSubscribers(boost::bind(&ProxySignal::onSubscribe, this, _1, + object, signalName, link)); + } + + template + AnyReference ProxySignal::bounceEvent(const AnyReferenceVector args) + { + // Trigger on our signal, bypassing our trigger overload + SignalType::callSubscribers(args); + return AnyReference(typeOf()); + } + + template + void ProxySignal::triggerOverride(const GenericFunctionParameters& params, MetaCallType, + GenericObject* object, std::string signalName) + { + // Just forward to backend, which will notify us in bouceEvent(), + // and then we will notify our local Subscribers + object->metaPost(signalName, params); + } + +} + + + +#endif // _QITYPE_PROXYSIGNAL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/signal.hpp b/naoModule/libnaoqi_files/include/qitype/signal.hpp new file mode 100755 index 0000000..05596a0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/signal.hpp @@ -0,0 +1,278 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_SIGNAL_HPP_ +#define _QITYPE_SIGNAL_HPP_ + +#include +#include + +#include +#include + +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +// Macro to be more expressive when emitting a signal. Does nothing, it's normal. +#define QI_EMIT + +namespace qi { + + class ManageablePrivate; + class SignalSubscriber; + class EventLoop; + + class SignalBasePrivate; + + typedef qi::uint64_t SignalLink; + + //Signal are not copyable, they belong to a class. + class QITYPE_API SignalBase : boost::noncopyable + { + public: + typedef boost::function OnSubscribers; + explicit SignalBase(const Signature &signature, OnSubscribers onSubscribers = OnSubscribers()); + SignalBase(OnSubscribers onSubscribers=OnSubscribers()); + virtual ~SignalBase(); + virtual qi::Signature signature() const; + template + SignalSubscriber& connect(const boost::function& func); + SignalSubscriber& connect(const SignalSubscriber& s); + SignalSubscriber& connect(AnyObject object, const unsigned int slot); + SignalSubscriber& connect(AnyObject object, const std::string& slot); + bool disconnectAll(); + + /** Disconnect a SignalHandler. The associated callback will not be called + * anymore as soon as this function returns, but might be called in an + * other thread while this function runs. + */ + bool disconnect(const SignalLink& link); + + /** Trigger the signal with given type-erased parameters. + * @param params the signal arguments + * @param callType specify how to invoke subscribers. + * Used in combination with each subscriber's MetaCallType to + * chose between synchronous and asynchronous call. + * The combination rule is to honor subscriber's override, then \p callType, + * then signal's callType and default to asynchronous + */ + virtual void trigger(const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto); + /// Set the MetaCallType used by operator()(). + void setCallType(MetaCallType callType); + /// Trigger the signal with given arguments, and call type set by setCallType() + void operator()( + qi::AutoAnyReference p1 = qi::AutoAnyReference(), + qi::AutoAnyReference p2 = qi::AutoAnyReference(), + qi::AutoAnyReference p3 = qi::AutoAnyReference(), + qi::AutoAnyReference p4 = qi::AutoAnyReference(), + qi::AutoAnyReference p5 = qi::AutoAnyReference(), + qi::AutoAnyReference p6 = qi::AutoAnyReference(), + qi::AutoAnyReference p7 = qi::AutoAnyReference(), + qi::AutoAnyReference p8 = qi::AutoAnyReference()); + + std::vector subscribers(); + bool hasSubscribers(); + static const SignalLink invalidSignalLink; + protected: + typedef boost::function Trigger; + void callSubscribers(const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto); + void setTriggerOverride(Trigger trigger); + void setOnSubscribers(OnSubscribers onSubscribers); + void callOnSubscribe(bool v); + void createNewTrackLink(int& id, SignalLink*& trackLink); + void disconnectTrackLink(int id); + public: + void _setSignature(const Signature &s); + // C4251 + boost::shared_ptr _p; + friend class SignalBasePrivate; + }; + +#define QI_SIGNAL_TEMPLATE_DECL typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7 +#define QI_SIGNAL_TEMPLATE P0,P1,P2,P3,P4,P5,P6,P7 + +template class Signal; + + template + class SignalF: public SignalBase, public boost::function + { + public: + /** Signal constructor + * @param onSubscribers invoked each time number of subscribers switch + * between 0 and 1, with argument '!subscribers.empty()' + * Will not be called when destructor is invoked and all subscribers are removed + */ + SignalF(OnSubscribers onSubscribers = OnSubscribers()); + typedef T FunctionType; + virtual qi::Signature signature() const; + using boost::function::operator(); + +#ifdef DOXYGEN + /** Connect a subscriber to this signal. + * + * Multiple forms can be used: + * - connect(function, argOrPlaceholder1, argOrPlaceholder2, ...) + * Where function is a function or callable object (such as a boost::function). + * If the first argument is a weak ptr or inherits qi::Trackable, the slot + * will automatically disconnect if object is no longuer available. + * - connect(AnyObject target, unsigned int slot) + * - connect(AnyObject target, const std::string& slotName) + * - connect(AnyFunction func) + * - connect(const SignalSubscriber&) + * - connect(qi::Signal& otherSignal) + * + * @return a SignalSubscriber object. This object can be implicitly + * converted to a SignalLink. + * @throw runtime_error if the connection could not be made (because of invalid callback + * arity or argument type) + */ + SignalSubscriber& connect(...); +#else + + template SignalSubscriber& connect(CALLABLE c); + SignalSubscriber& connect(AnyFunction func); + SignalSubscriber& connect(const SignalSubscriber& sub); + SignalSubscriber& connect(const boost::function& func); + template SignalSubscriber& connect(SignalF& signal); + template SignalSubscriber& connect(Signal& signal); + + #define genConnect(n, ATYPEDECL, ATYPES, ADECL, AUSE, comma) \ + template \ + SignalSubscriber& connect(F func, P p comma ADECL); + QI_GEN(genConnect) + #undef genConnect + + SignalSubscriber& connect(const AnyObject &obj, unsigned int slot); + SignalSubscriber& connect(const AnyObject &obj, const std::string& slot); +#endif + }; + +namespace detail +{ + template struct VoidFunctionType { typedef void(type)(P0, P1, P2, P3, P4, P5, P6, P7); }; + template struct VoidFunctionType { typedef void(type)(P0, P1, P2, P3, P4, P5, P6); }; + template struct VoidFunctionType { typedef void(type)(P0, P1, P2, P3, P4, P5); }; + template struct VoidFunctionType { typedef void(type)(P0, P1, P2, P3, P4); }; + template struct VoidFunctionType { typedef void(type)(P0, P1, P2, P3); }; + template struct VoidFunctionType { typedef void(type)(P0, P1, P2); }; + template struct VoidFunctionType { typedef void(type)(P0, P1); }; + template struct VoidFunctionType { typedef void(type)(P0); }; + template< > struct VoidFunctionType { typedef void(type)(); }; + +} +template< + typename P0 = void, + typename P1 = void, + typename P2 = void, + typename P3 = void, + typename P4 = void, + typename P5 = void, + typename P6 = void, + typename P7 = void + > + class Signal: public SignalF::type> + { + public: + typedef typename detail::VoidFunctionType::type FunctionType; + typedef SignalF ParentType; + typedef typename ParentType::OnSubscribers OnSubscribers; + Signal(OnSubscribers onSubscribers = OnSubscribers()) + : ParentType(onSubscribers) {} + using boost::function::operator(); + }; + + + /** Event subscriber info. + * + * Only one of handler or target must be set. + */ + class QITYPE_API SignalSubscriber + : public boost::enable_shared_from_this + { + public: + SignalSubscriber() + : source(0), linkId(SignalBase::invalidSignalLink), target(0), method(0), enabled(true) + {} + + + SignalSubscriber(AnyFunction func, MetaCallType callType = MetaCallType_Auto); + SignalSubscriber(const AnyObject& target, unsigned int method); + + SignalSubscriber(const SignalSubscriber& b); + + ~SignalSubscriber(); + + void operator = (const SignalSubscriber& b); + + /* Perform the call. + * Threading rules in order: + * - Honor threadingModel if set (not auto) + * - Honor callTypoe if set (not auto) + * - Be asynchronous + */ + void call(const GenericFunctionParameters& args, MetaCallType callType); + + SignalSubscriber& setCallType(MetaCallType ct); + + //wait till all threads are inactive except the current thread. + void waitForInactive(); + + void addActive(bool acquireLock, boost::thread::id tid = boost::this_thread::get_id()); + void removeActive(bool acquireLock, boost::thread::id tid = boost::this_thread::get_id()); + operator SignalLink() const + { + return linkId; + } + /** Try to extract exact signature of this subscriber. + * @return the signature, or an invalid signature if extraction is impossible + */ + Signature signature() const; + public: + // Source information + SignalBase* source; + /// Uid that can be passed to GenericObject::disconnect() + SignalLink linkId; + + // Target information, kept here to be able to introspect a Subscriber + // Mode 1: Direct functor call + AnyFunction handler; + MetaCallType threadingModel; + + // Mode 2: metaCall + AnyWeakObject* target; + unsigned int method; + + boost::mutex mutex; + // Fields below are protected by lock + + // If enabled is set to false while lock is acquired, + // No more callback will trigger (activeThreads will se no push-back) + bool enabled; + // Number of calls in progress. + // Each entry there is a subscriber call that can no longuer be aborted + std::vector activeThreads; // order not preserved + + boost::condition inactiveThread; + }; + typedef boost::shared_ptr SignalSubscriberPtr; +} + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#include + +QI_NO_TYPE(qi::SignalBase) + +#endif // _QITYPE_SIGNAL_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/signature.hpp b/naoModule/libnaoqi_files/include/qitype/signature.hpp new file mode 100755 index 0000000..6b971cd --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/signature.hpp @@ -0,0 +1,164 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_SIGNATURE_HPP_ +#define _QITYPE_SIGNATURE_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) +#endif + +namespace qi { + + QITYPE_API std::vector signatureSplit(const std::string &fullSignature); + + class SignaturePrivate; + + class AnyReference; + class AnyValue; + class TypeInterface; + class Signature; + QITYPE_API qi::Signature makeTupleSignature(const std::vector& vgv, + bool resolveDynamic = false, + const std::string &name = std::string(), + const std::vector& names = std::vector()); + QITYPE_API qi::Signature makeTupleSignature(const std::vector& vgv, + const std::string &name = std::string(), + const std::vector& names = std::vector()); + + QITYPE_API qi::Signature makeTupleSignature(const qi::Signature &element); + QITYPE_API qi::Signature makeListSignature(const qi::Signature &element); + QITYPE_API qi::Signature makeVarArgsSignature(const qi::Signature &element); + QITYPE_API qi::Signature makeKwArgsSignature(const qi::Signature &element); + QITYPE_API qi::Signature makeMapSignature(const qi::Signature &key, const qi::Signature &value); + + /* Represent the serialisation signature of a Type. + * pseudo-grammar: + * root: element + * element: signature annotation.opt + * sinature: + * | primitive // in bcCwWiIlLfdsmro, see Type + * | [element] + * | {elementelement} + * | (elementsequence) + * elementsequence: a list of 1 or more elements + * annotation.opt: empty or + * annotation: may contain arbitrary content except \0 + and must balance all (), {}, [] and <> within + * for tuple annotation has the following form: "" + */ + class Signature; + typedef std::vector SignatureVector; + + class QITYPE_API Signature { + protected: + Signature(const std::string &signature, size_t begin, size_t end); + friend class SignaturePrivate; + + public: + Signature(); + Signature(const char *signature); + Signature(const std::string &signature); + + bool isValid() const; + + bool hasChildren() const; + + const SignatureVector& children() const; + + //TODO use the type than "network type" + enum Type { + // Used only for empty containers when Dynamic resolution is used. + Type_None = '_', + Type_Bool = 'b', + + Type_Int8 = 'c', + Type_UInt8 = 'C', + + Type_Void = 'v', + + Type_Int16 = 'w', + Type_UInt16 = 'W', + + Type_Int32 = 'i', + Type_UInt32 = 'I', + + Type_Int64 = 'l', + Type_UInt64 = 'L', + + Type_Float = 'f', + Type_Double = 'd', + + Type_String = 's', + Type_List = '[', + Type_List_End = ']', + + Type_Map = '{', + Type_Map_End = '}', + + Type_Tuple = '(', + Type_Tuple_End= ')', + + Type_Dynamic = 'm', + + Type_Raw = 'r', + + //This type should not be used, it's will be removed when we get ride of legacy void *. + Type_Pointer = '*', + + Type_Object = 'o', + Type_VarArgs = '#', + Type_KwArgs = '~', + + Type_Unknown = 'X', + }; + + Type type() const; + std::string annotation() const; + + inline bool operator!=(const Signature &rhs) const { return !(*this == rhs); } + bool operator==(const Signature &rhs) const; + + /** Encode the signature in a plain struct, + * suitable for further serialization. + * [typeString, childrenList, annotationString ] + */ + AnyValue toData() const; + std::string toPrettySignature() const; + const std::string& toString() const; + + /** Tell if arguments with this signature can be converted to \p b. + * @return 0 if conversion is impossible, or a score in ]0,1] indicating + * the amount of type mismatch (the closer signatures are the bigger) + */ + float isConvertibleTo(const Signature& b) const; + + static Signature fromType(Type t); + protected: + // C4251 + boost::shared_ptr _p; + + }; + + +} + +extern "C" QITYPE_API char* signature_to_json(const char* sig); + +#ifdef _MSC_VER +# pragma warning( pop ) +#endif + +#endif // _QITYPE_SIGNATURE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/traceanalyzer.hpp b/naoModule/libnaoqi_files/include/qitype/traceanalyzer.hpp new file mode 100755 index 0000000..4ee7dbc --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/traceanalyzer.hpp @@ -0,0 +1,63 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_TRACEANALYZER_HPP_ +#define _QITYPE_TRACEANALYZER_HPP_ + +#include + +#include + + +namespace qi +{ + class TraceAnalyzerImpl; + + class QITYPE_API TraceAnalyzer: public boost::noncopyable + { + public: + TraceAnalyzer(); + ~TraceAnalyzer(); + /// Clear all traces + void clear(); + /// Clear traces older than limit. Can loose dataflow informations. + void clear(const qi::os::timeval& limit); + /// Add a new trace to the system. There is no order requirement between traces. + void addTrace(const qi::EventTrace& e, unsigned int objectId); + struct FlowLink + { + FlowLink(unsigned int srcObj, unsigned int srcFun, unsigned int dstObj, unsigned int dstFun, bool sync) + : srcObj(srcObj), srcFun(srcFun), dstObj(dstObj), dstFun(dstFun), sync(sync) {} + unsigned int srcObj, srcFun, dstObj, dstFun; + bool sync; + }; + /// Append the set of discovered links between traces to \p links + void analyze(std::set& links); + /// Debug-dump the internal structures to given ostream + void dumpTraces(std::ostream& o); + std::string dumpTraces(); + protected: + TraceAnalyzerImpl* _p; + }; +} + + +namespace qi +{ + inline bool operator < (const TraceAnalyzer::FlowLink& a, const TraceAnalyzer::FlowLink& b) + { + #define _qi_FIELD(f) if (a.f != b.f) return a.f < b.f + _qi_FIELD(srcObj); + _qi_FIELD(srcFun); + _qi_FIELD(dstObj); + _qi_FIELD(dstFun); + _qi_FIELD(sync); + return false; + #undef _qi_FIELD + } +} + +#endif diff --git a/naoModule/libnaoqi_files/include/qitype/typedispatcher.hpp b/naoModule/libnaoqi_files/include/qitype/typedispatcher.hpp new file mode 100755 index 0000000..de13f60 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/typedispatcher.hpp @@ -0,0 +1,44 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_TYPEDISPATCHER_HPP_ +#define _QITYPE_TYPEDISPATCHER_HPP_ + +#include + +namespace qi { + + /** Invoke one of the visitor functions in dispatcher based on kind(). + * Dispatcher must implement TypeDispatcher. + */ + template + Dispatcher& typeDispatch(const Dispatcher& dispatcher, AnyReference value); + + + // class QITYPE_API TypeDispatcher + // { + // public: + // void visitUnknown(qi::AnyReference value); + // void visitVoid(); + // void visitInt(qi::int64_t value, bool isSigned, int byteSize); + // void visitFloat(double value, int byteSize); + // void visitString(char* data, size_t size); + // void visitList(qi::AnyIterator begin, qi::AnyIterator end); + // void visitMap(qi::AnyIterator begin, qi::AnyIterator end); + // void visitObject(qi::GenericObject value); + // void visitPointer(qi::AnyReference pointee); + // void visitTuple(const std::string &className, const std::vector& tuple, const std::vector& elementNames); + // void visitDynamic(qi::AnyReference pointee); + // void visitRaw(qi::AnyReference value); + // void visitIterator(qi::AnyReference value); + // void visitAnyObject(qi::AnyObject& ptr); + // }; + +} + +#include + +#endif // _QITYPE_TYPEDISPATCHER_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/typeinterface.hpp b/naoModule/libnaoqi_files/include/qitype/typeinterface.hpp new file mode 100755 index 0000000..baa4bd5 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/typeinterface.hpp @@ -0,0 +1,391 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_TYPEINTERFACE_HPP_ +#define _QITYPE_TYPEINTERFACE_HPP_ + +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +# pragma warning( push ) +# pragma warning( disable: 4251 ) + // C4503 decorated name length exceeded, name was truncated + // The only workaround is to make structs to hide the template complexity + // We don't want to have to do that +# pragma warning( disable: 4503 ) +#endif + +/* A lot of class are found in this headers... to kill circular dependencies. + Futhermore we need that all "default template" types are registered (included) + when type.hpp is used. (for typeOf to works reliably) +*/ + +namespace qi{ + + /// Declare that a type has no accessible default constructor. + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_TYPE_NOT_CONSTRUCTIBLE(T) \ + namespace qi { namespace detail { \ + template<> struct TypeManager: public TypeManagerNotConstructible {};}} + + /// Declare that a type has no metatype and cannot be used in a Value + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_NO_TYPE(T) namespace qi {template<> class TypeImpl: public detail::ForbiddenInTypeSystem {};} + + /// Declare that a type has no accessible constructor + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_TYPE_INTERFACE(T) \ + namespace qi { namespace detail { \ + template<> struct TypeManager: public TypeManagerDefaultInterface {};}} + + /// Declare that a type can be constructed and copied + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_TYPE_CONCRETE(T) \ + namespace qi { namespace detail { \ + template<> struct TypeManager: public TypeManagerDefaultStruct {}; }} + + /// Register TypeImpl in runtime type factory for 't'. Must be called from a .cpp file + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_TYPE_REGISTER(t) \ + QI_TYPE_REGISTER_CUSTOM(t, qi::TypeImpl) + + /// Register 'typeimpl' in runtime type factory for 'type'. + /// \warning Be careful to put the declaration outside any namespaces. + #define QI_TYPE_REGISTER_CUSTOM(type, typeimpl) \ + static bool BOOST_PP_CAT(__qi_registration, __LINE__) = qi::registerType(typeid(type), new typeimpl) + + + class ListTypeInterface; + class StructTypeInterface; + + // Interfaces for specialized types + class QITYPE_API IntTypeInterface: public TypeInterface + { + public: + /// Get the integer value + virtual int64_t get(void* value) = 0; + /// Return the size in bytes + virtual unsigned int size() = 0; + /// Return true if the integer is signed + virtual bool isSigned() = 0; + /// Set the value of the integer + virtual void set(void** storage, int64_t value) = 0; + virtual TypeKind kind() { return TypeKind_Int;} + }; + + class QITYPE_API FloatTypeInterface: public TypeInterface + { + public: + /// Get the float value + virtual double get(void* value) = 0; + /// Return the size in bytes + virtual unsigned int size() = 0; // size in bytes + /// Set the value of the float + virtual void set(void** storage, double value) = 0; + virtual TypeKind kind() { return TypeKind_Float;} + }; + + class QITYPE_API StringTypeInterface: public TypeInterface + { + public: + typedef std::pair RawString; + typedef boost::function Deleter; + typedef std::pair ManagedRawString; + + /// Get a copy of the string value + std::string getString(void* storage); + /// Get the internal string representation as UTF-8. It may or may not be a + /// copy. + virtual ManagedRawString get(void* storage) = 0; + /// Set the value of the string + void set(void** storage, const std::string& value); + /// Set the value of the string + virtual void set(void** storage, const char* ptr, size_t sz) = 0; + virtual TypeKind kind() { return TypeKind_String; } + + }; + + /** + * Interface for a buffer of data + */ + class QITYPE_API RawTypeInterface: public TypeInterface + { + public: + /// Get the buffer of data (not a copy) + virtual std::pair get(void* storage) = 0; + /// Set the buffer of data (buffer is copied) + virtual void set(void** storage, const char* ptr, size_t sz) = 0; + virtual TypeKind kind() { return TypeKind_Raw; } + }; + + class QITYPE_API PointerTypeInterface: public TypeInterface + { + public: + enum PointerKind + { + Raw, + Shared, + }; + /// Return whether the pointer has raw or shared semantics + virtual PointerKind pointerKind() = 0; + /// Get the type of the pointed element + virtual TypeInterface* pointedType() = 0; + /// Get the pointed element (must not be destroyed) + virtual AnyReference dereference(void* storage) = 0; + /// Set new pointee value. pointer must be a *pointer* to type pointedType() + virtual void setPointee(void** storage, void* pointer) = 0; + virtual TypeKind kind() { return TypeKind_Pointer; } + }; + + /** + * Interface for an iterator (on a list or a map) + * + * Iterators become invalid if the parent container is destroyed and no + * method should be called in such a case. + */ + class QITYPE_API IteratorTypeInterface: public TypeInterface + { + public: + /** + * Get the value pointed by the iterator + * + * Returned reference is expected to point to somewhere in the iterator, or + * the container. It remains valid as long as the iterator is neither + * modified by next() nor destroyed, and the parent container is not + * destroyed. + */ + virtual AnyReference dereference(void* storage) = 0; + /// Increment the iterator + virtual void next(void** storage) = 0; + /// Check for iterator equality + virtual bool equals(void* s1, void* s2) = 0; + virtual TypeKind kind() { return TypeKind_Iterator; } + }; + + /** + * Interface for a list of elements (like std::vector) + * + * Elements must have the same types (may be dynamic) + */ + class QITYPE_API ListTypeInterface: public TypeInterface + { + public: + /// Get the type of the elements of the list + virtual TypeInterface* elementType() = 0; + /// Return the number of elements in the list + virtual size_t size(void* storage) = 0; + /// Return an iterator pointing to the first element of the list + virtual AnyIterator begin(void* storage) = 0; + /// Return an iterator pointing to one past the last element of the list + /// (do not dereference this iterator!) + virtual AnyIterator end(void* storage) = 0; + /// Append an element to the end of the list + virtual void pushBack(void** storage, void* valueStorage) = 0; + /// Get the element at index + virtual void* element(void* storage, int index); + virtual TypeKind kind() { return TypeKind_List;} + }; + + /** + * Interface for a map of elements (like std::map) + * + * Keys must have the same types and values must have the same types (both + * may be dynamic) + */ + class QITYPE_API MapTypeInterface: public TypeInterface + { + public: + /// Get the types of the values of the map + virtual TypeInterface* elementType() = 0; + /// Get the types of the keys of the map + virtual TypeInterface* keyType() = 0; + /// Return the number of elements in the map + virtual size_t size(void* storage) = 0; + /// Return an iterator pointing to the first key-value pair of the map + virtual AnyIterator begin(void* storage) = 0; + /// Return an iterator pointing to one past the last key-value pair of the + /// list (do not dereference this iterator!) + virtual AnyIterator end(void* storage) = 0; + /// Set a key to a value and creates it if it does not exist + virtual void insert(void** storage, void* keyStorage, void* valueStorage) = 0; + /** + * Get the value corresponding to the requested key + * + * If the key does not exist and autoInsert is true, it is created, + * otherwise an invalid reference is returned. + */ + virtual AnyReference element(void** storage, void* keyStorage, bool autoInsert) = 0; + virtual TypeKind kind() { return TypeKind_Map; } + // Since our typesystem has no erased operator < or operator ==, + // MapTypeInterface does not provide a find() + }; + + class QITYPE_API StructTypeInterface: public TypeInterface + { + public: + /// Get all the fields of the structure + AnyReferenceVector values(void* storage); + /** + * Get all the member types + * + * Note that this function does not recieve a storage argument. There must + * be one instance of StructTypeInterface per type of struct. If you need + * dynamic structs, look at makeTupleType(). + */ + virtual std::vector memberTypes() = 0; + /// Get all the fields storages of the struct (not a copy) + virtual std::vector get(void* storage); + /// Get the field storage at index (not a copy) + virtual void* get(void* storage, unsigned int index) = 0; + /// Set all the fields of the struct (copies the values given in the vector) + virtual void set(void** storage, const std::vector&); + /// Set the fields of the struct at index (copies the value given) + virtual void set(void** storage, unsigned int index, void* valStorage) = 0; + virtual TypeKind kind() { return TypeKind_Tuple; } + /// Get the names of the fields of the struct + virtual std::vector elementsName() { return std::vector();} + /// Get the type name of the struct + virtual std::string className() { return std::string(); } + + /** @{ + * + * Versioning support. + * + * Conversion between non-equivalent structs will be attempted if all + * fields are named: fields with matching names will be automatically mapped + * to each other. + * canDropFields() will be called on the source to ask + * if fields given as argument can be dropped (because they do not exist + * on the target). + * + * fillMissingFields(fields, missing) will be called on the target, + * with a map of + * fields that were converted, and the list of missing field names. + * The function must fill fields with a value for each of the missing fields, + * or return false (no storage is provided, because the struct cant be + * instanciated without a value for all fields being available. + */ + + /// Return whether struct accepts field-name-based conversion that drops \p fieldNames. + virtual bool canDropFields(void* storage, const std::vector& fieldNames) { return false;} + /// Fill missing fields caused by conversion from a different struct. Return whether fill succeeded. + virtual bool fillMissingFields(std::map& fields, const std::vector& missing) { return false;} + + /// @} + }; + + /** + * Type that contains a value of any type. + * + * The workings of a dynamic type is similar to that of a union. + */ + class QITYPE_API DynamicTypeInterface: public TypeInterface + { + public: + /// Get a reference to the underlying element + virtual AnyReference get(void* storage) = 0; + /// Set the underlying element + virtual void set(void** storage, AnyReference source) = 0; + virtual TypeKind kind() { return TypeKind_Dynamic; } + }; + + /** + * Type that contains variable arguments + */ + class QITYPE_API VarArgsTypeInterface: public ListTypeInterface + { + public: + //virtual AnyReference get(void *storage) = 0; + //virtual TypeInterface* elementType() = 0; + virtual TypeKind kind() { return TypeKind_VarArgs; } + }; + + ///@return a Type of the specified Kind. This do not work for list, map and tuple. + /// kind Int and Float will create the biggest possible type. use makeFloatType and makeIntType + /// to be more specific. + QITYPE_API TypeInterface* makeTypeOfKind(const qi::TypeKind& kind); + + ///@return a Type of kind float, bytelen can be 4 or 8 + QITYPE_API TypeInterface* makeFloatType(int bytelen); + + ///@return a Type of kind int, bytelen can be 0,1,2,4,8 + QITYPE_API TypeInterface* makeIntType(bool issigned, int bytelen); + + ///@return a Type of kind VarArgs that can contains elements of type elementType. + QITYPE_API TypeInterface* makeVarArgsType(TypeInterface* elementType); + + ///@return a Type of kind List that can contains elements of type elementType. + QITYPE_API TypeInterface* makeListType(TypeInterface* elementType); + + ///@return a Type of kind Map with given key and element types + QITYPE_API TypeInterface* makeMapType(TypeInterface* keyType, TypeInterface* ElementType); + + ///@return a Type of kind Tuple with givent memberTypes + QITYPE_API TypeInterface* makeTupleType(const std::vector& memberTypes, const std::string &name = std::string(), const std::vector& elementNames = std::vector()); + + + + /** Declare a templated-type taking one type argument. + * Required to be able to use QI_TEMPLATE_TYPE_GET + */ + #define QI_TEMPLATE_TYPE_DECLARE(n) \ + namespace qi { \ + template class QITYPE_TEMPLATE_API TypeImpl >: public TypeOfTemplateImpl {}; \ + } + /** Return a TemplateTypeInterface pointer if \p typeInst represents an instanciation + * of template type templateName, 0 otherwise + */ + #define QI_TEMPLATE_TYPE_GET(typeInst, templateName) \ + dynamic_cast< ::qi::TypeOfTemplate*>(typeInst) + + + /** + * TODO: Find the right size of enum values + */ + #define QI_TYPE_ENUM_REGISTER(Enum) \ + namespace qi { \ + template<> class TypeImpl: public IntTypeInterfaceImpl {}; \ + } + +#define QI_TYPE_STRUCT_DECLARE(name) \ + __QI_TYPE_STRUCT_DECLARE(name, /**/) + +} + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +QI_NO_TYPE(qi::TypeInterface) +QI_NO_TYPE(qi::TypeInterface*) + +#ifdef _MSC_VER +# pragma warning( pop ) +// restore the disabling of this warning +# pragma warning( disable: 4503 ) +#endif + +#endif // _QITYPE_TYPEINTERFACE_HPP_ diff --git a/naoModule/libnaoqi_files/include/qitype/typeobject.hpp b/naoModule/libnaoqi_files/include/qitype/typeobject.hpp new file mode 100755 index 0000000..6a405a0 --- /dev/null +++ b/naoModule/libnaoqi_files/include/qitype/typeobject.hpp @@ -0,0 +1,63 @@ +#pragma once +/* +** Copyright (C) 2013 Aldebaran Robotics +** See COPYING for the license +*/ + +#ifndef _QITYPE_TYPEOBJECT_HPP_ +#define _QITYPE_TYPEOBJECT_HPP_ + +#include +#include +#include + +namespace qi { + + /** Specifies how a call should be made. + * Can be used at both call-site, and callback-registration site. + */ + enum MetaCallType { + /// Honor the default behavior + MetaCallType_Auto = 0, + /// Force a synchronous call + MetaCallType_Direct = 1, + /// Force an asynchronous call in an other thread + MetaCallType_Queued = 2, + }; + class SignalSubscriber; + class Manageable; + typedef qi::uint64_t SignalLink; + + /* We will have 2 implementations for 2 classes of C++ class: + * - DynamicObject: Use DynamicObjectBuilder + * - T: Use ObjectTypeBuilder + * + * All values of this type (GenericObject) will be handled + * + * + * NOTE: no SignalBase accessor at this point, but the backend is such that it would be possible + * but if we do that, virtual emit/connect/disconnect must go away, as they could be bypassed + * ->RemoteObject, ALBridge will have to adapt + * + */ + class QITYPE_API ObjectTypeInterface: public TypeInterface + { + public: + virtual const MetaObject& metaObject(void* instance) = 0; + virtual qi::Future metaCall(void* instance, AnyObject context, unsigned int method, const GenericFunctionParameters& params, MetaCallType callType = MetaCallType_Auto, Signature returnSig = Signature())=0; + virtual void metaPost(void* instance, AnyObject context, unsigned int signal, const GenericFunctionParameters& params)=0; + virtual qi::Future connect(void* instance, AnyObject context, unsigned int event, const SignalSubscriber& subscriber)=0; + /// Disconnect an event link. Returns if disconnection was successful. + virtual qi::Future disconnect(void* instance, AnyObject context, SignalLink linkId)=0; + /// @return parent types with associated poniter offset + virtual const std::vector >& parentTypes() = 0; + virtual qi::Future property(void* instance, unsigned int id) = 0; + virtual qi::Future setProperty(void* instance, unsigned int id, AnyValue value) = 0; + virtual TypeKind kind() { return TypeKind_Object;} + /// @return -1 if there is no inheritance, or the pointer offset + int inherits(TypeInterface* other); + }; + +} + +#endif // _QITYPE_TYPEOBJECT_HPP_ diff --git a/naoModule/libnaoqi_files/include/rttools/atomic.h b/naoModule/libnaoqi_files/include/rttools/atomic.h new file mode 100755 index 0000000..1ccc579 --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/atomic.h @@ -0,0 +1,57 @@ +/** + * @author Cedric GESTES + * Copyright (c) Aldebaran Robotics 2008 All Rights Reserved + * + */ + + +/** + * atomic operation on int + */ + + +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_ATOMIC_H_ +#define _LIB_RTTOOLS_RTTOOLS_ATOMIC_H_ + +# if (TARGET_HOST == TARGET_HOST_WINDOWS) || !defined(i386) + +static inline int +exchange_and_add(volatile signed long* mem, int val) +{ + *mem = val; + return *mem; +} +static inline void +atomic_add(volatile signed long* mem, int val) +{ + *mem = val; +} +# else +static inline int //__attribute__ ((__unused__)) +exchange_and_add(volatile signed long* mem, int val) +{ + register int result; + asm volatile ("lock; \n" \ + "xaddl %0,%1" + : "=r" (result), + "=m" (*mem) + : "0" (val), + "m" (*mem) + ); + return result; +} + +static inline void //__attribute__ ((__unused__)) +atomic_add(volatile signed long* mem, int val) +{ + asm volatile ("lock; \n" \ + "addl %1,%0 \n" + : "=m" (*mem) + : "ir" (val), + "m" (*mem)); +} +#endif + +#endif // _LIB_RTTOOLS_RTTOOLS_ATOMIC_H_ diff --git a/naoModule/libnaoqi_files/include/rttools/rtperiod.h b/naoModule/libnaoqi_files/include/rttools/rtperiod.h new file mode 100755 index 0000000..c245269 --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/rtperiod.h @@ -0,0 +1,76 @@ +/* -*- C++ -*- */ +/** + * @author Cedric GESTES + * Copyright (c) Aldebaran Robotics 2008 All Rights Reserved + * + */ + +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_RTPERIOD_H_ +#define _LIB_RTTOOLS_RTTOOLS_RTPERIOD_H_ + +# include +# include + +/** + * @brief this class allow to create periodic loop or thread + * set the period, then before the loop call periodInit + * and loop on periodWait + */ +class RtPeriod { +public: + RtPeriod(); + + + void setPeriod(const signed long mSec); + + + /** + * init the period + */ + void periodInit(); + +/** + * wait for the end of the timeslice (interval) + * if the timeslice is already elapsed, it doesnt wait and return a negative value + * @return the delta between the current time and the time we wanted (microsec) + * + * 1) get the current time, verify that we dont missed the deadline + * 2) if (waittime > 1000us) wait till the end of the timeslice (if needed) + * 3) update values for the next time + * + * @param pAllowDrift If false, we hope to be woken at exact multiples + * of mSec relative to the start + */ + int periodWait(bool pAllowDrift = true); + +protected: + void computeStat(); + +protected: + struct timespec fNow; + struct timespec fNext; + struct timespec fInterval; + int fUsedClock; + + ///stat +protected: + signed long fCurrentDiff; + signed long fCurrentWait; + + signed long fMinDiff; + signed long fMinWait; + + signed long fMaxDiff; + signed long fMaxWait; + + signed long fAvgDiff; + signed long fAvgWait; + + unsigned long fTickCount; + +}; + + +#endif // _LIB_RTTOOLS_RTTOOLS_RTPERIOD_H_ diff --git a/naoModule/libnaoqi_files/include/rttools/rtprintf.h b/naoModule/libnaoqi_files/include/rttools/rtprintf.h new file mode 100755 index 0000000..18d500c --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/rtprintf.h @@ -0,0 +1,25 @@ +/** + * @author Cedric GESTES + * Copyright (c) Aldebaran Robotics 2008 All Rights Reserved + * + */ + + +/** + * This file implement a real-time thread safe printf + */ +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_RTPRINTF_H_ +#define _LIB_RTTOOLS_RTTOOLS_RTPRINTF_H_ + +typedef int (*RtPrintfCallback)(const char *); + +/* + * set the rtprintf callback to do the effective print + */ +void rtPrintfSetCallback(RtPrintfCallback cb); + +void rtprintf(const char *fmt, ...); + +#endif // _LIB_RTTOOLS_RTTOOLS_RTPRINTF_H_ diff --git a/naoModule/libnaoqi_files/include/rttools/rtthread.h b/naoModule/libnaoqi_files/include/rttools/rtthread.h new file mode 100755 index 0000000..4f79b57 --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/rtthread.h @@ -0,0 +1,64 @@ +/* -*- C++ -*- */ +/** + * @author Cedric GESTES + * Copyright (c) Aldebaran Robotics 2008 All Rights Reserved + * + */ + +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_RTTHREAD_H_ +#define _LIB_RTTOOLS_RTTOOLS_RTTHREAD_H_ + +# include +# include +# include + +class RtThread : public RtPeriod { +public: + typedef void *(funcptr)(void *); + +public: + RtThread(); + virtual ~RtThread(); + + /** + * set the realtime capability of the thread + * scheduler maybe: + * SCHED_OTHER: system scheduler + * SCHED_FIFO : execute the thread til a blocking function (or preemption by a higher priority function) + * SCHED_RR : same as FIFO, but dont execute for more than a timeslice (less agressive for the system) + * rtprio have no impact when using SCHED_OTHER + */ + int setRealtime(int scheduler, int rtprio); + + /** + * Create the thread + */ + int create(); + + /** + * Join the thread + */ + int join(); + + /** + * cancel the thread + */ + int cancel(); + + + +public: + virtual void *execute() = 0; + virtual void postExecute() {;} + virtual void preExecute() {;} + +protected: + int fUsedClock; + pthread_attr_t fAttr; + pthread_t fThread; +}; + + +#endif // _LIB_RTTOOLS_RTTOOLS_RTTHREAD_H_ diff --git a/naoModule/libnaoqi_files/include/rttools/rttime.h b/naoModule/libnaoqi_files/include/rttools/rttime.h new file mode 100755 index 0000000..e4023f7 --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/rttime.h @@ -0,0 +1,149 @@ +/* -*- C++ -*- */ +/** + * @author Cedric GESTES, modifications Pierre-Emmanuel VIEL + * Copyright (c) Aldebaran Robotics 2008 All Rights Reserved + * + */ + +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_RTTIME_H_ +#define _LIB_RTTOOLS_RTTOOLS_RTTIME_H_ + +#include +#include + +static const long gUsecPerSec = 1000000; +static const long gNsecPerSec = 1000000000; + + +/** + * add two timespec + */ +inline struct timespec timespec_add(const struct timespec &ts, const struct timespec &ts2) +{ + struct timespec ret; + + ret.tv_sec = ts.tv_sec + ts2.tv_sec; + ret.tv_nsec = ts.tv_nsec + ts2.tv_nsec; + + while (ret.tv_nsec >= gNsecPerSec) { + ret.tv_nsec -= gNsecPerSec; + ret.tv_sec++; + } + return ret; +} + +/** + * return the difference between t1 and t2 in nanosecond + * t1: stop, t2: start + */ +inline long timespec_diff_ns(const struct timespec &t1, const struct timespec &t2) +{ + long diff; + + diff = (long)((long long)gNsecPerSec * (long long)(t1.tv_sec - t2.tv_sec)); + diff += t1.tv_nsec - t2.tv_nsec; + return diff; +} + +/** + * return the difference between t1 and t2 in microsecond + */ +inline signed long timespec_diff_us(const struct timespec &t1, const struct timespec &t2) +{ + long diff; + + diff = (long)((long long)gUsecPerSec * (long long)(t1.tv_sec - t2.tv_sec)); + diff += ((long)((long long)(t1.tv_nsec - t2.tv_nsec)) / 1000); + return diff; +} + + +/** + * Encapsulation of the clock_gettime() function for precise time operations (nanoseconds). + */ +class RtTime { +public: + /** + * Default constructor. + * @param clockType The type of clock used between 0:CLOCK_REALTIME 1:CLOCK_MONOTONIC 2:CLOCK_PROCESS_CPUTIME_ID 3:CLOCK_THREAD_CPUTIME_ID \n + * If no argument is provided, 1 by default \n + * If the requested clock level is not provided by the kernel, and if the use of a lower clock level isn't managed by it, constructor will decrease the level. + */ + RtTime(const int clockType = 0); // 0:CLOCK_REALTIME 1:CLOCK_MONOTONIC 2:CLOCK_PROCESS_CPUTIME_ID 3:CLOCK_THREAD_CPUTIME_ID + +public: + /** + * Default start clock. + */ + void start(); + /** + * Default stop clock. + */ + void stop(); + /** + * User defined clock. + * @param t The user defined timespec variable receiving the current time + */ + void getTime(timespec &t); // allows users to use their own time variables (for more complex time profiling) + + /** + * Difference between stop and start in ns. + */ + unsigned long diffNs(); + + /** + * Difference between stop and start in ns. + */ + unsigned long diffUs(); + + /** + * Difference between tstop and tstart in ns + * Allows users to obtain time differences using their own time variables (for more complex time profiling) + * @param tstart The user defined start time + * @param tstop The user defined stop time + */ + unsigned long diffNs(const struct timespec &tstart, const struct timespec &tstop); + + /** + * Difference between tstop and tstart in us + * Allows users to obtain time differences using their own time variables (for more complex time profiling) + * @param tstart The user defined start time + * @param tstop The user defined stop time + */ + unsigned long diffUs(const struct timespec &tstart, const struct timespec &tstop); + + /** + * Returns the type of clock accepted by the kernel, that might be different from the one asked in the constructor + */ + unsigned long getUsedClock(); // returns the clock mode accepted by the kernel that might be different from the one provided in the constructor + + signed long absSleep(const timespec &tm)const; + static signed long mSleep(const unsigned long sleepMs); + static signed long uSleep(const unsigned long sleepUs); + static signed long nSleep(const unsigned long sleepNs); + + static int checkClock(int pClock); + static int getClock(const int clockType = 0); + +private: + unsigned long fUsedClock; + timespec fDiffStart; + timespec fDiffStop; +}; + + +/** + * Prints the time spent executing of `f' ; also prints a message `m' before. + */ +# define RTDIFF(m, f) \ + { \ + RtTime rtm; \ + rtm.start(); \ + f; \ + rtm.stop(); \ + std::cout << m << " " << rtm.diffNs() << "ns" << std::endl; \ + } + +#endif // _LIB_RTTOOLS_RTTOOLS_RTTIME_H_ diff --git a/naoModule/libnaoqi_files/include/rttools/time-winp.h b/naoModule/libnaoqi_files/include/rttools/time-winp.h new file mode 100755 index 0000000..359e8cb --- /dev/null +++ b/naoModule/libnaoqi_files/include/rttools/time-winp.h @@ -0,0 +1,77 @@ +/* -*- C++ -*- */ +/** + * @author Cedric GESTES + * Copyright (c) Aldebaran Robotics 2008, 2011 All Rights Reserved + * + * time.h => Windows Is Not Posix version + */ +#pragma once + +#ifndef _LIB_RTTOOLS_RTTOOLS_TIME_WINP_H_ +#define _LIB_RTTOOLS_RTTOOLS_TIME_WINP_H_ + +/** + * missing function under windows and mac + * + * for windows: use QueryPerformanceCounter/QueryPerformanceFrequency to get precise time + * + */ +# ifndef __linux__ + +# include +# include + +# define CLOCK_MONOTONIC (0) +# define CLOCK_REALTIME (0) +# define CLOCK_PROCESS_CPUTIME_ID (0) +# define CLOCK_THREAD_CPUTIME_ID (0) + +# define TIMER_ABSTIME (0) + +inline int clock_getres(int clk, struct timespec *tm) +{ + return 0; +} + +inline int clock_gettime(int clk, struct timespec *tm) +{ + struct qi::os::timeval tv; + qi::os::gettimeofday(&tv); + tm->tv_sec = tv.tv_sec; + tm->tv_nsec = tv.tv_usec * 1000; + return 0; +} + +inline int clock_nanosleep(int clk, int flag, const struct timespec *tm, struct timespec *tm2) +{ + struct timespec t1; + long diff; + int diffms = 0; + + clock_gettime(0, &t1); + +// printf("T1: (%ld,%ld)\n", (&t1)->tv_sec, (&t1)->tv_nsec); +// printf("T2: (%ld,%ld)\n", tm->tv_sec, tm->tv_nsec); + diff = timespec_diff_ns(*tm, t1); + diffms = diff / 1000 / 1000; +//printf("diff(%ld): %ld\n", diff, diffms); + if (diffms > 0) + qi::os::msleep(diffms); + return 0; +} + +# endif + +/** + * missing function under windows + */ +#ifdef _WIN32 + +inline int nanosleep(const struct timespec *tm, const struct timespec *tm2) +{ + qi::os::msleep(tm->tv_nsec / (1000000)); + return 0; +} +# endif + +#endif // _LIB_RTTOOLS_RTTOOLS_TIME_WINP_H_ diff --git a/naoModule/libnaoqi_files/lib/libalagilityutils.a b/naoModule/libnaoqi_files/lib/libalagilityutils.a new file mode 100755 index 0000000..e039c76 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalagilityutils.a differ diff --git a/naoModule/libnaoqi_files/lib/libalaudio.so b/naoModule/libnaoqi_files/lib/libalaudio.so new file mode 100755 index 0000000..fa81886 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalaudio.so differ diff --git a/naoModule/libnaoqi_files/lib/libalautomatictest.so b/naoModule/libnaoqi_files/lib/libalautomatictest.so new file mode 100755 index 0000000..6edee76 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalautomatictest.so differ diff --git a/naoModule/libnaoqi_files/lib/libalbehavior.so b/naoModule/libnaoqi_files/lib/libalbehavior.so new file mode 100755 index 0000000..29265fe Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalbehavior.so differ diff --git a/naoModule/libnaoqi_files/lib/libalcommon.so b/naoModule/libnaoqi_files/lib/libalcommon.so new file mode 100755 index 0000000..f6dd0b9 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalcommon.so differ diff --git a/naoModule/libnaoqi_files/lib/libalerror.so b/naoModule/libnaoqi_files/lib/libalerror.so new file mode 100755 index 0000000..2034d7f Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalerror.so differ diff --git a/naoModule/libnaoqi_files/lib/libalextractor.so b/naoModule/libnaoqi_files/lib/libalextractor.so new file mode 100755 index 0000000..8eb2bc7 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalextractor.so differ diff --git a/naoModule/libnaoqi_files/lib/liballauncher.so b/naoModule/libnaoqi_files/lib/liballauncher.so new file mode 100755 index 0000000..2d1d290 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/liballauncher.so differ diff --git a/naoModule/libnaoqi_files/lib/libalmath.so b/naoModule/libnaoqi_files/lib/libalmath.so new file mode 100755 index 0000000..00f5723 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalmath.so differ diff --git a/naoModule/libnaoqi_files/lib/libalmathinternal.so b/naoModule/libnaoqi_files/lib/libalmathinternal.so new file mode 100755 index 0000000..cd5731d Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalmathinternal.so differ diff --git a/naoModule/libnaoqi_files/lib/libalmemoryfastaccess.so b/naoModule/libnaoqi_files/lib/libalmemoryfastaccess.so new file mode 100755 index 0000000..4166f20 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalmemoryfastaccess.so differ diff --git a/naoModule/libnaoqi_files/lib/libalparammanager.so b/naoModule/libnaoqi_files/lib/libalparammanager.so new file mode 100755 index 0000000..fcd0671 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalparammanager.so differ diff --git a/naoModule/libnaoqi_files/lib/libalproxies.so b/naoModule/libnaoqi_files/lib/libalproxies.so new file mode 100755 index 0000000..6ae8e42 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalproxies.so differ diff --git a/naoModule/libnaoqi_files/lib/libalpythontools.so b/naoModule/libnaoqi_files/lib/libalpythontools.so new file mode 100755 index 0000000..8518f49 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalpythontools.so differ diff --git a/naoModule/libnaoqi_files/lib/libalserial.so b/naoModule/libnaoqi_files/lib/libalserial.so new file mode 100755 index 0000000..da7e348 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalserial.so differ diff --git a/naoModule/libnaoqi_files/lib/libalsoap.so b/naoModule/libnaoqi_files/lib/libalsoap.so new file mode 100755 index 0000000..7512716 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalsoap.so differ diff --git a/naoModule/libnaoqi_files/lib/libalthread.so b/naoModule/libnaoqi_files/lib/libalthread.so new file mode 100755 index 0000000..67b8165 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalthread.so differ diff --git a/naoModule/libnaoqi_files/lib/libalvalue.so b/naoModule/libnaoqi_files/lib/libalvalue.so new file mode 100755 index 0000000..3bcda47 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalvalue.so differ diff --git a/naoModule/libnaoqi_files/lib/libalvalueutils.so b/naoModule/libnaoqi_files/lib/libalvalueutils.so new file mode 100755 index 0000000..c46a9a4 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalvalueutils.so differ diff --git a/naoModule/libnaoqi_files/lib/libalvision.so b/naoModule/libnaoqi_files/lib/libalvision.so new file mode 100755 index 0000000..4ec86e0 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libalvision.so differ diff --git a/naoModule/libnaoqi_files/lib/libqi.so b/naoModule/libnaoqi_files/lib/libqi.so new file mode 100755 index 0000000..7655cf9 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqi.so differ diff --git a/naoModule/libnaoqi_files/lib/libqic.so b/naoModule/libnaoqi_files/lib/libqic.so new file mode 100755 index 0000000..d247ca4 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqic.so differ diff --git a/naoModule/libnaoqi_files/lib/libqimessaging.so b/naoModule/libnaoqi_files/lib/libqimessaging.so new file mode 100755 index 0000000..29866e0 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqimessaging.so differ diff --git a/naoModule/libnaoqi_files/lib/libqiperf.so b/naoModule/libnaoqi_files/lib/libqiperf.so new file mode 100755 index 0000000..ad58197 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqiperf.so differ diff --git a/naoModule/libnaoqi_files/lib/libqipython.so b/naoModule/libnaoqi_files/lib/libqipython.so new file mode 100755 index 0000000..0b231ba Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqipython.so differ diff --git a/naoModule/libnaoqi_files/lib/libqitype.so b/naoModule/libnaoqi_files/lib/libqitype.so new file mode 100755 index 0000000..79ed50e Binary files /dev/null and b/naoModule/libnaoqi_files/lib/libqitype.so differ diff --git a/naoModule/libnaoqi_files/lib/librttools.so b/naoModule/libnaoqi_files/lib/librttools.so new file mode 100755 index 0000000..ca463f2 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/librttools.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/libalbase.so b/naoModule/libnaoqi_files/lib/naoqi/libalbase.so new file mode 100755 index 0000000..9c41eda Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/libalbase.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/libaldummyvisionextractor.so b/naoModule/libnaoqi_files/lib/naoqi/libaldummyvisionextractor.so new file mode 100755 index 0000000..90e31ee Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/libaldummyvisionextractor.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/libalfilemanager.so b/naoModule/libnaoqi_files/lib/naoqi/libalfilemanager.so new file mode 100755 index 0000000..14f060b Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/libalfilemanager.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/liballogger.so b/naoModule/libnaoqi_files/lib/naoqi/liballogger.so new file mode 100755 index 0000000..83894dc Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/liballogger.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/libalmemory.so b/naoModule/libnaoqi_files/lib/naoqi/libalmemory.so new file mode 100755 index 0000000..bb7e9c8 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/libalmemory.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/libalpreferences.so b/naoModule/libnaoqi_files/lib/naoqi/libalpreferences.so new file mode 100755 index 0000000..b8e70cf Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/libalpreferences.so differ diff --git a/naoModule/libnaoqi_files/lib/naoqi/liblauncher.so b/naoModule/libnaoqi_files/lib/naoqi/liblauncher.so new file mode 100755 index 0000000..835aba6 Binary files /dev/null and b/naoModule/libnaoqi_files/lib/naoqi/liblauncher.so differ diff --git a/naoModule/libnaoqi_files/share/cmake/NAOQI-PLUGINS-TOOLS/NAOQI-PLUGINS-TOOLSConfig.cmake b/naoModule/libnaoqi_files/share/cmake/NAOQI-PLUGINS-TOOLS/NAOQI-PLUGINS-TOOLSConfig.cmake new file mode 100755 index 0000000..bfaee00 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/NAOQI-PLUGINS-TOOLS/NAOQI-PLUGINS-TOOLSConfig.cmake @@ -0,0 +1,71 @@ +## +## Author(s): +## - Cedric GESTES +## +## Copyright (C) 2008, 2010 Aldebaran Robotics + + +#configure preferences +#copy each .xml +#todo: take an argument to specify another prefs folder +function (create_prefs) + if (EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/prefs/") + file(GLOB _prefs "${CMAKE_CURRENT_SOURCE_DIR}/prefs/*.xml") + file(COPY ${_prefs} DESTINATION "${SDK_DIR}/${_SDK_CONF}/naoqi") + qi_install_conf(${_prefs} SUBFOLDER naoqi) + endif (EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/prefs/") +endfunction (create_prefs) + + +function (create_module moduleName) + string(TOUPPER ${moduleName} _MODULENAME) + string(REPLACE "-" "_" MODULENAME ${_MODULENAME}) + create_prefs() + + set(_default_remote) + + set(_default_remote "OFF") + if("${ARGV1}" STREQUAL DEFAULT_REMOTE_ON) + set(_default_remote "ON") + endif() + if("${ARGV1}" STREQUAL DEFAULT_REMOTE_OFF) + set(_default_remote "OFF") + endif() + + option(${MODULENAME}_IS_REMOTE "module is compile as a remote module (ON or OFF)" "${_default_remote}") + + if (${MODULENAME}_IS_REMOTE) + add_definitions(" -D${MODULENAME}_IS_REMOTE_ON ") + else (${MODULENAME}_IS_REMOTE) + add_definitions(" -D${MODULENAME}_IS_REMOTE_OFF ") + endif (${MODULENAME}_IS_REMOTE) + + + if(MSVC) + add_definitions (" -DNOMINMAX ") + add_definitions (" -DWIN32_LEAN_AND_MEAN ") + endif() + +endfunction() + + +function (configure_src_module moduleName) + string(TOUPPER ${moduleName} _MODULENAME) + string(REPLACE "-" "_" MODULENAME ${_MODULENAME}) + + if (${MODULENAME}_IS_REMOTE STREQUAL "OFF") + create_lib(${moduleName} NOBINDLL SUBFOLDER naoqi SHARED ${ARGN}) + if(APPLE) + # On mac, ALError does not work through static libraries. + # See FS#2827 for more information: + # Also : http://gcc.gnu.org/wiki/Visibility + # |_ Problems with C++ exceptions (please read!) + set_target_properties(${moduleName} + PROPERTIES + LINK_FLAGS "-Wl,-flat_namespace" + ) + endif() + else() + create_bin(${moduleName} ${ARGN}) + endif() +endfunction() diff --git a/naoModule/libnaoqi_files/share/cmake/alagilityutils/alagilityutils-config.cmake b/naoModule/libnaoqi_files/share/cmake/alagilityutils/alagilityutils-config.cmake new file mode 100755 index 0000000..53bbc3d --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alagilityutils/alagilityutils-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALAGILITYUTILS_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALAGILITYUTILS_INCLUDE_DIRS) + + +find_library(ALAGILITYUTILS_DEBUG_LIBRARY alagilityutils_d) +find_library(ALAGILITYUTILS_LIBRARY alagilityutils) + + +if (ALAGILITYUTILS_DEBUG_LIBRARY) + set(ALAGILITYUTILS_LIBRARIES optimized;${ALAGILITYUTILS_LIBRARY};debug;${ALAGILITYUTILS_DEBUG_LIBRARY}) +else() + set(ALAGILITYUTILS_LIBRARIES ${ALAGILITYUTILS_LIBRARY}) +endif() + +set(ALAGILITYUTILS_LIBRARIES ${ALAGILITYUTILS_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALAGILITYUTILS DEFAULT_MSG + ALAGILITYUTILS_LIBRARIES + ALAGILITYUTILS_INCLUDE_DIRS +) +set(ALAGILITYUTILS_PACKAGE_FOUND ${ALAGILITYUTILS_FOUND} CACHE INTERNAL "" FORCE) + +set(ALAGILITYUTILS_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT;BOOST" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alaudio/alaudio-config.cmake b/naoModule/libnaoqi_files/share/cmake/alaudio/alaudio-config.cmake new file mode 100755 index 0000000..fa7b73b --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alaudio/alaudio-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALAUDIO_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALAUDIO_INCLUDE_DIRS) + + +find_library(ALAUDIO_DEBUG_LIBRARY alaudio_d) +find_library(ALAUDIO_LIBRARY alaudio) + + +if (ALAUDIO_DEBUG_LIBRARY) + set(ALAUDIO_LIBRARIES optimized;${ALAUDIO_LIBRARY};debug;${ALAUDIO_DEBUG_LIBRARY}) +else() + set(ALAUDIO_LIBRARIES ${ALAUDIO_LIBRARY}) +endif() + +set(ALAUDIO_LIBRARIES ${ALAUDIO_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALAUDIO DEFAULT_MSG + ALAUDIO_LIBRARIES + ALAUDIO_INCLUDE_DIRS +) +set(ALAUDIO_PACKAGE_FOUND ${ALAUDIO_FOUND} CACHE INTERNAL "" FORCE) + +set(ALAUDIO_DEPENDS "ALEXTRACTOR;ALTHREAD;ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/albehavior/albehavior-config.cmake b/naoModule/libnaoqi_files/share/cmake/albehavior/albehavior-config.cmake new file mode 100755 index 0000000..ebbb10f --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/albehavior/albehavior-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALBEHAVIOR_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALBEHAVIOR_INCLUDE_DIRS) + + +find_library(ALBEHAVIOR_DEBUG_LIBRARY albehavior_d) +find_library(ALBEHAVIOR_LIBRARY albehavior) + + +if (ALBEHAVIOR_DEBUG_LIBRARY) + set(ALBEHAVIOR_LIBRARIES optimized;${ALBEHAVIOR_LIBRARY};debug;${ALBEHAVIOR_DEBUG_LIBRARY}) +else() + set(ALBEHAVIOR_LIBRARIES ${ALBEHAVIOR_LIBRARY}) +endif() + +set(ALBEHAVIOR_LIBRARIES ${ALBEHAVIOR_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALBEHAVIOR DEFAULT_MSG + ALBEHAVIOR_LIBRARIES + ALBEHAVIOR_INCLUDE_DIRS +) +set(ALBEHAVIOR_PACKAGE_FOUND ${ALBEHAVIOR_FOUND} CACHE INTERNAL "" FORCE) + +set(ALBEHAVIOR_DEPENDS "ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;QIMESSAGING;QITYPE;BOOST_DATE_TIME;ALTHREAD;ALERROR;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;DL;RT;PTHREAD;BOOST" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alcommon/alcommon-config.cmake b/naoModule/libnaoqi_files/share/cmake/alcommon/alcommon-config.cmake new file mode 100755 index 0000000..f0c25fd --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alcommon/alcommon-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALCOMMON_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALCOMMON_INCLUDE_DIRS) + + +find_library(ALCOMMON_DEBUG_LIBRARY alcommon_d) +find_library(ALCOMMON_LIBRARY alcommon) + + +if (ALCOMMON_DEBUG_LIBRARY) + set(ALCOMMON_LIBRARIES optimized;${ALCOMMON_LIBRARY};debug;${ALCOMMON_DEBUG_LIBRARY}) +else() + set(ALCOMMON_LIBRARIES ${ALCOMMON_LIBRARY}) +endif() + +set(ALCOMMON_LIBRARIES ${ALCOMMON_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALCOMMON DEFAULT_MSG + ALCOMMON_LIBRARIES + ALCOMMON_INCLUDE_DIRS +) +set(ALCOMMON_PACKAGE_FOUND ${ALCOMMON_FOUND} CACHE INTERNAL "" FORCE) + +set(ALCOMMON_DEPENDS "ALVALUE;ALERROR;QIMESSAGING;QITYPE;BOOST;BOOST_DATE_TIME;BOOST_SIGNALS;RTTOOLS;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;RT;DL" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/aldebaran-settings/aldebaran-settings-config.cmake b/naoModule/libnaoqi_files/share/cmake/aldebaran-settings/aldebaran-settings-config.cmake new file mode 100755 index 0000000..b508571 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/aldebaran-settings/aldebaran-settings-config.cmake @@ -0,0 +1,64 @@ +## +## Copyright (C) 2011 Aldebaran Robotics +## + +## +# This file contains specific Aldebaran +# settings for every 'desktop' projects: + + +# We you use CDash, for your tests, you use: +# include(CTest) +# and this handles the call to enable_testing() +# +# We do not use CDash, so we can safely always call this: +enable_testing() + +# We need this for boost 1.44 to use boost::filesystem v3 API +# (the v3 version is on by default in later versions of boost) +add_definitions("-DBOOST_FILESYSTEM_VERSION=3") + +if(MSVC) + # If your using Visual Studio Express and this setting is on, you + # will get a annoying pop-up and visual studio will convert the project + # to remove the subfolders, so let's not use this by default. + set_property(GLOBAL PROPERTY USE_FOLDERS ON) + # Avoid GTEST using its own tuple, when we have a real tuple. + # Note: for this to work on vs2008 you need to install the Feature pack + add_definitions(" -DGTEST_USE_OWN_TR1_TUPLE=0 ") + # Fix annoying windows.h quirks: + add_definitions(" -DNOMINMAX ") + add_definitions(" -D_CRT_SECURE_NO_DEPRECATE ") + add_definitions(" -D_SCL_SECURE_NO_WARNINGS ") + + # Make sure _M_PI et al are defined when including + add_definitions(" -D_USE_MATH_DEFINES ") + + # Specific to Aldebaran: + # This reduces the build time when you + # include Windows.h, but you have to include winsock2.h + # yourself. + add_definitions(" -DWIN32_LEAN_AND_MEAN ") +endif() + +if(UNIX) + # on gcc no return statement in function returning non-void, + # does not cause any error or warning, but on cl.exe it won't + # compile, so at least add the compile flag: + add_definitions(" -Wreturn-type ") +endif() + +# For efficiency reasons, constructors of Eigen matrices do not initialize the +# matrix elements. Initialisation should be done explicitly. +# It's quite easy to forget to do so, or to initialize only parts of a matrix. +# Generally valgrind and coverity don't spot these errors. Moreover, it seems +# that in debug, all memory is zero initialized anyway so the error is hard to +# spot. +# So we use the EIGEN_INITIALIZE_MATRICES_BY_NAN flag to tell eigen to first +# initialize the matrices to NaN, in the hope that somethig will break and go +# noticed. This feature was added in Eigen 3.2, and we backported it to Eigen +# 3.1.2. + +if("${CMAKE_BUILD_TYPE}" STREQUAL "Debug") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DEIGEN_INITIALIZE_MATRICES_BY_NAN=1") +endif() diff --git a/naoModule/libnaoqi_files/share/cmake/alerror/alerror-config.cmake b/naoModule/libnaoqi_files/share/cmake/alerror/alerror-config.cmake new file mode 100755 index 0000000..186be85 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alerror/alerror-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALERROR_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALERROR_INCLUDE_DIRS) + + +find_library(ALERROR_DEBUG_LIBRARY alerror_d) +find_library(ALERROR_LIBRARY alerror) + + +if (ALERROR_DEBUG_LIBRARY) + set(ALERROR_LIBRARIES optimized;${ALERROR_LIBRARY};debug;${ALERROR_DEBUG_LIBRARY}) +else() + set(ALERROR_LIBRARIES ${ALERROR_LIBRARY}) +endif() + +set(ALERROR_LIBRARIES ${ALERROR_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALERROR DEFAULT_MSG + ALERROR_LIBRARIES + ALERROR_INCLUDE_DIRS +) +set(ALERROR_PACKAGE_FOUND ${ALERROR_FOUND} CACHE INTERNAL "" FORCE) + +set(ALERROR_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alextractor/alextractor-config.cmake b/naoModule/libnaoqi_files/share/cmake/alextractor/alextractor-config.cmake new file mode 100755 index 0000000..913844a --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alextractor/alextractor-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALEXTRACTOR_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALEXTRACTOR_INCLUDE_DIRS) + + +find_library(ALEXTRACTOR_DEBUG_LIBRARY alextractor_d) +find_library(ALEXTRACTOR_LIBRARY alextractor) + + +if (ALEXTRACTOR_DEBUG_LIBRARY) + set(ALEXTRACTOR_LIBRARIES optimized;${ALEXTRACTOR_LIBRARY};debug;${ALEXTRACTOR_DEBUG_LIBRARY}) +else() + set(ALEXTRACTOR_LIBRARIES ${ALEXTRACTOR_LIBRARY}) +endif() + +set(ALEXTRACTOR_LIBRARIES ${ALEXTRACTOR_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALEXTRACTOR DEFAULT_MSG + ALEXTRACTOR_LIBRARIES + ALEXTRACTOR_INCLUDE_DIRS +) +set(ALEXTRACTOR_PACKAGE_FOUND ${ALEXTRACTOR_FOUND} CACHE INTERNAL "" FORCE) + +set(ALEXTRACTOR_DEPENDS "ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;QIMESSAGING;QITYPE;BOOST_DATE_TIME;ALTHREAD;ALERROR;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;DL;RT;PTHREAD;BOOST" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/allauncher/allauncher-config.cmake b/naoModule/libnaoqi_files/share/cmake/allauncher/allauncher-config.cmake new file mode 100755 index 0000000..ded81e3 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/allauncher/allauncher-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALLAUNCHER_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALLAUNCHER_INCLUDE_DIRS) + + +find_library(ALLAUNCHER_DEBUG_LIBRARY allauncher_d) +find_library(ALLAUNCHER_LIBRARY allauncher) + + +if (ALLAUNCHER_DEBUG_LIBRARY) + set(ALLAUNCHER_LIBRARIES optimized;${ALLAUNCHER_LIBRARY};debug;${ALLAUNCHER_DEBUG_LIBRARY}) +else() + set(ALLAUNCHER_LIBRARIES ${ALLAUNCHER_LIBRARY}) +endif() + +set(ALLAUNCHER_LIBRARIES ${ALLAUNCHER_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALLAUNCHER DEFAULT_MSG + ALLAUNCHER_LIBRARIES + ALLAUNCHER_INCLUDE_DIRS +) +set(ALLAUNCHER_PACKAGE_FOUND ${ALLAUNCHER_FOUND} CACHE INTERNAL "" FORCE) + +set(ALLAUNCHER_DEPENDS "ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/almath/almath-config.cmake b/naoModule/libnaoqi_files/share/cmake/almath/almath-config.cmake new file mode 100755 index 0000000..d14dc7a --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/almath/almath-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALMATH_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALMATH_INCLUDE_DIRS) + + +find_library(ALMATH_DEBUG_LIBRARY almath_d) +find_library(ALMATH_LIBRARY almath) + + +if (ALMATH_DEBUG_LIBRARY) + set(ALMATH_LIBRARIES optimized;${ALMATH_LIBRARY};debug;${ALMATH_DEBUG_LIBRARY}) +else() + set(ALMATH_LIBRARIES ${ALMATH_LIBRARY}) +endif() + +set(ALMATH_LIBRARIES ${ALMATH_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALMATH DEFAULT_MSG + ALMATH_LIBRARIES + ALMATH_INCLUDE_DIRS +) +set(ALMATH_PACKAGE_FOUND ${ALMATH_FOUND} CACHE INTERNAL "" FORCE) + +set(ALMATH_DEPENDS "" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/almemoryfastaccess/almemoryfastaccess-config.cmake b/naoModule/libnaoqi_files/share/cmake/almemoryfastaccess/almemoryfastaccess-config.cmake new file mode 100755 index 0000000..4f59ec6 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/almemoryfastaccess/almemoryfastaccess-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALMEMORYFASTACCESS_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALMEMORYFASTACCESS_INCLUDE_DIRS) + + +find_library(ALMEMORYFASTACCESS_DEBUG_LIBRARY almemoryfastaccess_d) +find_library(ALMEMORYFASTACCESS_LIBRARY almemoryfastaccess) + + +if (ALMEMORYFASTACCESS_DEBUG_LIBRARY) + set(ALMEMORYFASTACCESS_LIBRARIES optimized;${ALMEMORYFASTACCESS_LIBRARY};debug;${ALMEMORYFASTACCESS_DEBUG_LIBRARY}) +else() + set(ALMEMORYFASTACCESS_LIBRARIES ${ALMEMORYFASTACCESS_LIBRARY}) +endif() + +set(ALMEMORYFASTACCESS_LIBRARIES ${ALMEMORYFASTACCESS_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALMEMORYFASTACCESS DEFAULT_MSG + ALMEMORYFASTACCESS_LIBRARIES + ALMEMORYFASTACCESS_INCLUDE_DIRS +) +set(ALMEMORYFASTACCESS_PACKAGE_FOUND ${ALMEMORYFASTACCESS_FOUND} CACHE INTERNAL "" FORCE) + +set(ALMEMORYFASTACCESS_DEPENDS "ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alparammanager/alparammanager-config.cmake b/naoModule/libnaoqi_files/share/cmake/alparammanager/alparammanager-config.cmake new file mode 100755 index 0000000..d5bad87 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alparammanager/alparammanager-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALPARAMMANAGER_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALPARAMMANAGER_INCLUDE_DIRS) + + +find_library(ALPARAMMANAGER_DEBUG_LIBRARY alparammanager_d) +find_library(ALPARAMMANAGER_LIBRARY alparammanager) + + +if (ALPARAMMANAGER_DEBUG_LIBRARY) + set(ALPARAMMANAGER_LIBRARIES optimized;${ALPARAMMANAGER_LIBRARY};debug;${ALPARAMMANAGER_DEBUG_LIBRARY}) +else() + set(ALPARAMMANAGER_LIBRARIES ${ALPARAMMANAGER_LIBRARY}) +endif() + +set(ALPARAMMANAGER_LIBRARIES ${ALPARAMMANAGER_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALPARAMMANAGER DEFAULT_MSG + ALPARAMMANAGER_LIBRARIES + ALPARAMMANAGER_INCLUDE_DIRS +) +set(ALPARAMMANAGER_PACKAGE_FOUND ${ALPARAMMANAGER_FOUND} CACHE INTERNAL "" FORCE) + +set(ALPARAMMANAGER_DEPENDS "" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alproxies/alproxies-config.cmake b/naoModule/libnaoqi_files/share/cmake/alproxies/alproxies-config.cmake new file mode 100755 index 0000000..e2e1501 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alproxies/alproxies-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALPROXIES_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALPROXIES_INCLUDE_DIRS) + + +find_library(ALPROXIES_DEBUG_LIBRARY alproxies_d) +find_library(ALPROXIES_LIBRARY alproxies) + + +if (ALPROXIES_DEBUG_LIBRARY) + set(ALPROXIES_LIBRARIES optimized;${ALPROXIES_LIBRARY};debug;${ALPROXIES_DEBUG_LIBRARY}) +else() + set(ALPROXIES_LIBRARIES ${ALPROXIES_LIBRARY}) +endif() + +set(ALPROXIES_LIBRARIES ${ALPROXIES_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALPROXIES DEFAULT_MSG + ALPROXIES_LIBRARIES + ALPROXIES_INCLUDE_DIRS +) +set(ALPROXIES_PACKAGE_FOUND ${ALPROXIES_FOUND} CACHE INTERNAL "" FORCE) + +set(ALPROXIES_DEPENDS "ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alpythontools/alpythontools-config.cmake b/naoModule/libnaoqi_files/share/cmake/alpythontools/alpythontools-config.cmake new file mode 100755 index 0000000..66f20b3 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alpythontools/alpythontools-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALPYTHONTOOLS_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALPYTHONTOOLS_INCLUDE_DIRS) + + +find_library(ALPYTHONTOOLS_DEBUG_LIBRARY alpythontools_d) +find_library(ALPYTHONTOOLS_LIBRARY alpythontools) + + +if (ALPYTHONTOOLS_DEBUG_LIBRARY) + set(ALPYTHONTOOLS_LIBRARIES optimized;${ALPYTHONTOOLS_LIBRARY};debug;${ALPYTHONTOOLS_DEBUG_LIBRARY}) +else() + set(ALPYTHONTOOLS_LIBRARIES ${ALPYTHONTOOLS_LIBRARY}) +endif() + +set(ALPYTHONTOOLS_LIBRARIES ${ALPYTHONTOOLS_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALPYTHONTOOLS DEFAULT_MSG + ALPYTHONTOOLS_LIBRARIES + ALPYTHONTOOLS_INCLUDE_DIRS +) +set(ALPYTHONTOOLS_PACKAGE_FOUND ${ALPYTHONTOOLS_FOUND} CACHE INTERNAL "" FORCE) + +set(ALPYTHONTOOLS_DEPENDS "ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD;BOOST;PYTHON" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alserial/alserial-config.cmake b/naoModule/libnaoqi_files/share/cmake/alserial/alserial-config.cmake new file mode 100755 index 0000000..437b303 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alserial/alserial-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALSERIAL_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALSERIAL_INCLUDE_DIRS) + + +find_library(ALSERIAL_DEBUG_LIBRARY alserial_d) +find_library(ALSERIAL_LIBRARY alserial) + + +if (ALSERIAL_DEBUG_LIBRARY) + set(ALSERIAL_LIBRARIES optimized;${ALSERIAL_LIBRARY};debug;${ALSERIAL_DEBUG_LIBRARY}) +else() + set(ALSERIAL_LIBRARIES ${ALSERIAL_LIBRARY}) +endif() + +set(ALSERIAL_LIBRARIES ${ALSERIAL_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALSERIAL DEFAULT_MSG + ALSERIAL_LIBRARIES + ALSERIAL_INCLUDE_DIRS +) +set(ALSERIAL_PACKAGE_FOUND ${ALSERIAL_FOUND} CACHE INTERNAL "" FORCE) + +set(ALSERIAL_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT;TINYXML" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alsoap/alsoap-config.cmake b/naoModule/libnaoqi_files/share/cmake/alsoap/alsoap-config.cmake new file mode 100755 index 0000000..fbdc2ce --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alsoap/alsoap-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALSOAP_INCLUDE_DIRS "${ROOT_DIR}/include;${ROOT_DIR}/include/soap;${ROOT_DIR}/include/alsoap" CACHE STRING "" FORCE) +mark_as_advanced(ALSOAP_INCLUDE_DIRS) + + +find_library(ALSOAP_DEBUG_LIBRARY alsoap_d) +find_library(ALSOAP_LIBRARY alsoap) + + +if (ALSOAP_DEBUG_LIBRARY) + set(ALSOAP_LIBRARIES optimized;${ALSOAP_LIBRARY};debug;${ALSOAP_DEBUG_LIBRARY}) +else() + set(ALSOAP_LIBRARIES ${ALSOAP_LIBRARY}) +endif() + +set(ALSOAP_LIBRARIES ${ALSOAP_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALSOAP DEFAULT_MSG + ALSOAP_LIBRARIES + ALSOAP_INCLUDE_DIRS +) +set(ALSOAP_PACKAGE_FOUND ${ALSOAP_FOUND} CACHE INTERNAL "" FORCE) + +set(ALSOAP_DEPENDS "ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD;TINYXML" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/althread/althread-config.cmake b/naoModule/libnaoqi_files/share/cmake/althread/althread-config.cmake new file mode 100755 index 0000000..c3328f9 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/althread/althread-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALTHREAD_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALTHREAD_INCLUDE_DIRS) + + +find_library(ALTHREAD_DEBUG_LIBRARY althread_d) +find_library(ALTHREAD_LIBRARY althread) + + +if (ALTHREAD_DEBUG_LIBRARY) + set(ALTHREAD_LIBRARIES optimized;${ALTHREAD_LIBRARY};debug;${ALTHREAD_DEBUG_LIBRARY}) +else() + set(ALTHREAD_LIBRARIES ${ALTHREAD_LIBRARY}) +endif() + +set(ALTHREAD_LIBRARIES ${ALTHREAD_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALTHREAD DEFAULT_MSG + ALTHREAD_LIBRARIES + ALTHREAD_INCLUDE_DIRS +) +set(ALTHREAD_PACKAGE_FOUND ${ALTHREAD_FOUND} CACHE INTERNAL "" FORCE) + +set(ALTHREAD_DEPENDS "ALERROR;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;DL;RT;PTHREAD;BOOST" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alvalue/alvalue-config.cmake b/naoModule/libnaoqi_files/share/cmake/alvalue/alvalue-config.cmake new file mode 100755 index 0000000..4831395 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alvalue/alvalue-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALVALUE_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALVALUE_INCLUDE_DIRS) + + +find_library(ALVALUE_DEBUG_LIBRARY alvalue_d) +find_library(ALVALUE_LIBRARY alvalue) + + +if (ALVALUE_DEBUG_LIBRARY) + set(ALVALUE_LIBRARIES optimized;${ALVALUE_LIBRARY};debug;${ALVALUE_DEBUG_LIBRARY}) +else() + set(ALVALUE_LIBRARIES ${ALVALUE_LIBRARY}) +endif() + +set(ALVALUE_LIBRARIES ${ALVALUE_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALVALUE DEFAULT_MSG + ALVALUE_LIBRARIES + ALVALUE_INCLUDE_DIRS +) +set(ALVALUE_PACKAGE_FOUND ${ALVALUE_FOUND} CACHE INTERNAL "" FORCE) + +set(ALVALUE_DEPENDS "ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alvalueutils/alvalueutils-config.cmake b/naoModule/libnaoqi_files/share/cmake/alvalueutils/alvalueutils-config.cmake new file mode 100755 index 0000000..2674b1a --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alvalueutils/alvalueutils-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALVALUEUTILS_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALVALUEUTILS_INCLUDE_DIRS) + + +find_library(ALVALUEUTILS_DEBUG_LIBRARY alvalueutils_d) +find_library(ALVALUEUTILS_LIBRARY alvalueutils) + + +if (ALVALUEUTILS_DEBUG_LIBRARY) + set(ALVALUEUTILS_LIBRARIES optimized;${ALVALUEUTILS_LIBRARY};debug;${ALVALUEUTILS_DEBUG_LIBRARY}) +else() + set(ALVALUEUTILS_LIBRARIES ${ALVALUEUTILS_LIBRARY}) +endif() + +set(ALVALUEUTILS_LIBRARIES ${ALVALUEUTILS_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALVALUEUTILS DEFAULT_MSG + ALVALUEUTILS_LIBRARIES + ALVALUEUTILS_INCLUDE_DIRS +) +set(ALVALUEUTILS_PACKAGE_FOUND ${ALVALUEUTILS_FOUND} CACHE INTERNAL "" FORCE) + +set(ALVALUEUTILS_DEPENDS "ALVALUE;ALERROR;QIMESSAGING;QITYPE;BOOST_DATE_TIME;ALMATHINTERNAL;ALMATH;EIGEN3;ALAGILITYUTILS;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT;BOOST" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/alvision/alvision-config.cmake b/naoModule/libnaoqi_files/share/cmake/alvision/alvision-config.cmake new file mode 100755 index 0000000..001286f --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/alvision/alvision-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(ALVISION_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(ALVISION_INCLUDE_DIRS) + + +find_library(ALVISION_DEBUG_LIBRARY alvision_d) +find_library(ALVISION_LIBRARY alvision) + + +if (ALVISION_DEBUG_LIBRARY) + set(ALVISION_LIBRARIES optimized;${ALVISION_LIBRARY};debug;${ALVISION_DEBUG_LIBRARY}) +else() + set(ALVISION_LIBRARIES ${ALVISION_LIBRARY}) +endif() + +set(ALVISION_LIBRARIES ${ALVISION_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(ALVISION DEFAULT_MSG + ALVISION_LIBRARIES + ALVISION_INCLUDE_DIRS +) +set(ALVISION_PACKAGE_FOUND ${ALVISION_FOUND} CACHE INTERNAL "" FORCE) + +set(ALVISION_DEPENDS "ALEXTRACTOR;ALTHREAD;ALPROXIES;ALCOMMON;BOOST_SIGNALS;RTTOOLS;ALVALUE;ALERROR;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qi/qi-config.cmake b/naoModule/libnaoqi_files/share/cmake/qi/qi-config.cmake new file mode 100755 index 0000000..3e76605 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qi/qi-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QI_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QI_INCLUDE_DIRS) + + +find_library(QI_DEBUG_LIBRARY qi_d) +find_library(QI_LIBRARY qi) + + +if (QI_DEBUG_LIBRARY) + set(QI_LIBRARIES optimized;${QI_LIBRARY};debug;${QI_DEBUG_LIBRARY}) +else() + set(QI_LIBRARIES ${QI_LIBRARY}) +endif() + +set(QI_LIBRARIES ${QI_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QI DEFAULT_MSG + QI_LIBRARIES + QI_INCLUDE_DIRS +) +set(QI_PACKAGE_FOUND ${QI_FOUND} CACHE INTERNAL "" FORCE) + +set(QI_DEPENDS "BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qic/qic-config.cmake b/naoModule/libnaoqi_files/share/cmake/qic/qic-config.cmake new file mode 100755 index 0000000..9f70520 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qic/qic-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QIC_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QIC_INCLUDE_DIRS) + + +find_library(QIC_DEBUG_LIBRARY qic_d) +find_library(QIC_LIBRARY qic) + + +if (QIC_DEBUG_LIBRARY) + set(QIC_LIBRARIES optimized;${QIC_LIBRARY};debug;${QIC_DEBUG_LIBRARY}) +else() + set(QIC_LIBRARIES ${QIC_LIBRARY}) +endif() + +set(QIC_LIBRARIES ${QIC_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QIC DEFAULT_MSG + QIC_LIBRARIES + QIC_INCLUDE_DIRS +) +set(QIC_PACKAGE_FOUND ${QIC_FOUND} CACHE INTERNAL "" FORCE) + +set(QIC_DEPENDS "QIMESSAGING;QITYPE;BOOST;BOOST_DATE_TIME;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qimessaging/qimessaging-config.cmake b/naoModule/libnaoqi_files/share/cmake/qimessaging/qimessaging-config.cmake new file mode 100755 index 0000000..304eea3 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qimessaging/qimessaging-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QIMESSAGING_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QIMESSAGING_INCLUDE_DIRS) + + +find_library(QIMESSAGING_DEBUG_LIBRARY qimessaging_d) +find_library(QIMESSAGING_LIBRARY qimessaging) + + +if (QIMESSAGING_DEBUG_LIBRARY) + set(QIMESSAGING_LIBRARIES optimized;${QIMESSAGING_LIBRARY};debug;${QIMESSAGING_DEBUG_LIBRARY}) +else() + set(QIMESSAGING_LIBRARIES ${QIMESSAGING_LIBRARY}) +endif() + +set(QIMESSAGING_LIBRARIES ${QIMESSAGING_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QIMESSAGING DEFAULT_MSG + QIMESSAGING_LIBRARIES + QIMESSAGING_INCLUDE_DIRS +) +set(QIMESSAGING_PACKAGE_FOUND ${QIMESSAGING_FOUND} CACHE INTERNAL "" FORCE) + +set(QIMESSAGING_DEPENDS "QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qiperf/qiperf-config.cmake b/naoModule/libnaoqi_files/share/cmake/qiperf/qiperf-config.cmake new file mode 100755 index 0000000..17e6eae --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qiperf/qiperf-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QIPERF_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QIPERF_INCLUDE_DIRS) + + +find_library(QIPERF_DEBUG_LIBRARY qiperf_d) +find_library(QIPERF_LIBRARY qiperf) + + +if (QIPERF_DEBUG_LIBRARY) + set(QIPERF_LIBRARIES optimized;${QIPERF_LIBRARY};debug;${QIPERF_DEBUG_LIBRARY}) +else() + set(QIPERF_LIBRARIES ${QIPERF_LIBRARY}) +endif() + +set(QIPERF_LIBRARIES ${QIPERF_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QIPERF DEFAULT_MSG + QIPERF_LIBRARIES + QIPERF_INCLUDE_DIRS +) +set(QIPERF_PACKAGE_FOUND ${QIPERF_FOUND} CACHE INTERNAL "" FORCE) + +set(QIPERF_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qiprobes/qiprobes-config.cmake b/naoModule/libnaoqi_files/share/cmake/qiprobes/qiprobes-config.cmake new file mode 100755 index 0000000..a67e63b --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qiprobes/qiprobes-config.cmake @@ -0,0 +1,223 @@ +##### preliminaries + +get_filename_component(_PROBES_CMAKE_DIR ${CMAKE_CURRENT_LIST_FILE} PATH) + +# Find python, but avoid using python from python package +find_program(_python_executable + NAMES python2 python python.exe + NO_CMAKE_FIND_ROOT_PATH) +if (NOT _python_executable) + qi_error("qiprobes needs python executable in PATH") +endif() + +# this variable lets us choose how we build and link the probes providers +# todo: maybe we should make it a real option (in the cache) or set it +# on a per probe basis +if(NOT DEFINED QIPROBES_PROVIDER_BUILD_MODE) + set(QIPROBES_PROVIDER_BUILD_MODE "BUILTIN") +endif() + +##### internal functions + +## +# append_source_file_property(property value +# file0.c file1.c ... +# ) +function(append_source_file_property property value) + foreach(_file IN LISTS ARGN) + get_source_file_property(_current_value "${_file}" "${property}") + if ("${_current_value}" STREQUAL "NOTFOUND") + set(_new_value "${value}") + else() + set(_new_value "${_current_value} ${value}") + endif() + set_source_files_properties(${_file} + PROPERTIES "${property}" + "${_new_value}") + endforeach() +endfunction() + +##### public functions + +## +# qiprobes_create_probe(tp_sensorlog +# tp_sensorlog.in.h +# PROVIDER_NAME qi_sensorlog +# ) +function(qiprobes_create_probe probe tp_in_h) + cmake_parse_arguments(ARG "" "PROVIDER_NAME" "" ${ARGN}) + set(_provider "${ARG_PROVIDER_NAME}") + if(NOT _provider) + qi_error("Cannot create probe. PROVIDER_NAME argument is mandatory") + endif() + if(IS_ABSOLUTE tp_in_h) + qi_error("Cannot create probe. The path to the probe definitions file is absolute") + endif() + if(NOT (${tp_in_h} MATCHES "^.*\\.in\\.h$")) + qi_error("Cannot create probe. The probe definitions file ${tp_in_h} does not end with .in.h") + endif() + get_filename_component(_tp_in_h_abs "${tp_in_h}" ABSOLUTE) + if(NOT EXISTS ${_tp_in_h_abs}) + qi_error("Cannot create probe. Could not find probe definitions file ${tp_in_h}") + endif() + # Generate ${_tp}.h + get_filename_component(_tp_path "${tp_in_h}" PATH) + get_filename_component(_tp_name "${tp_in_h}" NAME_WE) + if(_tp_path) + set(_tp "${_tp_path}/${_tp_name}") + file(MAKE_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/${_tp_path}") + include_directories("${CMAKE_CURRENT_BINARY_DIR}/${_tp_path}") + else() + set(_tp "${_tp_name}") + include_directories("${CMAKE_CURRENT_BINARY_DIR}") + endif() + set(_tp_h "${CMAKE_CURRENT_BINARY_DIR}/${_tp}.h") + + # TODO: generate guard from _tp instead of _tp_name + # TODO: check the providers in ${_tp_in_h_abs} are all equal to ${_provider} + # or deduce one from the other. + string(TOUPPER "${_tp_name}_H" _tp_h_reinclusion_protection) + # call an external templating engine to include content from tp_in_h and + # get proper dependency declaration. + add_custom_command(OUTPUT "${_tp_h}" + COMMENT "Generating tracepoints declaration in ${_tp_h} ..." + COMMAND "${_python_executable}" ARGS + "${_PROBES_CMAKE_DIR}/tpl.py" -d _tp_h_reinclusion_protection "${_tp_h_reinclusion_protection}" + -d _provider "${_provider}" + -d _tp_h "${_tp_h}" + -i _tp_def_contents "${_tp_in_h_abs}" + -o "${_tp_h}" + "${_PROBES_CMAKE_DIR}/tp_probes.in.h" + DEPENDS ${tp_in_h}) + set_source_files_properties("${_tp_h}" PROPERTIES GENERATED TRUE) + # submodule collecting dependencies (sources files and libraries) of the + # instrumented objects + qi_submodule_create("${probe}" SRC "${_tp_h}") + + if(WITH_PROBES) + if(NOT UNIX OR APPLE) + qi_error("WITH_PROBES is only available on linux") + endif() + qi_submodule_add("${probe}" DEPENDS DL) + + # Generate ${probe}.c + set(_tp_c ${CMAKE_CURRENT_BINARY_DIR}/${probe}.c) + configure_file("${_PROBES_CMAKE_DIR}/probe.in.c" "${_tp_c}") + + # create the probes provider lib from ${_tp_c} + # We can either create a shared lib, which should be LD_PRELOAD'ed at + # runtime, or a static one, which should be linked at run time + # + # Here is an example: + # libbn-ipc implements the synchronisation mechanism between the HAL and + # the DCM. The HAL is a standalone application, the DCM is a module (shared + # library) which is LD_PRELOAD'ed by the NAOqi application. + # + # We added probes to libbn-ipc.a. If we build the probes provider into a + # shared library it should be LD_PRELOAD'ed when running both the HAL *and* + # NAOqi. The provider library must be linked with lttng-ust and the target + # applications (NAOqi and the HAL) must be linked with libdl. + # If we build the provider lib as a static library, we need to link it with + # lttng-ust, and then link libbn-ipc.a with the provier lib. C'est tout! + if(QIPROBES_PROVIDER_BUILD_MODE STREQUAL "BUILTIN") + # note: it is not really necessary to link with URCU, but LLTNG-UST needs + # the urcu/compiler.h header. + qi_submodule_add("${probe}" + SRC "${_tp_c}" + DEPENDS LIBLTTNG_UST LIBURCU) + elseif((QIPROBES_PROVIDER_BUILD_MODE STREQUAL "STATIC") OR + (QIPROBES_PROVIDER_BUILD_MODE STREQUAL "SHARED")) + if(QIPROBES_PROVIDER_BUILD_MODE STREQUAL "STATIC") + qi_error("qiprobes: QIPROBES_PROVIDER_BUILD_MODE == STATIC is currently not supported") + # because it was never tested + endif() + set(_probe_lib ${probe}) + qi_create_lib("${_probe_lib}" + ${QIPROBES_PROVIDER_BUILD_MODE} # linkage (note: shoud we add INTERNAL?) + ${_tp_h} + ${_tp_c} + SUBFOLDER probes) + # note: it is not really necessary to link with URCU, but LLTNG-UST needs + # the urcu/compiler.h header. + qi_use_lib("${_probe_lib}" LIBLTTNG_UST LIBURCU DL) + if(QIPROBES_PROVIDER_BUILD_MODE STREQUAL "STATIC") + # note: we do not stage the shared lib because it will be LD_PRELOADED + # but not linked with. + qi_stage_lib("${_probe_lib}") + qi_submodule_add("${probe}" DEPENDS "${_probe_lib}") + endif() + else() + qi_error("QIPROBES_PROVIDER_BUILD_MODE should be BUILTIN, STATIC or SHARED. However its current value is: \"${QIPROBES_PROVIDER_BUILD_MODE}\"") + endif() + + # In addition to the flag set in qi_instrument_files, + # one and only one of the application files + # should include ${_tp_h} with the TRACEPOINT_DEFINE macro set. + # + # As its name suggests, this macro will trigger the definition of + # functions. + # If it is done multiple times, compilation will fail because of multiple + # definitions. If it is not done, (or if the file does not include + # ${_tp_h}), linking will fail with messages like "undefined reference to + # `tracepoint_dlopen'". + # + # To avoid these issues, instead of using an (user-provided) instrumented + # file for this purpose, we use a generated file (${_tp_ccp}) + # which acts as an empty instrumented file. + # Alas, I do not expect this trick to work for C projects. (We may + # detect the language and generate C/C++ accordingly). + set(_tp_cpp ${CMAKE_CURRENT_BINARY_DIR}/${probe}.cpp) + configure_file("${_PROBES_CMAKE_DIR}/probe.in.cpp" "${_tp_cpp}") + set(_flags "-DWITH_PROBES -DTRACEPOINT_DEFINE") + if(QIPROBES_PROVIDER_BUILD_MODE STREQUAL "SHARED") + set(_flags "${_flags} -DTRACEPOINT_PROBE_DYNAMIC_LINKAGE") + endif() + append_source_file_property(COMPILE_FLAGS "${_flags}" "${_tp_cpp}") + qi_submodule_add("${probe}" SRC "${_tp_cpp}") + endif() + # tell the world the probe has been created + qi_global_set("QIPROBES_${probe}_IS_CREATED" TRUE) +endfunction() + +## +# qiprobes_instrument_files(probe +# PROVIDER_NAME qi_sensorlog +# ) +function(qiprobes_instrument_files probe) + qi_global_is_set(_is_probe_created "QIPROBES_${probe}_IS_CREATED") + if(NOT _is_probe_created) + qi_error("Cannot instrument files. The probe ${probe} does not exist.") + endif() + # Check the instrumented files really exist. This is not strictly necessary, + # but helps wasting hours because of a stupid typo (trust me). + foreach(_file IN LISTS ARGN) + # get absolute filename, otherwise cmake cannot test file existence + get_filename_component(_file_abs "${_file}" ABSOLUTE) + if(NOT EXISTS ${_file_abs}) + get_source_file_property(_generated "${_file}" GENERATED) + if(NOT _generated) + qi_error("Cannot create probe. The following instrumented file does not exist and is not marked as a generated source: ${_file}") + endif() + endif() + endforeach() + if(WITH_PROBES) + if(NOT UNIX OR APPLE) + qi_error("WITH_PROBES is only available on linux") + endif() + # Set flag to enable probe in each instrumented files + # Setting the flag file per file instead of setting it globally helps + # avoiding full-rebuilds when we toggle the probes. + append_source_file_property(COMPILE_FLAGS "-DWITH_PROBES" "${ARGN}") + endif() +endfunction() + +##### DEPRECATED for compat +function(qi_create_probe) + message(STATUS "DEPRECATED: replace qi_create_probe with qiprobes_create_probe") + qiprobes_create_probe(${ARGN}) +endfunction() + +function(qi_instrument_files) + message(STATUS "DEPRECATED: replace qi_instrument_files with qiprobes_instrument_files") + qiprobes_instrument_files(${ARGN}) +endfunction() diff --git a/naoModule/libnaoqi_files/share/cmake/qipython/qipython-config.cmake b/naoModule/libnaoqi_files/share/cmake/qipython/qipython-config.cmake new file mode 100755 index 0000000..521bd6b --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qipython/qipython-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QIPYTHON_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QIPYTHON_INCLUDE_DIRS) + + +find_library(QIPYTHON_DEBUG_LIBRARY qipython_d) +find_library(QIPYTHON_LIBRARY qipython) + + +if (QIPYTHON_DEBUG_LIBRARY) + set(QIPYTHON_LIBRARIES optimized;${QIPYTHON_LIBRARY};debug;${QIPYTHON_DEBUG_LIBRARY}) +else() + set(QIPYTHON_LIBRARIES ${QIPYTHON_LIBRARY}) +endif() + +set(QIPYTHON_LIBRARIES ${QIPYTHON_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QIPYTHON DEFAULT_MSG + QIPYTHON_LIBRARIES + QIPYTHON_INCLUDE_DIRS +) +set(QIPYTHON_PACKAGE_FOUND ${QIPYTHON_FOUND} CACHE INTERNAL "" FORCE) + +set(QIPYTHON_DEPENDS "BOOST_PYTHON;PYTHON;QIMESSAGING;QITYPE;QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/qitype/qitype-config.cmake b/naoModule/libnaoqi_files/share/cmake/qitype/qitype-config.cmake new file mode 100755 index 0000000..ffb381d --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/qitype/qitype-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(QITYPE_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(QITYPE_INCLUDE_DIRS) + + +find_library(QITYPE_DEBUG_LIBRARY qitype_d) +find_library(QITYPE_LIBRARY qitype) + + +if (QITYPE_DEBUG_LIBRARY) + set(QITYPE_LIBRARIES optimized;${QITYPE_LIBRARY};debug;${QITYPE_DEBUG_LIBRARY}) +else() + set(QITYPE_LIBRARIES ${QITYPE_LIBRARY}) +endif() + +set(QITYPE_LIBRARIES ${QITYPE_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(QITYPE DEFAULT_MSG + QITYPE_LIBRARIES + QITYPE_INCLUDE_DIRS +) +set(QITYPE_PACKAGE_FOUND ${QITYPE_FOUND} CACHE INTERNAL "" FORCE) + +set(QITYPE_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;DL;RT;BOOST;BOOST_DATE_TIME;BOOST_SYSTEM;BOOST_LOCALE;BOOST_THREAD;PTHREAD" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/cmake/rttools/rttools-config.cmake b/naoModule/libnaoqi_files/share/cmake/rttools/rttools-config.cmake new file mode 100755 index 0000000..79eb543 --- /dev/null +++ b/naoModule/libnaoqi_files/share/cmake/rttools/rttools-config.cmake @@ -0,0 +1,32 @@ +# This is an autogenerated file. Do not edit + +get_filename_component(_cur_dir ${CMAKE_CURRENT_LIST_FILE} PATH) +set(_root_dir "${_cur_dir}/../../../") +get_filename_component(ROOT_DIR ${_root_dir} ABSOLUTE) + + +set(RTTOOLS_INCLUDE_DIRS "${ROOT_DIR}/include;" CACHE STRING "" FORCE) +mark_as_advanced(RTTOOLS_INCLUDE_DIRS) + + +find_library(RTTOOLS_DEBUG_LIBRARY rttools_d) +find_library(RTTOOLS_LIBRARY rttools) + + +if (RTTOOLS_DEBUG_LIBRARY) + set(RTTOOLS_LIBRARIES optimized;${RTTOOLS_LIBRARY};debug;${RTTOOLS_DEBUG_LIBRARY}) +else() + set(RTTOOLS_LIBRARIES ${RTTOOLS_LIBRARY}) +endif() + +set(RTTOOLS_LIBRARIES ${RTTOOLS_LIBRARIES} CACHE INTERNAL "" FORCE) + +include(FindPackageHandleStandardArgs) +FIND_PACKAGE_HANDLE_STANDARD_ARGS(RTTOOLS DEFAULT_MSG + RTTOOLS_LIBRARIES + RTTOOLS_INCLUDE_DIRS +) +set(RTTOOLS_PACKAGE_FOUND ${RTTOOLS_FOUND} CACHE INTERNAL "" FORCE) + +set(RTTOOLS_DEPENDS "QI;BOOST_CHRONO;BOOST_FILESYSTEM;BOOST_SYSTEM;BOOST_PROGRAM_OPTIONS;BOOST_REGEX;BOOST_LOCALE;BOOST_THREAD;PTHREAD;DL;RT" CACHE INTERNAL "" FORCE) + \ No newline at end of file diff --git a/naoModule/libnaoqi_files/share/naoqi/almemory_map_signal_event.txt b/naoModule/libnaoqi_files/share/naoqi/almemory_map_signal_event.txt new file mode 100755 index 0000000..e3d3836 --- /dev/null +++ b/naoModule/libnaoqi_files/share/naoqi/almemory_map_signal_event.txt @@ -0,0 +1,10 @@ +#ALTabletService +ALTabletService.onTouch:tabletTouched + +#Package Manager +PackageManager._onPackageInstalled:packageInstalled +PackageManager._onPackageRemoved:packageRemoved + +#ALStore +ALStore.systemImageDowloaded:ALStore/SystemImageDownloaded +ALStore.updated:ALStore/Updated diff --git a/naoModule/tagEstimation/camera_calibration_nao.cpp b/naoModule/tagEstimation/camera_calibration_nao.cpp new file mode 100644 index 0000000..7b9f9b7 --- /dev/null +++ b/naoModule/tagEstimation/camera_calibration_nao.cpp @@ -0,0 +1,723 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This file is based on the OpenCV camera calibration from the ArUco library:* +* https://github.com/clearpathrobotics/aruco * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ +#include "opencv2/core/core.hpp" +#include "opencv2/imgproc/imgproc.hpp" +#include "opencv2/calib3d/calib3d.hpp" +#include "opencv2/highgui/highgui.hpp" + +#include +#include +#include +#include + +// Aldebaran includes. +#include +#include +//#include +//#include +#include +#include +#include +#include +//#include + +#include + + +#include +#include +#include +#include +#include + +using namespace cv; +using namespace std; +//using namespace AL; + + +const char * usage = + " \nexample command line for calibration from a live feed.\n" + " calibration -w 4 -h 5 -s 0.025 -o camera.yml -op -oe\n" + " \n" + " example command line for calibration from a list of stored images:\n" + " imagelist_creator image_list.xml *.png\n" + " calibration -w 4 -h 5 -s 0.025 -o camera.yml -op -oe image_list.xml\n" + " where image_list.xml is the standard OpenCV XML/YAML\n" + " use imagelist_creator to create the xml or yaml list\n" + " file consisting of the list of strings, e.g.:\n" + " \n" + "\n" + "\n" + "\n" + "view000.png\n" + "view001.png\n" + "\n" + "view003.png\n" + "view010.png\n" + "one_extra_view.jpg\n" + "\n" + "\n"; + + + + +const char* liveCaptureHelp = + "When the live video from camera is used as input, the following hot-keys may be used:\n" + " , 'q' - quit the program\n" + " 'g' - start capturing images\n" + " 'u' - switch undistortion on/off\n"; + +static void help() +{ + printf( "This is a camera calibration sample.\n" + "Usage: calibration\n" + " -w # the number of inner corners per one of board dimension\n" + " -h # the number of inner corners per another board dimension\n" + " [-pip ] # robot IP (127.0.0.1 by default)\n" + " [-pport ] # robot port (9559 by default)\n" + " [-cam ] # camera index for the robot (0 for top camera, 1 for bottom camera (default))" + " [-r ] # camera resolution of the robot. \n" + " # possible values: 40x30, 80x60, 160x120, 320x240 (default), 640x480, 1280x960\n" + " [-pt ] # the type of pattern: chessboard or circles' grid\n" + " [-n ] # the number of frames to use for calibration\n" + " # (if not specified, it will be set to the number\n" + " # of board views actually available)\n" + " [-d ] # a minimum delay in ms between subsequent attempts to capture a next view\n" + " # (used only for video capturing)\n" + " [-s ] # square size in some user-defined units (1 by default)\n" + " [-o ] # the output filename for intrinsic [and extrinsic] parameters\n" + " [-op] # write detected feature points\n" + " [-oe] # write extrinsic parameters\n" + " [-zt] # assume zero tangential distortion\n" + " [-a ] # fix aspect ratio (fx/fy)\n" + " [-p] # fix the principal point at the center\n" + " [-v] # flip the captured images around the horizontal axis\n" + " [-V] # use a video file, and not an image list, uses\n" + " # [input_data] string for the video file name\n" + " [-su] # show undistorted images after calibration\n" + " [input_data] # input data, one of the following:\n" + " # - text file with a list of the images of the board\n" + " # the text file can be generated with imagelist_creator\n" + " # - name of video file with a video of the board\n" + " # if input_data not specified, a live view from the camera is used\n" + "\n" ); + printf("\n%s",usage); + printf( "\n%s", liveCaptureHelp ); +} + +enum { DETECTION = 0, CAPTURING = 1, CALIBRATED = 2 }; +enum Pattern { CHESSBOARD, CIRCLES_GRID, ASYMMETRIC_CIRCLES_GRID }; + +static double computeReprojectionErrors( + const vector >& objectPoints, + const vector >& imagePoints, + const vector& rvecs, const vector& tvecs, + const Mat& cameraMatrix, const Mat& distCoeffs, + vector& perViewErrors ) +{ + vector imagePoints2; + int i, totalPoints = 0; + double totalErr = 0, err; + perViewErrors.resize(objectPoints.size()); + + for( i = 0; i < (int)objectPoints.size(); i++ ) + { + projectPoints(Mat(objectPoints[i]), rvecs[i], tvecs[i], + cameraMatrix, distCoeffs, imagePoints2); + err = norm(Mat(imagePoints[i]), Mat(imagePoints2), CV_L2); + int n = (int)objectPoints[i].size(); + perViewErrors[i] = (float)std::sqrt(err*err/n); + totalErr += err*err; + totalPoints += n; + } + + return std::sqrt(totalErr/totalPoints); +} + +static void calcChessboardCorners(Size boardSize, float squareSize, vector& corners, Pattern patternType = CHESSBOARD) +{ + corners.resize(0); + + switch(patternType) + { + case CHESSBOARD: + case CIRCLES_GRID: + for( int i = 0; i < boardSize.height; i++ ) + for( int j = 0; j < boardSize.width; j++ ) + corners.push_back(Point3f(float(j*squareSize), + float(i*squareSize), 0)); + break; + + case ASYMMETRIC_CIRCLES_GRID: + for( int i = 0; i < boardSize.height; i++ ) + for( int j = 0; j < boardSize.width; j++ ) + corners.push_back(Point3f(float((2*j + i % 2)*squareSize), + float(i*squareSize), 0)); + break; + + default: + CV_Error(CV_StsBadArg, "Unknown pattern type\n"); + } +} + +static bool runCalibration( vector > imagePoints, + Size imageSize, Size boardSize, Pattern patternType, + float squareSize, float aspectRatio, + int flags, Mat& cameraMatrix, Mat& distCoeffs, + vector& rvecs, vector& tvecs, + vector& reprojErrs, + double& totalAvgErr) +{ + cameraMatrix = Mat::eye(3, 3, CV_64F); + if( flags & CV_CALIB_FIX_ASPECT_RATIO ) + cameraMatrix.at(0,0) = aspectRatio; + + distCoeffs = Mat::zeros(8, 1, CV_64F); + + vector > objectPoints(1); + calcChessboardCorners(boardSize, squareSize, objectPoints[0], patternType); + + objectPoints.resize(imagePoints.size(),objectPoints[0]); + + double rms = calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix, + distCoeffs, rvecs, tvecs, flags|CV_CALIB_FIX_K4|CV_CALIB_FIX_K5); + ///*|CV_CALIB_FIX_K3*/|CV_CALIB_FIX_K4|CV_CALIB_FIX_K5); + printf("RMS error reported by calibrateCamera: %g\n", rms); + + bool ok = checkRange(cameraMatrix) && checkRange(distCoeffs); + + totalAvgErr = computeReprojectionErrors(objectPoints, imagePoints, + rvecs, tvecs, cameraMatrix, distCoeffs, reprojErrs); + + return ok; +} + + +static void saveCameraParams( const string& filename, + Size imageSize, Size boardSize, + float squareSize, float aspectRatio, int flags, + const Mat& cameraMatrix, const Mat& distCoeffs, + const vector& rvecs, const vector& tvecs, + const vector& reprojErrs, + const vector >& imagePoints, + double totalAvgErr ) +{ + FileStorage fs( filename, FileStorage::WRITE ); + + time_t tt; + time( &tt ); + struct tm *t2 = localtime( &tt ); + char buf[1024]; + strftime( buf, sizeof(buf)-1, "%c", t2 ); + + fs << "calibration_time" << buf; + + if( !rvecs.empty() || !reprojErrs.empty() ) + fs << "nframes" << (int)std::max(rvecs.size(), reprojErrs.size()); + fs << "image_width" << imageSize.width; + fs << "image_height" << imageSize.height; + fs << "board_width" << boardSize.width; + fs << "board_height" << boardSize.height; + fs << "square_size" << squareSize; + + if( flags & CV_CALIB_FIX_ASPECT_RATIO ) + fs << "aspectRatio" << aspectRatio; + + if( flags != 0 ) + { + sprintf( buf, "flags: %s%s%s%s", + flags & CV_CALIB_USE_INTRINSIC_GUESS ? "+use_intrinsic_guess" : "", + flags & CV_CALIB_FIX_ASPECT_RATIO ? "+fix_aspectRatio" : "", + flags & CV_CALIB_FIX_PRINCIPAL_POINT ? "+fix_principal_point" : "", + flags & CV_CALIB_ZERO_TANGENT_DIST ? "+zero_tangent_dist" : "" ); + cvWriteComment( *fs, buf, 0 ); + } + + fs << "flags" << flags; + + fs << "camera_matrix" << cameraMatrix; + fs << "distortion_coefficients" << distCoeffs; + + fs << "avg_reprojection_error" << totalAvgErr; + if( !reprojErrs.empty() ) + fs << "per_view_reprojection_errors" << Mat(reprojErrs); + + if( !rvecs.empty() && !tvecs.empty() ) + { + CV_Assert(rvecs[0].type() == tvecs[0].type()); + Mat bigmat((int)rvecs.size(), 6, rvecs[0].type()); + for( int i = 0; i < (int)rvecs.size(); i++ ) + { + Mat r = bigmat(Range(i, i+1), Range(0,3)); + Mat t = bigmat(Range(i, i+1), Range(3,6)); + + CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1); + CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1); + //*.t() is MatExpr (not Mat) so we can use assignment operator + r = rvecs[i].t(); + t = tvecs[i].t(); + } + cvWriteComment( *fs, "a set of 6-tuples (rotation vector + translation vector) for each view", 0 ); + fs << "extrinsic_parameters" << bigmat; + } + + if( !imagePoints.empty() ) + { + Mat imagePtMat((int)imagePoints.size(), (int)imagePoints[0].size(), CV_32FC2); + for( int i = 0; i < (int)imagePoints.size(); i++ ) + { + Mat r = imagePtMat.row(i).reshape(2, imagePtMat.cols); + Mat imgpti(imagePoints[i]); + imgpti.copyTo(r); + } + fs << "image_points" << imagePtMat; + } +} + +static bool readStringList( const string& filename, vector& l ) +{ + l.resize(0); + FileStorage fs(filename, FileStorage::READ); + if( !fs.isOpened() ) + return false; + FileNode n = fs.getFirstTopLevelNode(); + if( n.type() != FileNode::SEQ ) + return false; + FileNodeIterator it = n.begin(), it_end = n.end(); + for( ; it != it_end; ++it ) + l.push_back((string)*it); + return true; +} + + +static bool runAndSave(const string& outputFilename, + const vector >& imagePoints, + Size imageSize, Size boardSize, Pattern patternType, float squareSize, + float aspectRatio, int flags, Mat& cameraMatrix, + Mat& distCoeffs, bool writeExtrinsics, bool writePoints ) +{ + vector rvecs, tvecs; + vector reprojErrs; + double totalAvgErr = 0; + + bool ok = runCalibration(imagePoints, imageSize, boardSize, patternType, squareSize, + aspectRatio, flags, cameraMatrix, distCoeffs, + rvecs, tvecs, reprojErrs, totalAvgErr); + printf("%s. avg reprojection error = %.2f\n", + ok ? "Calibration succeeded" : "Calibration failed", + totalAvgErr); + + if( ok ) + saveCameraParams( outputFilename, imageSize, + boardSize, squareSize, aspectRatio, + flags, cameraMatrix, distCoeffs, + writeExtrinsics ? rvecs : vector(), + writeExtrinsics ? tvecs : vector(), + writeExtrinsics ? reprojErrs : vector(), + writePoints ? imagePoints : vector >(), + totalAvgErr ); + return ok; +} + + +int main( int argc, char** argv ) +{ + Size boardSize, imageSize; + float squareSize = 1.f, aspectRatio = 1.f; + Mat cameraMatrix, distCoeffs; + const char* outputFilename = "out_camera_data.yml"; + const char* inputFilename = 0; + + int i, nframes = 10; + bool writeExtrinsics = false, writePoints = false; + bool undistortImage = false; + int flags = 0; + VideoCapture capture; + bool flipVertical = false; + bool showUndistorted = false; + bool videofile = false; + int delay = 1000; + clock_t prevTimestamp = 0; + int mode = DETECTION; + int cameraId = 0; + vector > imagePoints; + vector imageList; + Pattern pattern = CHESSBOARD; + + std::string robotIp = "192.168.1.115"; //local IP for running the code on the robot + int robotPort = 9559; //default port for the robot + int cameraIndex = 1; //bottom camera + + int cameraRes = AL::kQVGA; + int inputWidth = 320; //camera resolution width + int inputHeight = 240; //camera resolution height + + boost::shared_ptr camProxy; + + std::string clientName; + + bool cameraOpened = true; + + if( argc < 2 ) + { + help(); + return 0; + } + + for( i = 1; i < argc; i++ ) + { + const char* s = argv[i]; + if( strcmp( s, "-w" ) == 0 ) + { + if( sscanf( argv[++i], "%u", &boardSize.width ) != 1 || boardSize.width <= 0 ) + return fprintf( stderr, "Invalid board width\n" ), -1; + } + else if( strcmp( s, "-h" ) == 0 ) + { + if( sscanf( argv[++i], "%u", &boardSize.height ) != 1 || boardSize.height <= 0 ) + return fprintf( stderr, "Invalid board height\n" ), -1; + } + else if( strcmp( s, "-pip" ) == 0 ) + { + robotIp = std::string(argv[++i]); + } + else if( strcmp( s, "-pport" ) == 0 ) + { + robotPort = atoi(argv[++i]); + } + else if( strcmp( s, "-cam" ) == 0 ) + { + cameraIndex = atoi(argv[++i]); + } + else if( strcmp( s, "-r" ) == 0 ) + { + i++; + if( strcmp( argv[i], "40x30" ) == 0) { + cameraRes = AL::kQQQQVGA; + inputWidth = 40; + inputHeight = 30; + } + else if( strcmp( argv[i], "80x60" ) == 0) { + cameraRes = AL::kQQQVGA; + inputWidth = 80; + inputHeight = 60; + } + else if( strcmp( argv[i], "160x120" ) == 0) { + cameraRes = AL::kQQVGA; + inputWidth = 160; + inputHeight = 120; + } + else if( strcmp( argv[i], "320x240" ) == 0) { + cameraRes = AL::kQVGA; + inputWidth = 320; + inputHeight = 240; + } + else if( strcmp( argv[i], "640x480" ) == 0) { + cameraRes = AL::kVGA; + inputWidth = 640; + inputHeight = 480; + } + else if( strcmp( argv[i], "1280x960" ) == 0) { + cameraRes = AL::k4VGA; + inputWidth = 1280; + inputHeight = 960; + } + else{ + return fprintf( stderr, "Invalid resolution. Possible values: 40x30, 80x60, 160x120, 320x240 (default), 640x480, 1280x960\n" ), -1; + } + } + else if( strcmp( s, "-pt" ) == 0 ) + { + i++; + if( !strcmp( argv[i], "circles" ) ) + pattern = CIRCLES_GRID; + else if( !strcmp( argv[i], "acircles" ) ) + pattern = ASYMMETRIC_CIRCLES_GRID; + else if( !strcmp( argv[i], "chessboard" ) ) + pattern = CHESSBOARD; + else + return fprintf( stderr, "Invalid pattern type: must be chessboard or circles\n" ), -1; + } + else if( strcmp( s, "-s" ) == 0 ) + { + if( sscanf( argv[++i], "%f", &squareSize ) != 1 || squareSize <= 0 ) + return fprintf( stderr, "Invalid board square width\n" ), -1; + } + else if( strcmp( s, "-n" ) == 0 ) + { + if( sscanf( argv[++i], "%u", &nframes ) != 1 || nframes <= 3 ) + return printf("Invalid number of images\n" ), -1; + } + else if( strcmp( s, "-a" ) == 0 ) + { + if( sscanf( argv[++i], "%f", &aspectRatio ) != 1 || aspectRatio <= 0 ) + return printf("Invalid aspect ratio\n" ), -1; + flags |= CV_CALIB_FIX_ASPECT_RATIO; + } + else if( strcmp( s, "-d" ) == 0 ) + { + if( sscanf( argv[++i], "%u", &delay ) != 1 || delay <= 0 ) + return printf("Invalid delay\n" ), -1; + } + else if( strcmp( s, "-op" ) == 0 ) + { + writePoints = true; + } + else if( strcmp( s, "-oe" ) == 0 ) + { + writeExtrinsics = true; + } + else if( strcmp( s, "-zt" ) == 0 ) + { + flags |= CV_CALIB_ZERO_TANGENT_DIST; + } + else if( strcmp( s, "-p" ) == 0 ) + { + flags |= CV_CALIB_FIX_PRINCIPAL_POINT; + } + else if( strcmp( s, "-v" ) == 0 ) + { + flipVertical = true; + } + else if( strcmp( s, "-V" ) == 0 ) + { + videofile = true; + } + else if( strcmp( s, "-o" ) == 0 ) + { + outputFilename = argv[++i]; + } + else if( strcmp( s, "-su" ) == 0 ) + { + showUndistorted = true; + } + else if( s[0] != '-' ) + { + if( isdigit(s[0]) ) + sscanf(s, "%d", &cameraId); + else + inputFilename = s; + } + else + return fprintf( stderr, "Unknown option %s", s ), -1; + } + + if( inputFilename ) + { + if( !videofile && readStringList(inputFilename, imageList) ) + mode = CAPTURING; + else{ + capture.open(inputFilename); + if( !capture.isOpened() && imageList.empty() ) { + cameraOpened = false; + return fprintf( stderr, "Could not initialize video (%d) capture\n",cameraId ), -2; + } + } + } + else{ + // A broker needs a name, an IP and a port to listen: + const std::string brokerName = "calibrationBroker"; + + // Create your own broker + boost::shared_ptr broker = + AL::ALBroker::createBroker(brokerName, "0.0.0.0", 54000, robotIp, robotPort); + camProxy = boost::shared_ptr(new AL::ALProxy(broker, "ALVideoDevice")); + + /** Subscribe a client image requiring 320*240 and BGR colorspace.*/ + clientName = camProxy->call("subscribeCamera", "camCalibration", cameraIndex, cameraRes, AL::kBGRColorSpace, 30); + + if (!camProxy->call("openCamera",cameraIndex) || !camProxy->call("startCamera",cameraIndex)) + { + cameraOpened = false; + return fprintf( stderr, "Could not initialize video (%d) capture\n",cameraIndex ), -2; + } + } + + if( !imageList.empty() ) + nframes = (int)imageList.size(); + + if( cameraOpened ) + printf( "%s", liveCaptureHelp ); + + namedWindow( "Image View", 1 ); + + AL::ALValue img; + + for(i = 0;; i++) + { + cv::Mat view = cv::Mat(cv::Size(inputWidth, inputHeight), CV_8UC3); + cv::Mat viewGray; + //cv::Mat viewGray = cv::Mat(cv::Size(inputWidth, inputHeight), CV_BGR2GRAY); + bool blink = false; + + if( cameraOpened ) { + Mat view0; + img = camProxy->call("getImageRemote",clientName); + + /** Access the image buffer (6th field) and assign it to the opencv image + * container. */ + view.data = (uchar*) img[6].GetBinary(); + camProxy->callVoid("releaseImage", clientName); + + } + else if( i < (int)imageList.size() ) + view = imread(imageList[i], 1); + + if(!view.data) + { + if( imagePoints.size() > 0 ) + runAndSave(outputFilename, imagePoints, imageSize, + boardSize, pattern, squareSize, aspectRatio, + flags, cameraMatrix, distCoeffs, + writeExtrinsics, writePoints); + break; + } + + imageSize = view.size(); + + if( flipVertical ) + flip( view, view, 0 ); + + vector pointbuf; + cvtColor(view, viewGray, COLOR_BGR2GRAY); + bool found; + switch( pattern ) + { + case CHESSBOARD: + found = findChessboardCorners( view, boardSize, pointbuf, + CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FAST_CHECK | CV_CALIB_CB_NORMALIZE_IMAGE); + + break; + case CIRCLES_GRID: + found = findCirclesGrid( view, boardSize, pointbuf ); + break; + case ASYMMETRIC_CIRCLES_GRID: + found = findCirclesGrid( view, boardSize, pointbuf, CALIB_CB_ASYMMETRIC_GRID ); + break; + default: + return fprintf( stderr, "Unknown pattern type\n" ), -1; + } + + // improve the found corners' coordinate accuracy + if( pattern == CHESSBOARD && found) cornerSubPix( viewGray, pointbuf, Size(11,11), + Size(-1,-1), TermCriteria( CV_TERMCRIT_EPS+CV_TERMCRIT_ITER, 30, 0.1 )); + + if( mode == CAPTURING && found && + (cameraOpened || clock() - prevTimestamp > delay*1e-3*CLOCKS_PER_SEC) ) + { + imagePoints.push_back(pointbuf); + prevTimestamp = clock(); + blink = cameraOpened; + } + + if(found) + drawChessboardCorners( view, boardSize, Mat(pointbuf), found ); + + string msg = mode == CAPTURING ? "100/100" : + mode == CALIBRATED ? "Calibrated" : "Press 'g' to start"; + int baseLine = 0; + Size textSize = getTextSize(msg, 1, 1, 1, &baseLine); + Point textOrigin(view.cols - 2*textSize.width - 10, view.rows - 2*baseLine - 10); + + if( mode == CAPTURING ) + { + if(undistortImage) + msg = format( "%d/%d Undist", (int)imagePoints.size(), nframes ); + else + msg = format( "%d/%d", (int)imagePoints.size(), nframes ); + } + + putText( view, msg, textOrigin, 1, 1, + mode != CALIBRATED ? Scalar(0,0,255) : Scalar(0,255,0)); + + if( blink ) + bitwise_not(view, view); + + if( mode == CALIBRATED && undistortImage ) + { + Mat temp = view.clone(); + undistort(temp, view, cameraMatrix, distCoeffs); + } + + imshow("Image View", view); + + int key = 0xff & waitKey(cameraOpened ? 50 : 500); + + + if( (key & 255) == 27 ) + break; + + if( key == 'u' && mode == CALIBRATED ) + undistortImage = !undistortImage; + + if( cameraOpened && key == 'g' ) + { + mode = CAPTURING; + imagePoints.clear(); + } + + if( mode == CAPTURING && imagePoints.size() >= (unsigned)nframes ) + { + if( runAndSave(outputFilename, imagePoints, imageSize, + boardSize, pattern, squareSize, aspectRatio, + flags, cameraMatrix, distCoeffs, + writeExtrinsics, writePoints)) + mode = CALIBRATED; + else + mode = DETECTION; + if( !cameraOpened ) + break; + } + } + if( !cameraOpened && showUndistorted ) + { + Mat view, rview, map1, map2; + initUndistortRectifyMap(cameraMatrix, distCoeffs, Mat(), + getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, imageSize, 1, imageSize, 0), + imageSize, CV_16SC2, map1, map2); + + for( i = 0; i < (int)imageList.size(); i++ ) + { + view = imread(imageList[i], 1); + if(!view.data) + continue; + //undistort( view, rview, cameraMatrix, distCoeffs, cameraMatrix ); + remap(view, rview, map1, map2, INTER_LINEAR); + imshow("Image View", rview); + int c = 0xff & waitKey(); + if( (c & 255) == 27 || c == 'q' || c == 'Q' ) + break; + } + } + camProxy->callVoid("unsubscribe", clientName); + + return 0; +} diff --git a/naoModule/tagEstimation/estimate3d_nao.cpp b/naoModule/tagEstimation/estimate3d_nao.cpp new file mode 100644 index 0000000..5de5865 --- /dev/null +++ b/naoModule/tagEstimation/estimate3d_nao.cpp @@ -0,0 +1,226 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This file is based on EstimatePose3D.cpp adapted for the NAO robot. * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ + +#include "estimate3d_nao.hpp" + +EstimateTag::EstimateTag(){ + tagSize = 30.f; + readConfigFile = false; +} +void EstimateTag::estimateTagsNao(bool givenTagToDetect, std::string givenTagName, std::vector >& tagsVec){ + + /******************************/ + /* Setting up pose estimation */ + /******************************/ + + chilitags::Chilitags3D chilitags3D(Size(inputWidth, inputHeight)); + + cv::Mat mCameraMatrix = (cv::Mat_(3,3) << + focalLength, 0, inputWidth/2, + 0, focalLength, inputHeight/2, + 0, 0, 1 + ); + + if(readConfigFile) { + chilitags3D.readTagConfiguration(configFilename); + } + + chilitags3D.setDefaultTagSize(tagSize); + + chilitags3D.setCalibration(mCameraMatrix, noArray()); + + cv::Mat cameraMatrix, distCoeffs; + + cv::Mat imgHeader = cv::Mat(cv::Size(inputWidth,inputHeight), CV_8UC3); + + /*****************************/ + /* Go! */ + /*****************************/ + std::cout << "I'm now looking for objects...\n"; + AL::ALValue img; + + std::string delimiter = "tag_"; + bool tagDetected = false; + std::vector tv; + + tagsVec.clear(); + while(!tagDetected) { + img = camProxy->call("getImageRemote",clientName); + + /** Access the image buffer (6th field) and assign it to the opencv image + * container. */ + imgHeader.data = (uchar*) img[6].GetBinary(); + cv::Size imageSize = imgHeader.size(); + + for (auto& kv : chilitags3D.estimate(imgHeader)) { + tv.clear(); + std::string tagName = kv.first; + tagName.erase(0, tagName.find(delimiter) + delimiter.length()); + + if(!givenTagToDetect || tagName.compare(givenTagName) == 0) { + tagDetected = true; + tv.push_back(std::stof(tagName)); + cv::Mat transformCVMat = cv::Mat(kv.second); + for(int i=0; i<3; i++) { + transformCVMat.at(i,3) /= 1000; + } + + for (int i = 0; i < transformCVMat.rows; ++i) { + tv.insert(tv.end(), transformCVMat.ptr(i), transformCVMat.ptr(i)+transformCVMat.cols); + } + tagsVec.push_back(tv); + } + } + camProxy->callVoid("releaseImage", clientName); + + // std::this_thread::sleep_for(std::chrono::milliseconds(500)); + } +} + +bool EstimateTag::setCameraResolution(int cam_res_index){ + + if( cam_res_index == 0) { + inputWidth = 320; + inputHeight = 240; + cameraRes = AL::kQVGA; + if(camIndex == 0) //top camera + // focalLength = 420; + focalLength = 280; + else + // focalLength = 410; + focalLength = 275; + } + else if(cam_res_index == 1) { + inputWidth = 640; + inputHeight = 480; + cameraRes = AL::kVGA; + if(camIndex == 0) //top camera +// focalLength = 830; + focalLength = 380; + else +// focalLength = 820; + focalLength = 400; + } + else{ + std::cerr << "Wrong resolution for NAO camera. Possible values: cam_res_index = 0 for 320x240 (default), cam_res_index = 1 for 640x480\n"; + return false; + } + return true; +} + +bool EstimateTag::subscribeCamera(std::string robot_ip, int robot_port, int cam_index){ + // A broker needs a name, an IP and a port to listen: + const std::string brokerName = "chiliBroker"; + + camIndex = cam_index; + + setCameraResolution(0); //320x240 by default + + + // Create your own broker + boost::shared_ptr broker = + AL::ALBroker::createBroker(brokerName, "0.0.0.0", 54000, robot_ip, robot_port); + + camProxy = boost::shared_ptr(new AL::ALProxy(broker, "ALVideoDevice")); + + /** Subscribe a client image requiring 320*240 and BGR colorspace.*/ + clientName = camProxy->call("subscribeCamera", "cam", cam_index, cameraRes, AL::kBGRColorSpace, 30); + + /*****************************/ + /* Init camera capture */ + /*****************************/ + + if (!camProxy->call("openCamera",cam_index) || !camProxy->call("startCamera",cam_index)) + { + std::cerr << "Unable to initialise video capture.\n"; + return false; + } + + return true; +} + +void EstimateTag::unsubscribeCamera(){ + camProxy->callVoid("unsubscribe", clientName); +} + +void EstimateTag::setDefaultTagSize(float tag_size){ + tagSize = tag_size; +} + +void EstimateTag::readTagConfiguration(std::string config_filename){ + readConfigFile = true; + configFilename = config_filename; +} + +void EstimateTag::resetTagSettings(){ + tagSize = 30.f; + readConfigFile = false; +} +EstimateTag::~EstimateTag(){ + +} + +/* + * int main(int argc, char* argv[]) + *{ + * std::cout + * << "Usage: "<< argv[0] + * << " [-pip ] [-pport ] [-cam ] [-c ] [-i ]\n"; + * + * const char* intrinsicsFilename = 0; + * const char* configFilename = 0; + * std::string robotIp = "127.0.0.1"; + * int robotPort = 9559; + * int camIndex = 1; //bottom camera + * + * for( int i = 1; i < argc; i++ ) + * { + * if( strcmp(argv[i], "-pip") == 0 ) + * robotIp = std::string(argv[++i]); + * else if( strcmp(argv[i], "-pport") == 0 ) + * robotPort = atoi(argv[++i]); + * else if( strcmp(argv[i], "-cam") == 0 ) + * camIndex = atoi(argv[++i]); + * else if( strcmp(argv[i], "-c") == 0 ) + * configFilename = argv[++i]; + * else if( strcmp(argv[i], "-i") == 0 ) + * intrinsicsFilename = argv[++i]; + * } + * std::vector> tagsVec; + * + * EstimateTag ET; + * + * if(ET.subscribeCamera(robotIp, robotPort, camIndex)){ + * ET.estimateTagsNao(false, "8", tagsVec); + * ET.unsubscribeCamera(); + * } + * return 0; + *} + */ diff --git a/naoModule/tagEstimation/estimate3d_nao.hpp b/naoModule/tagEstimation/estimate3d_nao.hpp new file mode 100644 index 0000000..32b7202 --- /dev/null +++ b/naoModule/tagEstimation/estimate3d_nao.hpp @@ -0,0 +1,80 @@ +/******************************************************************************* +* Copyright (c) 2016-present, Bahar Irfan. All rights reserved. * +* * +* This file is based on EstimatePose3D adapted for the NAO robot. * +* * +* Please cite the following work if using this work: * +* * +* Chilitags for NAO Robot. B. Irfan and S. Lemaignan. University of * +* Plymouth, UK. https://github.com/birfan/chilitags. 2016. * +* * +* Chilitags 2: Robust Fiducial Markers for Augmented Reality. Q. Bonnard, * +* S. Lemaignan, G. Zufferey, A. Mazzei, S. Cuendet, N. Li, P. Dillenbourg.* +* CHILI, EPFL, Switzerland. http://chili.epfl.ch/software. 2013. * +* * +* Chilitags is free software: you can redistribute it and/or modify * +* it under the terms of the Lesser GNU General Public License as * +* published by the Free Software Foundation, either version 3 of the * +* License, or (at your option) any later version. * +* * +* Chilitags is distributed in the hope that it will be useful, * +* but WITHOUT ANY WARRANTY; without even the implied warranty of * +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * +* GNU Lesser General Public License for more details. * +* * +* ChilitagsModule is released under GNU Lesser General Public License v3.0 * +* (LGPL3) in accordance with Chilitags (Bonnard et al., 2013). You should * +* have received a copy of the GNU Lesser General Public License along with * +* Chilitags. If not, see . * +*******************************************************************************/ +#include + +#include + +#include // for cv::Mat + +// Aldebaran includes. +#include +#include +#include + +#include +#include +#include + +#include + +using namespace cv; + +class EstimateTag { +private: +/* proxy parameters */ +boost::shared_ptr camProxy; +std::string clientName; +/* camera parameters */ +int camIndex; +float inputWidth; +float inputHeight; +int cameraRes; +float focalLength; +float tagSize; +bool readConfigFile; +std::string configFilename; + +public: +EstimateTag(); +~EstimateTag(); +void estimateTagsNao(bool givenTagToDetect, std::string givenTagName, std::vector >& tagsVec); + +bool setCameraResolution(int cam_res_index); + +bool subscribeCamera(std::string robotIp, int robotPort, int cameraIndex); + +void unsubscribeCamera(); + +void setDefaultTagSize(float tag_size); + +void readTagConfiguration(std::string configFilename); + +void resetTagSettings(); +}; diff --git a/naoModule/tagEstimation/tag_configuration_sample.yml b/naoModule/tagEstimation/tag_configuration_sample.yml new file mode 100755 index 0000000..0500fa5 --- /dev/null +++ b/naoModule/tagEstimation/tag_configuration_sample.yml @@ -0,0 +1,49 @@ +%YAML:1.0 +# This file describes how tags are placed on objects. +# +# This can also be used to provide tag aliases, or transform the computed +# origin of a tag. +# +# This sample file define 3 objects, and covers the different options +# available. + +# This first object has only one tag (ID 0). 'myobject1' is the name returned +# by the object detector. The size of the tag is 20x20 (the unit does not +# matter, but must be consistent with the calibration unit. We recommend to use +# millimeters). +# This simple declaration allows to define name aliases for tags. 'tag' +# and 'size' are the only two mandatory fields. +myobject1: + - tag: 0 + size: 20 + +# The second object also has a single tag, but translated and rotated. The +# origin of 'myobject2' is will be 10 units *below* the tag, on the object's X +# axis, and the tag is rotated by 90 degrees along the object's Z axis. +# Rotations must be specified in degrees as XYZ Euler rotations, ie a rotation +# on the X axis followed by a rotation on the Y axis, followed by a rotation on +# the Z axis. +#myobject2: +# - tag: 1 +# size: 30 +# translation: [10., 0., 0.] +# rotation: [0., 0., 90.] + +# The third object features 3 tags, of various size, and at various positions. +# Here, the rotation is omitted (defaults to [0.,0.,0.]). +# If a tag sets the option 'keep' to '1', the tag 3D position is +# returned besides the object. By default, object components are not kept, but +# you can explicitely set keep to '0'. +#myobject3: +# - tag: 2 +# size: 20 +# translation: [-50., -100., 0.0] +# keep: 1 +# - tag: 3 +# size: 30 +# translation: [50., -100., 0.0] +# keep: 0 +# - tag: 4 +# size: 30 +# translation: [50., 100., 0.0] + diff --git a/uncrustify.cfg b/uncrustify.cfg index fcda878..de89b0d 100644 --- a/uncrustify.cfg +++ b/uncrustify.cfg @@ -238,7 +238,7 @@ sp_assign = ignore # ignore/add/remove/force sp_cpp_lambda_assign = ignore # ignore/add/remove/force # Add or remove space after the capture specification in C++11 lambda. -sp_cpp_lambda_paren = ignore # ignore/add/remove/force +sp_cpp_lambda_square_paren = ignore # ignore/add/remove/force # Add or remove space around assignment operator '=' in a prototype sp_assign_default = ignore # ignore/add/remove/force @@ -717,7 +717,7 @@ align_with_tabs = false # false/true align_on_tabstop = false # false/true # Whether to left-align numbers -align_number_left = false # false/true +align_number_right = true # false/true # Align variable definitions in prototypes and functions align_func_params = false # false/true