├── .gitignore
├── CMakeLists.txt
├── LICENSE
├── README.md
├── _config.yml
├── launch
├── collision_viewer.launch
├── joint_state_pub.launch
├── preprocessing.launch
├── relaxed_ik.launch
├── robot_state_pub.launch
├── sample.launch
└── urdf_viewer.launch
├── msg
├── EEPoseGoals.msg
└── JointAngles.msg
├── package.xml
├── rviz
├── collision_viewer.rviz
└── joint_viewer.rviz
├── setup.py
└── src
├── .idea
├── misc.xml
├── modules.xml
├── src.iml
└── workspace.xml
├── RelaxedIK
├── .idea
│ ├── RelaxedIK.iml
│ ├── misc.xml
│ ├── modules.xml
│ └── workspace.xml
├── Config
│ ├── __init__.py
│ └── collision_example.yaml
├── GROOVE
│ ├── .idea
│ │ ├── GROOVE.iml
│ │ ├── misc.xml
│ │ ├── modules.xml
│ │ ├── vcs.xml
│ │ └── workspace.xml
│ ├── GROOVE_Utils
│ │ ├── __init__.py
│ │ ├── __init__.pyc
│ │ ├── colors.py
│ │ ├── colors.pyc
│ │ ├── constraint.py
│ │ ├── constraint.pyc
│ │ ├── groove_type.py
│ │ ├── groove_type.pyc
│ │ ├── objective.py
│ │ ├── objective.pyc
│ │ ├── vars.py
│ │ ├── vars.pyc
│ │ ├── weight_function.py
│ │ └── weight_function.pyc
│ ├── README.md
│ ├── __init__.py
│ ├── __init__.pyc
│ ├── groove.py
│ ├── groove.pyc
│ └── setup_cython.py
├── GROOVE_RelaxedIK
│ ├── __init__.py
│ ├── __init__.pyc
│ ├── boost
│ │ ├── Makefile
│ │ ├── __init__.py
│ │ ├── objectives.cpp
│ │ └── objectives_ext.so
│ ├── objectives_ext.so
│ ├── relaxedIK_constraint.py
│ ├── relaxedIK_constraint.pyc
│ ├── relaxedIK_objective.py
│ ├── relaxedIK_objective.pyc
│ ├── relaxedIK_vars.py
│ ├── relaxedIK_vars.pyc
│ ├── relaxedIK_weight_function.py
│ └── relaxedIK_weight_function.pyc
├── LICENSE
├── README.md
├── Spacetime
│ ├── __init__.py
│ ├── __init__.pyc
│ ├── adInterface.py
│ ├── adInterface.pyc
│ ├── arm.py
│ ├── arm.pyc
│ ├── boost
│ │ ├── Arm.cpp
│ │ ├── Arm_ext.so
│ │ ├── Makefile
│ │ ├── __init__.py
│ │ ├── hello.so
│ │ ├── test.cpp
│ │ └── world.cpp
│ ├── robot.py
│ ├── robot.pyc
│ ├── robot_function.py
│ ├── robot_function.pyc
│ ├── setup_cython.py
│ └── tester.py
├── Utils
│ ├── __init__.py
│ ├── __init__.pyc
│ ├── _transformations.so
│ ├── collision_graph.py
│ ├── collision_graph.pyc
│ ├── collision_utils.py
│ ├── collision_utils.pyc
│ ├── colors.py
│ ├── colors.pyc
│ ├── config_engine.py
│ ├── config_engine.pyc
│ ├── filter.py
│ ├── geometry_utils.py
│ ├── geometry_utils.pyc
│ ├── ik_task.py
│ ├── ik_task.pyc
│ ├── joint_utils.py
│ ├── joint_utils.pyc
│ ├── neural_net_trainer.py
│ ├── neural_net_trainer.pyc
│ ├── tf_fast.py
│ ├── tf_fast.pyc
│ ├── transformations.c
│ ├── transformations.py
│ ├── transformations.pyc
│ ├── urdf_load.py
│ └── urdf_load.pyc
├── __init__.py
├── __init__.pyc
├── relaxedIK.py
├── relaxedIK.pyc
└── urdfs
│ ├── hubo_description.urdf
│ ├── mico.urdf
│ └── ur5.urdf
├── broadcaster.py
├── collision_viewer.py
├── preprocessing.py
├── relaxed_ik_node.py
├── sample.py
├── start_here.py
└── urdf_viewer.py
/.gitignore:
--------------------------------------------------------------------------------
1 | # Byte-compiled / optimized / DLL files
2 | __pycache__/
3 | *.py[cod]
4 | *$py.class
5 |
6 | # C extensions
7 | # *.so
8 |
9 | start_here_*.py
10 | keras_test2.py
11 | keras_test.py
12 | sample2.py
13 | *.config
14 | collision_hubo.yaml
15 | collision_hubo_l.yaml
16 | collision_hubo_r.yaml
17 |
18 | # Distribution / packaging
19 | .Python
20 | build/
21 | develop-eggs/
22 | dist/
23 | downloads/
24 | eggs/
25 | .eggs/
26 | lib/
27 | lib64/
28 | parts/
29 | sdist/
30 | var/
31 | wheels/
32 | *.egg-info/
33 | .installed.cfg
34 | *.egg
35 | MANIFEST
36 |
37 | # PyInstaller
38 | # Usually these files are written by a python script from a template
39 | # before PyInstaller builds the exe, so as to inject date/other infos into it.
40 | *.manifest
41 | *.spec
42 |
43 | # Installer logs
44 | pip-log.txt
45 | pip-delete-this-directory.txt
46 |
47 | # Unit test / coverage reports
48 | htmlcov/
49 | .tox/
50 | .coverage
51 | .coverage.*
52 | .cache
53 | nosetests.xml
54 | coverage.xml
55 | *.cover
56 | .hypothesis/
57 | .pytest_cache/
58 |
59 | # Translations
60 | *.mo
61 | *.pot
62 |
63 | # Django stuff:
64 | *.log
65 | local_settings.py
66 | db.sqlite3
67 |
68 | # Flask stuff:
69 | instance/
70 | .webassets-cache
71 |
72 | # Scrapy stuff:
73 | .scrapy
74 |
75 | # Sphinx documentation
76 | docs/_build/
77 |
78 | # PyBuilder
79 | target/
80 |
81 | # Jupyter Notebook
82 | .ipynb_checkpoints
83 |
84 | # pyenv
85 | .python-version
86 |
87 | # celery beat schedule file
88 | celerybeat-schedule
89 |
90 | # SageMath parsed files
91 | *.sage.py
92 |
93 | # Environments
94 | .env
95 | .venv
96 | env/
97 | venv/
98 | ENV/
99 | env.bak/
100 | venv.bak/
101 |
102 | # Spyder project settings
103 | .spyderproject
104 | .spyproject
105 |
106 | # Rope project settings
107 | .ropeproject
108 |
109 | # mkdocs documentation
110 | /site
111 |
112 | # mypy
113 | .mypy_cache/
114 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(relaxed_ik)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS std_msgs message_generation geometry_msgs)
11 |
12 | ## System dependencies are found with CMake's conventions
13 | # find_package(Boost REQUIRED COMPONENTS system)
14 |
15 |
16 | ## Uncomment this if the package has a setup.py. This macro ensures
17 | ## modules and global scripts declared therein get installed
18 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
19 | catkin_python_setup()
20 |
21 | ################################################
22 | ## Declare ROS messages, services and actions ##
23 | ################################################
24 |
25 | ## To declare and build messages, services or actions from within this
26 | ## package, follow these steps:
27 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
28 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
29 | ## * In the file package.xml:
30 | ## * add a build_depend tag for "message_generation"
31 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
32 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
33 | ## but can be declared for certainty nonetheless:
34 | ## * add a run_depend tag for "message_runtime"
35 | ## * In this file (CMakeLists.txt):
36 | ## * add "message_generation" and every package in MSG_DEP_SET to
37 | ## find_package(catkin REQUIRED COMPONENTS ...)
38 | ## * add "message_runtime" and every package in MSG_DEP_SET to
39 | ## catkin_package(CATKIN_DEPENDS ...)
40 | ## * uncomment the add_*_files sections below as needed
41 | ## and list every .msg/.srv/.action file to be processed
42 | ## * uncomment the generate_messages entry below
43 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
44 |
45 | ## Generate messages in the 'msg' folder
46 | # add_message_files(
47 | # FILES
48 | # Message1.msg
49 | # Message2.msg
50 | # )
51 | add_message_files(
52 | FILES
53 | EEPoseGoals.msg
54 | JointAngles.msg
55 | )
56 |
57 | ## Generate services in the 'srv' folder
58 | # add_service_files(
59 | # FILES
60 | # Service1.srv
61 | # Service2.srv
62 | # )
63 |
64 | ## Generate actions in the 'action' folder
65 | # add_action_files(
66 | # FILES
67 | # Action1.action
68 | # Action2.action
69 | # )
70 |
71 | ## Generate added messages and services with any dependencies listed here
72 | # generate_messages(
73 | # DEPENDENCIES
74 | # std_msgs # Or other packages containing msgs
75 | # )
76 | generate_messages(
77 | DEPENDENCIES
78 | geometry_msgs # Or other packages containing msgs
79 | std_msgs
80 | )
81 |
82 | ################################################
83 | ## Declare ROS dynamic reconfigure parameters ##
84 | ################################################
85 |
86 | ## To declare and build dynamic reconfigure parameters within this
87 | ## package, follow these steps:
88 | ## * In the file package.xml:
89 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
90 | ## * In this file (CMakeLists.txt):
91 | ## * add "dynamic_reconfigure" to
92 | ## find_package(catkin REQUIRED COMPONENTS ...)
93 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
94 | ## and list every .cfg file to be processed
95 |
96 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
97 | # generate_dynamic_reconfigure_options(
98 | # cfg/DynReconf1.cfg
99 | # cfg/DynReconf2.cfg
100 | # )
101 |
102 | ###################################
103 | ## catkin specific configuration ##
104 | ###################################
105 | ## The catkin_package macro generates cmake config files for your package
106 | ## Declare things to be passed to dependent projects
107 | ## INCLUDE_DIRS: uncomment this if your package contains header files
108 | ## LIBRARIES: libraries you create in this project that dependent projects also need
109 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
110 | ## DEPENDS: system dependencies of this project that dependent projects also need
111 | catkin_package(
112 | # INCLUDE_DIRS include
113 | # LIBRARIES RelaxedIK-MC
114 | # CATKIN_DEPENDS other_catkin_pkg
115 | # DEPENDS system_lib
116 | )
117 |
118 | ###########
119 | ## Build ##
120 | ###########
121 |
122 | ## Specify additional locations of header files
123 | ## Your package locations should be listed before other locations
124 | include_directories(
125 | # include
126 | # ${catkin_INCLUDE_DIRS}
127 | )
128 |
129 | ## Declare a C++ library
130 | # add_library(${PROJECT_NAME}
131 | # src/${PROJECT_NAME}/RelaxedIK-MC.cpp
132 | # )
133 |
134 | ## Add cmake target dependencies of the library
135 | ## as an example, code may need to be generated before libraries
136 | ## either from message generation or dynamic reconfigure
137 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
138 |
139 | ## Declare a C++ executable
140 | ## With catkin_make all packages are built within a single CMake context
141 | ## The recommended prefix ensures that target names across packages don't collide
142 | # add_executable(${PROJECT_NAME}_node src/RelaxedIK-MC_node.cpp)
143 |
144 | ## Rename C++ executable without prefix
145 | ## The above recommended prefix causes long target names, the following renames the
146 | ## target back to the shorter version for ease of user use
147 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
148 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
149 |
150 | ## Add cmake target dependencies of the executable
151 | ## same as for the library above
152 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
153 |
154 | ## Specify libraries to link a library or executable target against
155 | # target_link_libraries(${PROJECT_NAME}_node
156 | # ${catkin_LIBRARIES}
157 | # )
158 |
159 | #############
160 | ## Install ##
161 | #############
162 |
163 | # all install targets should use catkin DESTINATION variables
164 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
165 |
166 | ## Mark executable scripts (Python etc.) for installation
167 | ## in contrast to setup.py, you can choose the destination
168 | # install(PROGRAMS
169 | # scripts/my_python_script
170 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
171 | # )
172 |
173 | ## Mark executables and/or libraries for installation
174 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
175 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
176 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
177 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
178 | # )
179 |
180 | ## Mark cpp header files for installation
181 | # install(DIRECTORY include/${PROJECT_NAME}/
182 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
183 | # FILES_MATCHING PATTERN "*.h"
184 | # PATTERN ".svn" EXCLUDE
185 | # )
186 |
187 | ## Mark other files for installation (e.g. launch and bag files, etc.)
188 | # install(FILES
189 | # # myfile1
190 | # # myfile2
191 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
192 | # )
193 |
194 | #############
195 | ## Testing ##
196 | #############
197 |
198 | ## Add gtest based cpp test target and link libraries
199 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_RelaxedIK-MC.cpp)
200 | # if(TARGET ${PROJECT_NAME}-test)
201 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
202 | # endif()
203 |
204 | ## Add folders to be run by python nosetests
205 | # catkin_add_nosetests(test)
206 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2020 UW Graphics Group
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # relaxed_ik
2 |
3 | :pushpin: We provide a seperate repository called [**relaxed_ik_core**](https://github.com/uwgraphics/relaxed_ik_core), which is complitable with more recent Rust version and Ubuntu 20.04 / ROS Noetic.
4 |
5 | Development update 10/26/21
6 |
7 | Hi all, we are excited to share some updates to our relaxed_ik library. Apologies for the delay, I have been attending to many unforeseen circumstances over the past few months.
8 |
9 | * The original RelaxedIK code was written as somewhat messy “research code” in 2016, and each iteration of the code after that focused on code cleanup and computation speed (e.g., the port to Julia, and subsequently to Rust). This long-term development on a single codebase has been nice for some use cases, e.g., everything is connected well with ROS, everything has maintained compatibility with legacy code in Python and Julia, etc, but this large monolithic structure has also made it difficult to port the RelaxedIK solver to other applications in a lightweight manner. Thus, much of our recent development has focused on improving the portability of RelaxedIK. To this end, we introduce a new repository called [relaxed_ik_core](https://github.com/uwgraphics/relaxed_ik_core) which contains just the central kernel of the RelaxedIK runtime without the extra ROS and robot setup baggage. The relaxed_ik_core repo comes prepackaged with a common set of pre-compiled and pre-trained robot models (UR5, Sawyer, etc.), allowing users with one of those robots to completely skip the setup steps. We are also hoping to grow that set of pre-compiled robots in that repo, so feel free to make pull requests with additional robot info files. The lightweight relaxed_ik_core package has allowed us to port the code to other applications and languates, such as the [Unity game engine](https://github.com/uwgraphics/relaxed_ik_unity), [Mujoco](https://github.com/uwgraphics/relaxed_ik_mujoco), [CoppeliaSim](https://github.com/uwgraphics/relaxed_ik_coppeliasim), [Python 2 & 3](https://github.com/uwgraphics/relaxed_ik_python), [ROS1](https://github.com/uwgraphics/relaxed_ik_ros1), and ongoing development for ROS2. Note that going forward, this current repository (i.e., github/uwgraphics/relaxed_ik) should ONLY be used for robot setup and compilation or to maintain any older legacy setups. For anything else, it is essentially deprecated and further development will shift over to [relaxed_ik_core](https://github.com/uwgraphics/relaxed_ik_core). For additional information, please consult the [documentation](https://pages.graphics.cs.wisc.edu/relaxed_ik_core/)
10 |
11 | * We recently presented a paper at ICRA 2021 on a new method called [CollisionIK](https://arxiv.org/abs/2102.13187) ([video](https://youtu.be/rdMl1gOPNoM)). CollisionIK is a per-instant pose optimization method that can generate configurations that achieve specified pose or motion objectives as best as possible over a sequence of solutions, while also simultaneously avoiding collisions with static or dynamic obstacles in the environment. This is in contrast to RelaxedIK, which could only avoid self-collisions. The current research code for CollisionIK is available on [relaxed_ik_core](https://github.com/uwgraphics/relaxed_ik_core), and I am also working on an improved implementation of collisionIK that will be released in the coming months. The citation for this paper is:
12 | ```
13 | @article{rakita2021collisionik,
14 | title={CollisionIK: A Per-Instant Pose Optimization Method for Generating Robot Motions with Environment Collision Avoidance},
15 | author={Rakita, Daniel and Shi, Haochen and Mutlu, Bilge and Gleicher, Michael},
16 | journal={arXiv preprint arXiv:2102.13187},
17 | year={2021}
18 | }
19 | ```
20 |
21 | Please email or post here if any questions come up!
22 |
23 |
24 |
25 | -----------------------------------------
26 |
27 | Development update 1/3/20
28 |
29 | RelaxedIK has been substantially rewritten in the Rust programming language. Everything is still completely ROS compatible and should serve as a drop-in replacement for older versions of the solver.
30 |
31 | The Rust relaxedIK solver is MUCH faster than its python and julia alternatives. Testing on my laptop has indicated that the solver can run at over 3000Hz for single arm robots (tested on ur3, ur5, jaco, sawyer, panda, kuka iiwa, etc) and about 2500Hz for bimanual robots (tested on ABB Yumi and Rainbow Robotics DRC-Hubo+). All of the new code has been pushed to the Development branch, and will be pushed to the main branch after a brief testing phase. It is highly recommended that the development branch be used at this point, as it has many more features and options than the main branch.
32 |
33 |
git clone -b dev https://github.com/uwgraphics/relaxed_ik.git
34 |
35 | If you are working with an older version of relaxedIK, note that you will have to start from a fresh repo and go through the start_here.py procedures again to work with the Rust version of the solver.
36 |
37 | If you have any comments or questions on any of this, or if you encounter any bugs in the new rust version of the solver, feel free to post an issue or email me directly at rakita@cs.wisc.edu
38 |
39 |
40 | ------------------------------------------
41 |
42 | RelaxedIK Solver
43 |
44 | Welcome to RelaxedIK! This solver implements the methods discussed in our paper RelaxedIK: Real-time Synthesis of Accurate and Feasible Robot Arm Motion (http://www.roboticsproceedings.org/rss14/p43.html)
45 |
46 | Video of presentation at RSS 2018 (RelaxedIK part starts around 12:00) :
47 | https://youtu.be/bih5e9MHc88?t=737
48 |
49 | Video explaining relaxedIK
50 | https://youtu.be/AhsQFJzB8WQ
51 |
52 | RelaxedIK is an inverse kinematics (IK) solver designed for robot platforms such that the conversion
53 | between Cartesian end-effector pose goals (such as "move the robot's right arm end-effector to position X, while maintaining an end-effector
54 | orientation Y") to Joint-Space (i.e., the robot's rotation values for each joint degree-of-freedom at a particular time-point) is
55 | done both ACCURATELY and FEASIBLY. By this, we mean that RelaxedIK attempts to find the closest possible solution to the
56 | desired end-effector pose goals without exhibiting negative effects such as self-collisions, environment collisions,
57 | kinematic-singularities, or joint-space discontinuities.
58 |
59 | To start using the solver, please follow the step-by-step instructions in the file start_here.py (in the root directory)
60 |
61 | If anything with the solver is not working as expected, or if you have any feedback, feel free to let us know! (email: rakita@cs.wisc.edu, website: http://pages.cs.wisc.edu/~rakita)
62 | We are actively supporting and extending this code, so we are interested to hear about how the solver is being used and any positive or negative experiences in using it.
63 |
64 | Citation
65 |
66 | If you use our solver, please cite our RSS paper RelaxedIK: Real-time Synthesis of Accurate and Feasible Robot Arm Motion
67 | http://www.roboticsproceedings.org/rss14/p43.html
68 |
69 |
70 | @INPROCEEDINGS{Rakita-RSS-18,
71 | AUTHOR = {Daniel Rakita AND Bilge Mutlu AND Michael Gleicher},
72 | TITLE = {{RelaxedIK: Real-time Synthesis of Accurate and Feasible Robot Arm Motion}},
73 | BOOKTITLE = {Proceedings of Robotics: Science and Systems},
74 | YEAR = {2018},
75 | ADDRESS = {Pittsburgh, Pennsylvania},
76 | MONTH = {June},
77 | DOI = {10.15607/RSS.2018.XIV.043}
78 | }
79 |
80 |
81 | If you use our solver for a robot teleoperation interface, also consider citing our prior work that shows the effectiveness of RelaxedIK in this setting:
82 |
83 |
84 | A Motion Retargeting Method for Effective Mimicry-based Teleoperation of Robot Arms
85 | https://dl.acm.org/citation.cfm?id=3020254
86 |
87 | @inproceedings{rakita2017motion,
88 | title={A motion retargeting method for effective mimicry-based teleoperation of robot arms},
89 | author={Rakita, Daniel and Mutlu, Bilge and Gleicher, Michael},
90 | booktitle={Proceedings of the 2017 ACM/IEEE International Conference on Human-Robot Interaction},
91 | pages={361--370},
92 | year={2017},
93 | organization={ACM}
94 | }
95 |
96 |
97 |
98 | An Autonomous Dynamic Camera Method for Effective Remote Teleoperation
99 | https://dl.acm.org/citation.cfm?id=3171221.3171279
100 |
101 | @inproceedings{rakita2018autonomous,
102 | title={An autonomous dynamic camera method for effective remote teleoperation},
103 | author={Rakita, Daniel and Mutlu, Bilge and Gleicher, Michael},
104 | booktitle={Proceedings of the 2018 ACM/IEEE International Conference on Human-Robot Interaction},
105 | pages={325--333},
106 | year={2018},
107 | organization={ACM}
108 | }
109 |
110 |
111 |
112 | Dependencies
113 |
114 | kdl urdf parser:
115 | >> sudo apt-get install ros-[your ros distro]-urdfdom-py
116 | >> sudo apt-get install ros-[your ros distro]-kdl-parser-py
117 | >> sudo apt-get install ros-[your ros distro]-kdl-conversions
118 |
119 |
120 |
121 | fcl collision library:
122 | https://github.com/BerkeleyAutomation/python-fcl
123 |
124 |
128 |
129 |
130 | scikit learn:
131 | http://scikit-learn.org/stable/index.html
132 |
133 |
134 | Tutorial
135 |
136 | For full setup and usage details, please refer to start_here.py in the src directory.
137 |
138 |
139 |
140 |
--------------------------------------------------------------------------------
/_config.yml:
--------------------------------------------------------------------------------
1 | theme: jekyll-theme-tactile
--------------------------------------------------------------------------------
/launch/collision_viewer.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/launch/joint_state_pub.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/launch/preprocessing.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/launch/relaxed_ik.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/launch/robot_state_pub.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/launch/sample.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/launch/urdf_viewer.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/msg/EEPoseGoals.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | geometry_msgs/Pose[] ee_poses
3 |
--------------------------------------------------------------------------------
/msg/JointAngles.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | std_msgs/Float32[] angles
3 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | relaxed_ik
4 | 0.0.0
5 | The relaxed_ik package
6 |
7 |
8 |
9 |
10 | rakita
11 |
12 |
13 |
14 |
15 |
16 | TODO
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 | catkin
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
--------------------------------------------------------------------------------
/rviz/joint_viewer.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /TF1/Frames1
9 | - /TF1/Tree1
10 | Splitter Ratio: 0.592391312
11 | Tree Height: 749
12 | - Class: rviz/Selection
13 | Name: Selection
14 | - Class: rviz/Tool Properties
15 | Expanded:
16 | - /2D Pose Estimate1
17 | - /2D Nav Goal1
18 | - /Publish Point1
19 | Name: Tool Properties
20 | Splitter Ratio: 0.588679016
21 | - Class: rviz/Views
22 | Expanded:
23 | - /Current View1
24 | Name: Views
25 | Splitter Ratio: 0.5
26 | - Class: rviz/Time
27 | Experimental: false
28 | Name: Time
29 | SyncMode: 0
30 | SyncSource: ""
31 | Visualization Manager:
32 | Class: ""
33 | Displays:
34 | - Alpha: 0.5
35 | Cell Size: 1
36 | Class: rviz/Grid
37 | Color: 160; 160; 164
38 | Enabled: true
39 | Line Style:
40 | Line Width: 0.0299999993
41 | Value: Lines
42 | Name: Grid
43 | Normal Cell Count: 0
44 | Offset:
45 | X: 0
46 | Y: 0
47 | Z: 0
48 | Plane: XY
49 | Plane Cell Count: 10
50 | Reference Frame:
51 | Value: true
52 | - Alpha: 1
53 | Class: rviz/RobotModel
54 | Collision Enabled: false
55 | Enabled: true
56 | Links:
57 | All Links Enabled: true
58 | Expand Joint Details: false
59 | Expand Link Details: false
60 | Expand Tree: false
61 | Link Tree Style: Links in Alphabetic Order
62 | base:
63 | Alpha: 1
64 | Show Axes: false
65 | Show Trail: false
66 | base_link:
67 | Alpha: 1
68 | Show Axes: false
69 | Show Trail: false
70 | Value: true
71 | ee_link:
72 | Alpha: 1
73 | Show Axes: false
74 | Show Trail: false
75 | Value: true
76 | forearm_link:
77 | Alpha: 1
78 | Show Axes: false
79 | Show Trail: false
80 | Value: true
81 | shoulder_link:
82 | Alpha: 1
83 | Show Axes: false
84 | Show Trail: false
85 | Value: true
86 | tool0:
87 | Alpha: 1
88 | Show Axes: false
89 | Show Trail: false
90 | upper_arm_link:
91 | Alpha: 1
92 | Show Axes: false
93 | Show Trail: false
94 | Value: true
95 | world:
96 | Alpha: 1
97 | Show Axes: false
98 | Show Trail: false
99 | wrist_1_link:
100 | Alpha: 1
101 | Show Axes: false
102 | Show Trail: false
103 | Value: true
104 | wrist_2_link:
105 | Alpha: 1
106 | Show Axes: false
107 | Show Trail: false
108 | Value: true
109 | wrist_3_link:
110 | Alpha: 1
111 | Show Axes: false
112 | Show Trail: false
113 | Value: true
114 | Name: RobotModel
115 | Robot Description: robot_description
116 | TF Prefix: ""
117 | Update Interval: 0
118 | Value: true
119 | Visual Enabled: true
120 | - Class: rviz/TF
121 | Enabled: true
122 | Frame Timeout: 15
123 | Frames:
124 | All Enabled: true
125 | base:
126 | Value: true
127 | base_link:
128 | Value: true
129 | common_world:
130 | Value: true
131 | ee_link:
132 | Value: true
133 | forearm_link:
134 | Value: true
135 | shoulder_link:
136 | Value: true
137 | tool0:
138 | Value: true
139 | upper_arm_link:
140 | Value: true
141 | world:
142 | Value: true
143 | wrist_1_link:
144 | Value: true
145 | wrist_2_link:
146 | Value: true
147 | wrist_3_link:
148 | Value: true
149 | Marker Scale: 0.5
150 | Name: TF
151 | Show Arrows: true
152 | Show Axes: true
153 | Show Names: true
154 | Tree:
155 | common_world:
156 | base_link:
157 | base:
158 | {}
159 | shoulder_link:
160 | upper_arm_link:
161 | forearm_link:
162 | wrist_1_link:
163 | wrist_2_link:
164 | wrist_3_link:
165 | ee_link:
166 | {}
167 | tool0:
168 | {}
169 | Update Interval: 0
170 | Value: true
171 | Enabled: true
172 | Global Options:
173 | Background Color: 48; 48; 48
174 | Default Light: true
175 | Fixed Frame: common_world
176 | Frame Rate: 30
177 | Name: root
178 | Tools:
179 | - Class: rviz/Interact
180 | Hide Inactive Objects: true
181 | - Class: rviz/MoveCamera
182 | - Class: rviz/Select
183 | - Class: rviz/FocusCamera
184 | - Class: rviz/Measure
185 | - Class: rviz/SetInitialPose
186 | Topic: /initialpose
187 | - Class: rviz/SetGoal
188 | Topic: /move_base_simple/goal
189 | - Class: rviz/PublishPoint
190 | Single click: true
191 | Topic: /clicked_point
192 | Value: true
193 | Views:
194 | Current:
195 | Class: rviz/Orbit
196 | Distance: 4.00203943
197 | Enable Stereo Rendering:
198 | Stereo Eye Separation: 0.0599999987
199 | Stereo Focal Distance: 1
200 | Swap Stereo Eyes: false
201 | Value: false
202 | Focal Point:
203 | X: 0
204 | Y: 0
205 | Z: 0
206 | Focal Shape Fixed Size: true
207 | Focal Shape Size: 0.0500000007
208 | Invert Z Axis: false
209 | Name: Current View
210 | Near Clip Distance: 0.00999999978
211 | Pitch: 0.520399034
212 | Target Frame:
213 | Value: Orbit (rviz)
214 | Yaw: 5.82990456
215 | Saved: ~
216 | Window Geometry:
217 | Displays:
218 | collapsed: false
219 | Height: 1056
220 | Hide Left Dock: false
221 | Hide Right Dock: true
222 | QMainWindow State: 000000ff00000000fd00000004000000000000016a0000037cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000037c000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000016c0000037cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000037c000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000058fc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000037c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
223 | Selection:
224 | collapsed: false
225 | Time:
226 | collapsed: false
227 | Tool Properties:
228 | collapsed: false
229 | Views:
230 | collapsed: true
231 | Width: 1855
232 | X: 65
233 | Y: 24
234 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup
2 | from catkin_pkg.python_setup import generate_distutils_setup
3 |
4 | d = generate_distutils_setup(
5 | packages=['bimanual_hubo'],
6 | scripts=[''],
7 | package_dir={'': 'src'}
8 | )
9 |
10 | setup(**d)
11 |
--------------------------------------------------------------------------------
/src/.idea/misc.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/src/.idea/modules.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/src/.idea/src.iml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/src/RelaxedIK/.idea/RelaxedIK.iml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/src/RelaxedIK/.idea/misc.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/src/RelaxedIK/.idea/modules.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/src/RelaxedIK/.idea/workspace.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 | 1524927470964
70 |
71 |
72 | 1524927470964
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Config/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Config/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/Config/collision_example.yaml:
--------------------------------------------------------------------------------
1 | robot_link_radius: 0.05
2 | sample_states: [ [-0.72980141, 1.82473686, 0.05004675, -1.17187243, -2.47790277, 0.14499504, -1.35150909, -1.13954413],
3 | [ 2.11062304, 1.36317257, -0.00849951, -1.35405792, -0.74341992, -0.83897834, -0.27372747, -0.70766507],
4 | [-1.88223643, -0.66435388, 0.09899378, 0.607408, -1.47676658, -1.58920619, 1.18318145, 0.99929842],
5 | [ 0.07338114, 0.18082921, -0.03380994, -0.6421907, -0.59007974, 0.52447233, -1.16469675, -0.34811331] ]
6 | boxes:
7 | - name: box1
8 | parameters: [1,1,0.1] # r
9 | coordinate_frame: 0
10 | rotation: [0,0,0]
11 | translation: [1,0,0]
12 | spheres:
13 | - name: sphere1
14 | parameters: .02
15 | coordinate_frame: 9
16 | rotation: [0,0,0]
17 | translation: [.115,0.025,-0.053]
18 | ellipsoids:
19 | capsules:
20 | cylinders:
21 |
22 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/.idea/GROOVE.iml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/.idea/misc.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/.idea/modules.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/.idea/vcs.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/colors.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | __author__ = 'drakita'
4 |
5 | class bcolors:
6 | HEADER = '\033[95m'
7 | OKBLUE = '\033[94m'
8 | OKGREEN = '\033[92m'
9 | WARNING = '\033[93m'
10 | FAIL = '\033[91m'
11 | ENDC = '\033[0m'
12 | BOLD = '\033[1m'
13 | UNDERLINE = '\033[4m'
14 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/colors.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/colors.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/constraint.py:
--------------------------------------------------------------------------------
1 | __author__ = 'drakita'
2 |
3 | from abc import ABCMeta, abstractmethod
4 | from objective import get_groove_global_vars
5 | import scipy.optimize as O
6 |
7 | class Constraint:
8 | __metaclass__ = ABCMeta
9 |
10 | def __init__(self, *args): pass
11 |
12 | @abstractmethod
13 | def constraintType(self):
14 | 'return eq for equality and ineq for inequality'
15 | return None
16 |
17 | @abstractmethod
18 | def name(self): pass
19 |
20 | @abstractmethod
21 | def func(self, x): pass
22 |
23 | def func_nlopt(self, x, grad):
24 | numDOF = len(x)
25 | g = O.approx_fprime(x, self.func, numDOF * [0.001])
26 | if grad.size > 0:
27 | for i in xrange(numDOF):
28 | grad[i] = -g[i]
29 | return -self.func(x)
30 |
31 | class Test_Constraint(Constraint):
32 | def __init__(self, *args): pass
33 | def constraintType(self): return 'ineq'
34 | def name(self): return 'test1'
35 | def func(self,x,*args):
36 | vars = get_groove_global_vars()
37 | return 1.0
38 |
39 | class Test_Constraint_2(Constraint):
40 | def __init__(self, *args): pass
41 | def constraintType(self): return 'ineq'
42 | def name(self): return 'test2'
43 | def func(self,x,*args):
44 | vars = get_groove_global_vars()
45 | f = x[1] - 0.5
46 | return x[1] - 0.5
47 |
48 |
49 |
50 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/constraint.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/constraint.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/groove_type.py:
--------------------------------------------------------------------------------
1 | import objective as obj
2 | import constraint as con
3 | from colors import bcolors
4 |
5 | class GrooveType:
6 | def __init__(self, vars):
7 | self.vars = vars
8 | obj.set_groove_global_vars(vars)
9 | self.constraint_dict = self.__construct_constraint_dict(self.vars.constraints)
10 | self.objective_function = self.vars.objective_function
11 |
12 |
13 | def __construct_constraint_dict(self, constraints):
14 | constraint_dicts = []
15 | for c in constraints:
16 | d = {
17 | 'type': c.constraintType(),
18 | 'fun': c.func,
19 | 'args': (self.vars,)
20 | }
21 | constraint_dicts.append(d)
22 |
23 | return tuple(constraint_dicts)
24 |
25 |
26 | class GrooveType_scipy(GrooveType):
27 | def __init__(self, vars, solver_name):
28 | GrooveType.__init__(self, vars)
29 | self.solver_name = solver_name
30 |
31 | def solve(self, prev_state=(), max_iter=100, verbose_output=False):
32 | if prev_state == ():
33 | initSol = self.vars.xopt
34 | else:
35 | initSol = prev_state
36 |
37 | if self.vars.unconstrained:
38 | xopt_full = obj.O.minimize(self.objective_function, initSol,
39 | bounds=self.vars.bounds, args=(), method=self.solver_name,
40 | options={'maxiter': max_iter, 'disp': verbose_output})
41 | else:
42 | xopt_full = obj.O.minimize(self.objective_function, initSol, constraints=self.constraint_dict,
43 | bounds=self.vars.bounds, args=(), method=self.solver_name,
44 | options={'maxiter': max_iter, 'disp': verbose_output})
45 |
46 | xopt = xopt_full.x
47 | f_obj = xopt_full.fun
48 |
49 | if verbose_output:
50 | print bcolors.OKBLUE + str(xopt_full) + bcolors.ENDC + '\n'
51 |
52 | self.vars.update(xopt, f_obj)
53 |
54 | return xopt
55 |
56 |
57 |
58 | class GrooveType_nlopt(GrooveType):
59 | def __init__(self, vars, solver_name):
60 | try:
61 | import nlopt as N
62 | except:
63 | raise Exception('Error: In order to use an NLopt solver, you must have NLopt installed.')
64 |
65 | GrooveType.__init__(self, vars)
66 | self.solver_name = solver_name
67 |
68 | if solver_name == 'slsqp':
69 | self.opt = N.opt(N.LD_SLSQP, len(self.vars.init_state))
70 | elif solver_name == 'ccsaq':
71 | self.opt = N.opt(N.LD_CCSAQ, len(self.vars.init_state))
72 | elif solver_name == 'mma':
73 | self.opt = N.opt(N.LD_MMA, len(self.vars.init_state))
74 | elif solver_name == 'bobyqa':
75 | self.opt = N.opt(N.LN_BOBYQA, len(self.vars.init_state))
76 | elif solver_name == 'cobyla':
77 | self.opt = N.opt(N.LN_COBYLA, len(self.vars.init_state))
78 | elif solver_name == 'lbfgs':
79 | self.opt = N.opt(N.LD_LBFGS, len(self.vars.init_state))
80 | elif solver_name == 'mlsl':
81 | self.opt = N.opt(N.GD_MLSL, len(self.vars.init_state))
82 | elif solver_name == 'direct':
83 | self.opt = N.opt(N.GN_DIRECT_L_RAND, len(self.vars.init_state))
84 | elif solver_name == 'newuoa':
85 | self.opt = N.opt(N.LN_NEWUOA_BOUND, len(self.vars.init_state))
86 | else:
87 | raise Exception('Invalid solver_name in subroutine [GrooveType_nlopt]!')
88 |
89 | self.opt.set_min_objective(obj.objective_master_nlopt)
90 | self.opt.set_xtol_rel(1e-4)
91 | # self.opt.set_maxtime(.025)
92 | if self.vars.bounds == ():
93 | self.opt.set_lower_bounds(len(self.vars.init_state) * [-50.0])
94 | self.opt.set_upper_bounds(len(self.vars.init_state) * [50.0])
95 | else:
96 | u = []
97 | l = []
98 | for b in self.vars.bounds:
99 | u.append(b[1])
100 | l.append(b[0])
101 |
102 | self.opt.set_lower_bounds(l)
103 | self.opt.set_upper_bounds(u)
104 |
105 |
106 | def solve(self, prev_state='', verbose_output=False, maxtime=None):
107 | if prev_state == '':
108 | initSol = self.vars.xopt
109 | else:
110 | initSol = prev_state
111 |
112 | if not maxtime == None:
113 | self.opt.set_maxtime(maxtime)
114 |
115 | if not self.vars.unconstrained:
116 | for c in self.vars.constraints:
117 | if c.constraintType() == 'ineq':
118 | self.opt.add_inequality_constraint(c.func_nlopt, 0.1)
119 | elif c.constraintType() == 'eq':
120 | self.opt.add_equality_constraint(c.func_nlopt, 0.1)
121 | else:
122 | self.opt.remove_inequality_constraints()
123 | self.opt.remove_equality_constraints()
124 |
125 | xopt = self.opt.optimize(initSol)
126 | f_obj = self.opt.last_optimum_value()
127 |
128 | if verbose_output:
129 | print bcolors.OKBLUE + str(xopt) + bcolors.ENDC + '\n'
130 |
131 | self.vars.update(xopt, f_obj)
132 |
133 | return xopt
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/groove_type.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/groove_type.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/objective.py:
--------------------------------------------------------------------------------
1 | __author__ = 'drakita'
2 |
3 |
4 | from abc import ABCMeta, abstractmethod
5 | import scipy.optimize as O
6 |
7 | groove_global_vars = []
8 |
9 | def set_groove_global_vars(vars):
10 | global groove_global_vars
11 | groove_global_vars = vars
12 |
13 | def get_groove_global_vars():
14 | global groove_global_vars
15 | return groove_global_vars
16 |
17 |
18 | def objective_master(x):
19 | global groove_global_vars
20 | vars = groove_global_vars
21 | objectives = vars.objectives
22 | weight_funcs = vars.weight_funcs
23 | weight_priors = vars.weight_priors
24 | objective_sum = 0.0
25 | for i,o in enumerate(objectives):
26 | if o.isVelObj() and not vars.vel_objectives_on:
27 | continue
28 | else:
29 | weight_func = weight_funcs[i]
30 | term_weight = weight_priors[i]*weight_func(vars)
31 | objective_sum += term_weight*o(x,vars)
32 |
33 | return float(objective_sum)
34 |
35 |
36 | def objective_master_nlopt(x, grad):
37 | vars = get_groove_global_vars()
38 | numDOF = len(x)
39 | g = O.approx_fprime(x, vars.objective_function, numDOF * [0.001])
40 | if grad.size > 0:
41 | for i in xrange(numDOF):
42 | grad[i] = g[i]
43 |
44 | return vars.objective_function(x)
45 |
46 |
47 | #################################################################################################
48 |
49 | class Objective:
50 | __metaclass__ = ABCMeta
51 |
52 | def __init__(self, *args): pass
53 |
54 | @abstractmethod
55 | def isVelObj(self): return False
56 |
57 | @abstractmethod
58 | def name(self): pass
59 |
60 | @abstractmethod
61 | def __call__(self, x, vars): pass
62 |
63 |
64 | class Test_Objective(Objective):
65 | def isVelObj(self): return False
66 | def name(self): return 'Test'
67 | def __call__(self, x, vars): return 1.0
68 |
69 | class Test_Objective2(Objective):
70 | def isVelObj(self): return False
71 | def name(self): return 'Test_2'
72 | def __call__(self, x, vars): return 1.5
73 |
74 | class Test_Objective3(Objective):
75 | def isVelObj(self): return False
76 | def name(self): return 'Test_3'
77 | def __call__(self, x, vars): return x[0]**2 + x[1]**2
78 |
79 | '''
80 | x_val = np.linalg.norm(v)
81 | t = 0.0
82 | d = 2.0
83 | c = .08
84 | f = 0.1
85 | g = 2
86 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2))) + f * (x_val - t) ** g
87 | '''
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/objective.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/objective.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/vars.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | import math as M
3 | from abc import ABCMeta, abstractmethod
4 | import rospy
5 | from std_msgs.msg import Float32
6 | # from numba import jit, jitclass
7 |
8 | # specific variable classes for specific solvers should inherit from Vars and initialize this super class and override update
9 | class Vars:
10 | def __init__(self, name, objective_function, init_state, objectives, weight_funcs, weight_priors, constraints=(), bounds=(), unconstrained=False):
11 | self.name = name
12 | self.objective_function = objective_function
13 | self.init_state = init_state
14 | self.objectives = objectives
15 | self.weight_funcs = weight_funcs
16 | self.weight_priors = weight_priors
17 | self.constraints = constraints
18 | self.bounds = bounds
19 |
20 | self.vel_objectives_on = True
21 |
22 | self.objective_publishers = []
23 | self.constraint_publishers = []
24 | self.weight_func_publishers = []
25 | self.f_obj_publisher = rospy.Publisher(self.name + '_f_obj', Float32, queue_size=5)
26 | self.__populate_publishers()
27 |
28 | self.xopt = init_state
29 | self.prev_state = init_state
30 | self.prev_state2 = init_state
31 | self.prev_state3 = init_state
32 | self.f_obj = 0.0
33 |
34 | self.unconstrained = unconstrained
35 |
36 | self.all_states = []
37 |
38 | def __populate_publishers(self):
39 | for o in self.objectives:
40 | self.objective_publishers.append(rospy.Publisher('/objective/' + o.name(), Float32, queue_size=5))
41 |
42 | for c in self.constraints:
43 | self.constraint_publishers.append(rospy.Publisher('/constraint/' + c.name(), Float32, queue_size=5))
44 |
45 | for wf in self.weight_funcs:
46 | self.weight_func_publishers.append(rospy.Publisher('/weight_function/' + wf.name(), Float32, queue_size=5))
47 |
48 |
49 | def update(self, xopt, f_obj, publish_objectives=True,publish_constraints=False, publish_weight_funcs=True):
50 | if publish_objectives:
51 | for i,o in enumerate(self.objective_publishers):
52 | data = self.objectives[i].__call__(xopt, self)
53 | data = self.weight_priors[i]*data
54 | o.publish(data)
55 |
56 | self.f_obj_publisher.publish(f_obj)
57 |
58 | if publish_weight_funcs:
59 | for i,w in enumerate(self.weight_func_publishers):
60 | if self.weight_funcs[i].name() == 'Identity_weight':
61 | continue
62 | else:
63 | data = self.weight_funcs[i].__call__(self)
64 | w.publish(data)
65 |
66 | if publish_constraints:
67 | if self.unconstrained == False:
68 | for i,c in enumerate(self.constraints):
69 | con_val = c.func(xopt)
70 | self.constraint_publishers[i].publish(con_val)
71 |
72 |
73 | self.prev_state3 = self.prev_state2
74 | self.prev_state2 = self.prev_state
75 | self.prev_state = self.xopt
76 | self.xopt = xopt
77 | self.f_obj = f_obj
78 |
79 | self.all_states.append(xopt)
80 |
81 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/vars.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/vars.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/weight_function.py:
--------------------------------------------------------------------------------
1 | __author__ = 'drakita'
2 |
3 | import numpy as np
4 | from abc import ABCMeta, abstractmethod, abstractproperty
5 |
6 | class Weight_Function:
7 | __metaclass__ = ABCMeta
8 |
9 | @abstractmethod
10 | def name(self): pass
11 |
12 | @abstractmethod
13 | def __call__(self, vars): pass
14 |
15 | class Identity_Weight(Weight_Function):
16 | def name(self): return 'Identity_weight'
17 | def __call__(self, vars): return 1.0
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/GROOVE_Utils/weight_function.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/GROOVE_Utils/weight_function.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/README.md:
--------------------------------------------------------------------------------
1 | # GROOVE
2 | A general optimization solver that utilizes a weighed sum objective with dynamically relaxed constraints
3 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/groove.py:
--------------------------------------------------------------------------------
1 | from GROOVE_Utils.groove_type import GrooveType_scipy, GrooveType_nlopt
2 |
3 | def get_groove(vars, optimization_package='scipy', solver_name='slsqp'):
4 | '''
5 | :param vars: vars object
6 | :param optimization_package: either 'scipy' or 'nlopt'
7 | :param solver_name:
8 | for scipy, options are 'methods' under this reference: https://docs.scipy.org/doc/scipy/reference/generated/scipy.optimize.minimize.html
9 | for nlopt, options are 'slsqp', 'ccsaq', 'mma', 'bobyqa', 'lbfgs', 'mlsl', 'newuoa'
10 | '''
11 | if optimization_package == 'scipy':
12 | return GrooveType_scipy(vars, solver_name)
13 | elif optimization_package == 'nlopt':
14 | return GrooveType_nlopt(vars, solver_name)
15 | else:
16 | raise Exception('Invalid optimization_package input in subroutine [groove]. Valid options are scipy or nlopt. Exiting.')
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/groove.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE/groove.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE/setup_cython.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup
2 | from Cython.Build import cythonize
3 |
4 | setup(
5 | ext_modules = cythonize("groove.pyx")
6 | )
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/boost/Makefile:
--------------------------------------------------------------------------------
1 | CC=g++
2 | src=objectives
3 | ext_name=objectives_ext
4 |
5 | ########################################################################################################################
6 |
7 | all:boost clean
8 |
9 | boost:obj.o
10 | $(CC) -o $(ext_name).so -shared obj.o -std=c++11 -lboost_python -lboost_numpy27 -lpython2.7 -L/usr/local/lib/ -I /home/rakita -I /usr/include/python2.7/ -I /home/rakita/boost_1_67_0/ -O2 -DNDEBUG
11 |
12 | obj.o:$(src).cpp
13 | $(CC) -lboost_python -lboost_system -std=c++11 -lpython2.7 -lboost_numpy27 -L/usr/local/lib/ -I /home/rakita -I /usr/include/python2.7/ -I /home/rakita/boost_1_67_0/ -O2 -DNDEBUG -fpic -c -o obj.o $(src).cpp
14 |
15 | clean:
16 | rm -rf *.o
17 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/boost/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/boost/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/boost/objectives.cpp:
--------------------------------------------------------------------------------
1 | // author: Danny Rakita
2 |
3 | #include
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 | using namespace std;
11 | namespace np = boost::python::numpy;
12 | namespace p = boost::python;
13 |
14 | int main(int argc, char **argv) {
15 | Py_Initialize();
16 | np::initialize();
17 | }
18 |
19 | string greet() {
20 | return "hello!";
21 | }
22 |
23 | inline double SIGN(double x) {
24 | return (x >= 0.0f) ? +1.0 : -1.0;
25 | }
26 |
27 | inline double NORM(double a, double b, double c, double d) {
28 | return sqrt(a * a + b * b + c * c + d * d);
29 | }
30 | // quaternion = [w, x, y, z]'
31 | vector mRot2Quat(np::ndarray m) {
32 | double r11 = p::extract(m[0][0]);
33 | double r12 = p::extract(m[0][1]);
34 | double r13 = p::extract(m[0][2]);
35 | double r21 = p::extract(m[1][0]);
36 | double r22 = p::extract(m[1][1]);
37 | double r23 = p::extract(m[1][2]);
38 | double r31 = p::extract(m[2][0]);
39 | double r32 = p::extract(m[2][1]);
40 | double r33 = p::extract(m[2][2]);
41 | double q0 = (r11 + r22 + r33 + 1.0) / 4.0;
42 | double q1 = (r11 - r22 - r33 + 1.0) / 4.0;
43 | double q2 = (-r11 + r22 - r33 + 1.0) / 4.0;
44 | double q3 = (-r11 - r22 + r33 + 1.0) / 4.0;
45 | if (q0 < 0.0) {
46 | q0 = 0.0;
47 | }
48 | if (q1 < 0.0) {
49 | q1 = 0.0;
50 | }
51 | if (q2 < 0.0) {
52 | q2 = 0.0;
53 | }
54 | if (q3 < 0.0) {
55 | q3 = 0.0;
56 | }
57 | q0 = sqrt(q0);
58 | q1 = sqrt(q1);
59 | q2 = sqrt(q2);
60 | q3 = sqrt(q3);
61 | if (q0 >= q1 && q0 >= q2 && q0 >= q3) {
62 | q0 *= +1.0;
63 | q1 *= SIGN(r32 - r23);
64 | q2 *= SIGN(r13 - r31);
65 | q3 *= SIGN(r21 - r12);
66 | }
67 | else if (q1 >= q0 && q1 >= q2 && q1 >= q3) {
68 | q0 *= SIGN(r32 - r23);
69 | q1 *= +1.0;
70 | q2 *= SIGN(r21 + r12);
71 | q3 *= SIGN(r13 + r31);
72 | }
73 | else if (q2 >= q0 && q2 >= q1 && q2 >= q3) {
74 | q0 *= SIGN(r13 - r31);
75 | q1 *= SIGN(r21 + r12);
76 | q2 *= +1.0;
77 | q3 *= SIGN(r32 + r23);
78 | }
79 | else if (q3 >= q0 && q3 >= q1 && q3 >= q2) {
80 | q0 *= SIGN(r21 - r12);
81 | q1 *= SIGN(r31 + r13);
82 | q2 *= SIGN(r32 + r23);
83 | q3 *= +1.0;
84 | }
85 | else {
86 | printf("coding error\n");
87 | }
88 | double r = NORM(q0, q1, q2, q3);
89 | q0 /= r;
90 | q1 /= r;
91 | q2 /= r;
92 | q3 /= r;
93 |
94 | vector res(4);
95 | res[0] = q0; res[1] = q1; res[2] = q2; res[3] = q3;
96 |
97 | return res;
98 | }
99 |
100 | vector quaternion_multiply(vector q1, vector q0) {
101 | vector q(4);
102 | q[0] = -q1[1]*q0[1] - q1[2]*q0[2] - q1[3]*q0[3] + q1[0]*q0[0];
103 | q[1] = q1[1]*q0[0] + q1[2]*q0[3] - q1[3]*q0[2] + q1[0]*q0[1];
104 | q[2] = -q1[1]*q0[3] + q1[2]*q0[0] + q1[3]*q0[1] + q1[0]*q0[2];
105 | q[3] = q1[1]*q0[2] - q1[2]*q0[1] + q1[3]*q0[0] + q1[0]*q0[3];
106 | return q;
107 | }
108 |
109 | vector quaternion_inverse(vector q) {
110 | vector q_i(4);
111 | q_i[0] = q[0];
112 | q_i[1] = -q[1];
113 | q_i[2] = -q[2];
114 | q_i[3] = -q[3];
115 | double dot = q_i[0]*q_i[0] + q_i[1]*q_i[1] + q_i[2]*q_i[2] + q_i[3]*q_i[3];
116 | q_i[0] = q_i[0] / dot;
117 | q_i[1] = q_i[1] / dot;
118 | q_i[2] = q_i[2] / dot;
119 | q_i[3] = q_i[3] / dot;
120 | return q_i;
121 | }
122 |
123 | vector quaternion_log(vector q) {
124 | vector rot_vec(3);
125 | rot_vec[0] = q[1]; rot_vec[1] = q[2]; rot_vec[2] = q[3];
126 | if(abs(q[0]) < 1.0) {
127 | double a = acos(q[0]);
128 | double sina = sin(a);
129 | if (abs(sina) >= 0.05) {
130 | double c = a/sina;
131 | rot_vec[0] *= c;
132 | rot_vec[1] *= c;
133 | rot_vec[2] *= c;
134 | }
135 | }
136 |
137 | return rot_vec;
138 |
139 | }
140 |
141 | vector quaternion_disp(vector q1, vector q2) {
142 | vector inv = quaternion_inverse(q1);
143 | vector m = quaternion_multiply(inv, q2);
144 | return quaternion_log(m);
145 | }
146 |
147 | double orientation_multiEE_obj(p::object frames, p::object goal_quats, p::list weights) {
148 | double num_ee = p::len(frames);
149 |
150 | double sum = 0.0;
151 |
152 | for(int q=0; q < num_ee; q++) {
153 | p::list f = p::extract(frames[q]);
154 |
155 | p::list rot_mats = p::extract(f[1]);
156 | int num_jts = p::len(rot_mats);
157 |
158 | np::ndarray ee_rot = p::extract(rot_mats[num_jts-1]);
159 |
160 | vector ee_quat = mRot2Quat(ee_rot);
161 | vector ee_quat2(4);
162 | ee_quat2[0] = -ee_quat[0];
163 | ee_quat2[1] = -ee_quat[1];
164 | ee_quat2[2] = -ee_quat[2];
165 | ee_quat2[3] = -ee_quat[3];
166 |
167 | p::object goal_quat_py = p::extract(goal_quats[q]);
168 | vector goal_quat(4);
169 | goal_quat[0] = p::extract(goal_quat_py[0]);
170 | goal_quat[1] = p::extract(goal_quat_py[1]);
171 | goal_quat[2] = p::extract(goal_quat_py[2]);
172 | goal_quat[3] = p::extract(goal_quat_py[3]);
173 |
174 | vector r1 = quaternion_disp(goal_quat, ee_quat);
175 | vector r2 = quaternion_disp(goal_quat, ee_quat2);
176 |
177 | double disp = sqrt(r1[0]*r1[0] + r1[1]*r1[1] + r1[2]*r1[2]);
178 | double disp2 = sqrt(r2[0]*r2[0] + r2[1]*r2[1] + r2[2]*r2[2]);
179 |
180 | sum += p::extract(weights[q])*min(disp, disp2);
181 |
182 | }
183 |
184 | return sum;
185 | }
186 |
187 | double position_multiEE_obj(p::object frames, p::object eeGoals, p::list weights) {
188 | double num_ee = p::len(frames);
189 |
190 | double sum = 0.0;
191 |
192 | for(int i = 0; i < num_ee; i++) {
193 | p::list f = p::extract(frames[i]);
194 |
195 | p::list positions = p::extract(f[0]);
196 | int num_jts = p::len(positions);
197 |
198 | np::ndarray eePos = p::extract(positions[num_jts-1]);
199 |
200 | double eX = p::extract(eePos[0]);
201 | double eY = p::extract(eePos[1]);
202 | double eZ = p::extract(eePos[2]);
203 |
204 | np::ndarray eeGoal = p::extract(eeGoals[i]);
205 | double gX = p::extract(eeGoal[0]);
206 | double gY = p::extract(eeGoal[1]);
207 | double gZ = p::extract(eeGoal[2]);
208 |
209 | double val = pow(eX-gX, 2.0) + pow(eY-gY, 2.0) + pow(eZ-gZ, 2.0);
210 | val = sqrt(val);
211 | sum += p::extract(weights[i]) * val;
212 | }
213 |
214 | return sum;
215 | }
216 |
217 | double min_jt_jerk_obj(np::ndarray x, p::object prev, p::object prev2, p::object prev3) {
218 | int vec_len = (int) p::len(x);
219 |
220 | double sum = 0.0;
221 |
222 | for(int i=0; i < vec_len; i++) {
223 | double v1 = p::extract(x[i]);
224 | double v2 = p::extract(prev[i]);
225 | double v3 = p::extract(prev2[i]);
226 | double v4 = p::extract(prev3[i]);
227 |
228 | double vel3 = v3 - v4;
229 | double vel2 = v2 - v3;
230 | double vel1 = v1 - v2;
231 |
232 | sum += pow((vel2 - vel3) - (vel1 - vel2), 2.0);
233 | }
234 |
235 | return sqrt(sum);
236 | }
237 |
238 | double min_jt_accel_obj(np::ndarray x, p::object prev, p::object prev2) {
239 | int vec_len = (int) p::len(x);
240 |
241 | double sum = 0.0;
242 |
243 | for(int i=0; i < vec_len; i++) {
244 | double v1 = p::extract(x[i]);
245 | double v2 = p::extract(prev[i]);
246 | double v3 = p::extract(prev2[i]);
247 |
248 | sum += pow((v2 - v3) - (v1 - v2), 2.0);
249 | }
250 |
251 | return sqrt(sum);
252 | }
253 |
254 | double min_jt_vel_obj(np::ndarray x, p::object prev) {
255 | int vec_len = (int) p::len(x);
256 |
257 | double sum = 0.0;
258 |
259 | for(int i=0; i < vec_len; i++) {
260 | double v1 = p::extract(x[i]);
261 | double v2 = p::extract(prev[i]);
262 |
263 | sum += pow((v1-v2), 2.0);
264 | }
265 | return sqrt(sum);
266 | }
267 |
268 |
269 | double nloss(double x_val, double t, double d, double c, double f, double g) {
270 | return -exp( (- pow( (x_val - t), d) ) / (2.0 * pow(c,2.0))) + f * pow( (x_val - t), g);
271 | }
272 |
273 |
274 |
275 |
276 |
277 | BOOST_PYTHON_MODULE(objectives_ext)
278 | {
279 | using namespace boost::python;
280 | def("greet", greet);
281 | def("orientation_multiEE_obj",orientation_multiEE_obj);
282 | def("position_multiEE_obj", position_multiEE_obj);
283 | def("min_jt_vel_obj", min_jt_vel_obj);
284 | def("min_jt_accel_obj", min_jt_accel_obj);
285 | def("min_jt_jerk_obj", min_jt_jerk_obj);
286 | def("nloss", nloss);
287 | }
288 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/boost/objectives_ext.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/boost/objectives_ext.so
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/objectives_ext.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/objectives_ext.so
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_constraint.py:
--------------------------------------------------------------------------------
1 | from ..GROOVE.GROOVE_Utils.constraint import Constraint
2 | from ..GROOVE.GROOVE_Utils.objective import get_groove_global_vars
3 |
4 |
5 | class Singularity_Avoidance_Constraint(Constraint):
6 | def __init__(self, *args): pass
7 | def constraintType(self): return 'ineq'
8 | def name(self): return 'singularity_avoidance'
9 | def func(self, x, *args):
10 | vars = get_groove_global_vars()
11 | mean = vars.yoshikawa_mean
12 | std = vars.yoshikawa_std
13 | min = mean - 2.6*std
14 |
15 | yoshikawa_score = vars.arm.getYoshikawaMeasure(x)
16 |
17 | return [yoshikawa_score - min]
18 |
19 | class Joint_Velocity_Constraint(Constraint):
20 | def __init__(self, *args):
21 | self.joint_idx = args[0]
22 | self.velocity_scale = args[1]
23 | def constraintType(self): return 'ineq'
24 | def name(self): return 'joint_velocity_constraint_{}'.format(self.joint_idx)
25 | def func(self, x, *args):
26 | vars = get_groove_global_vars()
27 | avg = vars.avg_solution_time
28 | avg = 0.02
29 | # print avg
30 | diff = abs(x[self.joint_idx] - vars.xopt[self.joint_idx])
31 | vel_limit = vars.robot.velocity_limits[self.joint_idx] * self.velocity_scale
32 | vel_limit_per_update = vel_limit * avg
33 | return vel_limit_per_update - diff
34 | # return .1*x[0]
35 |
36 |
37 |
38 |
39 |
40 |
41 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_constraint.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_constraint.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_objective.py:
--------------------------------------------------------------------------------
1 | from ..Utils.colors import *
2 |
3 | from ..GROOVE.GROOVE_Utils.objective import Objective, get_groove_global_vars, objective_master
4 | from ..Utils import tf_fast as Tf
5 | from ..Utils.geometry_utils import *
6 | from ..Utils.joint_utils import *
7 |
8 | # try:
9 | # from boost import objectives_ext
10 | # except:
11 | # print 'ERROR when importing boost library extension. Defaulting to python implementation (which will be slower). ' \
12 | # 'To get speed boost, please install and configure the boost python library: ' \
13 | # 'https://www.boost.org/doc/libs/1_67_0/more/getting_started/unix-variants.html'
14 |
15 |
16 | def objective_master_relaxedIK(x):
17 | vars = get_groove_global_vars()
18 | vars.frames = vars.robot.getFrames(x)
19 |
20 | return objective_master(x)
21 |
22 | ########################################################################################################################
23 |
24 | class Position_Obj(Objective):
25 | def __init__(self, *args): pass
26 | def isVelObj(self): return False
27 | def name(self): return 'Position'
28 |
29 | def __call__(self, x, vars):
30 | # positions = vars.arm.getFrames(x)[0]
31 | positions = vars.frames[0]
32 | eePos = positions[-1]
33 | goal_pos = vars.goal_pos
34 | diff = (eePos - goal_pos)
35 | norm_ord = 2
36 | x_val = np.linalg.norm(diff, ord=norm_ord)
37 | t = 0.0
38 | d = 2.0
39 | c = .1
40 | f = 10
41 | g = 2
42 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
43 |
44 | class Position_MultiEE_Obj(Objective):
45 | def __init__(self, *args): pass
46 | def isVelObj(self): return False
47 | def name(self): return 'Position_MultiEE'
48 |
49 | def __call__(self, x, vars):
50 | if vars.c_boost:
51 | x_val = objectives_ext.position_multiEE_obj(vars.frames, vars.goal_positions, [1.0, 1.0])
52 | else:
53 | x_val_sum = 0.0
54 |
55 | for i, f in enumerate(vars.frames):
56 | positions = f[0]
57 | eePos = positions[-1]
58 | goal_pos = vars.goal_positions[i]
59 | diff = (eePos - goal_pos)
60 | norm_ord = 2
61 | x_val = np.linalg.norm(diff, ord=norm_ord)
62 | x_val_sum += x_val
63 |
64 | x_val = x_val_sum
65 |
66 | t = 0.0
67 | d = 2.0
68 | c = .1
69 | f = 10
70 | g = 2
71 |
72 | if vars.c_boost:
73 | return objectives_ext.nloss(x_val, t, d, c, f, g)
74 | else:
75 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
76 |
77 | class Orientation_Obj(Objective):
78 | def __init__(self, *args): pass
79 | def isVelObj(self): return False
80 | def name(self): return 'Orientation'
81 |
82 | def __call__(self, x, vars):
83 | frames = vars.frames[1]
84 | eeMat = frames[-1]
85 |
86 | goal_quat = vars.goal_quat
87 | new_mat = np.zeros((4, 4))
88 | new_mat[0:3, 0:3] = eeMat
89 | new_mat[3, 3] = 1
90 |
91 | ee_quat = Tf.quaternion_from_matrix(new_mat)
92 |
93 | q = ee_quat
94 | ee_quat2 = [-q[0],-q[1],-q[2],-q[3]]
95 |
96 | norm_ord = 2
97 | # start = time.time()
98 | disp = np.linalg.norm(Tf.quaternion_disp(goal_quat,ee_quat), ord=norm_ord)
99 | disp2 = np.linalg.norm(Tf.quaternion_disp(goal_quat,ee_quat2),ord=norm_ord)
100 | # after = time.time()
101 | # print after - start
102 |
103 | x_val = min(disp, disp2)
104 | # x_val = np.min(np.array([disp,disp2]))
105 | t = 0.0
106 | d = 2.0
107 | c = .1
108 | f = 10
109 | g = 2
110 | if vars.c_boost:
111 | return objectives_ext.nloss(x_val, t, d, c, f, g)
112 | else:
113 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
114 |
115 |
116 | class Orientation_MultiEE_Obj(Objective):
117 | def __init__(self, *args): pass
118 | def isVelObj(self): return False
119 | def name(self): return 'Orientation_MultiEE'
120 |
121 | def __call__(self, x, vars):
122 | if vars.c_boost:
123 | x_val = objectives_ext.orientation_multiEE_obj(vars.frames, vars.goal_quats, [1.0, 1.0])
124 | else:
125 | x_val_sum = 0.0
126 |
127 | for i, f in enumerate(vars.frames):
128 | eeMat = f[1][-1]
129 |
130 | goal_quat = vars.goal_quats[i]
131 | new_mat = np.zeros((4, 4))
132 | new_mat[0:3, 0:3] = eeMat
133 | new_mat[3, 3] = 1
134 |
135 | ee_quat = Tf.quaternion_from_matrix(new_mat)
136 |
137 | q = ee_quat
138 | ee_quat2 = [-q[0], -q[1], -q[2], -q[3]]
139 |
140 | norm_ord = 2
141 | disp = np.linalg.norm(Tf.quaternion_disp(goal_quat, ee_quat), ord=norm_ord)
142 | disp2 = np.linalg.norm(Tf.quaternion_disp(goal_quat, ee_quat2), ord=norm_ord)
143 |
144 | x_val = min(disp, disp2)
145 | x_val_sum += x_val
146 |
147 | x_val = x_val_sum
148 |
149 | t = 0.0
150 | d = 2.0
151 | c = .1
152 | f = 10
153 | g = 2
154 | if vars.c_boost:
155 | return objectives_ext.nloss(x_val, t, d, c, f, g)
156 | else:
157 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
158 |
159 |
160 |
161 | class Min_Jt_Vel_Obj(Objective):
162 | def __init__(self, *args): pass
163 | def isVelObj(self): return True
164 | def name(self): return 'Min_Jt_Vel'
165 |
166 | def __call__(self, x, vars):
167 | if vars.c_boost:
168 | x_val = objectives_ext.min_jt_vel_obj(x, vars.xopt)
169 | else:
170 | v = x - np.array(vars.xopt)
171 | x_val = np.linalg.norm(v)
172 |
173 | t = 0.0
174 | d = 2.0
175 | c = .1
176 | f = 10.0
177 | g = 2
178 |
179 | if vars.c_boost:
180 | return objectives_ext.nloss(x_val, t, d, c, f, g)
181 | else:
182 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
183 |
184 |
185 |
186 | class Min_EE_Vel_Obj(Objective):
187 | def __init__(self, *args): pass
188 | def isVelObj(self): return True
189 | def name(self): return 'Min_EE_Vel'
190 |
191 | def __call__(self, x, vars):
192 | jtPt = vars.frames[0][-1]
193 | x_val = np.linalg.norm(vars.ee_pos - jtPt)
194 | t = 0.0
195 | d = 2.0
196 | c = .1
197 | f = 10.0
198 | g = 2
199 | if vars.c_boost:
200 | return objectives_ext.nloss(x_val, t, d, c, f, g)
201 | else:
202 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
203 |
204 |
205 | class Min_Jt_Accel_Obj(Objective):
206 | def __init__(self, *args): pass
207 | def isVelObj(self): return True
208 | def name(self): return 'Min_Jt_Accel'
209 |
210 | def __call__(self, x, vars):
211 | if vars.c_boost:
212 | x_val = objectives_ext.min_jt_accel_obj(x, vars.xopt, vars.prev_state)
213 | else:
214 | prev_state_2 = np.array(vars.prev_state)
215 | prev_state = np.array(vars.xopt)
216 |
217 | v2 = prev_state - prev_state_2
218 | v1 = x - prev_state
219 |
220 | a = v2 - v1
221 |
222 | x_val = np.linalg.norm(a)
223 |
224 | t = 0.0
225 | d = 2.0
226 | c = .1
227 | f = 10.0
228 | g = 2
229 | if vars.c_boost:
230 | return objectives_ext.nloss(x_val, t, d, c, f, g)
231 | else:
232 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
233 |
234 | class Min_EE_Accel_Obj(Objective):
235 | def __init__(self, *args): pass
236 | def isVelObj(self): return True
237 | def name(self): return 'Min_EE_Accel'
238 |
239 | def __call__(self, x, vars):
240 | jtPt = vars.frames[0][-1]
241 | prev_jtPt_2 = np.array(vars.prev_ee_pos)
242 | prev_jtPt = np.array(vars.ee_pos)
243 |
244 | v2 = prev_jtPt - prev_jtPt_2
245 | v1 = jtPt - prev_jtPt
246 |
247 | a = v2 - v1
248 |
249 | x_val = np.linalg.norm(a)
250 | t = 0.0
251 | d = 2.0
252 | c = .2
253 | f = 0.0
254 | g = 2
255 | if vars.c_boost:
256 | return objectives_ext.nloss(x_val, t, d, c, f, g)
257 | else:
258 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
259 |
260 | class Min_Jt_Jerk_Obj(Objective):
261 | def __init__(self, *args): pass
262 | def isVelObj(self): return True
263 | def name(self): return 'Min_Jt_Jerk'
264 |
265 | def __call__(self, x, vars):
266 | if vars.c_boost:
267 | x_val = objectives_ext.min_jt_jerk_obj(x, vars.xopt, vars.prev_state, vars.prev_state2)
268 | else:
269 | prev_state_3 = np.array(vars.prev_state2)
270 | prev_state_2 = np.array(vars.prev_state)
271 | prev_state = np.array(vars.xopt)
272 |
273 | v3 = prev_state_2 - prev_state_3
274 | v2 = prev_state - prev_state_2
275 | v1 = x - prev_state
276 |
277 | a2 = v2 - v3
278 | a1 = v1 - v2
279 |
280 | j = a1 - a2
281 |
282 | x_val = np.linalg.norm(j)
283 |
284 | t = 0.0
285 | d = 2.0
286 | c = .2
287 | f = 0.0
288 | g = 2
289 |
290 | if vars.c_boost:
291 | return objectives_ext.nloss(x_val, t, d, c, f, g)
292 | else:
293 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
294 |
295 | class Min_EE_Jerk_Obj(Objective):
296 | def __init__(self, *args): pass
297 | def isVelObj(self): return True
298 | def name(self): return 'Min_EE_Jerk'
299 |
300 | def __call__(self, x, vars):
301 | jtPt = vars.frames[0][-1]
302 | prev_jtPt_3 = np.array(vars.prev_ee_pos2)
303 | prev_jtPt_2 = np.array(vars.prev_ee_pos)
304 | prev_jtPt = np.array(vars.ee_pos)
305 |
306 | v3 = prev_jtPt_2 - prev_jtPt_3
307 | v2 = prev_jtPt - prev_jtPt_2
308 | v1 = jtPt - prev_jtPt
309 |
310 | a2 = v2 - v3
311 | a1 = v1 - v2
312 |
313 | j = a1 - a2
314 |
315 | x_val = np.linalg.norm(j)
316 | t = 0.0
317 | d = 2.0
318 | c = .2
319 | f = 1.0
320 | g = 2
321 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2))) + f * (x_val - t) ** g
322 |
323 |
324 | class Joint_Limit_Obj(Objective):
325 | def __init__(self, *args): pass
326 | def isVelObj(self): return False
327 | def name(self): return 'Joint_Limit'
328 |
329 | def __call__(self, x, vars):
330 | sum = 0.0
331 | penalty = 50.0
332 | d = 8
333 | joint_limits = vars.robot.bounds
334 | for i in xrange(vars.robot.numDOF):
335 | l = joint_limits[i][0]
336 | u = joint_limits[i][1]
337 | mid = (u + l) / 2.0
338 | a = penalty / (u - mid)**d
339 | sum += a*(x[i] - mid)**d
340 |
341 | vars.joint_limit_obj_value = sum
342 |
343 | x_val = sum
344 | t = 0
345 | d = 2
346 | c = 2.3
347 | f = .003
348 | g = 2
349 | if vars.c_boost:
350 | return objectives_ext.nloss(x_val, t, d, c, f, g)
351 | else:
352 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
353 |
354 |
355 | class Self_Collision_Avoidance_Obj(Objective):
356 | def __init__(self, *args): pass
357 | def isVelObj(self): return False
358 | def name(self): return 'Self_Collision_Avoidance'
359 |
360 | def __call__(self, x, vars):
361 | frames = vars.frames
362 | jt_pts = frames[0]
363 |
364 | x_val = vars.collision_graph.get_collision_score(frames)
365 | t = 0.0
366 | d = 2.0
367 | c = .08
368 | f = 1.0
369 | g = 2
370 | if vars.c_boost:
371 | return objectives_ext.nloss(x_val, t, d, c, f, g)
372 | else:
373 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
374 |
375 |
376 | class Collision_Avoidance_nn(Objective):
377 | def __init__(self, *args): pass
378 | def isVelObj(self): return False
379 | def name(self): return 'Collision_Avoidance_nn'
380 |
381 | def __call__(self, x, vars):
382 | frames = vars.frames
383 | out_vec = []
384 | for f in frames:
385 | jt_pts = f[0]
386 | for j in jt_pts:
387 | out_vec.append(j[0])
388 | out_vec.append(j[1])
389 | out_vec.append(j[2])
390 |
391 | val = vars.collision_nn.predict([out_vec])[0]
392 |
393 | # nn_stats = vars.nn_stats
394 |
395 | # x_val = (val - nn_stats[0])/ nn_stats[1]
396 | x_val = val
397 | t = 0
398 | d = 2
399 | c = 1.85
400 | f = .004
401 | g = 2
402 | if vars.c_boost:
403 | return objectives_ext.nloss(x_val, t, d, c, f, g)
404 | else:
405 | return (-math.e ** ((-(x_val - t) ** d) / (2.0 * c ** 2)) ) + f * (x_val - t) ** g
406 |
407 | # return math.exp(x_val - 0.64) - 1
408 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_objective.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_objective.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_vars.py:
--------------------------------------------------------------------------------
1 | from ..GROOVE.GROOVE_Utils.vars import Vars
2 | from ..GROOVE.GROOVE_Utils.weight_function import Weight_Function,Identity_Weight
3 | from ..GROOVE_RelaxedIK.relaxedIK_weight_function import Position_Weight
4 | from ..Spacetime.robot import Robot
5 | from geometry_msgs.msg import PoseStamped
6 | from visualization_msgs.msg import Marker
7 | from std_msgs.msg import Float32
8 | from ..Utils.urdf_load import *
9 | from ..GROOVE_RelaxedIK.relaxedIK_constraint import Singularity_Avoidance_Constraint, Joint_Velocity_Constraint
10 | from ..GROOVE_RelaxedIK.relaxedIK_objective import *
11 | from ..Utils.collision_graph import Collision_Graph
12 | from ..Utils.config_engine import Config_Engine
13 | import rospy
14 | import os
15 | from sklearn.externals import joblib
16 |
17 |
18 |
19 | class RelaxedIK_vars(Vars):
20 | def __init__(self, name,
21 | urdf_path,
22 | full_joint_lists,
23 | fixed_ee_joints,
24 | joint_order,
25 | objective_function=objective_master_relaxedIK,
26 | full_arms=[],
27 | init_state=6*[0],
28 | rotation_mode = 'relative', # could be 'absolute' or 'relative'
29 | position_mode = 'relative',
30 | objectives=(Position_MultiEE_Obj(), Orientation_MultiEE_Obj(), Min_Jt_Vel_Obj(),Min_Jt_Accel_Obj(),Min_Jt_Jerk_Obj(), Joint_Limit_Obj(), Collision_Avoidance_nn()),
31 | weight_funcs=(Identity_Weight(), Identity_Weight(), Identity_Weight(),Identity_Weight(),Identity_Weight(), Identity_Weight(), Identity_Weight()),
32 | weight_priors=(50.0,40.0,0.3,0.3,0.3,1.0,2.0),
33 | constraints=(),
34 | bounds=(),
35 | collision_file='',
36 | collision_link_exclusion_list=[],
37 | config_file_name='',
38 | pre_config=False,
39 | config_override=False,
40 | c_boost=False
41 | ):
42 |
43 | Vars.__init__(self,name, objective_function, init_state,objectives,weight_funcs,weight_priors,constraints,bounds)
44 | # check inputs #####################################################################################################################
45 | if not (rotation_mode == 'relative' or rotation_mode == 'absolute'):
46 | print bcolors.FAIL + 'Invalid rotation_mode. Must be or . Exiting.' + bcolors.ENDC
47 | raise ValueError('Invalid rotation_mode.')
48 | if not (position_mode == 'relative' or position_mode == 'absolute'):
49 | print bcolors.FAIL + 'Invalid position_mode. Must be or . Exiting.' + bcolors.ENDC
50 | raise ValueError('Invalid position_mode.')
51 | num_objs = len(objectives)
52 | if not (num_objs == len(weight_funcs) == len(weight_priors)):
53 | print bcolors.FAIL + 'Invalid Inputs. The number of objectives ({}) must be the same as the number' \
54 | 'of weight functions ({}) and weight priors ({}). Exiting.'.format(str(num_objs),
55 | str(len(
56 | weight_funcs)),
57 | str(len(
58 | weight_priors))) + bcolors.ENDC
59 | raise ValueError('Invalid function arguments.')
60 | ###################################################################################################################################
61 |
62 |
63 | self.full_joint_lists = full_joint_lists
64 | self.fixed_ee_joints = fixed_ee_joints
65 | self.joint_order = joint_order
66 | self.urdf_path = urdf_path
67 | self.collision_file = collision_file
68 | self.c_boost = c_boost
69 | self.num_chains = len(full_joint_lists)
70 | self.arms = []
71 | self.urdf_robots = []
72 | self.trees = []
73 |
74 | try:
75 | from boost import objectives_ext
76 | except:
77 | self.c_boost = False
78 |
79 |
80 | if full_arms == []:
81 | for i in xrange(self.num_chains):
82 | urdf_robot, arm, arm_c, tree = urdf_load(urdf_path, '', '', full_joint_lists[i], fixed_ee_joints[i])
83 | if self.c_boost:
84 | self.arms.append(arm_c)
85 | else:
86 | self.arms.append(arm)
87 | self.urdf_robots.append(urdf_robot)
88 | self.trees.append(tree)
89 | else:
90 | self.arms = full_arms
91 | self.urdf_robots = None
92 | self.trees = None
93 |
94 | # make robot
95 | self.robot = Robot(self.arms, full_joint_lists,joint_order)
96 |
97 | # self.urdf_robot = urdf_robot
98 | # self.arm = arm
99 | # self.tree = tree
100 | self.rotation_mode = rotation_mode
101 | self.position_mode = position_mode
102 |
103 | self.numDOF = self.robot.numDOF
104 |
105 | if bounds == ():
106 | self.bounds = self.robot.bounds
107 | else:
108 | self.bounds = bounds
109 |
110 | # if not pre_config:
111 | dirname = os.path.dirname(__file__)
112 | if collision_file == '':
113 | cf = os.path.join(dirname, '../Config/collision.yaml')
114 | # cf = 'RelaxedIK/Config/collision.yaml'
115 | else:
116 | cf = os.path.join(dirname, '../Config/' + collision_file)
117 | # cf = 'RelaxedIK/Config/' + collision_file
118 | self.collision_graph = Collision_Graph(cf, self.robot, collision_link_exclusion_list)
119 |
120 |
121 | if pre_config:
122 | '''
123 | response = raw_input(bcolors.FAIL + 'WARNING: Running in pre-config mode should only be used in simulation for diagnostics or generating a collision.yaml'
124 | 'file. Collisions will NOT be avoided in this mode, which could result in damage if run on a real robot. Continue? (y or n): ' + bcolors.ENDC)
125 | if not response == 'y':
126 | exit(1)
127 | '''
128 |
129 | objectives = list(objectives)
130 | weight_funcs = list(weight_funcs)
131 | weight_priors = list(weight_priors)
132 | del objectives[-1]
133 | del weight_funcs[-1]
134 | del weight_priors[-1]
135 | objectives = tuple(objectives)
136 | weight_funcs = tuple(weight_funcs)
137 | weight_priors = tuple(weight_priors)
138 |
139 | velocity_constraints = True
140 | velocity_scale = 1.0
141 | if velocity_constraints:
142 | for i in xrange(self.robot.numDOF):
143 | self.constraints += (Joint_Velocity_Constraint(i,velocity_scale),)
144 |
145 |
146 | if not self.numDOF == len(init_state):
147 | # self.init_state = self.numDOF * [0]
148 | # print bcolors.WARNING + 'WARNING: Length of init_state does not match number of robot DOFs. Automatically ' \
149 | # 'initializing init_state as {}. This may cause errors.'.format(
150 | # str(self.init_state)) + bcolors.ENDC
151 | print bcolors.WARNING + 'WARNING: Length of init_state does not match number of robot DOFs. Is this what you intended?' + bcolors.ENDC
152 |
153 | Vars.__init__(self,name, objective_function, self.init_state,objectives,weight_funcs,weight_priors,constraints=self.constraints,bounds=self.bounds)
154 |
155 | self.goal_positions = []
156 | for i in range(self.num_chains):
157 | self.goal_positions.append(np.array([0,0,0]))
158 | self.prev_goal_positions3 = self.goal_positions
159 | self.prev_goal_positions2 = self.goal_positions
160 | self.prev_goal_positions = self.goal_positions
161 | self.goal_quats = []
162 | for i in range(self.num_chains):
163 | self.goal_quats.append([1,0,0,0])
164 | self.prev_goal_quats3 = self.goal_quats
165 | self.prev_goal_quats2 = self.goal_quats
166 | self.prev_goal_quats = self.goal_quats
167 | self.frames = self.robot.getFrames(self.init_state)
168 | self.joint_limit_obj_value = 0.0
169 |
170 | self.init_ee_positions = self.robot.get_ee_positions(self.init_state)
171 | self.init_ee_quats = self.robot.get_ee_rotations(self.init_state)
172 | self.ee_positions = self.init_ee_positions
173 | self.prev_ee_positions3 = self.init_ee_positions
174 | self.prev_ee_positions2 = self.init_ee_positions
175 | self.prev_ee_positions = self.init_ee_positions
176 | self.first = True
177 | self.unconstrained = False
178 | self.marker_pub = rospy.Publisher('visualization_marker',Marker,queue_size=5)
179 |
180 | self.solveID = 1.0
181 | self.avg_solution_time = 0.0
182 | self.total_run_time = 0.0
183 | self.start_time = rospy.get_time()
184 | self.solverCounter = 0
185 |
186 | if not pre_config:
187 | self.ce = Config_Engine(self.collision_graph, self, config_fn=config_file_name, override=config_override)
188 | self.collision_nn = self.ce.collision_nn
189 |
190 | def update(self, xopt, f_obj, publish_objectives=True,publish_constraints=True, publish_weight_funcs=True):
191 | Vars.update(self, xopt, f_obj, publish_objectives=publish_objectives,publish_constraints=publish_constraints, publish_weight_funcs=publish_weight_funcs)
192 |
193 |
194 | def relaxedIK_vars_update(self, xopt):
195 | self.prev_ee_positions3 = self.prev_ee_positions2
196 | self.prev_ee_positions2 = self.prev_ee_positions
197 | self.prev_ee_positions = self.ee_positions
198 | self.ee_positions = self.robot.get_ee_positions(xopt)
199 | self.prev_goal_quats3 = self.prev_goal_quats2
200 | self.prev_goal_quats2 = self.prev_goal_quats
201 | self.prev_goal_quats = self.goal_quats
202 | self.prev_goal_positions3 = self.prev_goal_positions2
203 | self.prev_goal_positions2 = self.prev_goal_positions
204 | self.prev_goal_positions = self.goal_positions
205 | self.solveID += 1.0
206 | self.total_run_time = rospy.get_time() - self.start_time
207 | self.avg_solution_time = self.total_run_time / self.solveID
208 |
209 |
210 |
211 |
212 |
213 |
214 |
215 |
216 |
217 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_vars.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_vars.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_weight_function.py:
--------------------------------------------------------------------------------
1 | from ..GROOVE.GROOVE_Utils.weight_function import Weight_Function, Identity_Weight
2 |
3 | class Position_Weight(Weight_Function):
4 | def name(self): return 'Position_weight'
5 | def __call__(self, vars):
6 | dof = vars.arm.numDOF
7 | max_val = dof * 10.0
8 | return max((max_val - vars.joint_limit_obj_value) / max_val, 0.5)
9 |
10 |
11 |
--------------------------------------------------------------------------------
/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_weight_function.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/GROOVE_RelaxedIK/relaxedIK_weight_function.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/README.md:
--------------------------------------------------------------------------------
1 | # RelaxedIK
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/__init__.py:
--------------------------------------------------------------------------------
1 | __author__ = 'gleicher'
2 |
3 | __all__ = ["robot"]
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/adInterface.py:
--------------------------------------------------------------------------------
1 | __author__ = 'gleicher'
2 |
3 | # note:
4 | # using defaultdict IS faster than using dict in my experiments
5 | # (if you use a regular dictionary, you need a try/except for the +=)
6 | # (although only marginally so)
7 | # the code is much much cleaner, so I am sticking with it
8 |
9 | import ad
10 | import ad.admath as MATH
11 |
12 | from collections import defaultdict
13 |
14 | ADF = ad.ADF
15 | AVD = ad.ADV
16 |
17 | def adnumber(val, name):
18 | return ad.adnumber(val, name)
19 |
20 | def apply_chain_rule_noHess(ad_funcs, variables, lc_wrt_args, qc_wrt_args,
21 | cp_wrt_args):
22 | """
23 | This function applies the first and second-order chain rule to calculate
24 | the derivatives with respect to original variables (i.e., objects created
25 | with the ``adnumber(...)`` constructor).
26 |
27 | For reference:
28 | - ``lc`` refers to "linear coefficients" or first-order terms
29 | - ``qc`` refers to "quadratic coefficients" or pure second-order terms
30 | - ``cp`` refers to "cross-product" second-order terms
31 |
32 | """
33 | grad = defaultdict(float)
34 | for f,df in zip(ad_funcs, lc_wrt_args):
35 | try:
36 | for fvar,fval in f._lc.iteritems():
37 | grad[fvar] += df * fval
38 | except:
39 | pass
40 | return (grad, None, None)
41 |
42 | withHessians = ad._apply_chain_rule
43 |
44 | # set up for no hessians
45 | ad._apply_chain_rule = apply_chain_rule_noHess
46 |
47 | # compute the sum - quickly
48 | def fsum(list):
49 | # compute the sum of values, but also keep any AD objects
50 | # in case we are computing a derivative - this may be a
51 | # little slower in the event of value computation, but better for
52 | # derivatives
53 | val = 0
54 | ads = []
55 | for v in list:
56 | try:
57 | val += v.x
58 | ads.append(v)
59 | except AttributeError:
60 | val += v
61 |
62 | if len(ads):
63 | grad = defaultdict(float)
64 | for f in ads:
65 | for fvar,fval in f._lc.iteritems():
66 | grad[fvar] += fval
67 | return ADF(val, grad, None, None)
68 | else:
69 | return val
70 |
71 | # replace the slow parts
72 | def ADF_Mult(self,val):
73 | try:
74 | x = self.x
75 | dx = self._lc
76 | except AttributeError:
77 | x = self
78 | dx = None
79 | if x==0.0: return 0.0
80 | try:
81 | y = val.x
82 | dy = val._lc
83 | except AttributeError:
84 | y = val
85 | dy = None
86 | if y==0.0: return 0.0
87 |
88 | if dx or dy:
89 | grad = defaultdict(float)
90 | if dx:
91 | for a,b in dx.iteritems():
92 | grad[a] = b * y
93 | if dy:
94 | for a,b in dy.iteritems():
95 | grad[a] += b * x
96 | return ADF(x*y, grad, None, None)
97 | else:
98 | return x*y
99 |
100 | def ADF_Add(self,val):
101 | try:
102 | x = self.x
103 | dx = self._lc
104 | except AttributeError:
105 | x = self
106 | dx = None
107 | try:
108 | y = val.x
109 | dy = val._lc
110 | except AttributeError:
111 | y = val
112 | dy = None
113 |
114 | if dx and dy:
115 | grad = defaultdict(float)
116 | for a,b in dx.iteritems():
117 | grad[a] = b
118 | for a,b in dy.iteritems():
119 | grad[a] += b
120 | return ADF(x+y, grad, None, None)
121 | elif dx:
122 | return ADF(x+y, dx, None, None)
123 | elif dy:
124 | return ADF(x+y, dy, None, None)
125 | else:
126 | return x+y
127 |
128 | def ADF_Sub(self,val):
129 | try:
130 | x = self.x
131 | dx = self._lc
132 | except AttributeError:
133 | x = self
134 | dx = None
135 | try:
136 | y = val.x
137 | dy = val._lc
138 | except AttributeError:
139 | y = val
140 | dy = None
141 |
142 | if dx and dy:
143 | grad = defaultdict(float)
144 | for a,b in dx.iteritems():
145 | grad[a] = b
146 | for a,b in dy.iteritems():
147 | grad[a] -= b
148 | return ADF(x-y, grad, None, None)
149 | elif dx:
150 | return ADF(x-y, dx, None, None)
151 | elif dy:
152 | return ADF(x-y, dy, None, None)
153 | else:
154 | return x-y
155 |
156 | def fastLC2(a1,t1,a2,t2):
157 | """
158 | t1 * a1 + t2 * a2 - assumes that the t's are constant
159 | :param a1:
160 | :param t1:
161 | :param a2:
162 | :param t2:
163 | :return:
164 | """
165 | try:
166 | if t1 != 0.0:
167 | x = a1.x
168 | dx = a1._lc
169 | else:
170 | x = 0.0
171 | dx = None
172 | except AttributeError:
173 | x = a1
174 | dx = None
175 | try:
176 | if t2 != 0.0:
177 | y = a2.x
178 | dy = a2._lc
179 | else:
180 | y = 0.0
181 | dy = None
182 | except AttributeError:
183 | y = a2
184 | dy = None
185 |
186 | if dx or dy:
187 | grad = defaultdict(float)
188 | if dx:
189 | for a,b in dx.iteritems():
190 | grad[a] = b * t1
191 | if dy:
192 | for a,b in dy.iteritems():
193 | grad[a] += b * t2
194 | return ADF(t1*x + t2*y, grad, None, None)
195 | else:
196 | return t1*x + t2*y
197 |
198 |
199 | ADF.__add__ = ADF_Add
200 | ADF.__mul__ = ADF_Mult
201 | ADF.__sub__ = ADF_Sub
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/adInterface.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/adInterface.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/arm.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/arm.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/Arm.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 |
11 | using namespace std;
12 | using namespace boost::python;
13 | using namespace Eigen;
14 | namespace np = boost::python::numpy;
15 |
16 | typedef vector vec;
17 | typedef vector mat;
18 |
19 | #define PI 3.14159265
20 |
21 | class Arm {
22 | public:
23 | int numDOF;
24 | boost::python::list displacements;
25 | boost::python::list axes;
26 | boost::python::list rotOffsets;
27 | boost::python::tuple dispOffset;
28 | boost::python::list velocity_limits;
29 | boost::python::list joint_limits;
30 | char* name;
31 | Matrix3d rotX;
32 | Matrix3d rotY;
33 | Matrix3d rotZ;
34 |
35 |
36 | Arm(boost::python::list axes, boost::python::list displacements,
37 | boost::python::list rotOffsets, boost::python::tuple dispOffset, char* name) {
38 | Py_Initialize();
39 | np::initialize();
40 | this->axes = axes;
41 | this->displacements = displacements;
42 | this->rotOffsets = rotOffsets;
43 | this->dispOffset = dispOffset;
44 | this->numDOF = len(displacements);
45 | this->name = name;
46 |
47 | this->rotX = MatrixXd::Zero(3,3);
48 | this->rotY = MatrixXd::Zero(3,3);
49 | this->rotZ = MatrixXd::Zero(3,3);
50 |
51 | this->rotX(0,0) = 1.0;
52 | this->rotY(1,1) = 1.0;
53 | this->rotZ(2,2) = 1.0;
54 | }
55 |
56 | Matrix3d& rot3(char axis, double s, double c) {
57 | if (axis == 'z' || axis == 'Z') {
58 | this->rotZ(0,0) = c;
59 | this->rotZ(0,1) = -s;
60 | this->rotZ(1,0) = s;
61 | this->rotZ(1,1) = c;
62 | return this->rotZ;
63 | }
64 | else if(axis == 'y' || axis == 'Y') {
65 | this->rotY(0,0) = c;
66 | this->rotY(0,2) = s;
67 | this->rotY(2,0) = -s;
68 | this->rotY(2,2) = c;
69 | return this->rotY;
70 | }
71 | else if(axis == 'x' || axis == 'X') {
72 | this->rotX(1,1) = c;
73 | this->rotX(1,2) = -s;
74 | this->rotX(2,1) = s;
75 | this->rotX(2,2) = c;
76 | return this->rotX;
77 | }
78 | else {
79 | cout << "ERROR: not a valid axis label";
80 | }
81 | }
82 |
83 | boost::python::list getFrames(boost::python::list state) {
84 | boost::python::list ret;
85 | boost::python::list pts;
86 | Vector3d pt = this->array(this->dispOffset);
87 | pts.append(this->tolist(pt));
88 | boost::python::list frames;
89 | Matrix3d rot = MatrixXd::Zero(3,3);
90 | rot(0,0) = 1.0;
91 | rot(1,1) = 1.0;
92 | rot(2,2) = 1.0;
93 | frames.append(np::array(this->tolist(rot)));
94 |
95 | for(int i = 0; i < this->numDOF; i++) {
96 | double s = sin(extract(state[i]));
97 | double c = cos(extract(state[i]));
98 |
99 | //TODO: do rotation offsets
100 |
101 | char curr_axis = extract(this->axes[i]);
102 |
103 | Matrix3d rmat = this->rot3(curr_axis,s,c);
104 | rot = rot*rmat;
105 | Vector3d disp;
106 | disp(0) = extract((this->displacements[i])[0]);
107 | disp(1) = extract((this->displacements[i])[1]);
108 | disp(2) = extract((this->displacements[i])[2]);
109 | // cout << rot(1,1);
110 | // cout << "\n";
111 | // high_resolution_clock::time_point t1 = high_resolution_clock::now();
112 | pt = (rot*disp) + pt;
113 | // high_resolution_clock::time_point t2 = high_resolution_clock::now();
114 | // duration time_span = duration_cast>(t2 - t1);
115 | // std::cout << "It took me " << time_span.count() << " seconds.\n";
116 |
117 | pts.append(np::array(this->tolist(pt)));
118 | frames.append(np::array(this->tolist(rot)));
119 | }
120 |
121 | ret.append(pts);
122 | ret.append(frames);
123 | return ret;
124 | }
125 |
126 | private:
127 |
128 | Vector3d array(boost::python::list input) {
129 | Vector3d v;
130 | v(0) = extract(input[0]);
131 | v(1) = extract(input[1]);
132 | v(2) = extract(input[2]);
133 | return v;
134 | }
135 |
136 | Vector3d array(boost::python::tuple input) {
137 | Vector3d v;
138 | v(0) = extract(input[0]);
139 | v(1) = extract(input[1]);
140 | v(2) = extract(input[2]);
141 | return v;
142 | }
143 |
144 | boost::python::list tolist(Vector3d v) {
145 | boost::python::list l;
146 | l.append(v(0));
147 | l.append(v(1));
148 | l.append(v(2));
149 | return l;
150 | }
151 |
152 | mat tomat(Vector3d v) {
153 | mat ret;
154 | vec ve;
155 | ve.push_back(v(0));
156 | ve.push_back(v(1));
157 | ve.push_back(v(2));
158 | ret.push_back(ve);
159 | return ret;
160 | }
161 |
162 | mat tomat(Matrix3d m) {
163 | mat ret;
164 | vec row1;
165 | vec row2;
166 | vec row3;
167 |
168 | row1.push_back(m(0,0));
169 | row1.push_back(m(0,1));
170 | row1.push_back(m(0,2));
171 |
172 | row2.push_back(m(1,0));
173 | row2.push_back(m(1,1));
174 | row2.push_back(m(1,2));
175 |
176 | row3.push_back(m(2,0));
177 | row3.push_back(m(2,1));
178 | row3.push_back(m(2,2));
179 |
180 | ret.push_back(row1);
181 | ret.push_back(row2);
182 | ret.push_back(row3);
183 |
184 | return ret;
185 | }
186 |
187 | boost::python::list tolist(Matrix3d m) {
188 | boost::python::list ret;
189 | boost::python::list row1;
190 | boost::python::list row2;
191 | boost::python::list row3;
192 |
193 | row1.append(m(0,0));
194 | row1.append(m(0,1));
195 | row1.append(m(0,2));
196 |
197 | row2.append(m(1,0));
198 | row2.append(m(1,1));
199 | row2.append(m(1,2));
200 |
201 | row3.append(m(2,0));
202 | row3.append(m(2,1));
203 | row3.append(m(2,2));
204 |
205 | ret.append(row1);
206 | ret.append(row2);
207 | ret.append(row3);
208 |
209 | return ret;
210 | }
211 |
212 | np::ndarray convert_to_numpy(mat const & input) {
213 | u_int n_rows = input.size();
214 | u_int n_cols = input[0].size();
215 | boost::python::tuple shape = boost::python::make_tuple(n_rows, n_cols);
216 | boost::python::tuple stride = boost::python::make_tuple(sizeof(double));
217 | np::dtype dtype = np::dtype::get_builtin();
218 | boost::python::object own;
219 | np::ndarray converted = np::zeros(shape, dtype);
220 |
221 | for (u_int i = 0; i < n_rows; i++)
222 | {
223 | shape = boost::python::make_tuple(n_cols);
224 | converted[i] = np::from_data(input[i].data(), dtype, shape, stride, own);
225 | }
226 | return converted;
227 | }
228 |
229 | };
230 |
231 |
232 | BOOST_PYTHON_MODULE(Arm_ext) {
233 | class_("Arm", init())
235 | .def("getFrames", &Arm::getFrames)
236 | .def_readwrite("numDOF", &Arm::numDOF)
237 | .def_readwrite("name", &Arm::name)
238 | .def_readwrite("velocity_limits", &Arm::velocity_limits)
239 | .def_readwrite("rotOffsets", &Arm::rotOffsets)
240 | .def_readwrite("dispOffset", &Arm::dispOffset)
241 | .def_readwrite("joint_limits", &Arm::joint_limits)
242 | .def_readwrite("displacements", &Arm::displacements)
243 | .def_readwrite("axes", &Arm::axes)
244 | ;
245 | }
246 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/Arm_ext.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/boost/Arm_ext.so
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/Makefile:
--------------------------------------------------------------------------------
1 | CC=g++
2 | src=Arm
3 | ext_name=Arm_ext
4 |
5 | ########################################################################################################################
6 |
7 | all:boost clean
8 |
9 | boost:obj.o
10 | $(CC) -o $(ext_name).so -shared obj.o -std=c++11 -lboost_python -lboost_numpy27 -lpython2.7 -L/usr/local/lib/ -I /home/rakita -I /usr/include/python2.7/ -I /home/rakita/boost_1_67_0/ -O2 -DNDEBUG
11 |
12 | obj.o:$(src).cpp
13 | $(CC) -lboost_python -lboost_system -std=c++11 -lpython2.7 -lboost_numpy27 -L/usr/local/lib/ -I /home/rakita -I /usr/include/python2.7/ -I /home/rakita/boost_1_67_0/ -O2 -DNDEBUG -fpic -c -o obj.o $(src).cpp
14 |
15 | clean:
16 | rm -rf *.o
17 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/boost/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/hello.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/boost/hello.so
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/test.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | boost::python::list greet()
4 | {
5 | boost::python::list l;
6 | l.append(3.0);
7 | l.append(2.0);
8 | l.append(1.0);
9 | return l;
10 | }
11 |
12 | BOOST_PYTHON_MODULE(hello_ext)
13 | {
14 | using namespace boost::python;
15 | def("greet", greet);
16 | }
17 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/boost/world.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 |
4 | class World
5 | {
6 | public:
7 | void set(std::string msg) { this->msg = msg; }
8 | std::string greet() { return msg; }
9 | std::string msg;
10 | };
11 |
12 |
13 | using namespace boost::python;
14 |
15 | BOOST_PYTHON_MODULE(hello)
16 | {
17 | class_("World")
18 | .def("greet", &World::greet)
19 | .def("set", &World::set)
20 | ;
21 | }
22 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/robot.py:
--------------------------------------------------------------------------------
1 | import arm
2 | from ..Utils.transformations import quaternion_from_matrix
3 |
4 | class Robot:
5 | def __init__(self, arms, full_joint_lists, joint_order):
6 | self.arms = arms
7 | self.full_joint_lists = full_joint_lists
8 | self.joint_order = joint_order
9 |
10 | self.numChains = len(self.arms)
11 | self.numDOF = len(self.joint_order)
12 |
13 | self.subchain_indices = []
14 | self.__initialize_subchain_indices()
15 |
16 | self.bounds = []
17 | self.__initialize_bounds()
18 |
19 | self.velocity_limits = []
20 | self.__initialize_velocity_limits()
21 |
22 | # self.__name__ = self.arms[0].__name__
23 |
24 | def __initialize_subchain_indices(self):
25 | for i in range(self.numChains):
26 | self.subchain_indices.append([])
27 |
28 | for i in range(self.numChains):
29 | for j in self.full_joint_lists[i]:
30 | idx = self.__get_index_from_joint_order(j)
31 | if not idx == None:
32 | self.subchain_indices[i].append(idx)
33 |
34 | def __get_index_from_joint_order(self, jt_name):
35 | for j,joint in enumerate(self.joint_order):
36 | if jt_name == self.joint_order[j]:
37 | return j
38 |
39 | return None
40 | # raise Exception('Error in Robot Class. It appears your full_joint_lists and joint_order lists are not congruent '
41 | # 'The joint {} was not found in joint_order. Is there perhaps a misspelling?'.format(jt_name) )
42 |
43 | def __initialize_bounds(self):
44 | bounds = self.numDOF*[0.0]
45 |
46 | for i,a in enumerate(self.arms):
47 | sub_bounds = a.joint_limits
48 | for j,l in enumerate(sub_bounds):
49 | idx = self.subchain_indices[i][j]
50 | bounds[idx] = l
51 |
52 | self.bounds = bounds
53 |
54 | def __initialize_velocity_limits(self):
55 | velocity_limits = self.numDOF*[0.0]
56 |
57 | for i,a in enumerate(self.arms):
58 | sub_vl = a.velocity_limits
59 | for j,l in enumerate(sub_vl):
60 | idx = self.subchain_indices[i][j]
61 | velocity_limits[idx] = l
62 |
63 | self.velocity_limits = velocity_limits
64 |
65 | def split_state_into_subchains(self, x):
66 | subchains = []
67 |
68 | for i in xrange(self.numChains):
69 | subchain = []
70 |
71 | for s in self.subchain_indices[i]:
72 | subchain.append(x[s])
73 |
74 | subchains.append(subchain)
75 |
76 | return subchains
77 |
78 | def get_ee_positions(self, x):
79 | frames = self.getFrames(x)
80 | positions = []
81 |
82 | for f in frames:
83 | positions.append(f[0][-1])
84 |
85 | return positions
86 |
87 | def get_ee_rotations(self, x, quaternions=True):
88 | frames = self.getFrames(x)
89 | rotations = []
90 |
91 | for f in frames:
92 | if quaternions:
93 | rotations.append(quaternion_from_matrix(f[1][-1]))
94 | else:
95 | rotations.append(f[1][-1])
96 |
97 | return rotations
98 |
99 | def getFrames(self, x):
100 | all_frames = []
101 |
102 | chains = self.split_state_into_subchains(x)
103 |
104 | for i,c in enumerate(chains):
105 | frames = self.arms[i].getFrames(c)
106 | all_frames.append(frames)
107 |
108 | return all_frames
109 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/robot.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/robot.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/robot_function.py:
--------------------------------------------------------------------------------
1 | __author__ = 'gleicher'
2 |
3 | """
4 | A second attempt at a spacetime trajectory optimizer, this time possibly a little
5 | simple and not tied to FuncDesigner
6 |
7 | because we don't know how the automatic differentiation will work, we have to
8 | assume it is naive
9 |
10 | a robot is basically a function that takes a state vector and produces a list of
11 | 3D positions (points)
12 |
13 | the function produces ALL of the points on the robot - rather than the specific ones needed.
14 | this is because we don't know about caching, so we might as well compute everything once
15 | (no lazy evaluation)
16 |
17 | because I don't know what the best kinds of variables are to have, i am making this
18 | generic - it's not just for robot arms
19 |
20 | ideally the function eval is built in a manner that allows for the gradient function
21 | to be evaluated as well (by using AD objects or oovars)
22 | """
23 |
24 | import numpy as N
25 | from itertools import chain
26 |
27 | class RobotFunction:
28 | """
29 | Abstract class for making a robot. The actual base class doesn't do much.
30 | """
31 | def __init__(self, _nvars, _npoints, _name=""):
32 | self.npoints = _npoints
33 | self.nvars = _nvars
34 | self.__name__ = "Robot" if _name=="" else "Robot:%s" % _name
35 | self.varnames = ["v"] * self.nvars
36 | self.noZ = False
37 | self.cleanupCallback = None
38 | #CB - added for ptipopt (default bounds are +- Inf)
39 | #MG - infinite bounds are problematic - just pick a big number
40 | self.xUBounds = N.full(self.nvars,float(1000))
41 | self.xLBounds = N.full(self.nvars,float(-1000))
42 | # this used to be a method, but now let's make it a variable that can be adjusted
43 | self.default = N.zeros(self.nvars)
44 |
45 | def __call__(self, state):
46 | """
47 | allows the robot to be treated as a function:
48 | state -> list(points)
49 | :param state: a state vector (numpy array or list)
50 | :return: a list of points
51 | """
52 | raise NotImplementedError
53 |
54 | def getFrames(self,state):
55 | """
56 | just call call - but returns a two things - the points (like call) and the frames
57 | :param state:
58 | :return: a list of points and a list of 3x3 matrices (in global coords)
59 | """
60 | pts = self(state)
61 | eye = N.eye(3)
62 | return pts, [eye for i in range(len(pts))]
63 |
64 | def constraint(self, **kwargs):
65 | """
66 | returns the evaluation of 2 sets of constraint functions (eq, ineq)
67 | the first list should be eq 0
68 | the second list should be geq 0
69 | note: like the evaluation function, this should be able to take ad (or oovar)
70 | objects
71 | note that we take points - which is exactly self(state) - to have compatibility
72 | with the constraint functions
73 | :param state:
74 | :param points:
75 | :return: pair of lists of values
76 | """
77 | raise NotImplementedError
78 |
79 |
80 | ##################################################################################
81 | """
82 | Simplest possible test robot - a collection of 2D points
83 | Useful for testing various things
84 | """
85 | class Particle2DRobot(RobotFunction):
86 | def __init__(self, _npoints):
87 | RobotFunction.__init__(self, _nvars =_npoints * 2, _npoints=_npoints, _name="Particle2D")
88 | self.noZ = True
89 | self.varnames = list(chain.from_iterable([["x%d"%i,"y%d"%i] for i in range(self.npoints)]))
90 |
91 | def __call__(self, state):
92 | return [ (state[i*2], state[i*2+1], 0) for i in range(self.npoints) ]
93 |
94 | def constraint(self, **kwargs):
95 | return [],[]
96 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/robot_function.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Spacetime/robot_function.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/setup_cython.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup
2 | from Cython.Build import cythonize
3 |
4 | setup(
5 | ext_modules = cythonize("arm.pyx")
6 | )
--------------------------------------------------------------------------------
/src/RelaxedIK/Spacetime/tester.py:
--------------------------------------------------------------------------------
1 | import boost.Arm_ext as Arm_ext
2 | from arm import UR5, Mico, IIWA7, Hubo_R
3 | import numpy as np
4 | import time
5 |
6 | a = Hubo_R()
7 | axes = a.axes
8 |
9 | state = [0, 0.78852112, -0.14649155, -0.17695991, -1.86374666, -0.09144152, -0.46006443, -0.1494651]
10 |
11 |
12 | ac = Arm_ext.Arm(a.axes, a.displacements, a.rotOffsets, a.dispOffset, 'name')
13 |
14 | # print a.axes
15 |
16 | test_size = 10000
17 | # print a.dispOffset
18 |
19 | start = time.clock()
20 | for i in xrange(test_size):
21 | frames = a.getFrames(state)
22 | ee_pos = frames[0][-1]
23 | # print frames[0][0]
24 | end = time.clock()
25 |
26 | print (end - start) / test_size
27 |
28 | start = time.clock()
29 | for i in xrange(test_size):
30 | frames = ac.getFrames(state)
31 | ee_pos_c = frames[0][-1]
32 | # print frames[0][0]
33 | end = time.clock()
34 |
35 | print (end - start) / test_size
36 |
37 | print 'l1: ' + str(np.linalg.norm(ee_pos_c - ee_pos, ord=1))
38 | print 'l2: ' + str(np.linalg.norm(ee_pos_c - ee_pos))
39 | print 'linf: ' + str(np.linalg.norm(ee_pos_c - ee_pos, ord=np.inf))
40 |
41 |
42 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/_transformations.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/_transformations.so
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/collision_graph.py:
--------------------------------------------------------------------------------
1 | from collision_utils import Collision_Object_Container
2 | import numpy as np
3 | import itertools
4 | import math
5 |
6 |
7 | class Collision_Graph:
8 | def __init__(self, yaml_path, robot, link_exclusion_list = []):
9 | self.c = Collision_Object_Container(yaml_path)
10 | self.c.add_collision_objects_from_robot(robot, link_exclusion_list)
11 | self.robot = robot
12 | self.sample_states = self.c.sample_states
13 | self.num_objects = len(self.c.collision_objects)
14 | self.original_distances = 10000*np.ones((self.num_objects, self.num_objects))
15 | self.combinations = list(itertools.combinations(range(self.num_objects),r=2))
16 | self.b_value = 50
17 | self.collision_color_array = self.num_objects*[0]
18 |
19 | self.initialize_table()
20 | self.c_values = self.get_c_values(self.original_distances)
21 |
22 |
23 | def get_collision_score(self, frames):
24 | sum = 0.0
25 | self.c.update_all_transforms(frames)
26 | c_values = self.c_values
27 | self.collision_color_array = self.num_objects * [0]
28 | for i, pair in enumerate(self.combinations):
29 | l1 = pair[0]
30 | l2 = pair[1]
31 |
32 | dis = self.c.get_min_distance(pair)
33 | if dis == -1:
34 | dis = 0.0
35 | # print dis
36 |
37 | c = c_values[l1,l2]
38 | if not c == 0.0:
39 | val = self.b_value * (math.e ** ((-(dis) ** 4.0) / (2.0 * c ** 2)))
40 | if val > 5.0:
41 | self.c.collision_objects[l1].update_rviz_color(1.0,0,0,0.4)
42 | self.c.collision_objects[l2].update_rviz_color(1.0,0,0,0.4)
43 | self.collision_color_array[l1] = 2
44 | self.collision_color_array[l2] = 2
45 | elif val > 0.5 and val < 5.0:
46 | if not self.collision_color_array[l1] > 1:
47 | self.c.collision_objects[l1].update_rviz_color(1.0,1.0,0.0,0.4)
48 | self.collision_color_array[l1] = 1
49 | if not self.collision_color_array[l2] > 1:
50 | self.c.collision_objects[l2].update_rviz_color(1.0,1.0,0.0,0.4)
51 | self.collision_color_array[l2] = 1
52 | else:
53 | if not self.collision_color_array[l1] > 0:
54 | self.c.collision_objects[l1].update_rviz_color(0,1.0,0.7,0.4)
55 | if not self.collision_color_array[l2] > 0:
56 | self.c.collision_objects[l2].update_rviz_color(0,1.0,0.7,0.4)
57 |
58 | sum += val
59 |
60 | return sum
61 |
62 | def initialize_table(self):
63 | for s in self.sample_states:
64 | frames = self.robot.getFrames(s)
65 | self.c.update_all_transforms(frames)
66 | for pair in self.combinations:
67 | a = pair[0]
68 | b = pair[1]
69 | dis = self.c.get_min_distance(pair)
70 | if dis == -1:
71 | dis = 0.0
72 | if dis < self.original_distances[a,b]:
73 | self.original_distances[a, b] = dis
74 | self.original_distances[b, a] = dis
75 |
76 | def get_c_values(self, original_distances):
77 | shape = self.original_distances.shape
78 | c_values = np.zeros(shape)
79 | for i in xrange(shape[0]):
80 | for j in xrange(shape[1]):
81 | if original_distances[i,j] <= .001:
82 | c_values[i,j] = 0.0
83 | else:
84 | c_values[i,j] = self.get_c_value_from_dis(original_distances[i,j],self.b_value)
85 | return c_values
86 |
87 | def get_c_value_from_dis(self, dis, b, v=1.0e-15):
88 | return math.sqrt(-(dis) ** 4 / (2.0 * math.log(v / b)))
89 |
90 |
91 |
92 |
93 |
94 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/collision_graph.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/collision_graph.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/collision_utils.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/collision_utils.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/colors.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | __author__ = 'drakita'
4 |
5 | class bcolors:
6 | HEADER = '\033[95m'
7 | OKBLUE = '\033[94m'
8 | OKGREEN = '\033[92m'
9 | WARNING = '\033[93m'
10 | FAIL = '\033[91m'
11 | ENDC = '\033[0m'
12 | BOLD = '\033[1m'
13 | UNDERLINE = '\033[4m'
14 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/colors.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/colors.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/config_engine.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | from colors import bcolors
3 | from os import listdir
4 | from sklearn.externals import joblib
5 | from os.path import isfile, join
6 | from neural_net_trainer import Collision_NN_Trainer
7 | import os
8 |
9 |
10 | class Config_Engine:
11 | def __init__(self, collision_graph, vars, config_fn='', override=False):
12 | self.collision_graph = collision_graph
13 | self.config_fn = config_fn
14 | self.vars = vars
15 | dirname = os.path.dirname(__file__)
16 | self.path = os.path.join(dirname, '../Config/')
17 |
18 | if override:
19 | self.robot_name, self.collision_nn, self.init_state, self.full_joint_lists, self.fixed_ee_joints, \
20 | self.joint_order, self.urdf_path, self.collision_file = self.generate_config_file()
21 | else:
22 | config_file = self.check_for_config_file()
23 | if config_file == None:
24 | self.robot_name, self.collision_nn, self.init_state, self.full_joint_lists, self.fixed_ee_joints, \
25 | self.joint_order, self.urdf_path, self.collision_file = self.generate_config_file()
26 |
27 | else:
28 | self.config_data = joblib.load(self.path + config_file)
29 | self.robot_name = self.config_data[0]
30 | self.collision_nn = self.config_data[1]
31 | self.init_state = self.config_data[2]
32 | self.full_joint_lists = self.config_data[3]
33 | self.fixed_ee_joints = self.config_data[4]
34 | self.joint_order = self.config_data[5]
35 | self.urdf_path = self.config_data[6]
36 | self.collision_file = self.config_data[7]
37 |
38 | def check_for_config_file(self):
39 | files = [f for f in listdir(self.path) if isfile(join(self.path, f))]
40 | if self.config_fn in files:
41 | return self.config_fn
42 |
43 | elif 'relaxedIK.config' in files:
44 | return 'relaxedIK.config'
45 |
46 | for f in files:
47 | f_arr = f.split('.')
48 | ext = f_arr[-1]
49 | if ext == 'config':
50 | response = raw_input(bcolors.OKGREEN + 'Found saved config file ' + f + '. Would you like to use this config file? (y or n): ' + bcolors.ENDC)
51 | if response == 'y':
52 | return f
53 | else:
54 | response = raw_input(bcolors.OKGREEN + 'Would you like to generate a new config file? (y or n): ' + bcolors.ENDC)
55 | if response == 'y':
56 | return None
57 | else:
58 | print bcolors.FAIL + 'Exiting. Please manually specify which config file you would like to use on the next run.' + bcolors.ENDC
59 | exit(1)
60 |
61 | response = raw_input(bcolors.OKBLUE + 'Config file not found, generating a new one! This will take some time. Continue? (y or n): ' + bcolors.ENDC)
62 | if response == 'y':
63 | return None
64 | else:
65 | exit(1)
66 |
67 | def generate_config_file(self):
68 | trainer = Collision_NN_Trainer(self.collision_graph)
69 | collision_nn = trainer.clf
70 | # robot_name = trainer.robot.__name__
71 | robot_name = 'robot'
72 |
73 | file_vars = [robot_name, collision_nn, self.vars.init_state, self.vars.full_joint_lists, self.vars.fixed_ee_joints, \
74 | self.vars.joint_order, self.vars.urdf_path, self.vars.collision_file]
75 |
76 | joblib.dump(file_vars,self.path + 'relaxedIK.config')
77 |
78 | return robot_name, collision_nn, self.vars.init_state, self.vars.full_joint_lists, self.vars.fixed_ee_joints, \
79 | self.vars.joint_order, self.vars.urdf_path, self.vars.collision_file
80 |
81 | if __name__ == '__main__':
82 | ce = Config_Engine()
83 | print ce.check_for_config_file()
84 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/config_engine.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/config_engine.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/filter.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 |
3 | class EMA_filter:
4 | def __init__(self, init_state, a = 0.6, window_size = 25):
5 | if a > 1.0 or a < 0.0:
6 | raise Exception('a must be between 0 and 1 in EMA_filter')
7 |
8 | self.a = a
9 | self.window_size = window_size
10 | self.filtered_signal = []
11 | for i in xrange(window_size):
12 | self.filtered_signal.append(np.array(init_state))
13 |
14 | def filter(self, state):
15 | state_arr = np.array(state)
16 |
17 | weights = self.window_size*[0]
18 | filtered_state = np.zeros((len(state)))
19 |
20 | sum = 0.0
21 | for i in xrange(self.window_size):
22 | weights[i] = self.a*(1.0 - self.a)**(i)
23 | if i == 0:
24 | filtered_state = weights[i]*state_arr
25 | else:
26 | try:
27 | filtered_state = filtered_state + weights[i]*self.filtered_signal[-i]
28 | except:
29 | return state
30 |
31 | sum += weights[i]
32 |
33 | self.filtered_signal.append(filtered_state)
34 | return filtered_state
35 |
36 |
37 | if __name__ == '__main__':
38 | ema = EMA_filter([1,2,3])
39 | for i in range(20):
40 | print ema.filter([4,5,6])
41 |
42 |
43 |
44 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/geometry_utils.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | import math
3 |
4 | def closest_point_on_2_lines(u1,u2,v1,v2):
5 | u1_arr = np.array(u1)
6 | u2_arr = np.array(u2)
7 | v1_arr = np.array(v1)
8 | v2_arr = np.array(v2)
9 |
10 | u = u2_arr - u1_arr
11 | v = v2_arr - v1_arr
12 | rho = v1_arr - u1_arr
13 | uv = np.dot(u,v)
14 | uu = np.dot(u,u)
15 | vv = np.dot(v,v)
16 | urho = np.dot(u,rho)
17 | vrho = np.dot(v,rho)
18 | try:
19 | vt = (vrho*uu - urho*uv) / (uv*uv - vv*uu)
20 | ut = (uv * vt + urho) / uu
21 | except: pass
22 |
23 | if math.isnan(vt) or math.isinf(vt): vt = 0.0
24 | if math.isnan(ut) or math.isinf(ut): ut = 0.0
25 |
26 | ut = np.max(np.array([0.0, ut]))
27 | ut = np.min(np.array([1.0, ut]))
28 | vt = np.max(np.array([0.0, vt]))
29 | vt = np.min(np.array([1.0, vt]))
30 |
31 | return ut, vt, u1_arr + ut*(u2_arr - u1_arr), v1_arr + vt*(v2_arr - v1_arr)
32 |
33 | def dis_between_line_segments( u1,u2,v1,v2 ):
34 | ut,vt,p1,p2 = closest_point_on_2_lines( u1,u2,v1,v2 )
35 | return np.linalg.norm(p1-p2)
36 |
37 | def pt_dis_to_line_seg(pt,a,b):
38 | u = np.dot(pt-a, b-a) / max(np.linalg.norm(a-b)**2, 0.000000001)
39 | u = np.min(np.array( [np.max( np.array([u,0]) ) ,1] ))
40 | p = a + u*(b - a)
41 | dis = np.linalg.norm(p - pt)
42 | return p, u, dis
43 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/geometry_utils.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/geometry_utils.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/ik_task.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 |
3 | from abc import ABCMeta, abstractmethod
4 | import math
5 | from ..Utils import transformations as T
6 | import tf.broadcaster
7 | import rospy
8 | from visualization_msgs.msg import Marker
9 | from geometry_msgs.msg import PoseStamped
10 |
11 | keyboard_pos_goal = [0,0,0]
12 | keyboard_quat_goal = [1,0,0,0]
13 | def keyboard_goal_cb(data):
14 | global keyboard_pos_goal, keyboard_quat_goal
15 | keyboard_pos_goal[0] = data.pose.position.x
16 | keyboard_pos_goal[1] = data.pose.position.y
17 | keyboard_pos_goal[2] = data.pose.position.z
18 | keyboard_quat_goal[0] = data.pose.orientation.w
19 | keyboard_quat_goal[1] = data.pose.orientation.x
20 | keyboard_quat_goal[2] = data.pose.orientation.y
21 | keyboard_quat_goal[3] = data.pose.orientation.z
22 |
23 |
24 | class IK_Task:
25 | @abstractmethod
26 | def __init__(self, *args): pass
27 |
28 | @abstractmethod
29 | def name(self): pass
30 |
31 | @abstractmethod
32 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None): return None
33 |
34 | ########################################################################################################################
35 |
36 | tf_broadcaster = tf.broadcaster.TransformBroadcaster()
37 | marker_pub = rospy.Publisher('visualization_marker',Marker,queue_size=10)
38 | def display_ik_goal(pos_goal, quat_goal):
39 | global tf_broadcaster, marker_pub
40 | quat_mat = T.quaternion_matrix(quat_goal)
41 | quat_goal = T.quaternion_from_matrix(quat_mat)
42 | tf_broadcaster.sendTransform(tuple(pos_goal), (quat_goal[1],quat_goal[2],quat_goal[3],quat_goal[0]), rospy.Time.now(), 'ik_goal', 'common_world')
43 | marker = Marker()
44 | marker.header.frame_id = 'common_world'
45 | marker.id = 100
46 | marker.type = marker.SPHERE
47 | marker.action = marker.ADD
48 | marker.pose.position.x = pos_goal[0]
49 | marker.pose.position.y = pos_goal[1]
50 | marker.pose.position.z = pos_goal[2]
51 | marker.scale.x = .05
52 | marker.scale.y = .05
53 | marker.scale.z = .05
54 | marker.color.a = 1
55 | marker.color.r = 0.0
56 | marker.color.g = 0.9
57 | marker.color.b = 0.2
58 | marker_pub.publish(marker)
59 |
60 | def translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos):
61 | p = np.array(pos_goal)
62 | o = np.array(orig_ee_pos)
63 | vec = (o + scale_factor*p)
64 | return vec
65 |
66 | def get_relative_orientation(quat_goal, orig_ee_quat):
67 | return T.quaternion_multiply(quat_goal, orig_ee_quat)
68 |
69 | class Keyboard_input(IK_Task):
70 | def __init__(self):
71 | rospy.Subscriber('keyboard_ik_goal',PoseStamped,keyboard_goal_cb)
72 | def name(self): return 'keyboardInput'
73 | def type(self): return 'keyboardInput'
74 |
75 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
76 | global keyboard_pos_goal, keyboard_quat_goal
77 | if orig_ee_pos.all() == None:
78 | orig_ee_pos = [0,0,0]
79 |
80 |
81 | pos_goal = keyboard_pos_goal
82 | quat_goal = keyboard_quat_goal
83 |
84 | if not task_recorder == None:
85 | task_recorder.add_line(time, pos_goal, quat_goal)
86 |
87 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
88 |
89 |
90 | if not orig_ee_quat == None:
91 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
92 |
93 | if display_goal:
94 | display_ik_goal(pos_goal, quat_goal)
95 |
96 | return pos_goal, quat_goal
97 |
98 | class File_input(IK_Task):
99 | def __init__(self, file_name, loop=False):
100 | root = '/home/rakita/catkin_ws/src/relaxed_ik_rss/bin/FileIO/task_recordings/'
101 | fp = root + file_name
102 | self.file = open(fp, 'r')
103 | self.file_name = file_name
104 | self.times = []
105 | self.ik_pos_goals = []
106 | self.ik_quat_goals = []
107 | self.loop = loop
108 | self.task_name = self.file_name
109 |
110 | line = self.file.readline()
111 | while not line == '':
112 | line_arr = line.split(';')
113 | self.times.append(float(line_arr[0]))
114 | ik_pos_goal = [float(f) for f in line_arr[1].split(',')]
115 | self.ik_pos_goals.append(ik_pos_goal)
116 | ik_quat_goal = [float(f) for f in line_arr[2].split(',')]
117 | self.ik_quat_goals.append(ik_quat_goal)
118 |
119 | line = self.file.readline()
120 |
121 | self.num_goals = len(self.ik_pos_goals)
122 | self.idx = 0
123 |
124 | def name(self): return self.task_name
125 | def type(self): return 'fileInput'
126 |
127 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
128 | if orig_ee_pos == None:
129 | orig_ee_pos = [0,0,0]
130 |
131 | if self.idx >= self.num_goals:
132 | if self.loop == True:
133 | self.idx = 0
134 | else:
135 | return None, None
136 |
137 | pos_goal = self.ik_pos_goals[self.idx]
138 | quat_goal = self.ik_quat_goals[self.idx]
139 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
140 |
141 | if not orig_ee_quat == None:
142 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
143 |
144 | if display_goal:
145 | display_ik_goal(pos_goal, quat_goal)
146 |
147 | self.idx += 1
148 |
149 | return pos_goal, quat_goal
150 |
151 |
152 |
153 | class Test_Task1(IK_Task):
154 | def __init__(self, max_time):
155 | self.max_time = max_time
156 | def name(self): return 'testTask1'
157 |
158 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
159 | if orig_ee_pos == None:
160 | orig_ee_pos = [0,0,0]
161 | pos_goal = [0.0,0.2*math.sin(time),0.3*math.sin(time)]
162 | quat_goal = [1, 0, 0, 0]
163 | task_recorder.add_line(time, pos_goal, quat_goal)
164 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
165 |
166 | if not orig_ee_quat == None:
167 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
168 |
169 | if display_goal:
170 | display_ik_goal(pos_goal, quat_goal)
171 |
172 | return pos_goal, quat_goal
173 |
174 | class Test_SelfCollision(IK_Task):
175 | def __init__(self, max_time):
176 | self.max_time = max_time
177 | def name(self): return 'testSelfCollision'
178 |
179 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
180 | if orig_ee_pos == None:
181 | orig_ee_pos = [0,0,0]
182 | pos_goal = [min(math.sin(time),0.0) ,0.1,-.5]
183 | quat_goal = [1,0,0,0]
184 |
185 | task_recorder.add_line(time, pos_goal, quat_goal)
186 |
187 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
188 |
189 | if not orig_ee_quat == None:
190 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
191 |
192 | if display_goal:
193 | display_ik_goal(pos_goal, quat_goal)
194 |
195 | return pos_goal, quat_goal
196 |
197 | class Up_and_down(IK_Task):
198 | def __init__(self, max_time):
199 | self.max_time = max_time
200 | def name(self): return 'UpAndDown'
201 |
202 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
203 | if orig_ee_pos == None:
204 | orig_ee_pos = [0,0,0]
205 | pos_goal = [0.0,0.0, .5*math.sin(time)]
206 | quat_goal = [1,0,0,0]
207 |
208 | task_recorder.add_line(time, pos_goal, quat_goal)
209 |
210 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
211 |
212 | if not orig_ee_quat == None:
213 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
214 |
215 | if display_goal:
216 | display_ik_goal(pos_goal, quat_goal)
217 |
218 | return pos_goal, quat_goal
219 |
220 | class Test_Task_Reactor(IK_Task):
221 | def __init__(self, max_time):
222 | self.max_time = max_time
223 | def name(self): return 'testTaskReactor'
224 |
225 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
226 | if orig_ee_pos == None:
227 | orig_ee_pos = [0,0,0]
228 | pos_goal = [0.1*math.sin(time),0.0,0.05*math.sin(time)]
229 | quat_goal = [1,0,0,0]
230 |
231 | task_recorder.add_line(time, pos_goal, quat_goal)
232 |
233 | pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
234 |
235 | if not orig_ee_quat == None:
236 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
237 |
238 | if display_goal:
239 | display_ik_goal(pos_goal, quat_goal)
240 |
241 | return pos_goal, quat_goal
242 |
243 | class Static_test(IK_Task):
244 | def __init__(self, max_time):
245 | self.max_time = max_time
246 | def name(self): return 'static'
247 |
248 | def get_goal(self, time, task_recorder, display_goal=True, scale_factor=1.0, orig_ee_pos=None, orig_ee_quat=None):
249 | if orig_ee_pos == None:
250 | orig_ee_pos = [0,0,0]
251 | pos_goal = [0,0,0]
252 | # pos_goal = translate_and_scale_pos_goal(pos_goal, scale_factor, orig_ee_pos)
253 | quat_goal = [1,0,0,0]
254 |
255 | task_recorder.add_line(time, pos_goal, quat_goal)
256 |
257 | if not orig_ee_quat == None:
258 | quat_goal = get_relative_orientation(quat_goal, orig_ee_quat)
259 |
260 | if display_goal:
261 | display_ik_goal(pos_goal, quat_goal)
262 |
263 | return pos_goal, quat_goal
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/ik_task.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/ik_task.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/joint_utils.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | from numba import jit
3 |
4 | def interpolate_to_joint_limits(from_q, to_q, t=0.1, numDOF=6, joint_limits=None):
5 | '''
6 | interpolates from state from_q to sate to_q going as fast as the joints can in time t
7 | :param from_q:
8 | :param to_q:
9 | :param time:
10 | :param joint_limits:
11 | :return:
12 | '''
13 | ret_q = []
14 | ret_k = []
15 |
16 | if joint_limits == None:
17 | limits = numDOF*[6.0]
18 | else:
19 | limits = joint_limits
20 |
21 | for i in xrange(numDOF):
22 | disp = to_q[i] - from_q[i]
23 | disp_norm = abs(disp)
24 |
25 | # how far can joint go in the amount of time?
26 | max_disp = limits[i]*t
27 |
28 | if disp_norm > max_disp:
29 | k = max_disp/disp_norm
30 | else:
31 | k = 1.0
32 |
33 | ret_k.append(k)
34 | interp = from_q[i] + k*(disp)
35 | ret_q.append(interp)
36 |
37 | return ret_q, ret_k
38 |
39 | def check_legal_velocity(from_q, to_q, t=0.1, numDOF=6, joint_limits=None):
40 | q,k = interpolate_to_joint_limits(from_q,to_q,t,numDOF,joint_limits)
41 | if not k == numDOF*[1.0]:
42 | return False
43 | else:
44 | return True
45 |
46 | if __name__ == '__main__':
47 | q,k= interpolate_to_joint_limits([-.1,.3,0],[-.2,.3,.1],numDOF=3, joint_limits=[3.15,6.0,3.15])
48 | print check_legal_velocity([-.1,.3,0],[-.1,.4,.07],numDOF=3, t=0.02,joint_limits=[3.15,6.0,3.15])
49 |
50 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/joint_utils.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/joint_utils.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/neural_net_trainer.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | from collision_graph import Collision_Graph
3 | from sklearn.neural_network import MLPClassifier, MLPRegressor
4 | from sklearn.externals import joblib
5 | import pickle
6 |
7 | import time
8 | import numpy.random as r
9 |
10 | def frames_to_jt_pt_vec(all_frames):
11 | out_vec = []
12 | for frames in all_frames:
13 | jt_pts = frames[0]
14 | for j in jt_pts:
15 | out_vec.append(j[0])
16 | out_vec.append(j[1])
17 | out_vec.append(j[2])
18 |
19 | return out_vec
20 |
21 | def rand_vec(bounds):
22 | vec = []
23 | for b in bounds:
24 | b1 = b[0]
25 | b2 = b[1]
26 | rand = r.uniform(low=b1, high=b2, size=(1))[0]
27 | vec.append(rand)
28 |
29 | return np.array(vec)
30 |
31 | class Collision_NN_Trainer:
32 | def __init__(self, collision_graph, num_samples=300000):
33 | self.num_samples = num_samples
34 | self.cg = collision_graph
35 | self.inputs = []
36 | self.outputs = []
37 | self.robot = self.cg.robot
38 | self.bounds = self.cg.robot.bounds
39 |
40 | for i in xrange(num_samples):
41 | rvec = rand_vec(self.bounds)
42 | frames = self.robot.getFrames(rvec)
43 | score = self.cg.get_collision_score(frames)
44 | input = frames_to_jt_pt_vec(frames)
45 | self.inputs.append(input)
46 | self.outputs.append(score)
47 | print str(i) + ' of ' + str(num_samples) + ' samples' + ': ' + str(score)
48 |
49 |
50 |
51 | self.clf = MLPRegressor(solver='adam', alpha=1,
52 | hidden_layer_sizes=(70, 70, 70, 70, 70, 70), max_iter=300000, verbose=True,
53 | learning_rate='adaptive')
54 |
55 | self.clf.fit(self.inputs, self.outputs)
56 |
57 |
58 | self.output_comparisons()
59 |
60 | def output_comparisons(self, num_samples=100):
61 | print 'output comparisons...'
62 | for i in xrange(num_samples):
63 | rand = rand_vec(self.robot.bounds)
64 | frames = self.robot.getFrames(rand)
65 | jt_pt_vec = frames_to_jt_pt_vec(frames)
66 | predicted = self.clf.predict([jt_pt_vec])
67 | print predicted
68 | print self.cg.get_collision_score(frames)
69 | print
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/neural_net_trainer.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/neural_net_trainer.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/tf_fast.py:
--------------------------------------------------------------------------------
1 | import math
2 | import numpy
3 | from _transformations import *
4 |
5 | # added by Danny Rakita
6 | def quaternion_log(quaternion):
7 | """
8 | Returns the log map vec3 of quaternion
9 |
10 | quaternion list is [w x y z]
11 | :param quaternion:
12 | :return:
13 | """
14 | v = numpy.array([quaternion[1], quaternion[2], quaternion[3]])
15 | if abs(quaternion[0] < 1.0):
16 | a = 1
17 | try:
18 | a = math.acos(quaternion[0])
19 | except: pass
20 | sina = math.sin(a)
21 | if abs(sina >= 0.005):
22 | c = a/sina
23 | v[0] *= c
24 | v[1] *= c
25 | v[2] *= c
26 |
27 | return v
28 |
29 |
30 | # added by Danny Rakita
31 | def quaternion_exp(vec3):
32 | """
33 | Returns the exponentiated quaternion from rotation vector vec3
34 | :param vec3:
35 | :return: quaternion in format [w x y z]
36 | """
37 | q = numpy.array([1.0, vec3[0], vec3[1], vec3[2]])
38 | a = numpy.linalg.norm(q)
39 | sina = math.sin(a)
40 | if abs(sina) >= 0.005:
41 | c = sina/a
42 | q[1] *= c
43 | q[2] *= c
44 | q[3] *= c
45 |
46 | q[0] = math.cos(a)
47 |
48 | return q
49 |
50 | # added by Danny Rakita
51 | def quaternion_disp(q, qPrime):
52 | """
53 | finds rotation vector displacement between two quaternions (from q1 to q2)
54 | :param q1: input quaternions in form [w x y z]
55 | :param q2:
56 | :return:
57 | """
58 | inv = quaternion_inverse(q)
59 | m = quaternion_multiply(inv, qPrime)
60 | return quaternion_log(m)
61 |
62 | def quaternion_dispQ(q,qPrime):
63 | inv = quaternion_inverse(q)
64 | return quaternion_multiply(inv, qPrime)
65 |
66 |
67 | if __name__ == '__main__':
68 | q1 = random_quaternion()
69 | q2 = random_quaternion()
70 | print quaternion_disp(q1,q2)
71 |
72 |
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/tf_fast.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/tf_fast.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/transformations.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/transformations.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/urdf_load.py:
--------------------------------------------------------------------------------
1 | __author__ = 'drakita'
2 |
3 |
4 | from urdf_parser_py.urdf import URDF
5 | from ..Spacetime.arm import *
6 |
7 |
8 | # try:
9 | # from ..Spacetime.boost import Arm_ext
10 | # except:
11 | # print 'ERROR when importing boost library extension. Defaulting to python implementation (which will be slower). ' \
12 | # 'To get speed boost, please install and configure the boost python library: ' \
13 | # 'https://www.boost.org/doc/libs/1_67_0/more/getting_started/unix-variants.html'
14 | # arm_c = False
15 |
16 | from colors import *
17 | import kdl_parser_py.urdf as pyurdf
18 | import PyKDL as kdl
19 |
20 | '''
21 | NOTE:
22 | These functions require kdl_parser_py and urdf_parser_py to be installed
23 |
24 | commands to install these:
25 | >> sudo apt-get install ros-[your ros distro]-urdfdom-py
26 |
27 | >> sudo apt-get install ros-[your ros distro]-kdl-parser-py
28 | >> sudo apt-get install ros-[your ros distro]-kdl-conversions
29 |
30 | '''
31 |
32 |
33 | def urdf_load(urdfString, startJoint, endJoint, full_joint_list, fixed_ee_joint = None, Debug=False):
34 | '''
35 | Takes in a urdf file and parses that into different object representations of the robot arm
36 |
37 | :param urdfString: (string) file path to the urdf file. example: < 'mico.urdf' >
38 | :param startJoint: (string) name of the starting joint in the chain
39 | :param endJoint: (string) name of the final joint in the chain
40 | NOTE: this is the final ROTATING joint in the chain, for a fixed joint on the end effector, add this as the fixed joint!
41 | :param fixed_ee_joint (string) name of the fixed joint after end joint in the chain. This is read in just to get a final
42 | displacement on the chain, i.e. usually just to add in an extra displacement offset for the end effector
43 | :return: returns the robot parsed object from urdf_parser, Mike's "arm" version of the robot arm, as well as the kdl tree
44 | '''
45 |
46 | if urdfString == '':
47 | urdf_robot = URDF.from_parameter_server()
48 | (ok, kdl_tree) = pyurdf.treeFromParam('/robot_description')
49 | else:
50 | urdf_robot = URDF.from_xml_file(urdfString)
51 | (ok, kdl_tree) = pyurdf.treeFromFile(urdfString)
52 |
53 | if not (startJoint == '' or endJoint == ''):
54 | chain = kdl_tree.getChain(startJoint, endJoint)
55 | if full_joint_list == ():
56 | arm, arm_c = convertToArm(urdf_robot, startJoint, endJoint, fixed_ee_joint, Debug=Debug)
57 | else:
58 | arm, arm_c = convertToArmJointList(urdf_robot, full_joint_list, fixed_ee_joint, Debug=Debug)
59 |
60 | if Debug:
61 | o = open('out', 'w')
62 | o.write(str(urdf_robot))
63 |
64 | return urdf_robot, arm, arm_c, kdl_tree
65 |
66 | def convertToArmJointList(urdf_robot, full_joint_list, fixedJoint, Debug=False):
67 | if urdf_robot == None:
68 | raise ValueError('Incorrect Argument in convertToArm. urdf_robot is None type.')
69 |
70 | joints = urdf_robot.joints
71 |
72 | name = urdf_robot.name
73 | axes = []
74 | offset = []
75 | displacements = []
76 | rotOffsets = []
77 | joint_limits = []
78 | velocity_limits = []
79 | joint_types = []
80 | firstPass = True
81 |
82 | for j in full_joint_list:
83 | for js in joints:
84 | if js.name == j:
85 | if firstPass:
86 | joint_types.append(js.type)
87 | offset = tuple(js.origin.xyz)
88 | rotOffsets.append(tuple(js.origin.rpy))
89 | if not js.type == 'fixed':
90 | axes.append(toAxisLetter(js.axis))
91 | joint_limits.append((js.limit.lower, js.limit.upper))
92 | velocity_limits.append(js.limit.velocity)
93 | firstPass = False
94 | else:
95 | joint_types.append(js.type)
96 | displacements.append(tuple(js.origin.xyz))
97 | rotOffsets.append(tuple(js.origin.rpy))
98 | if not js.type == 'fixed':
99 | axes.append(toAxisLetter(js.axis))
100 | joint_limits.append((js.limit.lower, js.limit.upper))
101 | velocity_limits.append(js.limit.velocity)
102 |
103 |
104 | # add any additional joints in the chain listed after the end joint
105 | if not fixedJoint == None:
106 | currJoint = []
107 | for j in joints:
108 | if j.name == fixedJoint:
109 | currJoint = j
110 | displacements.append(tuple(currJoint.origin.xyz))
111 | if currJoint == []:
112 | print bcolors.FAIL + 'fixed_ee_joint: {} not found!'.format(fixedJoint) + bcolors.ENDC
113 | raise Exception('Invalid fixed_ee_joint. Exiting.')
114 |
115 |
116 | numDOF = len(axes)
117 | # rotOffsets = rotOffsets[0:numDOF]
118 |
119 | if Debug:
120 | outStr = 'name:\n {} \n axes:\n {} \n displacements:\n {} \n ' \
121 | 'rotOffsets:\n {} \n offset:\n {} offset'.format(name, tuple(axes), displacements, rotOffsets, offset)
122 |
123 | print outStr
124 |
125 | # if not arm_c:
126 | # arm = Arm(tuple(axes), displacements, rotOffsets, offset, name)
127 | # else:
128 | # arm = Arm_ext.Arm(list(axes), displacements, rotOffsets, offset, name)
129 | # arm.velocity_limits = velocity_limits
130 | # arm.joint_limits = joint_limits
131 |
132 |
133 | arm = Arm(tuple(axes), displacements, rotOffsets, offset, name)
134 | # arm_c = Arm_ext.Arm(list(axes), displacements, rotOffsets, offset, name)
135 | arm_c = None
136 | arm.velocity_limits = velocity_limits
137 | arm.joint_limits = joint_limits
138 | arm.joint_types = joint_types
139 | # arm_c.velocity_limits = velocity_limits
140 | # arm_c.joint_limits = joint_limits
141 | return arm, arm_c
142 |
143 |
144 | def convertToArm(urdf_robot, startJoint, endJoint, fixedJoint, Debug=False):
145 | '''
146 | This function parses the (axes, offset, displacements, rotOffsets) in order to return an Arm
147 | from mg's spacetime code
148 |
149 | :param urdf_robot: urdf_robot object returned from URDF.from_xml_file
150 | :param startJoint: start joint string, e.g. <'shoulder_pan_joint'> for UR5
151 | :param endJoint: end joint string, e.g. <'ee_fixed_joint'> for UR5
152 | :return: Arm object
153 | '''
154 |
155 | if urdf_robot == None:
156 | raise ValueError('Incorrect Argument in convertToArm. urdf_robot is None type.')
157 |
158 | joints = urdf_robot.joints
159 |
160 | s = []
161 | e = []
162 | for j in joints:
163 | if j.name == startJoint:
164 | s = j
165 | if j.name == endJoint:
166 | e = j
167 | if s == []:
168 | print bcolors.FAIL + 'startJoint: {} not found in joint list! Please check to make sure startJoint is a joint found in' \
169 | 'the URDF and is spelled correctly'.format(startJoint) + bcolors.ENDC
170 | raise ValueError('Invalid Value. Exiting.')
171 | if e == []:
172 | print bcolors.FAIL + 'endJoint: {} not found in joint list! Please check to make sure endJoint is a joint found in' \
173 | 'the URDF and is spelled correctly'.format(endJoint).format(startJoint) + bcolors.ENDC
174 | raise ValueError('Invalid Value. Exiting.')
175 |
176 | name = urdf_robot.name
177 | axes = []
178 | displacements = []
179 | rotOffsets = []
180 | joint_limits = []
181 | velocity_limits = []
182 |
183 | currJoint = s
184 | axes.append(toAxisLetter(currJoint.axis))
185 | offset = tuple(currJoint.origin.xyz)
186 | rotOffsets.append(tuple(currJoint.origin.rpy))
187 | joint_limits.append((currJoint.limit.lower, currJoint.limit.upper))
188 | velocity_limits.append(currJoint.limit.velocity)
189 |
190 | currJoint = findNextJoint(joints, currJoint.child)
191 |
192 | while True:
193 | axes.append(toAxisLetter(currJoint.axis))
194 | displacements.append(tuple(currJoint.origin.xyz))
195 | rotOffsets.append(tuple(currJoint.origin.rpy))
196 | joint_limits.append((currJoint.limit.lower, currJoint.limit.upper))
197 | velocity_limits.append(currJoint.limit.velocity)
198 | if currJoint.name == endJoint:
199 | break
200 | currJoint = findNextJoint(joints, currJoint.child)
201 |
202 | # add any additional joints in the chain listed after the end joint
203 | if not fixedJoint == None:
204 | currJoint = []
205 | for j in joints:
206 | if j.name == fixedJoint:
207 | currJoint = j
208 | displacements.append(tuple(currJoint.origin.xyz))
209 | if currJoint == []:
210 | print bcolors.FAIL + 'fixed_ee_joint: {} not found!'.format(fixedJoint) + bcolors.ENDC
211 | raise Exception('Invalid fixed_ee_joint. Exiting.')
212 |
213 | numDOF = len(axes)
214 | rotOffsets = rotOffsets[0:numDOF]
215 |
216 | if Debug:
217 | outStr = 'name:\n {} \n axes:\n {} \n displacements:\n {} \n ' \
218 | 'rotOffsets:\n {} \n offset:\n {} offset'.format(name, tuple(axes), displacements, rotOffsets, offset)
219 |
220 | print outStr
221 |
222 |
223 | arm = Arm(tuple(axes), displacements, rotOffsets, offset, name)
224 | # arm_c = Arm_ext.Arm(list(axes), displacements, rotOffsets, offset, name)
225 | arm_c = None
226 | arm.velocity_limits = velocity_limits
227 | arm.joint_limits = joint_limits
228 | # arm_c.velocity_limits = velocity_limits
229 | # arm_c.joint_limits = joint_limits
230 | return arm, arm_c
231 |
232 | def toAxisLetter(ax):
233 | if ax == None:
234 | return ''
235 | ax_val = ''
236 | if ax[0] == 1:
237 | ax_val = 'x'
238 | elif ax[0] == -1:
239 | ax_val = '-x'
240 | elif ax[1] == 1:
241 | ax_val = 'y'
242 | elif ax[1] == -1:
243 | ax_val = '-y'
244 | elif ax[2] == 1:
245 | ax_val = 'z'
246 | elif ax[2] == -1:
247 | ax_val = '-z'
248 | return ax_val
249 |
250 | def findNextJoint(joints, child):
251 | for j in joints:
252 | if j.parent == child:
253 | return j
254 | print bcolors.FAIL + 'joint with matching parent link: {} not found!'.format(child) + bcolors.ENDC
255 | raise Exception('Invalid joint chain. Exiting.')
--------------------------------------------------------------------------------
/src/RelaxedIK/Utils/urdf_load.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/Utils/urdf_load.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/__init__.py:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/__init__.py
--------------------------------------------------------------------------------
/src/RelaxedIK/__init__.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/__init__.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/relaxedIK.py:
--------------------------------------------------------------------------------
1 | from GROOVE.groove import get_groove
2 | import Utils.transformations as T
3 | import math as M
4 | import numpy as np
5 | import numpy.random as r
6 | from RelaxedIK.Utils.filter import EMA_filter
7 |
8 | def rand_vec(bounds):
9 | vec = []
10 | for b in bounds:
11 | b1 = b[0]
12 | b2 = b[1]
13 | rand = r.uniform(low=b1, high=b2, size=(1))[0]
14 | vec.append(rand)
15 |
16 | return vec
17 |
18 |
19 | class RelaxedIK(object):
20 | def __init__(self, vars, optimization_package='scipy', solver_name='slsqp'):
21 | self.vars = vars
22 | self.optimization_package = optimization_package
23 | self.solver_name = solver_name
24 | self.groove = get_groove(vars, optimization_package,solver_name)
25 | self.filter = EMA_filter(self.vars.init_state,a=0.5)
26 |
27 |
28 | @classmethod
29 | def init_from_config(self, config_name):
30 | import os
31 | from sklearn.externals import joblib
32 | from RelaxedIK.GROOVE_RelaxedIK.relaxedIK_vars import RelaxedIK_vars
33 | dirname = os.path.dirname(__file__)
34 | path = os.path.join(dirname, 'Config/{}'.format(config_name))
35 | file = open(path,'r')
36 | self.config_data = joblib.load(file)
37 |
38 | self.robot_name = self.config_data[0]
39 | self.collision_nn = self.config_data[1]
40 | self.init_state = self.config_data[2]
41 | self.full_joint_lists = self.config_data[3]
42 | self.fixed_ee_joints = self.config_data[4]
43 | self.joint_order = self.config_data[5]
44 | self.urdf_path = self.config_data[6]
45 | self.collision_file = self.config_data[7]
46 |
47 | vars = RelaxedIK_vars(self.robot_name,self.urdf_path,self.full_joint_lists,self.fixed_ee_joints,self.joint_order,
48 | config_file_name=config_name, collision_file=self.collision_file,init_state=self.init_state)
49 | return RelaxedIK(vars)
50 |
51 |
52 | def solve(self, goal_positions, goal_quats, prev_state=None, vel_objectives_on=True, unconstrained=True, verbose_output=False, max_iter=11, maxtime=.05, rand_start=False):
53 |
54 | if self.vars.rotation_mode == 'relative':
55 | self.vars.goal_quats = []
56 | for i, q in enumerate(goal_quats):
57 | self.vars.goal_quats.append(T.quaternion_multiply(q, self.vars.init_ee_quats[i]))
58 | elif self.vars.rotation_mode == 'absolute':
59 | self.vars.goal_quats = []
60 | for i, q in enumerate(goal_quats):
61 | self.vars.goal_quats.append(q)
62 |
63 | self.vars.vel_objectives_on = vel_objectives_on
64 | self.vars.unconstrained = unconstrained
65 |
66 | # flip goal quat if necessary
67 | for i, j in enumerate(goal_quats):
68 | disp = np.linalg.norm(T.quaternion_disp(self.vars.prev_goal_quats[i], self.vars.goal_quats[i]))
69 | q = self.vars.goal_quats[i]
70 | if disp > M.pi / 2.0:
71 | self.vars.goal_quats[i] = [-q[0], -q[1], -q[2], -q[3]]
72 |
73 | if self.vars.position_mode == 'relative':
74 | self.vars.goal_positions = []
75 | for i, p in enumerate(goal_positions):
76 | self.vars.goal_positions.append(np.array(p) + self.vars.init_ee_positions[i])
77 | elif self.vars.position_mode == 'absolute':
78 | self.vars.goal_positions = []
79 | for i, p in enumerate(goal_positions):
80 | self.vars.goal_positions.append(np.array(p))
81 |
82 | if prev_state == None:
83 | initSol = self.vars.xopt
84 | else:
85 | initSol = prev_state
86 |
87 | if rand_start:
88 | initSol = rand_vec(self.vars.arm.joint_limits)
89 | self.reset(initSol)
90 |
91 | ################################################################################################################
92 | if self.optimization_package == 'scipy':
93 | xopt = self.groove.solve(prev_state=initSol,max_iter=max_iter,verbose_output=verbose_output)
94 | elif self.optimization_package == 'nlopt':
95 | xopt = self.groove.solve(prev_state=initSol,maxtime=maxtime,verbose_output=verbose_output)
96 | else:
97 | raise Exception('Invalid optimization package in relaxedIK. Valid inputs are [scipy] and [nlopt]. Exiting.')
98 | ################################################################################################################
99 |
100 | xopt = self.filter.filter(xopt)
101 | self.vars.relaxedIK_vars_update(xopt)
102 |
103 | return xopt
104 |
105 |
106 | def reset(self, reset_state):
107 | self.vars.xopt = reset_state
108 | self.vars.prev_state = reset_state
109 | self.vars.prev_state2 = reset_state
110 | self.vars.prev_state3 = reset_state
111 | self.filter = EMA_filter(reset_state, a=0.5)
112 |
113 | self.vars.init_ee_pos = self.vars.arm.getFrames(reset_state)[0][-1]
114 | self.vars.init_ee_quat = T.quaternion_from_matrix(self.vars.arm.getFrames(reset_state)[1][-1])
115 | self.vars.ee_pos = self.vars.init_ee_pos
116 | self.vars.prev_ee_pos3 = self.vars.init_ee_pos
117 | self.vars.prev_ee_pos2 = self.vars.init_ee_pos
118 | self.vars.prev_ee_pos = self.vars.init_ee_pos
119 |
120 | self.vars.goal_pos = [0, 0, 0]
121 | self.vars.prev_goal_pos3 = self.vars.goal_pos
122 | self.vars.prev_goal_pos2 = self.vars.goal_pos
123 | self.vars.prev_goal_pos = self.vars.goal_pos
124 | self.vars.goal_quat = [1, 0, 0, 0]
125 | self.vars.prev_goal_quat3 = self.vars.goal_quat
126 | self.vars.prev_goal_quat2 = self.vars.goal_quat
127 | self.vars.prev_goal_quat = self.vars.goal_quat
128 |
--------------------------------------------------------------------------------
/src/RelaxedIK/relaxedIK.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/uwgraphics/relaxed_ik/3d3c54fccc667aef241090805f29ff8b8670f38f/src/RelaxedIK/relaxedIK.pyc
--------------------------------------------------------------------------------
/src/RelaxedIK/urdfs/ur5.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
158 |
159 |
160 |
161 |
162 |
163 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 |
180 |
181 |
182 |
183 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 |
197 |
198 |
199 |
200 |
201 |
202 |
203 |
204 |
205 |
206 |
207 |
208 |
209 |
210 |
211 |
212 |
213 |
214 |
215 |
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 |
226 |
227 |
228 |
229 |
230 |
231 |
232 |
233 |
234 |
235 |
236 |
237 |
238 |
239 |
240 |
241 |
242 |
243 |
244 |
245 |
246 |
247 |
248 |
249 |
250 |
251 |
252 |
253 |
254 |
255 |
256 |
257 |
258 |
259 |
260 |
261 |
262 |
263 |
264 |
265 |
266 |
267 | transmission_interface/SimpleTransmission
268 |
269 | PositionJointInterface
270 |
271 |
272 | 1
273 |
274 |
275 |
276 | transmission_interface/SimpleTransmission
277 |
278 | PositionJointInterface
279 |
280 |
281 | 1
282 |
283 |
284 |
285 | transmission_interface/SimpleTransmission
286 |
287 | PositionJointInterface
288 |
289 |
290 | 1
291 |
292 |
293 |
294 | transmission_interface/SimpleTransmission
295 |
296 | PositionJointInterface
297 |
298 |
299 | 1
300 |
301 |
302 |
303 | transmission_interface/SimpleTransmission
304 |
305 | PositionJointInterface
306 |
307 |
308 | 1
309 |
310 |
311 |
312 | transmission_interface/SimpleTransmission
313 |
314 | PositionJointInterface
315 |
316 |
317 | 1
318 |
319 |
320 |
321 |
322 |
323 |
324 |
328 |
329 |
330 |
331 |
332 |
333 |
334 |
335 |
336 |
337 |
338 |
339 |
340 |
341 |
342 |
343 |
344 |
345 |
346 |
347 |
--------------------------------------------------------------------------------
/src/broadcaster.py:
--------------------------------------------------------------------------------
1 | __author__ = 'drakita'
2 | import numpy as N
3 | import math
4 | # from robotiq_85_msgs.msg import GripperCmd, GripperStat
5 | import rospy
6 | from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
7 | from sensor_msgs.msg import JointState
8 | from copy import deepcopy
9 |
10 | def pubVREP(vrepFile, xopt):
11 | # solution file
12 | xoptS = ",".join(str(e) for e in xopt)
13 | f = open(vrepFile, 'w')
14 | f.write(xoptS)
15 | f.close()
16 |
17 | def pubROS(vars):
18 | # TODO: complete this
19 | rotDisp = N.array(vars.rosDisp)
20 | a = []
21 |
22 | def move_ur5(ur_sock, xopt, disp):
23 | '''
24 | author: drakita
25 | moves the physical ur5 robot using urscript
26 | this uses the command servoj to be used for real-time streaming commands, no interpolation is used
27 | :param q: configuration of robot in radians [q1, q2, q3 ,..., q6]
28 | :param sock: socket that communicates with robot via urscript (port number should be 30002)
29 | :return:
30 | '''
31 |
32 | xopt = N.array(xopt)
33 | disp = N.array(disp)
34 | xopt = (xopt + disp).tolist()
35 | q = xopt
36 | gain = '200'
37 | # switched t=.08 to t=.1
38 | command = "servoj([{0},{1},{2},{3},{4},{5}],t=.085,lookahead_time=0.01,gain={6})".format(str(q[0]),str(q[1]),str(q[2]),str(q[3]),str(q[4]),str(q[5]),gain) + "\n"
39 |
40 | ur_sock.send(command)
41 |
42 | def move_sawyer(xopt, limb, timeout=1.0, threshold=0.07):
43 | angles = limb.joint_angles()
44 | angles['right_j0'] = xopt[0]
45 | angles['right_j1'] = xopt[1]
46 | angles['right_j2'] = xopt[2]
47 | angles['right_j3'] = xopt[3]
48 | angles['right_j4'] = xopt[4]
49 | angles['right_j5'] = xopt[5]
50 | angles['right_j6'] = xopt[6]
51 |
52 | limb.move_to_joint_positions(angles, timeout=timeout, threshold=threshold)
53 |
54 | def move_sawyer_set_joints(xopt, limb):
55 | angles = limb.joint_angles()
56 | angles['right_j0'] = xopt[0]
57 | angles['right_j1'] = xopt[1]
58 | angles['right_j2'] = xopt[2]
59 | angles['right_j3'] = xopt[3]
60 | angles['right_j4'] = xopt[4]
61 | angles['right_j5'] = xopt[5]
62 | angles['right_j6'] = xopt[6]
63 |
64 | limb.set_joint_positions(angles)
65 |
66 |
67 | def move_sawyer_set_velocities(xopt, limb):
68 | joint_names = limb.joint_names()
69 | curr_angles = limb.joint_angles()
70 | curr_joints = []
71 | for name in joint_names:
72 | curr_joints.append(curr_angles[name])
73 |
74 | vels = []
75 | for i,x in enumerate(xopt):
76 | vels.append(x - curr_joints[i])
77 |
78 | for i,name in enumerate(joint_names):
79 | curr_angles[name] = vels[i]
80 |
81 | limb.set_joint_velocities(curr_angles)
82 |
83 |
84 | def pubGripper_vrep(gripperFile, val):
85 | f = open(gripperFile, 'w')
86 | f.write(str(val))
87 | f.close()
88 |
89 | '''
90 | def pubGripper_ur5(val):
91 | gripper_pub = rospy.Publisher('/gripper/cmd', GripperCmd, queue_size=10)
92 | gripper_cmd = GripperCmd()
93 | posValue = 0.085
94 | if val == 1:
95 | posValue = 0.0
96 |
97 | gripper_cmd.position = posValue
98 | gripper_cmd.speed = 0.5
99 | gripper_cmd.force = 100.0
100 | gripper_pub.publish(gripper_cmd)
101 | '''
102 |
103 | def pubGripper_sawyer(val, gripper):
104 | if val == 1:
105 | gripper.close()
106 | else:
107 | gripper.open()
108 |
109 | jt_pub_ur5 = rospy.Publisher('/ur5/arm_controller/command', JointTrajectory)
110 | def move_ur5_joint_trajectory(xopt, duration=0.1):
111 | '''
112 | generally for use with gazebo
113 | :param xopt:
114 | :return:
115 | '''
116 | global jt_pub_ur5
117 | jt_ur5 = JointTrajectory()
118 | jt_ur5.joint_names = ['shoulder_pan_joint','shoulder_lift_joint','elbow_joint',
119 | 'wrist_1_joint','wrist_2_joint','wrist_3_joint']
120 |
121 | jtpt = JointTrajectoryPoint()
122 | jtpt.positions = [xopt[0], xopt[1], xopt[2], xopt[3], xopt[4], xopt[5]]
123 | jtpt.time_from_start = rospy.Duration.from_sec(duration)
124 |
125 | jt_ur5.points.append(jtpt)
126 | jt_pub_ur5.publish(jt_ur5)
127 |
128 | jt_pub_sawyer = rospy.Publisher('/sawyer/arm_controller/command',JointTrajectory)
129 | def move_sawyer_joint_trajectory(xopt, duration=0.1):
130 | '''
131 | generally for use with gazebo
132 | :param xopt:
133 | :return:
134 | '''
135 | global jt_pub_sawyer
136 | jt_sawyer = JointTrajectory()
137 | jt_sawyer.joint_names = ['right_j0','right_j1','right_j2',
138 | 'right_j3','right_j4','right_j5', 'right_j6']
139 |
140 | jtpt = JointTrajectoryPoint()
141 | jtpt.positions = [xopt[0], xopt[1], xopt[2], xopt[3], xopt[4], xopt[5], xopt[6]]
142 | jtpt.time_from_start = rospy.Duration.from_sec(duration)
143 |
144 | jt_sawyer.points.append(jtpt)
145 | jt_pub_sawyer.publish(jt_sawyer)
146 |
147 |
148 |
149 | pub = rospy.Publisher('joint_states', JointState, queue_size=5)
150 | def joint_state_publish(xopt, robot, solver='relaxed_ik'):
151 |
152 | js = JointState()
153 | if robot == 'ur5':
154 | js.name = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
155 | js.position = tuple(xopt)
156 | elif robot == 'sawyer':
157 | js.name = ['right_j0', 'right_j1', 'right_j2', 'right_j3', 'right_j4', 'right_j5', 'right_j6']
158 | js.position = tuple(xopt)
159 | elif robot == 'mico':
160 | js.name = ['mico_joint_1','mico_joint_2','mico_joint_3','mico_joint_4','mico_joint_5','mico_joint_6','mico_joint_finger_1','mico_joint_finger_2']
161 | js.position = tuple(xopt) + (0,0)
162 | elif robot == 'jaco':
163 | js.name = ['jaco_joint_1', 'jaco_joint_2', 'jaco_joint_3', 'jaco_joint_4', 'jaco_joint_5', 'jaco_joint_6', 'jaco_joint_finger_1', 'jaco_joint_finger_2', 'jaco_joint_finger_3', 'jaco_joint_finger_tip_1', 'jaco_joint_finger_tip_2', 'jaco_joint_finger_tip_3']
164 | js.position = tuple(xopt) + (0,0,0,0,0,0)
165 | elif robot == 'reactor':
166 | js.name = ['shoulder_yaw_joint', 'shoulder_pitch_joint', 'elbow_pitch_joint', 'wrist_pitch_joint', 'wrist_roll_joint', 'gripper_revolute_joint', 'gripper_right_joint', 'gripper_left_joint']
167 | x = deepcopy(xopt)
168 | js.position = (x[0],x[1],-x[2],-x[3],x[4]) + (0,0,0)
169 | elif robot == 'iiwa':
170 | js.name = ['iiwa_joint_1', 'iiwa_joint_2', 'iiwa_joint_3', 'iiwa_joint_4', 'iiwa_joint_5', 'iiwa_joint_6', 'iiwa_joint_7']
171 | js.position = tuple(xopt)
172 | elif robot == 'fanuc':
173 | js.name = ['joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5']
174 | x = deepcopy(xopt)
175 | js.position = (x[0],x[1],-x[2],-x[3],-x[4])
176 | elif robot == 'hubo_right_arm':
177 | js.name = ['LEFT_SHOULDER_PITCH', 'LEFT_SHOULDER_ROLL', 'LEFT_SHOULDER_YAW', 'LEFT_ELBOW', 'LEFT_WRIST_YAW', # five per row
178 | 'LEFT_WRIST_PITCH', 'LWFT', 'LEFT_WRIST_YAW_2', 'LHAND_a1', 'LHAND_a2',
179 | 'LHAND_a3', 'LHAND_b1', 'LHAND_b2', 'LHAND_b3', 'LHAND_c1',
180 | 'LHAND_c2', 'LHAND_c3', 'RIGHT_SHOULDER_PITCH', 'RIGHT_SHOULDER_ROLL', 'RIGHT_SHOULDER_YAW',
181 | 'RIGHT_ELBOW', 'RIGHT_WRIST_YAW', 'RIGHT_WRIST_PITCH', 'RWFT', 'RIGHT_WRIST_YAW_2',
182 | 'RHAND_a1', 'RHAND_a2', 'RHAND_a3', 'RHAND_b1', 'RHAND_b2',
183 | 'RHAND_b3', 'RHAND_c1', 'RHAND_c2', 'RHAND_c3', 'WAIST',
184 | 'LEFT_HIP_YAW', 'LEFT_HIP_ROLL', 'LEFT_HIP_PITCH', 'LEFT_KNEE', 'LEFT_ANKLE_PITCH',
185 | 'LEFT_ANKLE_ROLL', 'LAFT', 'LFUNI', 'LFWH', 'LEFT_WHEEL',
186 | 'RIGHT_HIP_YAW', 'RIGHT_HIP_ROLL', 'RIGHT_HIP_PITCH', 'RIGHT_KNEE', 'RIGHT_ANKLE_PITCH',
187 | 'RIGHT_ANKLE_ROLL', 'RAFT', 'RFUNI','RFWH', 'RIGHT_WHEEL',
188 | 'NECK_PITCH_1', 'NECK_YAW', 'NECK_PITCH_2', 'NECK_ROLL']
189 |
190 | x = deepcopy(xopt)
191 | js.position = 59*[0]
192 | js.position[17] = x[0]
193 | js.position[18] = x[1]
194 | js.position[19] = x[2]
195 | js.position[20] = x[3]
196 | js.position[21] = x[4]
197 | js.position[22] = x[5]
198 | js.position[24] = x[6]
199 | js.position = tuple(js.position)
200 | # print js.position
201 | elif robot == 'hubo_upper_body':
202 | js.name = ['LEFT_SHOULDER_PITCH', 'LEFT_SHOULDER_ROLL', 'LEFT_SHOULDER_YAW', 'LEFT_ELBOW', 'LEFT_WRIST_YAW', # five per row
203 | 'LEFT_WRIST_PITCH', 'LWFT', 'LEFT_WRIST_YAW_2', 'LHAND_a1', 'LHAND_a2',
204 | 'LHAND_a3', 'LHAND_b1', 'LHAND_b2', 'LHAND_b3', 'LHAND_c1',
205 | 'LHAND_c2', 'LHAND_c3', 'RIGHT_SHOULDER_PITCH', 'RIGHT_SHOULDER_ROLL', 'RIGHT_SHOULDER_YAW',
206 | 'RIGHT_ELBOW', 'RIGHT_WRIST_YAW', 'RIGHT_WRIST_PITCH', 'RWFT', 'RIGHT_WRIST_YAW_2',
207 | 'RHAND_a1', 'RHAND_a2', 'RHAND_a3', 'RHAND_b1', 'RHAND_b2',
208 | 'RHAND_b3', 'RHAND_c1', 'RHAND_c2', 'RHAND_c3', 'WAIST',
209 | 'LEFT_HIP_YAW', 'LEFT_HIP_ROLL', 'LEFT_HIP_PITCH', 'LEFT_KNEE', 'LEFT_ANKLE_PITCH',
210 | 'LEFT_ANKLE_ROLL', 'LAFT', 'LFUNI', 'LFWH', 'LEFT_WHEEL',
211 | 'RIGHT_HIP_YAW', 'RIGHT_HIP_ROLL', 'RIGHT_HIP_PITCH', 'RIGHT_KNEE', 'RIGHT_ANKLE_PITCH',
212 | 'RIGHT_ANKLE_ROLL', 'RAFT', 'RFUNI','RFWH', 'RIGHT_WHEEL',
213 | 'NECK_PITCH_1', 'NECK_YAW', 'NECK_PITCH_2', 'NECK_ROLL']
214 |
215 | x = deepcopy(xopt)
216 | js.position = 59*[0]
217 | if solver == 'relaxed_ik':
218 | js.position[34] = -x[0]
219 | elif solver == 'trac_ik':
220 | js.position[34] = x[0]
221 | js.position[17] = x[1]
222 | js.position[18] = x[2]
223 | js.position[19] = x[3]
224 | js.position[20] = x[4]
225 | js.position[21] = x[5]
226 | js.position[22] = x[6]
227 | js.position[24] = x[7]
228 | js.position = tuple(js.position)
229 |
230 | elif robot == 'hubo_bimanual':
231 | js.name = ['LEFT_SHOULDER_PITCH', 'LEFT_SHOULDER_ROLL', 'LEFT_SHOULDER_YAW', 'LEFT_ELBOW', 'LEFT_WRIST_YAW', # five per row
232 | 'LEFT_WRIST_PITCH', 'LWFT', 'LEFT_WRIST_YAW_2', 'LHAND_a1', 'LHAND_a2',
233 | 'LHAND_a3', 'LHAND_b1', 'LHAND_b2', 'LHAND_b3', 'LHAND_c1',
234 | 'LHAND_c2', 'LHAND_c3', 'RIGHT_SHOULDER_PITCH', 'RIGHT_SHOULDER_ROLL', 'RIGHT_SHOULDER_YAW',
235 | 'RIGHT_ELBOW', 'RIGHT_WRIST_YAW', 'RIGHT_WRIST_PITCH', 'RWFT', 'RIGHT_WRIST_YAW_2',
236 | 'RHAND_a1', 'RHAND_a2', 'RHAND_a3', 'RHAND_b1', 'RHAND_b2',
237 | 'RHAND_b3', 'RHAND_c1', 'RHAND_c2', 'RHAND_c3', 'WAIST',
238 | 'LEFT_HIP_YAW', 'LEFT_HIP_ROLL', 'LEFT_HIP_PITCH', 'LEFT_KNEE', 'LEFT_ANKLE_PITCH',
239 | 'LEFT_ANKLE_ROLL', 'LAFT', 'LFUNI', 'LFWH', 'LEFT_WHEEL',
240 | 'RIGHT_HIP_YAW', 'RIGHT_HIP_ROLL', 'RIGHT_HIP_PITCH', 'RIGHT_KNEE', 'RIGHT_ANKLE_PITCH',
241 | 'RIGHT_ANKLE_ROLL', 'RAFT', 'RFUNI','RFWH', 'RIGHT_WHEEL',
242 | 'NECK_PITCH_1', 'NECK_YAW', 'NECK_PITCH_2', 'NECK_ROLL']
243 |
244 | x = deepcopy(xopt)
245 | js.position = 59*[0]
246 | if solver == 'relaxed_ik':
247 | js.position[34] = -x[0]
248 | elif solver == 'trac_ik':
249 | js.position[34] = x[0]
250 | js.position[17] = x[1]
251 | js.position[18] = x[2]
252 | js.position[19] = x[3]
253 | js.position[20] = x[4]
254 | js.position[21] = x[5]
255 | js.position[22] = x[6]
256 | js.position[24] = x[7]
257 | js.position[0] = x[8]
258 | js.position[1] = x[9]
259 | js.position[2] = x[10]
260 | js.position[3] = x[11]
261 | js.position[4] = x[12]
262 | js.position[5] = x[13]
263 | js.position[7] = x[14]
264 | js.position = tuple(js.position)
265 |
266 | js.velocity = ()
267 | now = rospy.Time.now()
268 | js.header.stamp.secs = now.secs
269 | js.header.stamp.nsecs = now.nsecs
270 |
271 | pub.publish(js)
272 |
273 |
--------------------------------------------------------------------------------
/src/collision_viewer.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | '''
3 | author: Danny Rakita
4 | website: http://pages.cs.wisc.edu/~rakita/
5 | email: rakita@cs.wisc.edu
6 | last update: 5/8/18
7 |
8 | PLEASE DO NOT CHANGE CODE IN THIS FILE. IF TRYING TO SET UP RELAXEDIK, PLEASE REFER TO start_here.py INSTEAD
9 | AND FOLLOW THE STEP-BY-STEP INSTRUCTIONS THERE. Thanks!
10 | '''
11 | ######################################################################################################
12 |
13 |
14 | from start_here import urdf_file_name, joint_names, joint_ordering, ee_fixed_joints, starting_config, \
15 | joint_state_define, collision_file_name, fixed_frame
16 | from RelaxedIK.GROOVE_RelaxedIK.relaxedIK_vars import RelaxedIK_vars
17 | from sensor_msgs.msg import JointState
18 | from visualization_msgs.msg import Marker
19 | import rospy
20 | import roslaunch
21 | import os
22 | import tf
23 |
24 |
25 | if __name__ == '__main__':
26 | rospy.init_node('collision_viewer')
27 |
28 | urdf_file = open(os.path.dirname(__file__) + '/RelaxedIK/urdfs/' + urdf_file_name, 'r')
29 | urdf_string = urdf_file.read()
30 | rospy.set_param('robot_description', urdf_string)
31 | js_pub = rospy.Publisher('joint_states',JointState,queue_size=5)
32 | marker_pub = rospy.Publisher('visualization_marker',Marker,queue_size=5)
33 | tf_pub = tf.TransformBroadcaster()
34 |
35 | rospy.sleep(0.2)
36 |
37 | uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
38 | roslaunch.configure_logging(uuid)
39 | launch_path = os.path.dirname(__file__) + '/../launch/robot_state_pub.launch'
40 | launch = roslaunch.parent.ROSLaunchParent(uuid, [launch_path])
41 | launch.start()
42 |
43 | vars = RelaxedIK_vars('relaxedIK',os.path.dirname(__file__) + '/RelaxedIK/urdfs/' + urdf_file_name,joint_names,ee_fixed_joints,
44 | joint_ordering,init_state=starting_config, collision_file=collision_file_name, pre_config=True)
45 |
46 | sample_states = vars.collision_graph.sample_states
47 | idx = 0
48 | rate = rospy.Rate(0.8)
49 | while not rospy.is_shutdown():
50 | if idx >= len(sample_states): idx = 0
51 |
52 | state = sample_states[idx]
53 | cg = vars.collision_graph
54 | robot = vars.robot
55 | frames = robot.getFrames(state)
56 | cg.get_collision_score(frames)
57 | cg.c.draw_all()
58 |
59 | js = joint_state_define(state)
60 | if js == None:
61 | js = JointState()
62 | js.name = joint_ordering
63 | for x in state:
64 | js.position.append(x)
65 | now = rospy.Time.now()
66 | js.header.stamp.secs = now.secs
67 | js.header.stamp.nsecs = now.nsecs
68 | js_pub.publish(js)
69 |
70 | tf_pub.sendTransform((0,0,0),
71 | tf.transformations.quaternion_from_euler(0, 0, 0),
72 | rospy.Time.now(),
73 | 'common_world',
74 | fixed_frame)
75 |
76 | marker = Marker()
77 | marker.type = marker.TEXT_VIEW_FACING
78 | marker.header.frame_id = 'common_world'
79 | marker.header.stamp.nsecs = now.nsecs
80 | marker.header.stamp.secs = now.secs
81 | marker.text = str(idx)
82 | marker.scale.x = 0.1
83 | marker.scale.y = 0.1
84 | marker.scale.z = 0.1
85 | marker.pose.position.z = 0.3
86 | marker.pose.position.x = -0.3
87 | marker.color.a = 1.0
88 | marker_pub.publish(marker)
89 |
90 |
91 | idx += 1
92 |
93 | rate.sleep()
--------------------------------------------------------------------------------
/src/preprocessing.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | '''
3 | author: Danny Rakita
4 | website: http://pages.cs.wisc.edu/~rakita/
5 | email: rakita@cs.wisc.edu
6 | last update: 5/9/18
7 |
8 | PLEASE DO NOT CHANGE CODE IN THIS FILE. IF TRYING TO SET UP RELAXEDIK, PLEASE REFER TO start_here.py INSTEAD
9 | AND FOLLOW THE STEP-BY-STEP INSTRUCTIONS THERE. Thanks!
10 | '''
11 | ######################################################################################################
12 |
13 | from start_here import urdf_file_name, joint_names, joint_ordering, ee_fixed_joints, starting_config, \
14 | joint_state_define, collision_file_name, fixed_frame
15 | from RelaxedIK.relaxedIK import RelaxedIK
16 | from RelaxedIK.GROOVE_RelaxedIK.relaxedIK_vars import RelaxedIK_vars
17 | from sensor_msgs.msg import JointState
18 | import rospy
19 | import roslaunch
20 | import os
21 | import tf
22 | import math
23 |
24 |
25 | if __name__ == '__main__':
26 | # Don't change this code####################################################################################
27 | rospy.init_node('configuration')
28 |
29 | vars = RelaxedIK_vars('relaxedIK',os.path.dirname(__file__) + '/RelaxedIK/urdfs/' + urdf_file_name,joint_names,ee_fixed_joints,
30 | joint_ordering,init_state=starting_config, collision_file=collision_file_name, config_override=True)
31 |
32 |
--------------------------------------------------------------------------------
/src/relaxed_ik_node.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | '''
3 | author: Danny Rakita
4 | website: http://pages.cs.wisc.edu/~rakita/
5 | email: rakita@cs.wisc.edu
6 | last update: 7/1/18
7 |
8 | PLEASE DO NOT CHANGE CODE IN THIS FILE. IF TRYING TO SET UP RELAXEDIK, PLEASE REFER TO start_here.py INSTEAD
9 | AND FOLLOW THE STEP-BY-STEP INSTRUCTIONS THERE. Thanks!
10 | '''
11 | ######################################################################################################
12 |
13 | import rospy
14 | from RelaxedIK.relaxedIK import RelaxedIK
15 | from relaxed_ik.msg import EEPoseGoals, JointAngles
16 | from std_msgs.msg import Float32
17 | from RelaxedIK.Utils.colors import bcolors
18 |
19 | eepg = None
20 | def eePoseGoals_cb(data):
21 | global eepg
22 | eepg = data
23 |
24 | if __name__ == '__main__':
25 | rospy.init_node('relaxed_ik_node')
26 | angles_pub = rospy.Publisher('/relaxed_ik/joint_angle_solutions',JointAngles,queue_size=3)
27 | rospy.Subscriber('/relaxed_ik/ee_pose_goals', EEPoseGoals, eePoseGoals_cb)
28 | rospy.sleep(0.3)
29 |
30 | config_file_name = rospy.get_param('config_file_name', default='relaxedIK.config')
31 | relaxedIK = RelaxedIK.init_from_config(config_file_name)
32 | num_chains = relaxedIK.vars.robot.numChains
33 |
34 | while eepg == None: continue
35 |
36 | rate = rospy.Rate(100)
37 | while not rospy.is_shutdown():
38 | pose_goals = eepg.ee_poses
39 | header = eepg.header
40 | num_poses = len(pose_goals)
41 | if not num_poses == num_chains:
42 | print bcolors.FAIL + 'ERROR: Number of pose goals ({}) ' \
43 | 'not equal to the number of kinematic chains ({}). Exiting relaxed_ik_node'.format(num_poses, num_chains)
44 | rospy.signal_shutdown()
45 |
46 | pos_goals = []
47 | quat_goals = []
48 |
49 | for p in pose_goals:
50 | pos_x = p.position.x
51 | pos_y = p.position.y
52 | pos_z = p.position.z
53 |
54 | quat_w = p.orientation.w
55 | quat_x = p.orientation.x
56 | quat_y = p.orientation.y
57 | quat_z = p.orientation.z
58 |
59 | pos_goals.append([pos_x, pos_y, pos_z])
60 | quat_goals.append([quat_w, quat_x, quat_y, quat_z])
61 |
62 | xopt = relaxedIK.solve(pos_goals, quat_goals)
63 | ja = JointAngles()
64 | ja.header = header
65 | for x in xopt:
66 | ja.angles.append(Float32(x))
67 |
68 | angles_pub.publish(ja)
69 |
70 | rate.sleep()
71 |
72 |
73 |
74 |
75 |
76 |
--------------------------------------------------------------------------------
/src/sample.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | '''
3 | author: Danny Rakita
4 | website: http://pages.cs.wisc.edu/~rakita/
5 | email: rakita@cs.wisc.edu
6 | last update: 5/10/18
7 | '''
8 | ######################################################################################################
9 |
10 | from start_here import urdf_file_name, joint_names, joint_ordering, ee_fixed_joints, starting_config, \
11 | joint_state_define, collision_file_name, fixed_frame, config_file_name
12 | from RelaxedIK.relaxedIK import RelaxedIK
13 | from relaxed_ik.msg import EEPoseGoals
14 | from geometry_msgs.msg import Pose
15 | from sensor_msgs.msg import JointState
16 | import rospy
17 | import roslaunch
18 | import os
19 | import tf
20 | import math
21 |
22 |
23 | if __name__ == '__main__':
24 | # Don't change this code####################################################################################
25 | rospy.init_node('sample_node')
26 |
27 | ####################################################################################################################
28 | relaxedIK = RelaxedIK.init_from_config(config_file_name)
29 | ####################################################################################################################
30 |
31 | urdf_file = open(relaxedIK.vars.urdf_path, 'r')
32 | urdf_string = urdf_file.read()
33 | rospy.set_param('robot_description', urdf_string)
34 | js_pub = rospy.Publisher('joint_states',JointState,queue_size=5)
35 | ee_pose_goals_pub = rospy.Publisher('/relaxed_ik/ee_pose_goals', EEPoseGoals, queue_size=3)
36 | tf_pub = tf.TransformBroadcaster()
37 |
38 | rospy.sleep(0.3)
39 |
40 | # Don't change this code ###########################################################################################
41 | uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
42 | roslaunch.configure_logging(uuid)
43 | launch_path = os.path.dirname(__file__) + '/../launch/robot_state_pub.launch'
44 | launch = roslaunch.parent.ROSLaunchParent(uuid, [launch_path])
45 | launch.start()
46 | ####################################################################################################################
47 |
48 | rospy.sleep(1.0)
49 |
50 | counter = 0.0
51 | stride = 0.08
52 | idx = 0
53 | while not rospy.is_shutdown():
54 | c = math.cos(counter)
55 | s = 0.2
56 | num_ee = relaxedIK.vars.robot.numChains
57 | goal_pos = []
58 | goal_quat = []
59 | goal_pos.append([0,s*c,0])
60 | for i in range(num_ee):
61 | goal_quat.append([1,0,0,0])
62 | if i == 0:
63 | continue
64 | else:
65 | goal_pos.append([0,0,0])
66 |
67 | xopt = relaxedIK.solve(goal_pos, goal_quat)
68 |
69 | js = joint_state_define(xopt)
70 | if js == None:
71 | js = JointState()
72 | js.name = joint_ordering
73 | for x in xopt:
74 | js.position.append(x)
75 | now = rospy.Time.now()
76 | js.header.stamp.secs = now.secs
77 | js.header.stamp.nsecs = now.nsecs
78 | js_pub.publish(js)
79 |
80 | ee_pose_goals = EEPoseGoals()
81 | ee_pose_goals.header.seq = idx
82 | for i in range(num_ee):
83 | p = Pose()
84 | curr_goal_pos = goal_pos[i]
85 | curr_goal_quat = goal_quat[i]
86 | p.position.x = curr_goal_pos[0]
87 | p.position.y = curr_goal_pos[1]
88 | p.position.z = curr_goal_pos[2]
89 |
90 | p.orientation.w = curr_goal_quat[0]
91 | p.orientation.x = curr_goal_quat[1]
92 | p.orientation.y = curr_goal_quat[2]
93 | p.orientation.z = curr_goal_quat[3]
94 | ee_pose_goals.ee_poses.append(p)
95 |
96 | ee_pose_goals_pub.publish(ee_pose_goals)
97 |
98 | tf_pub.sendTransform((0, 0, 0),
99 | tf.transformations.quaternion_from_euler(0, 0, 0),
100 | rospy.Time.now(),
101 | 'common_world',
102 | fixed_frame)
103 |
104 | idx += 1
105 | counter += stride
--------------------------------------------------------------------------------
/src/urdf_viewer.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | '''
3 | author: Danny Rakita
4 | website: http://pages.cs.wisc.edu/~rakita/
5 | email: rakita@cs.wisc.edu
6 | last update: 5/8/18
7 |
8 | PLEASE DO NOT CHANGE CODE IN THIS FILE. IF TRYING TO SET UP RELAXEDIK, PLEASE REFER TO start_here.py INSTEAD
9 | AND FOLLOW THE STEP-BY-STEP INSTRUCTIONS THERE. Thanks!
10 | '''
11 | ######################################################################################################
12 |
13 | from start_here import urdf_file_name, fixed_frame
14 | import rospy
15 | import roslaunch
16 | import tf
17 | import os
18 | from sensor_msgs.msg import JointState
19 |
20 | joint_state = None
21 | def joint_state_cb(data):
22 | global joint_state
23 | joint_state = data
24 |
25 | if __name__ == '__main__':
26 | rospy.init_node('urdf_viewer')
27 |
28 | urdf_file = open(os.path.dirname(__file__) + '/RelaxedIK/urdfs/' + urdf_file_name, 'r')
29 | urdf_string = urdf_file.read()
30 | rospy.set_param('robot_description', urdf_string)
31 | tf_pub = tf.TransformBroadcaster()
32 | rospy.Subscriber('joint_states', JointState, joint_state_cb)
33 |
34 | rospy.sleep(1.0)
35 |
36 | uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
37 | roslaunch.configure_logging(uuid)
38 | launch_path = os.path.dirname(__file__) + '/../launch/joint_state_pub.launch'
39 | launch = roslaunch.parent.ROSLaunchParent(uuid, [launch_path])
40 | launch.start()
41 |
42 | rate = rospy.Rate(5.0)
43 | while not rospy.is_shutdown():
44 | tf_pub.sendTransform((0,0,0),
45 | tf.transformations.quaternion_from_euler(0, 0, 0),
46 | rospy.Time.now(),
47 | 'common_world',
48 | fixed_frame)
49 |
50 | if not joint_state == None:
51 | print 'current joint state: ' + str(list(joint_state.position))
52 |
53 | rate.sleep()
--------------------------------------------------------------------------------