diff --git a/c++/include/dynamixel_sdk.h b/c++/include/dynamixel_sdk.h index a32b2def299f39d56f858cb584b4297c9c4ef114..a0fdf2abd4cfdd75f3c55daf788f66e9e965359b 100644 --- a/c++/include/dynamixel_sdk.h +++ b/c++/include/dynamixel_sdk.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * dynamixel_sdk.h * * Created on: 2016. 3. 8. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_DYNAMIXELSDK_H_ diff --git a/c++/include/dynamixel_sdk/group_bulk_read.h b/c++/include/dynamixel_sdk/group_bulk_read.h index c42dbc381c63caa3728a06821476928713daeb1b..29b0dba88b0e60b9b48e363356e318e4301fb4ea 100644 --- a/c++/include/dynamixel_sdk/group_bulk_read.h +++ b/c++/include/dynamixel_sdk/group_bulk_read.h @@ -1,3 +1,35 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_bulk_read.h * diff --git a/c++/include/dynamixel_sdk/group_bulk_write.h b/c++/include/dynamixel_sdk/group_bulk_write.h index 45d3a2530525438da5f590c19ac1d78a2c2d7985..71bd9ecf652037f8696c7105f036c4d7e789c7f7 100644 --- a/c++/include/dynamixel_sdk/group_bulk_write.h +++ b/c++/include/dynamixel_sdk/group_bulk_write.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_bulk_write.h * * Created on: 2016. 2. 2. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_ diff --git a/c++/include/dynamixel_sdk/group_sync_read.h b/c++/include/dynamixel_sdk/group_sync_read.h index c204ad33d8f56a5a695908abb33a2c1a66c40146..ec2a208298c5dbd090c18cb16b4e90e344ae0e8e 100644 --- a/c++/include/dynamixel_sdk/group_sync_read.h +++ b/c++/include/dynamixel_sdk/group_sync_read.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_sync_read.h * * Created on: 2016. 2. 2. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_H_ diff --git a/c++/include/dynamixel_sdk/group_sync_write.h b/c++/include/dynamixel_sdk/group_sync_write.h index 944c4a2ddef0202ef9300331ba83a317fb951d53..1c85666084d6afeb47ac56081c8d9355ec558c61 100644 --- a/c++/include/dynamixel_sdk/group_sync_write.h +++ b/c++/include/dynamixel_sdk/group_sync_write.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_sync_write.h * * Created on: 2016. 1. 28. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_ diff --git a/c++/include/dynamixel_sdk/packet_handler.h b/c++/include/dynamixel_sdk/packet_handler.h index 840a550f5c39aab40c3cb5d8dcb1afe8b6a65154..3816cbba01e9dca2a66d6fbf0aa72f5576394dce 100644 --- a/c++/include/dynamixel_sdk/packet_handler.h +++ b/c++/include/dynamixel_sdk/packet_handler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * packet_handler.h * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ diff --git a/c++/include/dynamixel_sdk/port_handler.h b/c++/include/dynamixel_sdk/port_handler.h index 561dead3cf07a3f00d90529a2d9788cc74ca57fa..93fbeedd4a9c486a5c0bbf05586650e65b35c62a 100644 --- a/c++/include/dynamixel_sdk/port_handler.h +++ b/c++/include/dynamixel_sdk/port_handler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * port_handler.h * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ diff --git a/c++/include/dynamixel_sdk/protocol1_packet_handler.h b/c++/include/dynamixel_sdk/protocol1_packet_handler.h index 84bcf1c9e16152a6b55142482832ba83f658cc7f..758556f47cb313d5794b7bb0e7e418d07edf9e8b 100644 --- a/c++/include/dynamixel_sdk/protocol1_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol1_packet_handler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * protocol1_packet_handler.h * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_ diff --git a/c++/include/dynamixel_sdk/protocol2_packet_handler.h b/c++/include/dynamixel_sdk/protocol2_packet_handler.h index a775481acb222c53b0b8612d57eb00e2dda93b62..ff7e2d198d3ec4e1b6e89213b9e4950a79355382 100644 --- a/c++/include/dynamixel_sdk/protocol2_packet_handler.h +++ b/c++/include/dynamixel_sdk/protocol2_packet_handler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * protocol2_packet_handler.h * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_ diff --git a/c++/include/dynamixel_sdk_linux/port_handler_linux.h b/c++/include/dynamixel_sdk_linux/port_handler_linux.h index 3e7e76583dd91753f4e9753892757ea6534b1746..3a9ed24fa2e7fd7dd51b1662ad77659c423b2439 100644 --- a/c++/include/dynamixel_sdk_linux/port_handler_linux.h +++ b/c++/include/dynamixel_sdk_linux/port_handler_linux.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * port_handler_linux.h * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_LINUX_PORTHANDLERLINUX_H_ diff --git a/c++/include/dynamixel_sdk_windows/port_handler_windows.h b/c++/include/dynamixel_sdk_windows/port_handler_windows.h index efe592871270e9c4835e87ccbad429ecc89be5de..09583cb7f8b13bf1585bf156e34c9c329bd4bc9f 100644 --- a/c++/include/dynamixel_sdk_windows/port_handler_windows.h +++ b/c++/include/dynamixel_sdk_windows/port_handler_windows.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * port_handler_windows.h * * Created on: 2016. 4. 26. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_ diff --git a/c++/src/dynamixel_sdk/group_bulk_read.cpp b/c++/src/dynamixel_sdk/group_bulk_read.cpp index 0c6a340e4fd06475ffe937c62ab545f1e070b3db..7ae113b4571929b99494c8299ef7c0b66d48e501 100644 --- a/c++/src/dynamixel_sdk/group_bulk_read.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_read.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_bulk_read.cpp * * Created on: 2016. 1. 28. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c++/src/dynamixel_sdk/group_bulk_write.cpp b/c++/src/dynamixel_sdk/group_bulk_write.cpp index 8c38e42cf257028cd16eac008f7153202326376f..7b84151845814942745ee4881657d543200cb15d 100644 --- a/c++/src/dynamixel_sdk/group_bulk_write.cpp +++ b/c++/src/dynamixel_sdk/group_bulk_write.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_bulk_write.cpp * * Created on: 2016. 2. 2. -* Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -28,7 +59,7 @@ void GroupBulkWrite::makeParam() if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0) return; - if (param_ != 0) + if (param_ != 0) delete[] param_; param_ = 0; diff --git a/c++/src/dynamixel_sdk/group_sync_read.cpp b/c++/src/dynamixel_sdk/group_sync_read.cpp index cb2fe6d789c715678da4d79eaf433579a48b32cb..13818ccbf5ef20695f2694ce7828fa12b17d0a42 100644 --- a/c++/src/dynamixel_sdk/group_sync_read.cpp +++ b/c++/src/dynamixel_sdk/group_sync_read.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_sync_read.cpp * * Created on: 2016. 2. 2. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -27,7 +58,7 @@ GroupSyncRead::GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t star void GroupSyncRead::makeParam() { - if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0) + if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0) return; if (param_ != 0) @@ -43,7 +74,7 @@ void GroupSyncRead::makeParam() bool GroupSyncRead::addParam(uint8_t id) { - if (ph_->getProtocolVersion() == 1.0) + if (ph_->getProtocolVersion() == 1.0) return false; if (std::find(id_list_.begin(), id_list_.end(), id) != id_list_.end()) // id already exist @@ -100,7 +131,7 @@ int GroupSyncRead::rxPacket() { last_result_ = false; - if (ph_->getProtocolVersion() == 1.0) + if (ph_->getProtocolVersion() == 1.0) return COMM_NOT_AVAILABLE; int cnt = id_list_.size(); diff --git a/c++/src/dynamixel_sdk/group_sync_write.cpp b/c++/src/dynamixel_sdk/group_sync_write.cpp index 437854a97a874c2b1bac08dbc8ba4e83feeba589..94dea6fefa2d9ee44f1eb155072692d5f442f91f 100644 --- a/c++/src/dynamixel_sdk/group_sync_write.cpp +++ b/c++/src/dynamixel_sdk/group_sync_write.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * group_sync_write.cpp * * Created on: 2016. 1. 28. -* Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c++/src/dynamixel_sdk/packet_handler.cpp b/c++/src/dynamixel_sdk/packet_handler.cpp index 7d7f940deacfee89546cb8b43515bdbd46713b27..04fdc205952e8abf326c002dd1f5c0b493c49c83 100644 --- a/c++/src/dynamixel_sdk/packet_handler.cpp +++ b/c++/src/dynamixel_sdk/packet_handler.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * packet_handler.cpp * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c++/src/dynamixel_sdk/port_handler.cpp b/c++/src/dynamixel_sdk/port_handler.cpp index 20c125159727c89045c6f6b2c53e2125a387f994..14c0c288024436489d863911cc1ccb268b88a399 100644 --- a/c++/src/dynamixel_sdk/port_handler.cpp +++ b/c++/src/dynamixel_sdk/port_handler.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * port_handler.cpp * * Created on: 2016. 2. 5. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp index b34a82cd2db973d5b572b52c893babdffb619776..5129164ead43953beb005ad9996914578fa85fff 100644 --- a/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol1_packet_handler.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * protocol1_packet_handler.cpp * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp index 29028f5ee151a4ebb021a853d0601617ee47e440..f814229ab6b8845ba4e7cd9b676b236fc5eff663 100644 --- a/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp +++ b/c++/src/dynamixel_sdk/protocol2_packet_handler.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * protocol2_packet_handler.cpp * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #if defined(_WIN32) || defined(_WIN64) diff --git a/c++/src/dynamixel_sdk_linux/port_handler_linux.cpp b/c++/src/dynamixel_sdk_linux/port_handler_linux.cpp index ee16b25c83598d3682ca0967ae08d580cdf8ce3c..0cc11e09e3a469ed9d9196e3e9ae14f79c06e123 100644 --- a/c++/src/dynamixel_sdk_linux/port_handler_linux.cpp +++ b/c++/src/dynamixel_sdk_linux/port_handler_linux.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: zerom, Leon Ryu Woon Jung */ + /* * port_handler_linux.cpp * * Created on: 2016. 1. 26. - * Author: zerom, leon */ #include <stdio.h> diff --git a/c++/src/dynamixel_sdk_windows/port_handler_windows.cpp b/c++/src/dynamixel_sdk_windows/port_handler_windows.cpp index 4090ee24f7d9995b195fc3c000cdffc0ffcc44ef..c47e76f4aea60f54cfa1b8a81b11d2f394e3a03c 100644 --- a/c++/src/dynamixel_sdk_windows/port_handler_windows.cpp +++ b/c++/src/dynamixel_sdk_windows/port_handler_windows.cpp @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandlerWindows.cpp * * Created on: 2016. 4. 06. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT diff --git a/c/include/DynamixelSDK.h b/c/include/DynamixelSDK.h index f98cf2aaa60b791594dbb66a7fbca64feadd4f62..3ffe7149c2c18120415c4cdb609e58b88316f326 100644 --- a/c/include/DynamixelSDK.h +++ b/c/include/DynamixelSDK.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * DynamixelSDK.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_DYNAMIXELSDK_C_H_ diff --git a/c/include/dynamixel_sdk/GroupBulkRead.h b/c/include/dynamixel_sdk/GroupBulkRead.h index cb6dcee411c31fddf52f2fbedd6b08e6e313472a..6d2cc1fa6bc3126b96fb0e3ad8317fa4ca7038ce 100644 --- a/c/include/dynamixel_sdk/GroupBulkRead.h +++ b/c/include/dynamixel_sdk/GroupBulkRead.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupBulkRead.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_C_H_ diff --git a/c/include/dynamixel_sdk/GroupBulkWrite.h b/c/include/dynamixel_sdk/GroupBulkWrite.h index bc5dfa5e34d7e00064ef7dda14ecba28099f5e39..a56c4287d5bee45971c49016ee2b117cfef4486b 100644 --- a/c/include/dynamixel_sdk/GroupBulkWrite.h +++ b/c/include/dynamixel_sdk/GroupBulkWrite.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupBulkWrite.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_C_H_ diff --git a/c/include/dynamixel_sdk/GroupSyncRead.h b/c/include/dynamixel_sdk/GroupSyncRead.h index d13aadc855bd057892cbd1f207e7b0a582503193..58c2b895cfbd6be9fe741e2106aebb96d2d7a83e 100644 --- a/c/include/dynamixel_sdk/GroupSyncRead.h +++ b/c/include/dynamixel_sdk/GroupSyncRead.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupSyncRead.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_C_H_ diff --git a/c/include/dynamixel_sdk/GroupSyncWrite.h b/c/include/dynamixel_sdk/GroupSyncWrite.h index 5844563e92b0bca9f744ac21946efc49070631db..380c7046c9698b15c814ac36765a75a7b1f2000f 100644 --- a/c/include/dynamixel_sdk/GroupSyncWrite.h +++ b/c/include/dynamixel_sdk/GroupSyncWrite.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupSyncWrite.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_C_H_ diff --git a/c/include/dynamixel_sdk/PacketHandler.h b/c/include/dynamixel_sdk/PacketHandler.h index 61a418de556f940654ed586d25d0a4796fa7fb26..8c981eb0a335201f6018830a70ea1f9f4cc59b6b 100644 --- a/c/include/dynamixel_sdk/PacketHandler.h +++ b/c/include/dynamixel_sdk/PacketHandler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PacketHandler.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_C_H_ diff --git a/c/include/dynamixel_sdk/PortHandler.h b/c/include/dynamixel_sdk/PortHandler.h index 8012e4710828cb6828f88c026493ae764a0b0785..09f8d6a435ff521058a47ae3e135afe35a20aabd 100644 --- a/c/include/dynamixel_sdk/PortHandler.h +++ b/c/include/dynamixel_sdk/PortHandler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandler.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_C_H_ diff --git a/c/include/dynamixel_sdk/Protocol1PacketHandler.h b/c/include/dynamixel_sdk/Protocol1PacketHandler.h index b549d3600ef3b6323b1033e651b44cccb1b08d3c..5981b4c33886aaac80896e670d2dffd729d0aaa5 100644 --- a/c/include/dynamixel_sdk/Protocol1PacketHandler.h +++ b/c/include/dynamixel_sdk/Protocol1PacketHandler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * Protocol1PacketHandler.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_C_H_ diff --git a/c/include/dynamixel_sdk/Protocol2PacketHandler.h b/c/include/dynamixel_sdk/Protocol2PacketHandler.h index 34851f3bda48950c514c586a70484d4d37cdf5af..1359de380b5e4fd61d4a9ce379d980604b5c8209 100644 --- a/c/include/dynamixel_sdk/Protocol2PacketHandler.h +++ b/c/include/dynamixel_sdk/Protocol2PacketHandler.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * Protocol2PacketHandler.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_C_H_ diff --git a/c/include/dynamixel_sdk/RobotisDef.h b/c/include/dynamixel_sdk/RobotisDef.h index 21d11a42c8d6de0e12f61aafa93a25b05508b9b3..8fd8977426b652d5f4a384150b1a71caeb700a83 100644 --- a/c/include/dynamixel_sdk/RobotisDef.h +++ b/c/include/dynamixel_sdk/RobotisDef.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * RobotisDef.h * * Created on: 2016. 5. 4. - * Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ROBOTISDEF_C_H_ diff --git a/c/include/dynamixel_sdk_linux/PortHandlerLinux.h b/c/include/dynamixel_sdk_linux/PortHandlerLinux.h index 04f0ed36b35759eef19c42a0aa0fc4dd3af3f41e..55214f189fe7eb64196453d8c9679c5044b86e50 100644 --- a/c/include/dynamixel_sdk_linux/PortHandlerLinux.h +++ b/c/include/dynamixel_sdk_linux/PortHandlerLinux.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandlerLinux.h * * Created on: 2016. 5. 17. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_LINUX_PORTHANDLERLINUX_C_H_ diff --git a/c/include/dynamixel_sdk_windows/PortHandlerWindows.h b/c/include/dynamixel_sdk_windows/PortHandlerWindows.h index 2029a0df4a17a0847de09f76b17a16a9f5b19f21..89a88ca07848d90680b3989d443e6f84d5401078 100644 --- a/c/include/dynamixel_sdk_windows/PortHandlerWindows.h +++ b/c/include/dynamixel_sdk_windows/PortHandlerWindows.h @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandlerWindows.h * * Created on: 2016. 5. 4. -* Author: leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_C_H_ diff --git a/c/src/dynamixel_sdk/GroupBulkRead.c b/c/src/dynamixel_sdk/GroupBulkRead.c index 12dc8ca3a168139ca1aec85f63e2e04105be337d..0b2d382c1b27ac579a55aa15c6dd2f02797cd9bc 100644 --- a/c/src/dynamixel_sdk/GroupBulkRead.c +++ b/c/src/dynamixel_sdk/GroupBulkRead.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupBulkRead.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -202,7 +233,7 @@ void GroupBulkRead_RxPacket(int group_num) { int _data_num, _c; int _port_num = groupDataBulkRead[group_num].port_num; - + packetData[_port_num].communication_result_ = COMM_RX_FAIL; groupDataBulkRead[group_num].last_result_ = false; diff --git a/c/src/dynamixel_sdk/GroupBulkWrite.c b/c/src/dynamixel_sdk/GroupBulkWrite.c index 4899e1534a3e4deff28fdc254ea794d2a67f52b2..b0f3e21dbbc996f9a4c7b6a163adc0ca645295a1 100644 --- a/c/src/dynamixel_sdk/GroupBulkWrite.c +++ b/c/src/dynamixel_sdk/GroupBulkWrite.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupBulkWrite.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -110,7 +141,7 @@ void GroupBulkWrite_MakeParam(int group_num) groupDataBulkWrite[group_num].param_length_ += 1 + 2 + 2 + groupDataBulkWrite[group_num].data_list_[_data_num].data_length_; - packetData[_port_num].data_write_ = (UINT8_T*)realloc(packetData[_port_num].data_write_, groupDataBulkWrite[group_num].param_length_ * sizeof(UINT8_T)); + packetData[_port_num].data_write_ = (UINT8_T*)realloc(packetData[_port_num].data_write_, groupDataBulkWrite[group_num].param_length_ * sizeof(UINT8_T)); packetData[_port_num].data_write_[_idx++] = groupDataBulkWrite[group_num].data_list_[_data_num].id_; packetData[_port_num].data_write_[_idx++] = DXL_LOBYTE(groupDataBulkWrite[group_num].data_list_[_data_num].start_address_); diff --git a/c/src/dynamixel_sdk/GroupSyncRead.c b/c/src/dynamixel_sdk/GroupSyncRead.c index 0b500e5551e0808b9c450798b809073c5cfccfd8..974280a431a547ca2d930472dfb541b249ae3652 100644 --- a/c/src/dynamixel_sdk/GroupSyncRead.c +++ b/c/src/dynamixel_sdk/GroupSyncRead.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * GroupSyncRead.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -134,7 +165,7 @@ bool GroupSyncRead_AddParam(int group_num, UINT8_T id) groupDataSyncRead[group_num].data_list_[_data_num].id_ = id; groupDataSyncRead[group_num].data_list_[_data_num].data_ = (UINT8_T *)calloc(groupDataSyncRead[group_num].data_length_, sizeof(UINT8_T)); } - + groupDataSyncRead[group_num].is_param_changed_ = true; return true; } @@ -209,7 +240,7 @@ void GroupSyncRead_RxPacket(int group_num) packetData[_port_num].communication_result_ = COMM_NOT_AVAILABLE; return; } - + packetData[groupDataSyncRead[group_num].port_num].communication_result_ = COMM_RX_FAIL; if (GroupSyncRead_Size(group_num) == 0) diff --git a/c/src/dynamixel_sdk/GroupSyncWrite.c b/c/src/dynamixel_sdk/GroupSyncWrite.c index 9f295df1d45d5921a11c767ae4ba038e6791d74e..c1aa5b175ef5d4dfbd5163f1b1ff0bfebed68323 100644 --- a/c/src/dynamixel_sdk/GroupSyncWrite.c +++ b/c/src/dynamixel_sdk/GroupSyncWrite.c @@ -1,8 +1,38 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ /* * GroupSyncWrite.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -24,7 +54,7 @@ typedef struct { int port_num; int protocol_version; - + int data_list_length_; bool is_param_changed_; @@ -172,7 +202,7 @@ void GroupSyncWrite_RemoveParam(int group_num, UINT8_T id) return; groupDataSyncWrite[group_num].data_list_[_data_num].data_end_ = 0; - + groupDataSyncWrite[group_num].data_list_[_data_num].data_ = 0; groupDataSyncWrite[group_num].data_list_[_data_num].id_ = NOT_USED_ID; diff --git a/c/src/dynamixel_sdk/PacketHandler.c b/c/src/dynamixel_sdk/PacketHandler.c index 2a6864781902ec2fef969ca2f2206ab43a07862b..c3869cfb2b58fde1eb72b86bb2ee4dce78f27db6 100644 --- a/c/src/dynamixel_sdk/PacketHandler.c +++ b/c/src/dynamixel_sdk/PacketHandler.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PacketHandler.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -56,7 +87,7 @@ int GetLastTxRxResult(int port_num, int protocol_version) else return GetLastTxRxResult2(port_num); } -UINT8_T GetLastRxPacketError(int port_num, int protocol_version) +UINT8_T GetLastRxPacketError(int port_num, int protocol_version) { if (protocol_version == 1) return GetLastRxPacketError1(port_num); diff --git a/c/src/dynamixel_sdk/PortHandler.c b/c/src/dynamixel_sdk/PortHandler.c index b1583d979ea6a8b5134d013490ead8017414e83d..bd3d9b2bcf527f42fbe846fbac8e64416674c9fc 100644 --- a/c/src/dynamixel_sdk/PortHandler.c +++ b/c/src/dynamixel_sdk/PortHandler.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandler.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) diff --git a/c/src/dynamixel_sdk/Protocol1PacketHandler.c b/c/src/dynamixel_sdk/Protocol1PacketHandler.c index 3627a5f119792f065d1f125dafafa5143767560c..5233d6a4b4b4dcc9d54c1f6d0d320be55387693d 100644 --- a/c/src/dynamixel_sdk/Protocol1PacketHandler.c +++ b/c/src/dynamixel_sdk/Protocol1PacketHandler.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * Protocol1PacketHandler.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) #define WINDLLEXPORT @@ -403,7 +434,7 @@ void ReadTx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length) packetData[port_num].txpacket_ = (UINT8_T *)realloc(packetData[port_num].txpacket_, 8); - if (id >= BROADCAST_ID) + if (id >= BROADCAST_ID) { packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE; return; @@ -665,7 +696,7 @@ void SyncWriteTxOnly1(int port_num, UINT16_T start_address, UINT16_T data_length UINT8_T _s; packetData[port_num].communication_result_ = COMM_TX_FAIL; - + packetData[port_num].txpacket_ = (UINT8_T *)realloc(packetData[port_num].txpacket_, param_length + 8); // 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM packetData[port_num].txpacket_[PKT_ID] = BROADCAST_ID; @@ -686,7 +717,7 @@ void BulkReadTx1(int port_num, UINT16_T param_length) int _i; packetData[port_num].communication_result_ = COMM_TX_FAIL; - + packetData[port_num].txpacket_ = (UINT8_T *)realloc(packetData[port_num].txpacket_, param_length + 7); // 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM packetData[port_num].txpacket_[PKT_ID] = BROADCAST_ID; diff --git a/c/src/dynamixel_sdk/Protocol2PacketHandler.c b/c/src/dynamixel_sdk/Protocol2PacketHandler.c index a8b06681ea12d28f02616dbeea84a0c899013d65..1d32f7200cc309c82ececc1a62e5dd9bc05ce6c4 100644 --- a/c/src/dynamixel_sdk/Protocol2PacketHandler.c +++ b/c/src/dynamixel_sdk/Protocol2PacketHandler.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * Protocol2PacketHandler.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) diff --git a/c/src/dynamixel_sdk_linux/PortHandlerLinux.c b/c/src/dynamixel_sdk_linux/PortHandlerLinux.c index f7d39aef15ba685b0cf6f97f5d502ad8b6b354ec..a8db500157b4b4ad0e0ec4b80a2b5ad9eb610a5c 100644 --- a/c/src/dynamixel_sdk_linux/PortHandlerLinux.c +++ b/c/src/dynamixel_sdk_linux/PortHandlerLinux.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandlerLinux.c * * Created on: 2016. 5. 17. -* Author: leon */ #include <stdio.h> diff --git a/c/src/dynamixel_sdk_windows/PortHandlerWindows.c b/c/src/dynamixel_sdk_windows/PortHandlerWindows.c index 407c3bfb9fc87628ae7d5c721756c2acce5c23e5..45ffb81fbd4568556d2de413cd5dc41c3309d922 100644 --- a/c/src/dynamixel_sdk_windows/PortHandlerWindows.c +++ b/c/src/dynamixel_sdk_windows/PortHandlerWindows.c @@ -1,8 +1,39 @@ +/******************************************************************************* +* Copyright (c) 2016, ROBOTIS CO., LTD. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* * Neither the name of ROBOTIS nor the names of its +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*******************************************************************************/ + +/* Author: Leon Ryu Woon Jung */ + /* * PortHandlerWindows.c * * Created on: 2016. 5. 4. -* Author: leon */ #if defined(_WIN32) || defined(_WIN64) @@ -14,7 +45,7 @@ #include <time.h> #include "dynamixel_sdk_windows/PortHandlerWindows.h" -#define LATENCY_TIMER 16 // msec (USB latency timer) +#define LATENCY_TIMER 16 // msec (USB latency timer) typedef struct { @@ -188,20 +219,20 @@ bool SetupPortWindows(int port_num, const int baudrate) DCB dcb; COMMTIMEOUTS timeouts; DWORD dwError; - + ClosePortWindows(port_num); - + portDataWindows[port_num].serial_handle_ = CreateFileA(portDataWindows[port_num].port_name_, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, NULL); if (portDataWindows[port_num].serial_handle_ == INVALID_HANDLE_VALUE) { printf("[PortHandlerWindows::SetupPort] Error opening serial port!\n"); return false; } - + dcb.DCBlength = sizeof(DCB); if (GetCommState(portDataWindows[port_num].serial_handle_, &dcb) == FALSE) goto DXL_HAL_OPEN_ERROR; - + // Set baudrate dcb.BaudRate = (DWORD)baudrate; dcb.ByteSize = 8; // Data bit = 8bit @@ -221,10 +252,10 @@ bool SetupPortWindows(int port_num, const int baudrate) dcb.fDsrSensitivity = 0; dcb.fOutxDsrFlow = 0; dcb.fOutxCtsFlow = 0; - + if (SetCommState(portDataWindows[port_num].serial_handle_, &dcb) == FALSE) goto DXL_HAL_OPEN_ERROR; - + if (SetCommMask(portDataWindows[port_num].serial_handle_, 0) == FALSE) // Not using Comm event goto DXL_HAL_OPEN_ERROR; if (SetupComm(portDataWindows[port_num].serial_handle_, 4096, 4096) == FALSE) // Buffer size (Rx,Tx) @@ -233,7 +264,7 @@ bool SetupPortWindows(int port_num, const int baudrate) goto DXL_HAL_OPEN_ERROR; if (ClearCommError(portDataWindows[port_num].serial_handle_, &dwError, NULL) == FALSE) goto DXL_HAL_OPEN_ERROR; - + if (GetCommTimeouts(portDataWindows[port_num].serial_handle_, &timeouts) == FALSE) goto DXL_HAL_OPEN_ERROR; // Timeout (Not using timeout) @@ -245,10 +276,10 @@ bool SetupPortWindows(int port_num, const int baudrate) timeouts.WriteTotalTimeoutConstant = 0; if (SetCommTimeouts(portDataWindows[port_num].serial_handle_, &timeouts) == FALSE) goto DXL_HAL_OPEN_ERROR; - + portDataWindows[port_num].tx_time_per_byte_ = (1000.0 / (double)portDataWindows[port_num].baudrate_) * 10.0; return true; - + DXL_HAL_OPEN_ERROR: ClosePortWindows(port_num);