diff --git a/LICENSE b/LICENSE index 23cb790338e191e29205d6f4123882c0583ef8eb..e8a5e3073bf9188ab29def9d2c1b4c06743dd885 100644 --- a/LICENSE +++ b/LICENSE @@ -1,339 +1,26 @@ - GNU GENERAL PUBLIC LICENSE - Version 2, June 1991 - - Copyright (C) 1989, 1991 Free Software Foundation, Inc., <http://fsf.org/> - 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The licenses for most software are designed to take away your -freedom to share and change it. By contrast, the GNU General Public -License is intended to guarantee your freedom to share and change free -software--to make sure the software is free for all its users. This -General Public License applies to most of the Free Software -Foundation's software and to any other program whose authors commit to -using it. (Some other Free Software Foundation software is covered by -the GNU Lesser General Public License instead.) You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -this service if you wish), that you receive source code or can get it -if you want it, that you can change the software or use pieces of it -in new free programs; and that you know you can do these things. - - To protect your rights, we need to make restrictions that forbid -anyone to deny you these rights or to ask you to surrender the rights. -These restrictions translate to certain responsibilities for you if you -distribute copies of the software, or if you modify it. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must give the recipients all the rights that -you have. You must make sure that they, too, receive or can get the -source code. And you must show them these terms so they know their -rights. - - We protect your rights with two steps: (1) copyright the software, and -(2) offer you this license which gives you legal permission to copy, -distribute and/or modify the software. - - Also, for each author's protection and ours, we want to make certain -that everyone understands that there is no warranty for this free -software. If the software is modified by someone else and passed on, we -want its recipients to know that what they have is not the original, so -that any problems introduced by others will not reflect on the original -authors' reputations. - - Finally, any free program is threatened constantly by software -patents. We wish to avoid the danger that redistributors of a free -program will individually obtain patent licenses, in effect making the -program proprietary. To prevent this, we have made it clear that any -patent must be licensed for everyone's free use or not licensed at all. - - The precise terms and conditions for copying, distribution and -modification follow. - - GNU GENERAL PUBLIC LICENSE - TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION - - 0. This License applies to any program or other work which contains -a notice placed by the copyright holder saying it may be distributed -under the terms of this General Public License. The "Program", below, -refers to any such program or work, and a "work based on the Program" -means either the Program or any derivative work under copyright law: -that is to say, a work containing the Program or a portion of it, -either verbatim or with modifications and/or translated into another -language. (Hereinafter, translation is included without limitation in -the term "modification".) Each licensee is addressed as "you". - -Activities other than copying, distribution and modification are not -covered by this License; they are outside its scope. The act of -running the Program is not restricted, and the output from the Program -is covered only if its contents constitute a work based on the -Program (independent of having been made by running the Program). -Whether that is true depends on what the Program does. - - 1. You may copy and distribute verbatim copies of the Program's -source code as you receive it, in any medium, provided that you -conspicuously and appropriately publish on each copy an appropriate -copyright notice and disclaimer of warranty; keep intact all the -notices that refer to this License and to the absence of any warranty; -and give any other recipients of the Program a copy of this License -along with the Program. - -You may charge a fee for the physical act of transferring a copy, and -you may at your option offer warranty protection in exchange for a fee. - - 2. You may modify your copy or copies of the Program or any portion -of it, thus forming a work based on the Program, and copy and -distribute such modifications or work under the terms of Section 1 -above, provided that you also meet all of these conditions: - - a) You must cause the modified files to carry prominent notices - stating that you changed the files and the date of any change. - - b) You must cause any work that you distribute or publish, that in - whole or in part contains or is derived from the Program or any - part thereof, to be licensed as a whole at no charge to all third - parties under the terms of this License. - - c) If the modified program normally reads commands interactively - when run, you must cause it, when started running for such - interactive use in the most ordinary way, to print or display an - announcement including an appropriate copyright notice and a - notice that there is no warranty (or else, saying that you provide - a warranty) and that users may redistribute the program under - these conditions, and telling the user how to view a copy of this - License. (Exception: if the Program itself is interactive but - does not normally print such an announcement, your work based on - the Program is not required to print an announcement.) - -These requirements apply to the modified work as a whole. If -identifiable sections of that work are not derived from the Program, -and can be reasonably considered independent and separate works in -themselves, then this License, and its terms, do not apply to those -sections when you distribute them as separate works. But when you -distribute the same sections as part of a whole which is a work based -on the Program, the distribution of the whole must be on the terms of -this License, whose permissions for other licensees extend to the -entire whole, and thus to each and every part regardless of who wrote it. - -Thus, it is not the intent of this section to claim rights or contest -your rights to work written entirely by you; rather, the intent is to -exercise the right to control the distribution of derivative or -collective works based on the Program. - -In addition, mere aggregation of another work not based on the Program -with the Program (or with a work based on the Program) on a volume of -a storage or distribution medium does not bring the other work under -the scope of this License. - - 3. You may copy and distribute the Program (or a work based on it, -under Section 2) in object code or executable form under the terms of -Sections 1 and 2 above provided that you also do one of the following: - - a) Accompany it with the complete corresponding machine-readable - source code, which must be distributed under the terms of Sections - 1 and 2 above on a medium customarily used for software interchange; or, - - b) Accompany it with a written offer, valid for at least three - years, to give any third party, for a charge no more than your - cost of physically performing source distribution, a complete - machine-readable copy of the corresponding source code, to be - distributed under the terms of Sections 1 and 2 above on a medium - customarily used for software interchange; or, - - c) Accompany it with the information you received as to the offer - to distribute corresponding source code. (This alternative is - allowed only for noncommercial distribution and only if you - received the program in object code or executable form with such - an offer, in accord with Subsection b above.) - -The source code for a work means the preferred form of the work for -making modifications to it. For an executable work, complete source -code means all the source code for all modules it contains, plus any -associated interface definition files, plus the scripts used to -control compilation and installation of the executable. However, as a -special exception, the source code distributed need not include -anything that is normally distributed (in either source or binary -form) with the major components (compiler, kernel, and so on) of the -operating system on which the executable runs, unless that component -itself accompanies the executable. - -If distribution of executable or object code is made by offering -access to copy from a designated place, then offering equivalent -access to copy the source code from the same place counts as -distribution of the source code, even though third parties are not -compelled to copy the source along with the object code. - - 4. You may not copy, modify, sublicense, or distribute the Program -except as expressly provided under this License. Any attempt -otherwise to copy, modify, sublicense or distribute the Program is -void, and will automatically terminate your rights under this License. -However, parties who have received copies, or rights, from you under -this License will not have their licenses terminated so long as such -parties remain in full compliance. - - 5. You are not required to accept this License, since you have not -signed it. However, nothing else grants you permission to modify or -distribute the Program or its derivative works. These actions are -prohibited by law if you do not accept this License. Therefore, by -modifying or distributing the Program (or any work based on the -Program), you indicate your acceptance of this License to do so, and -all its terms and conditions for copying, distributing or modifying -the Program or works based on it. - - 6. Each time you redistribute the Program (or any work based on the -Program), the recipient automatically receives a license from the -original licensor to copy, distribute or modify the Program subject to -these terms and conditions. You may not impose any further -restrictions on the recipients' exercise of the rights granted herein. -You are not responsible for enforcing compliance by third parties to -this License. - - 7. If, as a consequence of a court judgment or allegation of patent -infringement or for any other reason (not limited to patent issues), -conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot -distribute so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you -may not distribute the Program at all. For example, if a patent -license would not permit royalty-free redistribution of the Program by -all those who receive copies directly or indirectly through you, then -the only way you could satisfy both it and this License would be to -refrain entirely from distribution of the Program. - -If any portion of this section is held invalid or unenforceable under -any particular circumstance, the balance of the section is intended to -apply and the section as a whole is intended to apply in other -circumstances. - -It is not the purpose of this section to induce you to infringe any -patents or other property right claims or to contest validity of any -such claims; this section has the sole purpose of protecting the -integrity of the free software distribution system, which is -implemented by public license practices. Many people have made -generous contributions to the wide range of software distributed -through that system in reliance on consistent application of that -system; it is up to the author/donor to decide if he or she is willing -to distribute software through any other system and a licensee cannot -impose that choice. - -This section is intended to make thoroughly clear what is believed to -be a consequence of the rest of this License. - - 8. If the distribution and/or use of the Program is restricted in -certain countries either by patents or by copyrighted interfaces, the -original copyright holder who places the Program under this License -may add an explicit geographical distribution limitation excluding -those countries, so that distribution is permitted only in or among -countries not thus excluded. In such case, this License incorporates -the limitation as if written in the body of this License. - - 9. The Free Software Foundation may publish revised and/or new versions -of the General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - -Each version is given a distinguishing version number. If the Program -specifies a version number of this License which applies to it and "any -later version", you have the option of following the terms and conditions -either of that version or of any later version published by the Free -Software Foundation. If the Program does not specify a version number of -this License, you may choose any version ever published by the Free Software -Foundation. - - 10. If you wish to incorporate parts of the Program into other free -programs whose distribution conditions are different, write to the author -to ask for permission. For software which is copyrighted by the Free -Software Foundation, write to the Free Software Foundation; we sometimes -make exceptions for this. Our decision will be guided by the two goals -of preserving the free status of all derivatives of our free software and -of promoting the sharing and reuse of software generally. - - NO WARRANTY - - 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY -FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN -OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES -PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED -OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS -TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE -PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, -REPAIR OR CORRECTION. - - 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR -REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, -INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING -OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED -TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY -YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER -PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE -POSSIBILITY OF SUCH DAMAGES. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -convey the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - {description} - Copyright (C) {year} {fullname} - - This program is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License along - with this program; if not, write to the Free Software Foundation, Inc., - 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. - -Also add information on how to contact you by electronic and paper mail. - -If the program is interactive, make it output a short notice like this -when it starts in an interactive mode: - - Gnomovision version 69, Copyright (C) year name of author - Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, the commands you use may -be called something other than `show w' and `show c'; they could even be -mouse-clicks or menu items--whatever suits your program. - -You should also get your employer (if you work as a programmer) or your -school, if any, to sign a "copyright disclaimer" for the program, if -necessary. Here is a sample; alter the names: - - Yoyodyne, Inc., hereby disclaims all copyright interest in the program - `Gnomovision' (which makes passes at compilers) written by James Hacker. - - {signature of Ty Coon}, 1 April 1989 - Ty Coon, President of Vice - -This General Public License does not permit incorporating your program into -proprietary programs. If your program is a subroutine library, you may -consider it more useful to permit linking proprietary applications with the -library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. +Software License Agreement (BSD License) + +Copyright (c) 2014, ROBOTIS Inc. +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 ROBOTIS "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 ROBOTIS 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. \ No newline at end of file diff --git a/README.md b/README.md deleted file mode 100644 index 0f54c2f9734b65b5cf4351919608305aac9198c3..0000000000000000000000000000000000000000 --- a/README.md +++ /dev/null @@ -1 +0,0 @@ -#ROBOTIS Dynamixel SDK \ No newline at end of file diff --git a/c++/build/linux/Makefile b/c++/build/linux/Makefile deleted file mode 100644 index 58dc54e267b193a7999563a62a28c1f571d69919..0000000000000000000000000000000000000000 --- a/c++/build/linux/Makefile +++ /dev/null @@ -1,121 +0,0 @@ -################################################## -# PROJECT: DynamixelSDK - ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# C++ COMPILER, COMPILER FLAGS, AND TARGET PROGRAM NAME -#--------------------------------------------------------------------- -DIR_DXL = ../.. -DIR_OBJS = ./.objects - -INSTALL_ROOT = /usr/local - -MAJ_VERSION = 2 -MIN_VERSION = 0 -REV_VERSION = 0 - -TARGET = libdxl.so -TARGET1 = $(TARGET).$(MAJ_VERSION) -TARGET2 = $(TARGET).$(MAJ_VERSION).$(MIN_VERSION) -TARGET3 = $(TARGET).$(MAJ_VERSION).$(MIN_VERSION).$(REV_VERSION) - -CHK_DIR_EXISTS = test -d -PRINT = echo -STRIP = strip -AR = ar -ARFLAGS = cr -LD = g++ -LDFLAGS = -shared -fPIC #-Wl,-soname,dxl -LD_CONFIG = ldconfig -CP = cp -CP_ALL = cp -r -RM = rm -RM_ALL = rm -rf -SYMLINK = ln -s -MKDIR = mkdir -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) -fPIC -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall -c $(INCLUDES) -fPIC -g -# CXFLAGS += -DDEBUG -INCLUDES += -I$(DIR_DXL)/include - -#--------------------------------------------------------------------- -# Required external libraries -#--------------------------------------------------------------------- -#LIBRARIES += -lrt - -#--------------------------------------------------------------------- -# SDK Files -#--------------------------------------------------------------------- -SOURCES = src/dynamixel_sdk/GroupBulkRead.cpp \ - src/dynamixel_sdk/GroupBulkWrite.cpp \ - src/dynamixel_sdk/GroupSyncRead.cpp \ - src/dynamixel_sdk/GroupSyncWrite.cpp \ - src/dynamixel_sdk/PacketHandler.cpp \ - src/dynamixel_sdk/PortHandler.cpp \ - src/dynamixel_sdk/Protocol1PacketHandler.cpp \ - src/dynamixel_sdk/Protocol2PacketHandler.cpp \ - src/dynamixel_sdk_linux/PortHandlerLinux.cpp \ - - -OBJECTS=$(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) - - -#--------------------------------------------------------------------- -# COMPILING RULES -#--------------------------------------------------------------------- -$(TARGET): makedirs $(OBJECTS) - $(LD) $(LDFLAGS) -o ./$(TARGET) $(OBJECTS) $(LIBS) - -makedirs: - mkdir -p $(DIR_OBJS)/ - -clean: - rm -f $(OBJECTS) ./$(TARGET) - -install: $(TARGET) - # copy the binaries into the lib directory - @$(CHK_DIR_EXISTS) $(INSTALL_ROOT)/lib || $(MKDIR) $(INSTALL_ROOT)/lib - -$(CP) "./$(TARGET)" "$(INSTALL_ROOT)/lib/$(TARGET)" - -$(SYMLINK) "$(INSTALL_ROOT)/lib/$(TARGET)" "$(INSTALL_ROOT)/lib/$(TARGET1)" - -$(SYMLINK) "$(INSTALL_ROOT)/lib/$(TARGET)" "$(INSTALL_ROOT)/lib/$(TARGET2)" - -$(SYMLINK) "$(INSTALL_ROOT)/lib/$(TARGET)" "$(INSTALL_ROOT)/lib/$(TARGET3)" - - # copy the headers into the include directory - @$(CHK_DIR_EXISTS) $(INSTALL_ROOT)/include || $(MKDIR) $(INSTALL_ROOT)/include - $(CP_ALL) $(DIR_DXL)/include/* $(INSTALL_ROOT)/include/ - - $(LD_CONFIG) - -uninstall: - $(RM) $(INSTALL_ROOT)/lib/$(TARGET) - $(RM) $(INSTALL_ROOT)/lib/$(TARGET1) - $(RM) $(INSTALL_ROOT)/lib/$(TARGET2) - $(RM) $(INSTALL_ROOT)/lib/$(TARGET3) - - $(RM) $(INSTALL_ROOT)/include/DynamixelSDK.h - $(RM_ALL) $(INSTALL_ROOT)/include/dynamixel_sdk* - -reinstall: uninstall install - - -#--------------------------------------------------------------------- -# Make rules for all .c and .cpp files in each directory -#--------------------------------------------------------------------- - -$(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk/%.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk/%.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk_linux/%.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: $(DIR_DXL)/src/dynamixel_sdk_linux/%.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# END OF MAKEFILE -#--------------------------------------------------------------------- diff --git a/c++/example/DXLMonitor/DXLMonitor.cpp b/c++/example/DXLMonitor/DXLMonitor.cpp index 613988c8998b1402adb1ecdcb89c323c3663c412..08cea0928ed1e8f7444d6b7602b537c268d423a7 100644 --- a/c++/example/DXLMonitor/DXLMonitor.cpp +++ b/c++/example/DXLMonitor/DXLMonitor.cpp @@ -9,9 +9,9 @@ // ********* DXL Monitor Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 and 2.0 -// This example is tested with a DXL MX-28, a DXL PRO 54-200 and an USB2DYNAMIXEL -// Be sure that properties of DXL MX and PRO are already set as %% MX - ID : 1 / Baudnum : 1 (Baudrate : 1000000) , PRO - ID : 1 / Baudnum : 3 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 and 2.0 +// This example is tested with a Dynamixel MX-28, a Dynamixel PRO 54-200 and an USB2DYNAMIXEL +// Be sure that properties of Dynamixel MX and PRO are already set as %% MX - ID : 1 / Baudnum : 1 (Baudrate : 1000000) , PRO - ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ @@ -19,22 +19,25 @@ #include <fcntl.h> #include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> #include <stdlib.h> #include <string.h> #include <vector> -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Protocol version -#define PROTOCOL_VERSION1 1.0 +#define PROTOCOL_VERSION1 1.0 // See which protocol version is used in the Dynamixel #define PROTOCOL_VERSION2 2.0 // Default setting -#define DEFAULT_DEV_NAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -83,7 +86,7 @@ void Usage(char *progname) printf("-----------------------------------------------------------------------\n"); printf("Usage: %s\n" \ " [-h | --help]........: display this help\n" \ - " [-d | --device]......: port to open (/dev/ttyUSB0)\n" \ + " [-d | --device]......: port to open \n" \ , progname); printf("-----------------------------------------------------------------------\n"); } @@ -101,11 +104,11 @@ void Help() printf(" ex) baud 2400 (2400 bps) \n"); printf(" ex) baud 1000000 (1 Mbps) \n"); printf(" exit :Exit this program\n"); - printf(" scan :Outputs the current status of all DXLs\n"); + printf(" scan :Outputs the current status of all Dynamixels\n"); printf(" ping [ID] [ID] ... :Outputs the current status of [ID]s \n"); - printf(" bp :Broadcast ping (DXL Protocol 2.0 only)\n"); + printf(" bp :Broadcast ping (Dynamixel Protocol 2.0 only)\n"); printf(" \n"); - printf(" ==================== Commands for DXL Protocol 1.0 ====================\n"); + printf(" ==================== Commands for Dynamixel Protocol 1.0 ====================\n"); printf(" \n"); printf(" wrb1|w1 [ID] [ADDR] [VALUE] :Write byte [VALUE] to [ADDR] of [ID]\n"); printf(" wrw1 [ID] [ADDR] [VALUE] :Write word [VALUE] to [ADDR] of [ID]\n"); @@ -115,7 +118,7 @@ void Help() printf(" ([LENGTH] bytes from [ADDR])\n"); printf(" reset1|rst1 [ID] :Factory reset the Dynamixel of [ID]\n"); printf(" \n"); - printf(" ==================== Commands for DXL Protocol 2.0 ====================\n"); + printf(" ==================== Commands for Dynamixel Protocol 2.0 ====================\n"); printf(" \n"); printf(" wrb2|w2 [ID] [ADDR] [VALUE] :Write byte [VALUE] to [ADDR] of [ID]\n"); printf(" wrw2 [ID] [ADDR] [VALUE] :Write word [VALUE] to [ADDR] of [ID]\n"); @@ -138,7 +141,7 @@ void Scan(PortHandler *portHandler, PacketHandler* packetHandler1, PacketHandler UINT16_T dxl_model_num; fprintf(stderr, "\n"); - fprintf(stderr, "Scan DXL Using Protocol 1.0\n"); + fprintf(stderr, "Scan Dynamixel Using Protocol 1.0\n"); for(int id = 1; id < 253; id++) { if( packetHandler1-> Ping(portHandler, id, &dxl_model_num, &dxl_error)== COMM_SUCCESS) @@ -159,7 +162,7 @@ void Scan(PortHandler *portHandler, PacketHandler* packetHandler1, PacketHandler } fprintf(stderr, "\n\n"); - fprintf(stderr, "Scan DXL Using Protocol 2.0\n"); + fprintf(stderr, "Scan Dynamixel Using Protocol 2.0\n"); for(int id = 1; id < 253; id++) { if(packetHandler2-> Ping(portHandler, id, &dxl_model_num, &dxl_error)== COMM_SUCCESS) @@ -210,11 +213,11 @@ void Write(PortHandler *portHandler, PacketHandler *packetHandler, UINT8_T id, U void Read(PortHandler *portHandler, PacketHandler *packetHandler, UINT8_T id, UINT16_T addr, UINT16_T length) { UINT8_T dxl_error = 0; - int dxl_comm_result = COMM_TX_FAIL; + int dxl_comm_result = COMM_TX_FAIL; - INT8_T value8 = 0; - INT16_T value16 = 0; - INT32_T value32 = 0; + INT8_T value8 = 0; + INT16_T value16 = 0; + INT32_T value32 = 0; if(length == 1) @@ -245,9 +248,9 @@ void Read(PortHandler *portHandler, PacketHandler *packetHandler, UINT8_T id, UI void Dump(PortHandler *portHandler, PacketHandler *packetHandler, UINT8_T id, UINT16_T addr, UINT16_T len) { - UINT8_T dxl_error = 0; - int dxl_comm_result = COMM_TX_FAIL; - UINT8_T* data = (UINT8_T*)calloc(len, sizeof(UINT8_T)); + UINT8_T dxl_error = 0; + int dxl_comm_result = COMM_TX_FAIL; + UINT8_T* data = (UINT8_T*)calloc(len, sizeof(UINT8_T)); dxl_comm_result = packetHandler->ReadTxRx(portHandler, id, addr, len, data, &dxl_error); if(dxl_comm_result == COMM_SUCCESS) @@ -284,19 +287,20 @@ int main(int argc, char *argv[]) fprintf(stderr, "* DXL Monitor *\n"); fprintf(stderr, "***********************************************************************\n\n"); - char *dev_name = (char*)DEFAULT_DEV_NAME; + char *dev_name = (char*)DEVICENAME; +#ifdef __linux__ /* parameter parsing */ while(1) { - int option_index = 0, c = 0; - static struct option long_options[] = { + int option_index = 0, c = 0; + static struct option long_options[] = { {"h", no_argument, 0, 0}, {"help", no_argument, 0, 0}, {"d", required_argument, 0, 0}, {"device", required_argument, 0, 0}, {0, 0, 0, 0} - }; + }; /* parsing all parameters according to the list above is sufficent */ c = getopt_long_only(argc, argv, "", long_options, &option_index); @@ -306,7 +310,7 @@ int main(int argc, char *argv[]) /* unrecognized option */ if(c == '?') { - Usage(argv[0]); + Usage(argv[0]); return 0; } @@ -315,7 +319,7 @@ int main(int argc, char *argv[]) /* h, help */ case 0: case 1: - Usage(argv[0]); + Usage(argv[0]); return 0; break; @@ -333,15 +337,16 @@ int main(int argc, char *argv[]) break; default: - Usage(argv[0]); + Usage(argv[0]); return 0; } } +#endif - // Initialize PortHandler instance - // Set the port path - // Get methods and members of PortHandlerLinux or PortHandlerWindows - PortHandler *portHandler = PortHandler::GetPortHandler(dev_name); + // Initialize PortHandler instance + // Set the port path + // Get methods and members of PortHandlerLinux or PortHandlerWindows + PortHandler *portHandler = PortHandler::GetPortHandler(dev_name); // Open port if(portHandler->OpenPort()) @@ -358,11 +363,11 @@ int main(int argc, char *argv[]) return 0; } - char input[128]; - char cmd[80]; - char param[20][30]; - int num_param; - char* token; + char input[128]; + char cmd[80]; + char param[20][30]; + int num_param; + char* token; UINT8_T dxl_error; while(1) diff --git a/c++/example/DXLMonitor/Makefile b/c++/example/DXLMonitor/Makefile deleted file mode 100644 index 497d93ab2d163f83709ccf61f9751a11a7da9899..0000000000000000000000000000000000000000 --- a/c++/example/DXLMonitor/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Monitor tool Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = DXLMonitor - -# important directories used by assorted rules and other variables -DIR_DXL = ../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = DXLMonitor.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/BulkRead/BulkRead.cpp b/c++/example/Protocol1.0/BulkRead/BulkRead.cpp index f45a72edd353742dcb718555899efcd31ccb6310..93cfc9568ace19cb09af87a6a303f0c9b10dc169 100644 --- a/c++/example/Protocol1.0/BulkRead/BulkRead.cpp +++ b/c++/example/Protocol1.0/BulkRead/BulkRead.cpp @@ -9,48 +9,52 @@ // ********* Bulk Read Example ********* // // -// Available DXL model on this example : MX or X series set to Protocol 1.0 -// This example is tested with two DXL MX-28, and an USB2DYNAMIXEL -// Be sure that DXL MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) +// Available Dynamixel model on this example : MX or X series set to Protocol 1.0 +// This example is tested with two Dynamixel MX-28, and an USB2DYNAMIXEL +// Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) // - #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_MX_TORQUE_ENABLE 24 +#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model #define ADDR_MX_GOAL_POSITION 30 #define ADDR_MX_PRESENT_POSITION 36 #define ADDR_MX_MOVING 46 // Data Byte Length -#define LEN_MX_TORQUE_ENABLE 1 #define LEN_MX_GOAL_POSITION 2 #define LEN_MX_PRESENT_POSITION 2 #define LEN_MX_MOVING 1 // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold -#define STOP_MOVING_MARGIN 10 // Criteria for considering DXL moving status as stopped +#define ESC_ASCII_VALUE 0x1b -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -102,22 +106,22 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); // Initialize Groupbulkread instance GroupBulkRead groupBulkRead(portHandler, packetHandler); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_addparam_result = false; // AddParam result - int dxl_getdata_result = false; // GetParam result - int dxl_goal_position[2] = {100, 1000}; // Goal position + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // AddParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - UINT8_T dxl_moving2 = 0; // DXL moving status - UINT16_T dxl_present_position1 = 0; // Present position + UINT8_T dxl_error = 0; // Dynamixel error + UINT16_T dxl1_present_position = 0; // Present position + UINT8_T dxl2_moving = 0; // Dynamixel moving status // Open port if( portHandler->OpenPort() ) @@ -145,25 +149,25 @@ int main() return 0; } - // Enable DXL#1 Torque - dxl_comm_result= packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); - + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); - + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); - // Add parameter storage for DXL#1 present position value + // Add parameter storage for Dynamixel#1 present position value dxl_addparam_result = groupBulkRead.AddParam(DXL1_ID, ADDR_MX_PRESENT_POSITION, LEN_MX_PRESENT_POSITION); if( dxl_addparam_result != true ) { @@ -171,7 +175,7 @@ int main() return 0; } - // Add parameter storage for DXL#2 present moving value + // Add parameter storage for Dynamixel#2 present moving value dxl_addparam_result = groupBulkRead.AddParam(DXL2_ID, ADDR_MX_MOVING, LEN_MX_MOVING); if( dxl_addparam_result != true ) { @@ -181,48 +185,54 @@ int main() while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; - // Write DXL#1 goal position + // Write Dynamixel#1 goal position dxl_comm_result = packetHandler->Write2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Write DXL#2 goal position + // Write Dynamixel#2 goal position dxl_comm_result = packetHandler->Write2ByteTxRx(portHandler, DXL2_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - do{ + do + { // Bulkread present position and moving status dxl_comm_result = groupBulkRead.TxRxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - // Get DXL#1 present position value - dxl_getdata_result = groupBulkRead.GetData(DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position1); - if( dxl_getdata_result != true ) + dxl_getdata_result = groupBulkRead.IsAvailable(DXL1_ID, ADDR_MX_PRESENT_POSITION, LEN_MX_PRESENT_POSITION); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupBulkRead getdata failed", DXL1_ID); return 0; } - // Get DXL#2 moving status value - dxl_getdata_result = groupBulkRead.GetData(DXL2_ID, ADDR_MX_MOVING, &dxl_moving2); - if( dxl_getdata_result != true ) + dxl_getdata_result = groupBulkRead.IsAvailable(DXL2_ID, ADDR_MX_MOVING, LEN_MX_MOVING); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupBulkRead getdata failed", DXL2_ID); return 0; } - printf("[ID:%03d] Present Position : %d \t [ID:%03d] Is Moving : %d\n", DXL1_ID, dxl_present_position1, DXL2_ID, dxl_moving2); - }while((abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN) || (dxl_moving2 == 1)); + // Get Dynamixel#1 present position value + dxl1_present_position = groupBulkRead.GetData(DXL1_ID, ADDR_MX_PRESENT_POSITION, LEN_MX_PRESENT_POSITION); + + // Get Dynamixel#2 moving status value + dxl2_moving = groupBulkRead.GetData(DXL2_ID, ADDR_MX_MOVING, LEN_MX_MOVING); + + printf("[ID:%03d] Present Position : %d \t [ID:%03d] Is Moving : %d\n", DXL1_ID, dxl1_present_position, DXL2_ID, dxl2_moving); + + }while(abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD); // Change goal position if( index == 0 ) @@ -230,18 +240,16 @@ int main() else index = 0; } - // Clear bulkread parameter storage - groupBulkRead.ClearParam(); - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -250,7 +258,5 @@ int main() // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol1.0/BulkRead/Makefile b/c++/example/Protocol1.0/BulkRead/Makefile deleted file mode 100644 index 3158f3b5cecdc45ff76bf20d974dd89c1e879feb..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/BulkRead/Makefile +++ /dev/null @@ -1,79 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 BulkRead Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = BulkRead - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = BulkRead.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/MultiPort/Makefile b/c++/example/Protocol1.0/MultiPort/Makefile deleted file mode 100644 index 0455dd1c3cf46453404212ee5249d9271ec2d55a..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/MultiPort/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 MultiPort Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = MultiPort - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = MultiPort.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/MultiPort/MultiPort.cpp b/c++/example/Protocol1.0/MultiPort/MultiPort.cpp index 264391ee9c5d660e3a09c2a6de88d6e841f19c85..10dbabcfc0dd14ec6553d52b4fa7bc451cc107ee 100644 --- a/c++/example/Protocol1.0/MultiPort/MultiPort.cpp +++ b/c++/example/Protocol1.0/MultiPort/MultiPort.cpp @@ -9,42 +9,47 @@ // ********* Multi Port Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 -// This example is tested with a DXL MX-28, and two USB2DYNAMIXEL -// Be sure that DXL MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 +// This example is tested with a Dynamixel MX-28, and two USB2DYNAMIXEL +// Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_MX_TORQUE_ENABLE 24 +#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model #define ADDR_MX_GOAL_POSITION 30 #define ADDR_MX_PRESENT_POSITION 36 // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME1 "/dev/ttyUSB0" -#define DEVICENAME2 "/dev/ttyUSB1" +#define DEVICENAME1 "/dev/ttyUSB0" // Check which port is being used on your controller +#define DEVICENAME2 "/dev/ttyUSB1" // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define STOP_MOVING_MARGIN 10 // Criteria for considering DXL moving status as stopped +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold -using namespace ROBOTIS; +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -90,23 +95,24 @@ int _kbhit(void) int main() { - // Initialize Porthandlers instance + // Initialize PortHandler instance // Set the port path // Get methods and members of PortHandlerLinux or PortHandlerWindows PortHandler *portHandler1 = PortHandler::GetPortHandler(DEVICENAME1); PortHandler *portHandler2 = PortHandler::GetPortHandler(DEVICENAME2); + // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_goal_position[2] = {100, 1000}; // Goal position + int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - UINT16_T dxl_present_position1 = 0, dxl_present_position2 = 0; // Present position + UINT8_T dxl_error = 0; // Dynamixel error + UINT16_T dxl1_present_position = 0, dxl2_present_position = 0; // Present position // Open port1 if( portHandler1->OpenPort() ) @@ -137,7 +143,7 @@ int main() // Set port1 baudrate if(portHandler1->SetBaudRate(BAUDRATE) ) { - printf( "Succeed to change the baudrate port1!\n" ); + printf( "Succeed to change the baudrate port1!\n" ); } else { @@ -150,7 +156,7 @@ int main() // Set port2 baudrate if(portHandler2->SetBaudRate(BAUDRATE) ) { - printf( "Succeed to change the baudrate port2!\n" ); + printf( "Succeed to change the baudrate port2!\n" ); } else { @@ -160,36 +166,39 @@ int main() return 0; } - // Enable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; - // Write DXL#1 goal position + // Write Dynamixel#1 goal position dxl_comm_result = packetHandler->Write2ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Write DXL#2 goal position + // Write Dynamixel#2 goal position dxl_comm_result = packetHandler->Write2ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); @@ -198,22 +207,23 @@ int main() do { - // Read DXL#1 present position - dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position1, &dxl_error); + // Read Dynamixel#1 present position + dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl1_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Read DXL#2 present position - dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position2, &dxl_error); + // Read Dynamixel#2 present position + dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_PRESENT_POSITION, &dxl2_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl_present_position1, DXL2_ID, dxl_goal_position[index], dxl_present_position2); - }while((abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN) || (abs(dxl_goal_position[index] - dxl_present_position2) > STOP_MOVING_MARGIN)); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position); + + }while((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -222,15 +232,15 @@ int main() index = 0; } - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Unable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -242,7 +252,5 @@ int main() // Close port2 portHandler2->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol1.0/Ping/Makefile b/c++/example/Protocol1.0/Ping/Makefile deleted file mode 100644 index f9206dea44a9a9da1e09baced3c74a05774ba6a9..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/Ping/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 Ping Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = Ping - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = Ping.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/Ping/Ping.cpp b/c++/example/Protocol1.0/Ping/Ping.cpp index 92dfda6961808e0bd8b92a8a6db8ebe94704b1b8..ec3d7cc100572d2d549ba9e6c6174efa2ffa5cbb 100644 --- a/c++/example/Protocol1.0/Ping/Ping.cpp +++ b/c++/example/Protocol1.0/Ping/Ping.cpp @@ -9,33 +9,32 @@ // ********* Ping Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 -// This example is tested with a DXL MX-28, and an USB2DYNAMIXEL -// Be sure that DXL MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 +// This example is tested with a Dynamixel MX-28, and an USB2DYNAMIXEL +// Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> -#include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -87,12 +86,14 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_comm_result = COMM_TX_FAIL; // Communication result - UINT8_T dxl_error = 0; // DXL error - UINT16_T dxl_model_number; // DXL model number + UINT8_T dxl_error = 0; // Dynamixel error + UINT16_T dxl_model_number; // Dynamixel model number // Open port if( portHandler->OpenPort() ) @@ -120,20 +121,18 @@ int main() return 0; } - // Try to ping the DXL - // Get DXL model number from the DXL + // Try to ping the Dynamixel + // Get Dynamixel model number dxl_comm_result = packetHandler->Ping(portHandler, DXL_ID, &dxl_model_number, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] Ping Succeeded. DXL model number : %d\n", DXL_ID, dxl_model_number); + printf("[ID:%03d] Ping Succeeded. Dynamixel model number : %d\n", DXL_ID, dxl_model_number); // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol1.0/ReadWrite/Makefile b/c++/example/Protocol1.0/ReadWrite/Makefile deleted file mode 100644 index 04a2f4bf453b01112c30c1cbdc09716090e2ede7..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/ReadWrite/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 Read/Write Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = ReadWrite - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = ReadWrite.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/ReadWrite/ReadWrite.cpp b/c++/example/Protocol1.0/ReadWrite/ReadWrite.cpp index 1049cc67c0f168f617815eae74d610815bb2a8f8..d17b4e047573bc806259ca48286cbacddc74319f 100644 --- a/c++/example/Protocol1.0/ReadWrite/ReadWrite.cpp +++ b/c++/example/Protocol1.0/ReadWrite/ReadWrite.cpp @@ -17,31 +17,38 @@ #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_MX_TORQUE_ENABLE 24 +#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model #define ADDR_MX_GOAL_POSITION 30 #define ADDR_MX_PRESENT_POSITION 36 -#define ADDR_MX_MOVING 46 // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold + +#define ESC_ASCII_VALUE 0x1b -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -93,16 +100,15 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); int index = 0; int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_goal_position[2] = {100, 1000}; // Goal position + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Torque unable - UINT8_T dxl_error = 0; // DXL error - UINT8_T dxl_moving = 0; // DXL moving status + UINT8_T dxl_error = 0; // Dynamixel error UINT16_T dxl_present_position = 0; // Present position // Open port @@ -132,16 +138,18 @@ int main() } // Enable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("Dynamixel has been successfully connected \n"); while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Write goal position @@ -162,13 +170,7 @@ int main() printf("[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL_ID, dxl_goal_position[index], dxl_present_position); - // Read Moving status - dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_MX_MOVING, &dxl_moving, &dxl_error); - if(dxl_comm_result != COMM_SUCCESS) - packetHandler->PrintTxRxResult(dxl_comm_result); - else if(dxl_error != 0) - packetHandler->PrintRxPacketError(dxl_error); - }while(dxl_moving == 1); + }while((abs(dxl_goal_position[index] - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -177,8 +179,8 @@ int main() index = 0; } - // Disable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -187,7 +189,5 @@ int main() // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol1.0/Reset/Makefile b/c++/example/Protocol1.0/Reset/Makefile deleted file mode 100644 index 23fe5a84d763efd3d421e725dc883e4ef6016055..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/Reset/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 Reset Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = Reset - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = Reset.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/Reset/Reset.cpp b/c++/example/Protocol1.0/Reset/Reset.cpp index 6f35fe69f5bca5fe37901f9dc5ea645eedc3d3a7..7a602eed1a0187a51bb8bdb597b3356602119ec0 100644 --- a/c++/example/Protocol1.0/Reset/Reset.cpp +++ b/c++/example/Protocol1.0/Reset/Reset.cpp @@ -9,44 +9,46 @@ // ********* Factory Reset Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 -// This example is tested with a DXL MX-28, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 +// This example is tested with a Dynamixel MX-28, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) // // Be aware that: -// This example resets all properties of DXL to default values, such as %% ID : 1 / Baudnum : 34 (Baudrate : 57600) +// This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 34 (Baudrate : 57600) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> -#include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_MX_BAUDRATE 4 +#define ADDR_MX_BAUDRATE 4 // Control table address is different in Dynamixel model // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" + +#define FACTORYRST_DEFAULTBAUDRATE 57600 // Dynamixel baudrate set by factoryreset +#define NEW_BAUDNUM 1 // New baudnum to recover Dynamixel baudrate as it was +#define OPERATION_MODE 0x00 // Mode is unavailable in Protocol 1.0 Reset -#define FACTORYRST_DEFAULTBAUDRATE 57600 // DXL baudrate set by factoryreset -#define NEW_BAUDNUM 1 // New baudnum to recover DXL baudrate as it was -#define OPERATION_MODE 0x00 // Mode is unavailable in Protocol 1.0 Reset +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -90,6 +92,15 @@ int _kbhit(void) } #endif +void msecSleep(int waitTime) +{ +#ifdef __linux__ + usleep(waitTime * 1000); +#elif defined(_WIN32) || defined(_WIN64) + Sleep(waitTime); +#endif +} + int main() { // Initialize PortHandler instance @@ -98,12 +109,14 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_comm_result = COMM_TX_FAIL; // Communication result - UINT8_T dxl_baudnum_read; // Read baudnum - UINT8_T dxl_error = 0; // DXL error + UINT8_T dxl_error = 0; // Dynamixel error + UINT8_T dxl_baudnum_read; // Read baudnum // Open port if( portHandler->OpenPort() ) @@ -148,14 +161,14 @@ int main() // Wait for reset printf("Wait for reset...\n"); - usleep(2000 * 1000); + msecSleep(2000); - printf("[ID:%03d] FactoryReset Success!\n", DXL_ID); + printf("[ID:%03d] FactoryReset Success!\n", DXL_ID); - // Set controller baudrate to dxl default baudrate + // Set controller baudrate to dxl default baudrate if(portHandler->SetBaudRate(FACTORYRST_DEFAULTBAUDRATE)) { - printf( "Succeed to change the controller baudrate to : %d\n", FACTORYRST_DEFAULTBAUDRATE ); + printf( "Succeed to change the controller baudrate to : %d\n", FACTORYRST_DEFAULTBAUDRATE ); } else { @@ -165,27 +178,23 @@ int main() return 0; } - // Read DXL baudnum + // Read Dynamixel baudnum dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_MX_BAUDRATE, &dxl_baudnum_read, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) - { packetHandler->PrintTxRxResult(dxl_comm_result); - return 0; - } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] DXL baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); + else + printf("[ID:%03d] Dynamixel baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); // Write new baudnum dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_MX_BAUDRATE, NEW_BAUDNUM, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) - { packetHandler->PrintTxRxResult(dxl_comm_result); - return 0; - } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] Set DXL baudnum to : %d\n", DXL_ID, NEW_BAUDNUM); + else + printf("[ID:%03d] Set Dynamixel baudnum to : %d\n", DXL_ID, NEW_BAUDNUM); // Set port baudrate to BAUDRATE if(portHandler->SetBaudRate(BAUDRATE)) @@ -200,23 +209,19 @@ int main() return 0; } - usleep(200 * 1000); + msecSleep(200); - // Read DXL baudnum + // Read Dynamixel baudnum dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_MX_BAUDRATE, &dxl_baudnum_read, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) - { packetHandler->PrintTxRxResult(dxl_comm_result); - return 0; - } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] DXL Baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); + else + printf("[ID:%03d] Dynamixel Baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol1.0/SyncWrite/Makefile b/c++/example/Protocol1.0/SyncWrite/Makefile deleted file mode 100644 index ac4fc759836baf1f1ada2b709b64066f39d1b91c..0000000000000000000000000000000000000000 --- a/c++/example/Protocol1.0/SyncWrite/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 1.0 SyncWrite Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = SyncWrite - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = SyncWrite.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol1.0/SyncWrite/SyncWrite.cpp b/c++/example/Protocol1.0/SyncWrite/SyncWrite.cpp index 4652444e82663b7f652c8881e04d93fc104fca43..00d5a457b95d2f09693c1c318c851aea2e62e2e2 100644 --- a/c++/example/Protocol1.0/SyncWrite/SyncWrite.cpp +++ b/c++/example/Protocol1.0/SyncWrite/SyncWrite.cpp @@ -9,45 +9,51 @@ // ********* Sync Write Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 -// This example is tested with two DXL MX-28, and an USB2DYNAMIXEL -// Be sure that DXL MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 +// This example is tested with two Dynamixel MX-28, and an USB2DYNAMIXEL +// Be sure that Dynamixel MX properties are already set as %% ID : 1 / Baudnum : 1 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_MX_TORQUE_ENABLE 24 +#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model #define ADDR_MX_GOAL_POSITION 30 #define ADDR_MX_PRESENT_POSITION 36 // Data Byte Length -#define LEN_MX_TORQUE_ENABLE 1 #define LEN_MX_GOAL_POSITION 2 #define LEN_MX_PRESENT_POSITION 2 // Protocol version -#define PROTOCOL_VERSION 1.0 +#define PROTOCOL_VERSION 1.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define STOP_MOVING_MARGIN 10 // Criteria for considering DXL moving status as stopped +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 10 // Dynamixel moving status threshold -using namespace ROBOTIS; +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -99,21 +105,21 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); // Initialize Groupsyncwrite instance - GroupSyncWrite groupSyncWrite_GoalPos(portHandler, packetHandler, ADDR_MX_GOAL_POSITION, LEN_MX_GOAL_POSITION); + GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_MX_GOAL_POSITION, LEN_MX_GOAL_POSITION); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_addparam_result = false; // AddParam result - int dxl_goal_position[2] = {100, 1000}; // Goal position + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // AddParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error + UINT8_T dxl_error = 0; // Dynamixel error UINT8_T param_goal_position[2]; - UINT16_T dxl_present_position1, dxl_present_position2; // Present position + UINT16_T dxl1_present_position = 0, dxl2_present_position = 0; // Present position // Open port if( portHandler->OpenPort() ) @@ -141,48 +147,44 @@ int main() return 0; } - // Enable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) - { packetHandler->PrintTxRxResult(dxl_comm_result); - return 0; - } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) - { packetHandler->PrintTxRxResult(dxl_comm_result); - return 0; - } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Allocate goal position value into byte array param_goal_position[0] = DXL_LOBYTE(dxl_goal_position[index]); param_goal_position[1] = DXL_HIBYTE(dxl_goal_position[index]); - // Add DXL#1 goal position value to the Syncwrite storage - dxl_addparam_result = groupSyncWrite_GoalPos.AddParam(DXL1_ID, param_goal_position); + // Add Dynamixel#1 goal position value to the Syncwrite storage + dxl_addparam_result = groupSyncWrite.AddParam(DXL1_ID, param_goal_position); if( dxl_addparam_result != true ) { fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID); return 0; } - // Add DXL#2 goal position value to the Syncwrite parameter storage - dxl_addparam_result = groupSyncWrite_GoalPos.AddParam(DXL2_ID, param_goal_position); + // Add Dynamixel#2 goal position value to the Syncwrite parameter storage + dxl_addparam_result = groupSyncWrite.AddParam(DXL2_ID, param_goal_position); if( dxl_addparam_result != true ) { fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID); @@ -190,32 +192,32 @@ int main() } // Syncwrite goal position - dxl_comm_result = groupSyncWrite_GoalPos.TxPacket(); + dxl_comm_result = groupSyncWrite.TxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - else if(dxl_error != 0) - packetHandler->PrintRxPacketError(dxl_error); // Clear syncwrite parameter storage - groupSyncWrite_GoalPos.ClearParam(); + groupSyncWrite.ClearParam(); - do{ - // Read DXL#1 present position - dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position1, &dxl_error); + do + { + // Read Dynamixel#1 present position + dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl1_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Read DXL#2 present position - dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler, DXL2_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position2, &dxl_error); + // Read Dynamixel#2 present position + dxl_comm_result = packetHandler->Read2ByteTxRx(portHandler, DXL2_ID, ADDR_MX_PRESENT_POSITION, &dxl2_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl_present_position1, DXL2_ID, dxl_goal_position[index], dxl_present_position2); - }while((abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN) || (abs(dxl_goal_position[index] - dxl_present_position2) > STOP_MOVING_MARGIN)); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position); + + }while((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -224,24 +226,23 @@ int main() index = 0; } - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/BroadcastPing/BroadcastPing.cpp b/c++/example/Protocol2.0/BroadcastPing/BroadcastPing.cpp index 5747614173906b9299ddcf9f606cd7e39deb7a25..626888b84bd995ce534ee50c197e0746d45280a9 100644 --- a/c++/example/Protocol2.0/BroadcastPing/BroadcastPing.cpp +++ b/c++/example/Protocol2.0/BroadcastPing/BroadcastPing.cpp @@ -9,45 +9,44 @@ // ********* BroadcastPing Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with two DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with two Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> -#include <stdlib.h> -#include <string.h> #include <vector> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() { struct termios oldt, newt; int ch; - tcgetattr(STDIN_FILENO, &oldt); + tcgetattr( STDIN_FILENO, &oldt ); newt = oldt; newt.c_lflag &= ~(ICANON | ECHO); - tcsetattr(STDIN_FILENO, TCSANOW, &newt); + tcsetattr( STDIN_FILENO, TCSANOW, &newt ); ch = getchar(); - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + tcsetattr( STDIN_FILENO, TCSANOW, &oldt ); return ch; } @@ -87,54 +86,53 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_comm_result = COMM_TX_FAIL; // Communication result - std::vector<UINT8_T> vec; // DXL data storages + std::vector<UINT8_T> vec; // Dynamixel data storages // Open port - if(portHandler->OpenPort()) + if( portHandler->OpenPort() ) { - printf("Succeeded to open the port!\n"); + printf( "Succeeded to open the port!\n" ); } else { - printf("Failed to open the port!\n"); - printf("Press any key to terminate...\n"); + printf( "Failed to open the port!\n" ); + printf( "Press any key to terminate...\n" ); _getch(); return 0; } // Set port baudrate - if( portHandler->SetBaudRate(BAUDRATE)) + if( portHandler->SetBaudRate(BAUDRATE) ) { - printf("Succeeded to change the baudrate!\n"); + printf( "Succeeded to change the baudrate!\n" ); } else { - printf("Failed to change the baudrate!\n"); - printf("Press any key to terminate...\n"); + printf( "Failed to change the baudrate!\n" ); + printf( "Press any key to terminate...\n" ); _getch(); return 0; } - // Try to broadcast ping the DXL + // Try to broadcast ping the Dynamixel dxl_comm_result = packetHandler->BroadcastPing(portHandler, vec); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - // Try to broadcastping the DXL - printf("Detected DXL : \n"); + printf("Detected Dynamixel : \n"); for(int i = 0; i < (int)vec.size(); i++) { - printf("[ID:%03d]\n", vec.at(i)); + printf("[ID:%03d]\n", vec.at(i)); } // Close port portHandler->ClosePort(); - printf("Press Enter key to terminate...\n"); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/BroadcastPing/Makefile b/c++/example/Protocol2.0/BroadcastPing/Makefile deleted file mode 100644 index 3cfeffafc9e32f8226390308bf797548c09e97b5..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/BroadcastPing/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 BroadcastPing Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = BroadcastPing - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = BroadcastPing.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/BulkReadWrite/BulkReadWrite.cpp b/c++/example/Protocol2.0/BulkReadWrite/BulkReadWrite.cpp index aa9e2867fb0f5f4d716a819f9e1bf828de1e3a10..301b53569ecf5b6099b6207243d8fd166d44a9ff 100644 --- a/c++/example/Protocol2.0/BulkReadWrite/BulkReadWrite.cpp +++ b/c++/example/Protocol2.0/BulkReadWrite/BulkReadWrite.cpp @@ -9,48 +9,53 @@ // ********* Bulk Read and Bulk Write Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with two DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 and 2 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (DXL hardware error would be occurred when it is supplied by 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with two Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 and 2 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_TORQUE_ENABLE 562 +#define ADDR_PRO_TORQUE_ENABLE 562 // Control table address is different in Dynamixel model #define ADDR_PRO_LED_RED 563 #define ADDR_PRO_GOAL_POSITION 596 #define ADDR_PRO_PRESENT_POSITION 611 // Data Byte Length #define LEN_PRO_LED_RED 1 -#define LEN_PRO_TORQUE_ENABLE 1 #define LEN_PRO_GOAL_POSITION 4 #define LEN_PRO_PRESENT_POSITION 4 // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define STOP_MOVING_MARGIN 20 // Criteria for considering DXL moving status as stopped +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold -using namespace ROBOTIS; +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -102,43 +107,43 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); // Initialize GroupBulkWrite instance GroupBulkWrite groupBulkWrite(portHandler, packetHandler); - // Initialize GroupBulkRead instance + // Initialize Groupbulkread instance GroupBulkRead groupBulkRead(portHandler, packetHandler); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_addparam_result = false; // AddParam result - int dxl_getdata_result = false; // GetParam result - int dxl_goal_position[2] = {-150000, 150000}; // Goal position - - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - UINT8_T dxl_led_value[2] = {0x00, 0xFF}; // DXL LED value for write + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // AddParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position + + UINT8_T dxl_error = 0; // Dynamixel error + UINT8_T dxl_led_value[2] = {0x00, 0xFF}; // Dynamixel LED value for write UINT8_T param_goal_position[4]; - UINT8_T dxl_led_value_read2; // DXL LED value for read - INT32_T dxl_present_position1; // Present position + INT32_T dxl1_present_position = 0; // Present position + UINT8_T dxl2_led_value_read; // Dynamixel LED value for read // Open port if( portHandler->OpenPort() ) { - printf("Succeeded to open the port!\n"); + printf( "Succeeded to open the port!\n" ); } else { - printf("Failed to open the port!\n"); - printf("Press any key to terminate...\n"); + printf( "Failed to open the port!\n" ); + printf( "Press any key to terminate...\n" ); _getch(); return 0; } // Set port baudrate - if(portHandler->SetBaudRate(BAUDRATE)) + if( portHandler->SetBaudRate(BAUDRATE) ) { printf( "Succeeded to change the baudrate!\n" ); } @@ -150,23 +155,25 @@ int main() return 0; } - // Enable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("DXL#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("DXL#%d has been successfully connected \n", DXL2_ID); - // Add parameter storage for DXL#1 present position + // Add parameter storage for Dynamixel#1 present position dxl_addparam_result = groupBulkRead.AddParam(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); if(dxl_addparam_result != true) { @@ -174,18 +181,18 @@ int main() return 0; } - // Add parameter storage for DXL#2 LED value + // Add parameter storage for Dynamixel#2 LED value dxl_addparam_result = groupBulkRead.AddParam(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); if(dxl_addparam_result != true) { - fprintf(stderr, "[ID:%03d] grouBulkRead addparam failed", DXL2_ID); - return 0; + fprintf(stderr, "[ID:%03d] grouBulkRead addparam failed", DXL2_ID); + return 0; } while(1) { - printf("Press Enter key to continue!(press ESC and Enter to quit)\n"); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Allocate goal position value into byte array @@ -194,7 +201,7 @@ int main() param_goal_position[2] = DXL_LOBYTE(DXL_HIWORD(dxl_goal_position[index])); param_goal_position[3] = DXL_HIBYTE(DXL_HIWORD(dxl_goal_position[index])); - // Add parameter storage for DXL#1 goal position + // Add parameter storage for Dynamixel#1 goal position dxl_addparam_result = groupBulkWrite.AddParam(DXL1_ID, ADDR_PRO_GOAL_POSITION, LEN_PRO_GOAL_POSITION, param_goal_position); if(dxl_addparam_result != true) { @@ -202,7 +209,7 @@ int main() return 0; } - // Add parameter storage for DXL#2 LED value + // Add parameter storage for Dynamixel#2 LED value dxl_addparam_result = groupBulkWrite.AddParam(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED, &dxl_led_value[index]); if(dxl_addparam_result != true) { @@ -210,7 +217,7 @@ int main() return 0; } - // Syncwrite goal position and LED value + // Bulkwrite goal position and LED value dxl_comm_result = groupBulkWrite.TxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); @@ -220,51 +227,55 @@ int main() // Clear bulkwrite parameter storage groupBulkWrite.ClearParam(); - do{ - usleep(50*1000); - + do + { // Bulkread present position and LED status dxl_comm_result = groupBulkRead.TxRxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - // Get present position value - dxl_getdata_result = groupBulkRead.GetData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position1); - if(dxl_getdata_result != true) + // Check if groupbulkread data of Dynamixel#1 is available + dxl_getdata_result = groupBulkRead.IsAvailable(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupBulkRead getdata failed", DXL1_ID); return 0; } - // Get LED value - dxl_getdata_result = groupBulkRead.GetData(DXL2_ID, ADDR_PRO_LED_RED, &dxl_led_value_read2); - if(dxl_getdata_result != true) + // Check if groupbulkread data of Dynamixel#2 is available + dxl_getdata_result = groupBulkRead.IsAvailable(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupBulkRead getdata failed", DXL2_ID); return 0; } - printf("[ID:%03d] Present Position : %d \t [ID:%03d] LED Value: %d\n", DXL1_ID, dxl_present_position1, DXL2_ID, dxl_led_value_read2); + // Get present position value + dxl1_present_position = groupBulkRead.GetData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + // Get LED value + dxl2_led_value_read = groupBulkRead.GetData(DXL2_ID, ADDR_PRO_LED_RED, LEN_PRO_LED_RED); + + printf("[ID:%03d] Present Position : %d \t [ID:%03d] LED Value: %d\n", DXL1_ID, dxl1_present_position, DXL2_ID, dxl2_led_value_read); - }while(abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN); + }while(abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD); - if(index == 0) + // Change goal position + if( index == 0 ) index = 1; else index = 0; } - // Clear bulkread parameter storage - groupBulkRead.ClearParam(); - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -273,7 +284,5 @@ int main() // Close port portHandler->ClosePort(); - printf("Press Enter key to terminate...\n"); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/BulkReadWrite/Makefile b/c++/example/Protocol2.0/BulkReadWrite/Makefile deleted file mode 100644 index 6d8b3caef127eabca930067757cd839e6d985227..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/BulkReadWrite/Makefile +++ /dev/null @@ -1,79 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 BulkReadWrite Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = BulkReadWrite - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = BulkReadWrite.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/FactoryReset/FactoryReset.cpp b/c++/example/Protocol2.0/FactoryReset/FactoryReset.cpp index aae5c207e43ff4d650644e9674ae9b5b8622e172..2fdb19de188b40b2331a496371c380d04ab0e478 100644 --- a/c++/example/Protocol2.0/FactoryReset/FactoryReset.cpp +++ b/c++/example/Protocol2.0/FactoryReset/FactoryReset.cpp @@ -9,46 +9,44 @@ // ********* Factory Reset Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with a DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with a Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // // Be aware that: -// This example resets all properties of DXL to default values, such as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) / Min voltage limit : 150 +// This example resets all properties of Dynamixel to default values, such as %% ID : 1 / Baudnum : 1 (Baudrate : 57600) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif - #include <stdio.h> -#include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_BAUDRATE 8 +#define ADDR_PRO_BAUDRATE 8 // Control table address is different in Dynamixel model // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define FACTORYRST_DEFAULTBAUDRATE 57600 // DXL baudrate set by factoryreset -#define NEW_BAUDNUM 3 // New baudnum to recover DXL baudrate as it was -#define OPERATION_MODE 0x01 // 0xFF : reset all values - // 0x01 : reset all values except ID - // 0x02 : reset all values except ID and baudrate +#define FACTORYRST_DEFAULTBAUDRATE 57600 // Dynamixel baudrate set by factoryreset +#define NEW_BAUDNUM 3 // New baudnum to recover Dynamixel baudrate as it was +#define OPERATION_MODE 0x01 // 0xFF : reset all values + // 0x01 : reset all values except ID + // 0x02 : reset all values except ID and baudrate -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -92,6 +90,15 @@ int _kbhit(void) } #endif +void msecSleep(int waitTime) +{ +#ifdef __linux__ + usleep(waitTime * 1000); +#elif defined(_WIN32) || defined(_WIN64) + Sleep(waitTime); +#endif +} + int main() { // Initialize PortHandler instance @@ -100,12 +107,14 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_comm_result = COMM_TX_FAIL; // Communication result - UINT8_T dxl_baudnum_read; // Read baudnum - UINT8_T dxl_error = 0; // DXL error + UINT8_T dxl_error = 0; // Dynamixel error + UINT8_T dxl_baudnum_read; // Read baudnum // Open port if( portHandler->OpenPort() ) @@ -140,20 +149,24 @@ int main() printf("[ID:%03d] Try factoryreset : ", DXL_ID); dxl_comm_result = packetHandler->FactoryReset(portHandler, DXL_ID, OPERATION_MODE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) + { + printf("Aborted\n"); packetHandler->PrintTxRxResult(dxl_comm_result); + return 0; + } else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); // Wait for reset printf("Wait for reset...\n"); - usleep(2000 * 1000); + msecSleep(2000); printf("[ID:%03d] FactoryReset Success!\n", DXL_ID); - // Set port baudrate to factoryreset default baudrate + // Set controller baudrate to Dynamixel default baudrate if(portHandler->SetBaudRate(FACTORYRST_DEFAULTBAUDRATE)) { - printf( "Succeed to change the controller baudrate to : %d\n", FACTORYRST_DEFAULTBAUDRATE ); + printf( "Succeed to change the controller baudrate to : %d\n", FACTORYRST_DEFAULTBAUDRATE ); } else { @@ -163,12 +176,14 @@ int main() return 0; } - // Read DXL baudnum + // Read Dynamixel baudnum dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_BAUDRATE, &dxl_baudnum_read, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("[ID:%03d] DXL baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); // Write new baudnum dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_BAUDRATE, NEW_BAUDNUM, &dxl_error); @@ -176,11 +191,13 @@ int main() packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("[ID:%03d] Set Dynamixel baudnum to : %d\n", DXL_ID, NEW_BAUDNUM); - // Set controller baudrate to 1000000 + // Set port baudrate to BAUDRATE if(portHandler->SetBaudRate(BAUDRATE)) { - printf( "Succeed to change the controller baudrate to : %d\n", BAUDRATE ); + printf( "Succeed to change the controller baudrate to : %d\n", BAUDRATE ); } else { @@ -190,17 +207,19 @@ int main() return 0; } - // Read DXL baudnum + msecSleep(200); + + // Read Dynamixel baudnum dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_BAUDRATE, &dxl_baudnum_read, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("[ID:%03d] Dynamixel Baudnum is now : %d\n", DXL_ID, dxl_baudnum_read); // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/FactoryReset/Makefile b/c++/example/Protocol2.0/FactoryReset/Makefile deleted file mode 100644 index a95eabb65e0ba8eea468210aee4741391b41fcbc..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/FactoryReset/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 FactoryReset Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = FactoryReset - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = FactoryReset.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/IndirectAddress/IndirectAddress.cpp b/c++/example/Protocol2.0/IndirectAddress/IndirectAddress.cpp index a60314e82e01fd408b9577fe4488242532fd1ef8..3565f5445918d10bb25b63b92f407906a657c26a 100644 --- a/c++/example/Protocol2.0/IndirectAddress/IndirectAddress.cpp +++ b/c++/example/Protocol2.0/IndirectAddress/IndirectAddress.cpp @@ -9,27 +9,27 @@ // ********* Indirect Address Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with a DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (DXL hardware error would be occurred when it is supplied by 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with a Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_INDIRECTADDRESS_FOR_WRITE 49 // EEPROM region -#define ADDR_PRO_INDIRECTADDRESS_FOR_READ 59 // EEPROM region +// Control table address is different in Dynamixel model +#define ADDR_PRO_INDIRECTADDRESS_FOR_WRITE 49 // EEPROM region +#define ADDR_PRO_INDIRECTADDRESS_FOR_READ 59 // EEPROM region #define ADDR_PRO_TORQUE_ENABLE 562 #define ADDR_PRO_LED_RED 563 #define ADDR_PRO_GOAL_POSITION 596 @@ -39,32 +39,45 @@ #define ADDR_PRO_INDIRECTDATA_FOR_READ 639 // Data Byte Length +#define LEN_PRO_LED_RED 1 +#define LEN_PRO_GOAL_POSITION 4 +#define LEN_PRO_MOVING 1 +#define LEN_PRO_PRESENT_POSITION 4 #define LEN_PRO_INDIRECTDATA_FOR_WRITE 5 #define LEN_PRO_INDIRECTDATA_FOR_READ 5 // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MINIMUM_LED_VALUE 0 // Dynamixel LED will light between this value +#define DXL_MAXIMUM_LED_VALUE 255 // and this value +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold -#define STOP_MOVING_MARGIN 20 // Criteria for considering DXL moving status as stopped +#define ESC_ASCII_VALUE 0x1b -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() { struct termios oldt, newt; int ch; - tcgetattr(STDIN_FILENO, &oldt); + tcgetattr( STDIN_FILENO, &oldt ); newt = oldt; newt.c_lflag &= ~(ICANON | ECHO); - tcsetattr(STDIN_FILENO, TCSANOW, &newt); + tcsetattr( STDIN_FILENO, TCSANOW, &newt ); ch = getchar(); - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + tcsetattr( STDIN_FILENO, TCSANOW, &oldt ); return ch; } @@ -104,6 +117,8 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); // Initialize Groupsyncwrite instance @@ -113,52 +128,52 @@ int main() GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_PRO_INDIRECTDATA_FOR_READ, LEN_PRO_INDIRECTDATA_FOR_READ); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_addparam_result = false; // AddParam result - int dxl_getdata_result = false; // GetParam result - int dxl_goal_position[2] = {-150000, 150000}; // Goal Position - - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - UINT8_T dxl_moving; // DXL moving status - INT32_T dxl_present_position; // Present position - UINT8_T dxl_led_value[2] = {0x00, 0xFF}; // LED value + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // AddParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position + + UINT8_T dxl_error = 0; // Dynamixel error + UINT8_T dxl_moving = 0; // Dynamixel moving status UINT8_T param_indirect_data_for_write[LEN_PRO_INDIRECTDATA_FOR_WRITE]; + UINT8_T dxl_led_value[2] = {0x00, 0xFF}; // Dynamixel LED value + INT32_T dxl_present_position = 0; // Present position // Open port - if(portHandler->OpenPort()) + if( portHandler->OpenPort() ) { - printf("Succeeded to open the port!\n"); + printf( "Succeeded to open the port!\n" ); } else { - printf("Failed to open the port!\n"); - printf("Press any key to terminate...\n"); + printf( "Failed to open the port!\n" ); + printf( "Press any key to terminate...\n" ); _getch(); return 0; } // Set port baudrate - if(portHandler->SetBaudRate(BAUDRATE)) + if( portHandler->SetBaudRate(BAUDRATE) ) { - printf("Succeeded to change the baudrate!\n"); + printf( "Succeeded to change the baudrate!\n" ); } else { - printf("Failed to change the baudrate!\n"); - printf("Press any key to terminate...\n"); + printf( "Failed to change the baudrate!\n" ); + printf( "Press any key to terminate...\n" ); _getch(); return 0; } - // Disable DXL Torque : + // Disable Dynamixel Torque : // Indirect address would not accessible when the torque is already enabled - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("DXL has been successfully connected \n"); // INDIRECTDATA parameter storages replace LED, goal position, present position and moving status storages dxl_comm_result = packetHandler->Write2ByteTxRx(portHandler, DXL_ID, ADDR_PRO_INDIRECTADDRESS_FOR_WRITE + 0, ADDR_PRO_GOAL_POSITION + 0, &dxl_error); @@ -222,7 +237,7 @@ int main() packetHandler->PrintRxPacketError(dxl_error); // Enable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -232,14 +247,14 @@ int main() dxl_addparam_result = groupSyncRead.AddParam(DXL_ID); if( dxl_addparam_result != true ) { - fprintf(stderr, "[ID:%03d] groupsyncread addparam failed\n", DXL_ID); + fprintf(stderr, "[ID:%03d] groupSyncRead addparam failed\n", DXL_ID); return 0; } while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Allocate LED and goal position value into byte array @@ -253,7 +268,7 @@ int main() dxl_addparam_result = groupSyncWrite.AddParam(DXL_ID, param_indirect_data_for_write); if( dxl_addparam_result != true ) { - fprintf(stderr, "[ID:%03d] groupsyncread addparam failed\n", DXL_ID); + fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed\n", DXL_ID); return 0; } @@ -265,43 +280,48 @@ int main() // Clear syncwrite parameter storage groupSyncWrite.ClearParam(); - do{ - usleep(50*1000); - + do + { // Syncread present position from indirectdata2 dxl_comm_result = groupSyncRead.TxRxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - // Get DXL present position value - dxl_getdata_result = groupSyncRead.GetData(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ, (UINT32_T*)&dxl_present_position); - if( dxl_getdata_result != true ) + // Check if groupsyncread data of Dyanamixel is available + dxl_getdata_result = groupSyncRead.IsAvailable(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupSyncRead getdata failed", DXL_ID); return 0; } - // Get DXL moving status value - dxl_getdata_result = groupSyncRead.GetData(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ + 4, &dxl_moving); - if( dxl_getdata_result != true ) + // Check if groupsyncread data of Dyanamixel is available + dxl_getdata_result = groupSyncRead.IsAvailable(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ + LEN_PRO_PRESENT_POSITION, LEN_PRO_MOVING); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupSyncRead getdata failed", DXL_ID); return 0; } - printf("[ID:%03d] GoalPos:%03d PresPos:%03d IsMoving:%d\n", DXL_ID, dxl_goal_position[index], dxl_present_position, dxl_moving); - }while(abs(dxl_goal_position[index] - dxl_present_position) > STOP_MOVING_MARGIN); + // Get Dynamixel present position value + dxl_present_position = groupSyncRead.GetData(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ, LEN_PRO_PRESENT_POSITION); + + // Get Dynamixel moving status value + dxl_moving = groupSyncRead.GetData(DXL_ID, ADDR_PRO_INDIRECTDATA_FOR_READ + LEN_PRO_PRESENT_POSITION, LEN_PRO_MOVING); + + printf("[ID:%03d] GoalPos:%d PresPos:%d IsMoving:%d\n", DXL_ID, dxl_goal_position[index], dxl_present_position, dxl_moving); + + }while(abs(dxl_goal_position[index] - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD); + // Change goal position if( index == 0 ) index = 1; else index = 0; } - // Clear syncread parameter storage - groupSyncRead.ClearParam(); - // Disable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -310,7 +330,5 @@ int main() // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/IndirectAddress/Makefile b/c++/example/Protocol2.0/IndirectAddress/Makefile deleted file mode 100644 index 063a26dedc192c311ce8b4d87b1d03ac1fecf29a..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/IndirectAddress/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 IndirectAddress Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = IndirectAddress - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = IndirectAddress.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/MultiPort/Makefile b/c++/example/Protocol2.0/MultiPort/Makefile deleted file mode 100644 index 11b0284ca92457859993d69a080a119d4549d59f..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/MultiPort/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 MultiPort Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = MultiPort - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = MultiPort.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/MultiPort/MultiPort.cpp b/c++/example/Protocol2.0/MultiPort/MultiPort.cpp index 9736dcad19e88104cf310c8c2706d173ad3b66e9..8da37a5be92bfdd1a379b9051db7ff4597e7b94f 100644 --- a/c++/example/Protocol2.0/MultiPort/MultiPort.cpp +++ b/c++/example/Protocol2.0/MultiPort/MultiPort.cpp @@ -9,42 +9,47 @@ // ********* MultiPort Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with two DXL PRO 54-200, and two USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with two Dynamixel PRO 54-200, and two USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_TORQUE_ENABLE 562 +#define ADDR_PRO_TORQUE_ENABLE 562 // Control table address is different in Dynamixel model #define ADDR_PRO_GOAL_POSITION 596 #define ADDR_PRO_PRESENT_POSITION 611 // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 -#define BAUDRATE 1000000 -#define DEVICENAME1 "/dev/ttyUSB0" -#define DEVICENAME2 "/dev/ttyUSB1" +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 +#define BAUDRATE 1000000 +#define DEVICENAME1 "/dev/ttyUSB0" // Check which port is being used on your controller +#define DEVICENAME2 "/dev/ttyUSB1" // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define STOP_MOVING_MARGIN 20 // Criteria for considering DXL moving status as stopped +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold -using namespace ROBOTIS; +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -90,24 +95,24 @@ int _kbhit(void) int main() { - // Initialize Porthandlers instance + // Initialize PortHandler instance // Set the port path // Get methods and members of PortHandlerLinux or PortHandlerWindows - PortHandler *portHandler1 = (PortHandler*)PortHandler::GetPortHandler(DEVICENAME1); - PortHandler *portHandler2 = (PortHandler*)PortHandler::GetPortHandler(DEVICENAME2); + PortHandler *portHandler1 = PortHandler::GetPortHandler(DEVICENAME1); + PortHandler *portHandler2 = PortHandler::GetPortHandler(DEVICENAME2); + // Initialize Packethandler instance - // Get Protocol2PacketHandler methods and members + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_goal_position[2] = {-150000, 150000}; // Goal position + int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - INT32_T dxl_present_position1, dxl_present_position2; // Present position + UINT8_T dxl_error = 0; // Dynamixel error + INT32_T dxl1_present_position = 0, dxl2_present_position = 0; // Present position // Open port1 if( portHandler1->OpenPort() ) @@ -138,11 +143,11 @@ int main() // Set port1 baudrate if(portHandler1->SetBaudRate(BAUDRATE) ) { - printf( "Succeed to change the baudrate of port1!\n" ); + printf( "Succeed to change the baudrate port1!\n" ); } else { - printf( "Failed to change the baudrate of port1!\n" ); + printf( "Failed to change the baudrate port1!\n" ); printf( "Press any key to terminate...\n" ); _getch(); return 0; @@ -151,46 +156,49 @@ int main() // Set port2 baudrate if(portHandler2->SetBaudRate(BAUDRATE) ) { - printf( "Succeed to change the baudrate of port2!\n" ); + printf( "Succeed to change the baudrate port2!\n" ); } else { - printf( "Failed to change the baudrate of port2!\n" ); + printf( "Failed to change the baudrate port2!\n" ); printf( "Press any key to terminate...\n" ); _getch(); return 0; } - // Enable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; - // Write DXL#1 goal position + // Write Dynamixel#1 goal position dxl_comm_result = packetHandler->Write4ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Write DXL#2 goal position + // Write Dynamixel#2 goal position dxl_comm_result = packetHandler->Write4ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_GOAL_POSITION, dxl_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); @@ -199,24 +207,23 @@ int main() do { - usleep(50*1000); - - // Read DXL#1 present position - dxl_comm_result = packetHandler->Read4ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position1, &dxl_error); + // Read Dynamixel#1 present position + dxl_comm_result = packetHandler->Read4ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl1_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Read DXL#2 present position - dxl_comm_result = packetHandler->Read4ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position2, &dxl_error); + // Read Dynamixel#2 present position + dxl_comm_result = packetHandler->Read4ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl2_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] GoalPos:%03d PresPos:%03d [ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl_present_position1, DXL2_ID, dxl_goal_position[index], dxl_present_position2); - }while((abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN) || (abs(dxl_goal_position[index] - dxl_present_position2) > STOP_MOVING_MARGIN)); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position); + + }while((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -225,15 +232,15 @@ int main() index = 0; } - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler1, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler2, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -245,7 +252,5 @@ int main() // Close port2 portHandler2->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/Ping/Makefile b/c++/example/Protocol2.0/Ping/Makefile deleted file mode 100644 index f9a979d6635cc81e8ef283bab1b2317d1a8dc27f..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/Ping/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 Ping Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = Ping - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = Ping.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/Ping/Ping.cpp b/c++/example/Protocol2.0/Ping/Ping.cpp index 30958165fe86dec64896888e2872d86202b93176..211d11ff4af55129af15608d4838d9e44976d099 100644 --- a/c++/example/Protocol2.0/Ping/Ping.cpp +++ b/c++/example/Protocol2.0/Ping/Ping.cpp @@ -9,33 +9,32 @@ // ********* Ping Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with a DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with a Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> -#include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -81,18 +80,20 @@ int _kbhit(void) int main() { - // Initialize Porthandler instance + // Initialize PortHandler instance // Set the port path // Get methods and members of PortHandlerLinux or PortHandlerWindows - PortHandler *portHandler = (PortHandler*)PortHandler::GetPortHandler(DEVICENAME); + PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl_comm_result = COMM_TX_FAIL; // Communication result - UINT8_T dxl_error = 0; // DXL error - UINT16_T dxl_model_number; // DXL model number + UINT8_T dxl_error = 0; // Dynamixel error + UINT16_T dxl_model_number; // Dynamixel model number // Open port if( portHandler->OpenPort() ) @@ -120,20 +121,18 @@ int main() return 0; } - // Try to ping the DXL - // Get DXL model number from the DXL + // Try to ping the Dynamixel + // Get Dynamixel model number dxl_comm_result = packetHandler->Ping(portHandler, DXL_ID, &dxl_model_number, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] Ping Succeeded. DXL model number : %d\n", DXL_ID, dxl_model_number); + printf("[ID:%03d] Ping Succeeded. Dynamixel model number : %d\n", DXL_ID, dxl_model_number); - // Close port + // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); - return 0; + return 0; } diff --git a/c++/example/Protocol2.0/ReadWrite/Makefile b/c++/example/Protocol2.0/ReadWrite/Makefile deleted file mode 100644 index b05c7195a0b2e66deee4a3935fe8aa6aaf160844..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/ReadWrite/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 Read/Write Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = ReadWrite - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = ReadWrite.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/ReadWrite/ReadWrite.cpp b/c++/example/Protocol2.0/ReadWrite/ReadWrite.cpp index adfa4c6398de0b661e9cdd0b5711d9cfd87b2aaa..9588eb0fbe552d5a0458ef39e4af25f77d222d82 100644 --- a/c++/example/Protocol2.0/ReadWrite/ReadWrite.cpp +++ b/c++/example/Protocol2.0/ReadWrite/ReadWrite.cpp @@ -9,39 +9,46 @@ // ********* Read and Write Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with a DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with a Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_TORQUE_ENABLE 562 +#define ADDR_PRO_TORQUE_ENABLE 562 // Control table address is different in Dynamixel model #define ADDR_PRO_GOAL_POSITION 596 -#define ADDR_PRO_MOVING 610 #define ADDR_PRO_PRESENT_POSITION 611 // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold + +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -93,16 +100,15 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); int index = 0; int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_goal_position[2] = {-150000, 150000}; // Goal position + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque disable - UINT8_T dxl_error = 0; // DXL error - UINT8_T dxl_moving = 0; // DXL moving status + UINT8_T dxl_error = 0; // Dynamixel error INT32_T dxl_present_position = 0; // Present position // Open port @@ -121,7 +127,7 @@ int main() // Set port baudrate if( portHandler->SetBaudRate(BAUDRATE) ) { - printf( "Succeeded to change the baudrate!\n" ); + printf( "Succeeded to change the baudrate!\n" ); } else { @@ -131,16 +137,19 @@ int main() return 0; } - // Enable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + else + printf("Dynamixel has been successfully connected \n"); + while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Write goal position @@ -152,8 +161,6 @@ int main() do { - usleep(40*1000); - // Read present position dxl_comm_result = packetHandler->Read4ByteTxRx(portHandler, DXL_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) @@ -161,15 +168,9 @@ int main() else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Check moving done - dxl_comm_result = packetHandler->Read1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_MOVING, &dxl_moving, &dxl_error); - if(dxl_comm_result != COMM_SUCCESS) - packetHandler->PrintTxRxResult(dxl_comm_result); - else if(dxl_error != 0) - packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] GoalPos:%03d PresPos:%03d Moving:%d\n", DXL_ID, dxl_goal_position[index], dxl_present_position, dxl_moving); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL_ID, dxl_goal_position[index], dxl_present_position); - }while(dxl_moving == 1); + }while((abs(dxl_goal_position[index] - dxl_present_position) > DXL_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -178,8 +179,8 @@ int main() index = 0; } - // Disable DXL Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -188,7 +189,5 @@ int main() // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/Reboot/Makefile b/c++/example/Protocol2.0/Reboot/Makefile deleted file mode 100644 index 345847fb1df51b000c67ca03da653153924b2e86..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/Reboot/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 Reboot Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = Reboot - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = Reboot.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/Reboot/Reboot.cpp b/c++/example/Protocol2.0/Reboot/Reboot.cpp index 638531c509553687e692df245f4c8e356265ab02..924d45829b48f799937e3559450715fb98b02fa9 100644 --- a/c++/example/Protocol2.0/Reboot/Reboot.cpp +++ b/c++/example/Protocol2.0/Reboot/Reboot.cpp @@ -9,33 +9,32 @@ // ********* Reboot Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with a DXL PRO 54-200, and USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with a Dynamixel PRO 54-200, and USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif #include <stdio.h> -#include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL_ID 1 +#define DXL_ID 1 // Dynamixel ID: 1 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -87,11 +86,13 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); int dxl_comm_result = COMM_TX_FAIL; // Communication result - UINT8_T dxl_error = 0; + UINT8_T dxl_error = 0; // Dynamixel error // Open port if( portHandler->OpenPort() ) @@ -120,23 +121,22 @@ int main() } // Trigger - printf( "Press Enter key to reboot\n" ); + printf( "Press any key to reboot\n" ); _getch(); + printf("See the Dynamixel LED flickering\n"); // Try reboot - // DXL Green LED will flicker while it reboots + // Dynamixel LED will flicker while it reboots dxl_comm_result = packetHandler->Reboot(portHandler, DXL_ID, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("[ID:%03d] Reboot Succeeded\n", DXL_ID); + printf("[ID:%03d] Reboot Succeeded\n", DXL_ID); - // Close port + // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/Protocol2.0/SyncReadWrite/Makefile b/c++/example/Protocol2.0/SyncReadWrite/Makefile deleted file mode 100644 index 24112475d4b41df80e12f5468070981fcad3c11d..0000000000000000000000000000000000000000 --- a/c++/example/Protocol2.0/SyncReadWrite/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL Protocol 2.0 SyncReadWrite Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = SyncReadWrite - -# important directories used by assorted rules and other variables -DIR_DXL = ../../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = SyncReadWrite.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/Protocol2.0/SyncReadWrite/SyncReadWrite.cpp b/c++/example/Protocol2.0/SyncReadWrite/SyncReadWrite.cpp index 6bc48aafbecff239d97814bf91228f66e38b4e53..6437dc81a0f1eb3547bf7c131ea345cde18c0e30 100644 --- a/c++/example/Protocol2.0/SyncReadWrite/SyncReadWrite.cpp +++ b/c++/example/Protocol2.0/SyncReadWrite/SyncReadWrite.cpp @@ -9,46 +9,51 @@ // ********* Sync Read and Sync Write Example ********* // // -// Available DXL model on this example : All models using Protocol 2.0 -// This example is tested with two DXL PRO 54-200, and an USB2DYNAMIXEL -// Be sure that DXL PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) / Min voltage limit : under 110 (when using 12V power supplement) +// Available Dynamixel model on this example : All models using Protocol 2.0 +// This example is tested with two Dynamixel PRO 54-200, and an USB2DYNAMIXEL +// Be sure that Dynamixel PRO properties are already set as %% ID : 1 / Baudnum : 3 (Baudrate : 1000000) // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library // Control table address -#define ADDR_PRO_TORQUE_ENABLE 562 +#define ADDR_PRO_TORQUE_ENABLE 562 // Control table address is different in Dynamixel model #define ADDR_PRO_GOAL_POSITION 596 #define ADDR_PRO_PRESENT_POSITION 611 // Data Byte Length -#define LEN_PRO_TORQUE_ENABLE 1 -#define LEN_PRO_GOAL_POSITION 4 -#define LEN_PRO_PRESENT_POSITION 4 +#define LEN_PRO_GOAL_POSITION 4 +#define LEN_PRO_PRESENT_POSITION 4 // Protocol version -#define PROTOCOL_VERSION 2.0 +#define PROTOCOL_VERSION 2.0 // See which protocol version is used in the Dynamixel // Default setting -#define DXL1_ID 1 // DXL#1 ID:1 -#define DXL2_ID 2 // DXL#2 ID:2 +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" + +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL_MINIMUM_POSITION_VALUE -150000 // Dynamixel will rotate between this value +#define DXL_MAXIMUM_POSITION_VALUE 150000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL_MOVING_STATUS_THRESHOLD 20 // Dynamixel moving status threshold -#define STOP_MOVING_MARGIN 20 // Criteria for considering DXL moving status as stopped +#define ESC_ASCII_VALUE 0x1b -using namespace ROBOTIS; +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -100,25 +105,25 @@ int main() PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler = PacketHandler::GetPacketHandler(PROTOCOL_VERSION); - // Initialize Groupsyncwrite instance for Goal Position + // Initialize Groupsyncwrite instance GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_PRO_GOAL_POSITION, LEN_PRO_GOAL_POSITION); // Initialize Groupsyncread instance for Present Position GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_addparam_result = false; // AddParam result - int dxl_getdata_result = false; // GetParam result - int dxl_goal_position[2] = {-150000, 150000}; // Goal position - - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque unable - UINT8_T dxl_error = 0; // DXL error + int dxl_comm_result = COMM_TX_FAIL; // Communication result + bool dxl_addparam_result = false; // AddParam result + bool dxl_getdata_result = false; // GetParam result + int dxl_goal_position[2] = {DXL_MINIMUM_POSITION_VALUE, DXL_MAXIMUM_POSITION_VALUE}; // Goal position + + UINT8_T dxl_error = 0; // Dynamixel error UINT8_T param_goal_position[4]; - INT32_T dxl_present_position1, dxl_present_position2; // Present position + INT32_T dxl1_present_position = 0, dxl2_present_position = 0; // Present position // Open port if( portHandler->OpenPort() ) @@ -146,23 +151,25 @@ int main() return 0; } - // Enable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); - if(dxl_comm_result != COMM_SUCCESS) + // Enable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); + if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); - // Add parameter storage for DXL#1 present position value + // Add parameter storage for Dynamixel#1 present position value dxl_addparam_result = groupSyncRead.AddParam(DXL1_ID); if( dxl_addparam_result != true ) { @@ -170,7 +177,7 @@ int main() return 0; } - // Add parameter storage for DXL#2 present position value + // Add parameter storage for Dynamixel#2 present position value dxl_addparam_result = groupSyncRead.AddParam(DXL2_ID); if( dxl_addparam_result != true ) { @@ -180,8 +187,8 @@ int main() while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; // Allocate goal position value into byte array @@ -190,19 +197,19 @@ int main() param_goal_position[2] = DXL_LOBYTE(DXL_HIWORD(dxl_goal_position[index])); param_goal_position[3] = DXL_HIBYTE(DXL_HIWORD(dxl_goal_position[index])); - // Add DXL#1 goal position value to the Syncwrite storage + // Add Dynamixel#1 goal position value to the Syncwrite storage dxl_addparam_result = groupSyncWrite.AddParam(DXL1_ID, param_goal_position); if( dxl_addparam_result != true ) { - fprintf(stderr, "[ID:%03d] groupBulkWrite addparam failed", DXL1_ID); + fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL1_ID); return 0; } - // Add DXL#2 goal position value to the Syncwrite storage + // Add Dynamixel#2 goal position value to the Syncwrite parameter storage dxl_addparam_result = groupSyncWrite.AddParam(DXL2_ID, param_goal_position); if( dxl_addparam_result != true ) { - fprintf(stderr, "[ID:%03d] groupBulkWrite addparam failed", DXL2_ID); + fprintf(stderr, "[ID:%03d] groupSyncWrite addparam failed", DXL2_ID); return 0; } @@ -210,15 +217,12 @@ int main() dxl_comm_result = groupSyncWrite.TxPacket(); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); - else if(dxl_error != 0) - packetHandler->PrintRxPacketError(dxl_error); // Clear syncwrite parameter storage groupSyncWrite.ClearParam(); - do{ - //usleep(40*1000); - + do + { // Syncread present position dxl_comm_result = groupSyncRead.TxRxPacket(); if(dxl_comm_result != COMM_SUCCESS) @@ -226,52 +230,56 @@ int main() else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Get DXL#1 present position value - dxl_getdata_result = groupSyncRead.GetData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position1); - if( dxl_getdata_result != true ) + // Check if groupsyncread data of Dynamixel#1 is available + dxl_getdata_result = groupSyncRead.IsAvailable(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) { - fprintf(stderr, "[ID:%03d] groupSyncRead getdata failed", DXL2_ID); + fprintf(stderr, "[ID:%03d] groupSyncRead getdata failed", DXL1_ID); return 0; } - // Get DXL#2 present position value - dxl_getdata_result = groupSyncRead.GetData(DXL2_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position2); - if( dxl_getdata_result != true ) + // Check if groupsyncread data of Dynamixel#2 is available + dxl_getdata_result = groupSyncRead.IsAvailable(DXL2_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + if (dxl_getdata_result != true) { fprintf(stderr, "[ID:%03d] groupSyncRead getdata failed", DXL2_ID); return 0; } - printf("[ID:%03d] GoalPos:%03d PresPos:%03d [ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl_present_position1, DXL2_ID, dxl_goal_position[index], dxl_present_position2); - }while((abs(dxl_goal_position[index] - dxl_present_position1) > STOP_MOVING_MARGIN) || (abs(dxl_goal_position[index] - dxl_present_position2) > STOP_MOVING_MARGIN)); + // Get Dynamixel#1 present position value + dxl1_present_position = groupSyncRead.GetData(DXL1_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + + // Get Dynamixel#2 present position value + dxl2_present_position = groupSyncRead.GetData(DXL2_ID, ADDR_PRO_PRESENT_POSITION, LEN_PRO_PRESENT_POSITION); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d\t[ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position[index], dxl1_present_position, DXL2_ID, dxl_goal_position[index], dxl2_present_position); + + }while((abs(dxl_goal_position[index] - dxl1_present_position) > DXL_MOVING_STATUS_THRESHOLD) || (abs(dxl_goal_position[index] - dxl2_present_position) > DXL_MOVING_STATUS_THRESHOLD)); + + // Change goal position if( index == 0 ) index = 1; else index = 0; } - // Clear syncread parameter storage - groupSyncRead.ClearParam(); - - // Disable DXL#1 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler->PrintRxPacketError(dxl_error); + // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/example/ProtocolCombined/Makefile b/c++/example/ProtocolCombined/Makefile deleted file mode 100644 index 6b809a11b99a4cabd4add79d1b135d60c77d8ac6..0000000000000000000000000000000000000000 --- a/c++/example/ProtocolCombined/Makefile +++ /dev/null @@ -1,78 +0,0 @@ -################################################## -# PROJECT: DXL ProtocolCombined Example Makefile -# AUTHOR : ROBOTIS Ltd. -################################################## - -#--------------------------------------------------------------------- -# Makefile template for projects using DXL SDK -# -# Please make sure to follow these instructions when setting up your -# own copy of this file: -# -# 1- Enter the name of the target (the TARGET variable) -# 2- Add additional source files to the SOURCES variable -# 3- Add additional static library objects to the OBJECTS variable -# if necessary -# 4- Ensure that compiler flags, INCLUDES, and LIBRARIES are -# appropriate to your needs -# -# -# This makefile will link against several libraries, not all of which -# are necessarily needed for your project. Please feel free to -# remove libaries you do not need. -#--------------------------------------------------------------------- - -# *** ENTER THE TARGET NAME HERE *** -TARGET = ProtocolCombined - -# important directories used by assorted rules and other variables -DIR_DXL = ../.. -DIR_OBJS = .objects - -# compiler options -CC = gcc -CX = g++ -CCFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -CXFLAGS = -O2 -O3 -DLINUX -D_GNU_SOURCE -Wall $(INCLUDES) -g -LNKCC = $(CX) -LNKFLAGS = $(CXFLAGS) #-Wl,-rpath,$(DIR_THOR)/lib - -#--------------------------------------------------------------------- -# Core components (all of these are likely going to be needed) -#--------------------------------------------------------------------- -INCLUDES += -I$(DIR_DXL)/include -LIBRARIES += -ldxl - -#--------------------------------------------------------------------- -# Files -#--------------------------------------------------------------------- -SOURCES = ProtocolCombined.cpp \ - # *** OTHER SOURCES GO HERE *** - -OBJECTS = $(addsuffix .o,$(addprefix $(DIR_OBJS)/,$(basename $(notdir $(SOURCES))))) -#OBJETCS += *** ADDITIONAL STATIC LIBRARIES GO HERE *** - - -#--------------------------------------------------------------------- -# Compiling Rules -#--------------------------------------------------------------------- -$(TARGET): make_directory $(OBJECTS) - $(LNKCC) $(LNKFLAGS) $(OBJECTS) -o $(TARGET) $(LIBRARIES) - -all: $(TARGET) - -clean: - rm -rf $(TARGET) $(DIR_OBJS) core *~ *.a *.so *.lo - -make_directory: - mkdir -p $(DIR_OBJS)/ - -$(DIR_OBJS)/%.o: %.c - $(CC) $(CCFLAGS) -c $? -o $@ - -$(DIR_OBJS)/%.o: %.cpp - $(CX) $(CXFLAGS) -c $? -o $@ - -#--------------------------------------------------------------------- -# End of Makefile -#--------------------------------------------------------------------- diff --git a/c++/example/ProtocolCombined/ProtocolCombined.cpp b/c++/example/ProtocolCombined/ProtocolCombined.cpp index 4c8abed2948e38daac769fefcfbb7b3660a4d37c..e39ce313028f094c54380469ba6dcd0341d63a09 100644 --- a/c++/example/ProtocolCombined/ProtocolCombined.cpp +++ b/c++/example/ProtocolCombined/ProtocolCombined.cpp @@ -9,52 +9,60 @@ // ********* Protocol Combined Example ********* // // -// Available DXL model on this example : All models using Protocol 1.0 and 2.0 -// This example is tested with a DXL MX-28, a DXL PRO 54-200 and an USB2DYNAMIXEL -// Be sure that properties of DXL MX and PRO are already set as %% MX - ID : 1 / Baudnum : 1 (Baudrate : 1000000) , PRO - ID : 1 / Baudnum : 3 (Baudrate : 1000000) +// Available Dynamixel model on this example : All models using Protocol 1.0 and 2.0 +// This example is tested with a Dynamixel MX-28, a Dynamixel PRO 54-200 and an USB2DYNAMIXEL +// Be sure that properties of Dynamixel MX and PRO are already set as %% MX - ID : 1 / Baudnum : 1 (Baudrate : 1000000) , PRO - ID : 1 / Baudnum : 3 (Baudrate : 1000000) // // Be aware that: -// This example configures two different control tables (especially, if it uses DXL and DXL PRO). It may modify critical DXL parameter on the control table, if DXLs have wrong ID. +// This example configures two different control tables (especially, if it uses Dynamixel and Dynamixel PRO). It may modify critical Dynamixel parameter on the control table, if Dynamixels have wrong ID. // #ifdef __linux__ #include <unistd.h> #include <fcntl.h> -#include <getopt.h> #include <termios.h> +#elif defined(_WIN32) || defined(_WIN64) +#include <conio.h> #endif -#include <stdio.h> #include <stdlib.h> -#include <string.h> - -#include "DynamixelSDK.h" +#include <stdio.h> +#include "DynamixelSDK.h" // Uses Dynamixel SDK library -// Control table address for DXL MX -#define ADDR_MX_TORQUE_ENABLE 24 +// Control table address for Dynamixel MX +#define ADDR_MX_TORQUE_ENABLE 24 // Control table address is different in Dynamixel model #define ADDR_MX_GOAL_POSITION 30 #define ADDR_MX_PRESENT_POSITION 36 -// Control table address for DXL PRO +// Control table address for Dynamixel PRO #define ADDR_PRO_TORQUE_ENABLE 562 #define ADDR_PRO_GOAL_POSITION 596 #define ADDR_PRO_PRESENT_POSITION 611 -// Protocol versions -#define PROTOCOL_VERSION1 1.0 +// Protocol version +#define PROTOCOL_VERSION1 1.0 // See which protocol version is used in the Dynamixel #define PROTOCOL_VERSION2 2.0 // Default setting -#define DXL1_ID 1 // MX -#define DXL2_ID 2 // PRO +#define DXL1_ID 1 // Dynamixel#1 ID: 1 +#define DXL2_ID 2 // Dynamixel#2 ID: 2 #define BAUDRATE 1000000 -#define DEVICENAME "/dev/ttyUSB0" +#define DEVICENAME "/dev/ttyUSB0" // Check which port is being used on your controller + // ex) Windows: "COM1" Linux: "/dev/ttyUSB0" -#define STOP_MOVING_MARGIN1 10 -#define STOP_MOVING_MARGIN2 20 +#define TORQUE_ENABLE 1 // Value for enabling the torque +#define TORQUE_DISABLE 0 // Value for disabling the torque +#define DXL1_MINIMUM_POSITION_VALUE 100 // Dynamixel will rotate between this value +#define DXL1_MAXIMUM_POSITION_VALUE 4000 // and this value (note that the Dynamixel would not move when the position value is out of movable range. Check e-manual about the range of the Dynamixel you use.) +#define DXL2_MINIMUM_POSITION_VALUE -150000 +#define DXL2_MAXIMUM_POSITION_VALUE 150000 +#define DXL1_MOVING_STATUS_THRESHOLD 10 // Dynamixel MX moving status threshold +#define DXL2_MOVING_STATUS_THRESHOLD 20 // Dynamixel PRO moving status threshold -using namespace ROBOTIS; +#define ESC_ASCII_VALUE 0x1b + +using namespace ROBOTIS; // Uses functions defined in ROBOTIS namespace #ifdef __linux__ int _getch() @@ -103,26 +111,22 @@ int main() // Initialize PortHandler instance // Set the port path // Get methods and members of PortHandlerLinux or PortHandlerWindows - PortHandler *portHandler = (PortHandler*)PortHandler::GetPortHandler(DEVICENAME); + PortHandler *portHandler = PortHandler::GetPortHandler(DEVICENAME); - // Initialize Packethandler instance for Protocol 1.0 - // Get Protocol1PacketHandler methods and members + // Initialize Packethandler instance + // Set the protocol version + // Get methods and members of Protocol1PacketHandler or Protocol2PacketHandler PacketHandler *packetHandler1 = PacketHandler::GetPacketHandler(PROTOCOL_VERSION1); - - // Initialize Packethandler instance for Protocol 2.0 - // Get Protocol1PacketHandler methods and members PacketHandler *packetHandler2 = PacketHandler::GetPacketHandler(PROTOCOL_VERSION2); int index = 0; - int dxl_comm_result = COMM_TX_FAIL; // Communication result - int dxl_goal_position1[2] = { 100, 1000 }; // Goal position1 - int dxl_goal_position2[2] = {-150000, 150000 }; // Goal position2 + int dxl_comm_result = COMM_TX_FAIL; // Communication result + int dxl1_goal_position[2] = {DXL1_MINIMUM_POSITION_VALUE, DXL1_MAXIMUM_POSITION_VALUE}; // Goal position of Dynamixel MX + int dxl2_goal_position[2] = {DXL2_MINIMUM_POSITION_VALUE, DXL2_MAXIMUM_POSITION_VALUE}; // Goal position of Dynamixel PRO - UINT8_T dxl_torque_enable = 1; // Value for torque enable - UINT8_T dxl_torque_disable = 0; // Value for torque unable - UINT8_T dxl_error = 0; // DXL error - UINT16_T dxl_present_position1; // Present position1 - INT32_T dxl_present_position2; // Present position2 + UINT8_T dxl_error = 0; // Dynamixel error + UINT16_T dxl1_present_position = 0; // Present position of Dynamixel MX + INT32_T dxl2_present_position = 0; // Present position of Dynamixel PRO // Open port if( portHandler->OpenPort() ) @@ -150,37 +154,39 @@ int main() return 0; } - // Enable DXL#1 torque - dxl_comm_result = packetHandler1->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#1 torque + dxl_comm_result = packetHandler1->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler1->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler1->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL1_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL1_ID); - // Enable DXL#2 torque - dxl_comm_result = packetHandler2->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_enable, &dxl_error); + // Enable Dynamixel#2 torque + dxl_comm_result = packetHandler2->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_ENABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler2->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler2->PrintRxPacketError(dxl_error); - printf("DXL#%d successfully connected\n", DXL2_ID); + else + printf("Dynamixel#%d has been successfully connected \n", DXL2_ID); while(1) { - printf( "Press Enter key to continue!(press ESC and Enter to quit)\n" ); - if(_getch() == 0x1b) + printf("Press any key to continue! (or press ESC to quit!)\n"); + if(_getch() == ESC_ASCII_VALUE) break; - // Write DXL#1 goal position - dxl_comm_result = packetHandler1->Write2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_GOAL_POSITION, dxl_goal_position1[index], &dxl_error); + // Write Dynamixel#1 goal position + dxl_comm_result = packetHandler1->Write2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_GOAL_POSITION, dxl1_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler1->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler1->PrintRxPacketError(dxl_error); - // Write DXL#2 goal position - dxl_comm_result = packetHandler2->Write4ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_GOAL_POSITION, dxl_goal_position2[index], &dxl_error); + // Write Dynamixel#2 goal position + dxl_comm_result = packetHandler2->Write4ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_GOAL_POSITION, dxl2_goal_position[index], &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler2->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) @@ -188,24 +194,23 @@ int main() do { - usleep(40*1000); - - // Read DXL#1 present position - dxl_comm_result = packetHandler1->Read2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl_present_position1, &dxl_error); + // Read Dynamixel#1 present position + dxl_comm_result = packetHandler1->Read2ByteTxRx(portHandler, DXL1_ID, ADDR_MX_PRESENT_POSITION, &dxl1_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler1->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler1->PrintRxPacketError(dxl_error); - // Read DXL#2 present position - dxl_comm_result = packetHandler2->Read4ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl_present_position2, &dxl_error); + // Read Dynamixel#2 present position + dxl_comm_result = packetHandler2->Read4ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_PRESENT_POSITION, (UINT32_T*)&dxl2_present_position, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler2->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler2->PrintRxPacketError(dxl_error); - printf("[ID:%03d] GoalPos:%03d PresPos:%03d [ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl_goal_position1[index], dxl_present_position1, DXL2_ID, dxl_goal_position2[index], dxl_present_position2); - }while((abs(dxl_goal_position1[index] - dxl_present_position1) > STOP_MOVING_MARGIN1) || (abs(dxl_goal_position2[index] - dxl_present_position2) > STOP_MOVING_MARGIN2)); + printf("[ID:%03d] GoalPos:%03d PresPos:%03d [ID:%03d] GoalPos:%03d PresPos:%03d\n", DXL1_ID, dxl1_goal_position[index], dxl1_present_position, DXL2_ID, dxl2_goal_position[index], dxl2_present_position); + + }while((abs(dxl1_goal_position[index] - dxl1_present_position) > DXL1_MOVING_STATUS_THRESHOLD) || (abs(dxl2_goal_position[index] - dxl2_present_position) > DXL2_MOVING_STATUS_THRESHOLD)); // Change goal position if( index == 0 ) @@ -214,24 +219,22 @@ int main() index = 0; } - // Disable DXL#1 Torque - dxl_comm_result = packetHandler1->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#1 Torque + dxl_comm_result = packetHandler1->Write1ByteTxRx(portHandler, DXL1_ID, ADDR_MX_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler1->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler1->PrintRxPacketError(dxl_error); - // Disable DXL#2 Torque - dxl_comm_result = packetHandler2->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, dxl_torque_disable, &dxl_error); + // Disable Dynamixel#2 Torque + dxl_comm_result = packetHandler2->Write1ByteTxRx(portHandler, DXL2_ID, ADDR_PRO_TORQUE_ENABLE, TORQUE_DISABLE, &dxl_error); if(dxl_comm_result != COMM_SUCCESS) packetHandler2->PrintTxRxResult(dxl_comm_result); else if(dxl_error != 0) packetHandler2->PrintRxPacketError(dxl_error); - // Close port + // Close port portHandler->ClosePort(); - printf( "Press Enter key to terminate...\n" ); - _getch(); return 0; } diff --git a/c++/include/DynamixelSDK.h b/c++/include/DynamixelSDK.h index e64ae0d06624b050064d013f1856321fa5d679a8..0d34655c663577048b8cb8fbbd6a13fbcce27e6c 100644 --- a/c++/include/DynamixelSDK.h +++ b/c++/include/DynamixelSDK.h @@ -2,7 +2,7 @@ * DynamixelSDK.h * * Created on: 2016. 3. 8. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_DYNAMIXELSDK_H_ diff --git a/c++/include/dynamixel_sdk/GroupBulkRead.h b/c++/include/dynamixel_sdk/GroupBulkRead.h index 0f445eb9ebf381b55d1b258d790946c5568d57f7..bd3374b3db2bf1eaa201918d86240a983d5dad9e 100644 --- a/c++/include/dynamixel_sdk/GroupBulkRead.h +++ b/c++/include/dynamixel_sdk/GroupBulkRead.h @@ -2,7 +2,7 @@ * GroupBulkRead.h * * Created on: 2016. 1. 28. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ @@ -18,7 +18,7 @@ namespace ROBOTIS { -class GroupBulkRead +class WINDECLSPEC GroupBulkRead { private: PortHandler *port_; diff --git a/c++/include/dynamixel_sdk/GroupBulkWrite.h b/c++/include/dynamixel_sdk/GroupBulkWrite.h index 650bc25edf3e6dc0ccfb38701ef915dbba414b65..3efbb8095d360de6be44b9cd8a6ab8a6c3b8fa6f 100644 --- a/c++/include/dynamixel_sdk/GroupBulkWrite.h +++ b/c++/include/dynamixel_sdk/GroupBulkWrite.h @@ -2,7 +2,7 @@ * GroupBulkWrite.h * * Created on: 2016. 2. 2. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_ @@ -18,7 +18,7 @@ namespace ROBOTIS { -class GroupBulkWrite +class WINDECLSPEC GroupBulkWrite { private: PortHandler *port_; diff --git a/c++/include/dynamixel_sdk/GroupSyncRead.h b/c++/include/dynamixel_sdk/GroupSyncRead.h index 4e0e3a1b0e77b490b20f270ff2da9668e563bc12..b6599de1d0f4402addb304f98de57568ad710ec0 100644 --- a/c++/include/dynamixel_sdk/GroupSyncRead.h +++ b/c++/include/dynamixel_sdk/GroupSyncRead.h @@ -2,7 +2,7 @@ * GroupSyncRead.h * * Created on: 2016. 2. 2. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_H_ @@ -18,7 +18,7 @@ namespace ROBOTIS { -class GroupSyncRead +class WINDECLSPEC GroupSyncRead { private: PortHandler *port_; diff --git a/c++/include/dynamixel_sdk/GroupSyncWrite.h b/c++/include/dynamixel_sdk/GroupSyncWrite.h index 28e145852f2c7daf6f9d5d08c346ec2cfec16a65..1ff03b2915939dd9fb3bcbcabd5dbef5fdb04d60 100644 --- a/c++/include/dynamixel_sdk/GroupSyncWrite.h +++ b/c++/include/dynamixel_sdk/GroupSyncWrite.h @@ -2,7 +2,7 @@ * GroupSyncWrite.h * * Created on: 2016. 1. 28. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_ @@ -18,7 +18,7 @@ namespace ROBOTIS { -class GroupSyncWrite +class WINDECLSPEC GroupSyncWrite { private: PortHandler *port_; diff --git a/c++/include/dynamixel_sdk/PacketHandler.h b/c++/include/dynamixel_sdk/PacketHandler.h index 6edb44e05fd2283d7fd40944d2828b94eddc8c2d..921d3808dc4dfe18014281ee53a01c8db40332e3 100644 --- a/c++/include/dynamixel_sdk/PacketHandler.h +++ b/c++/include/dynamixel_sdk/PacketHandler.h @@ -2,7 +2,7 @@ * PacketHandler.h * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PACKETHANDLER_H_ @@ -54,7 +54,7 @@ namespace ROBOTIS { -class PacketHandler +class WINDECLSPEC PacketHandler { protected: PacketHandler() { } diff --git a/c++/include/dynamixel_sdk/PortHandler.h b/c++/include/dynamixel_sdk/PortHandler.h index 6920f8eab6023497ae1ea1536cbdb9ff23242a42..6d3e6ddf835dba8ae99834101083b0a8b652b6ee 100644 --- a/c++/include/dynamixel_sdk/PortHandler.h +++ b/c++/include/dynamixel_sdk/PortHandler.h @@ -2,19 +2,28 @@ * PortHandler.h * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PORTHANDLER_H_ +#ifdef __linux__ +#define WINDECLSPEC +#elif defined(_WIN32) || defined(_WIN64) +#ifdef WINDLLEXPORT +#define WINDECLSPEC __declspec(dllexport) +#else +#define WINDECLSPEC __declspec(dllimport) +#endif +#endif #include "RobotisDef.h" namespace ROBOTIS { -class PortHandler +class WINDECLSPEC PortHandler { public: static const int DEFAULT_BAUDRATE = 1000000; diff --git a/c++/include/dynamixel_sdk/Protocol1PacketHandler.h b/c++/include/dynamixel_sdk/Protocol1PacketHandler.h index 55182f4759c53338a891c6fe626b79bee350f224..1932d2723e67cd90ce1462645dc711d9bfd85349 100644 --- a/c++/include/dynamixel_sdk/Protocol1PacketHandler.h +++ b/c++/include/dynamixel_sdk/Protocol1PacketHandler.h @@ -2,7 +2,7 @@ * Protocol1PacketHandler.h * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_ @@ -14,7 +14,7 @@ namespace ROBOTIS { -class Protocol1PacketHandler : public PacketHandler +class WINDECLSPEC Protocol1PacketHandler : public PacketHandler { private: static Protocol1PacketHandler *unique_instance_; diff --git a/c++/include/dynamixel_sdk/Protocol2PacketHandler.h b/c++/include/dynamixel_sdk/Protocol2PacketHandler.h index 823c226c871317ab50ae92f040cd5795fd99e6f9..101413c31e06959f91ffa2e7e2e831a6603011b8 100644 --- a/c++/include/dynamixel_sdk/Protocol2PacketHandler.h +++ b/c++/include/dynamixel_sdk/Protocol2PacketHandler.h @@ -2,7 +2,7 @@ * Protocol2PacketHandler.h * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_ @@ -14,7 +14,7 @@ namespace ROBOTIS { -class Protocol2PacketHandler : public PacketHandler +class WINDECLSPEC Protocol2PacketHandler : public PacketHandler { private: static Protocol2PacketHandler *unique_instance_; diff --git a/c++/include/dynamixel_sdk/RobotisDef.h b/c++/include/dynamixel_sdk/RobotisDef.h index 1fe2c61aa97b0ce76c2bdd6fbe9918ef416b2614..95ab80492b76d675fd6d3fa63f9d4728af2c1a24 100644 --- a/c++/include/dynamixel_sdk/RobotisDef.h +++ b/c++/include/dynamixel_sdk/RobotisDef.h @@ -2,7 +2,7 @@ * RobotisDef.h * * Created on: 2016. 1. 27. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ROBOTISDEF_H_ diff --git a/c++/include/dynamixel_sdk_linux/PortHandlerLinux.h b/c++/include/dynamixel_sdk_linux/PortHandlerLinux.h index 02e4f63b8a118813e32efe65e4663012dab7225d..6ff516eeb919b0712cccbef523a298989bca4818 100644 --- a/c++/include/dynamixel_sdk_linux/PortHandlerLinux.h +++ b/c++/include/dynamixel_sdk_linux/PortHandlerLinux.h @@ -2,7 +2,7 @@ * PortHandlerLinux.h * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_LINUX_PORTHANDLERLINUX_H_ diff --git a/c++/src/dynamixel_sdk/GroupBulkRead.cpp b/c++/src/dynamixel_sdk/GroupBulkRead.cpp index fef9530e8ce4db96528a68896a0cc083c79f3f3f..d8f2b6dee205b915e9de926d3cfecff9eb393be6 100644 --- a/c++/src/dynamixel_sdk/GroupBulkRead.cpp +++ b/c++/src/dynamixel_sdk/GroupBulkRead.cpp @@ -2,8 +2,11 @@ * GroupBulkRead.cpp * * Created on: 2016. 1. 28. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include <stdio.h> #include <algorithm> @@ -194,4 +197,3 @@ UINT32_T GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT16_T data_leng return 0; } } - diff --git a/c++/src/dynamixel_sdk/GroupBulkWrite.cpp b/c++/src/dynamixel_sdk/GroupBulkWrite.cpp index 39e8eb435f592536b861575136746fd43193735a..399b32e30d88f8d59c3061d8009fd2ecf4aac82a 100644 --- a/c++/src/dynamixel_sdk/GroupBulkWrite.cpp +++ b/c++/src/dynamixel_sdk/GroupBulkWrite.cpp @@ -2,8 +2,11 @@ * GroupBulkWrite.cpp * * Created on: 2016. 2. 2. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include <algorithm> #include "dynamixel_sdk/GroupBulkWrite.h" diff --git a/c++/src/dynamixel_sdk/GroupSyncRead.cpp b/c++/src/dynamixel_sdk/GroupSyncRead.cpp index 3172ae2dce0e4628c291cd003df4eef4b3ec350d..8e602e3310947c3411e290adce53f886f4c69990 100644 --- a/c++/src/dynamixel_sdk/GroupSyncRead.cpp +++ b/c++/src/dynamixel_sdk/GroupSyncRead.cpp @@ -2,8 +2,11 @@ * GroupSyncRead.cpp * * Created on: 2016. 2. 2. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include <algorithm> #include "dynamixel_sdk/GroupSyncRead.h" @@ -170,4 +173,3 @@ UINT32_T GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T data_leng return 0; } } - diff --git a/c++/src/dynamixel_sdk/GroupSyncWrite.cpp b/c++/src/dynamixel_sdk/GroupSyncWrite.cpp index 38d381b3c4f38efde3813dd81813f11a9acaa857..45d90f8e7d745c0e7fce27ed7cbd827d6b230f7e 100644 --- a/c++/src/dynamixel_sdk/GroupSyncWrite.cpp +++ b/c++/src/dynamixel_sdk/GroupSyncWrite.cpp @@ -2,8 +2,11 @@ * GroupSyncWrite.cpp * * Created on: 2016. 1. 28. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include <algorithm> #include "dynamixel_sdk/GroupSyncWrite.h" diff --git a/c++/src/dynamixel_sdk/PacketHandler.cpp b/c++/src/dynamixel_sdk/PacketHandler.cpp index 57579b039b887402b93bf917ba2636ac6efd8b57..8ad1c48f34f1a9687fae5799731cf77d38c8daed 100644 --- a/c++/src/dynamixel_sdk/PacketHandler.cpp +++ b/c++/src/dynamixel_sdk/PacketHandler.cpp @@ -2,8 +2,11 @@ * PacketHandler.cpp * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include "dynamixel_sdk/PacketHandler.h" #include "dynamixel_sdk/Protocol1PacketHandler.h" diff --git a/c++/src/dynamixel_sdk/PortHandler.cpp b/c++/src/dynamixel_sdk/PortHandler.cpp index 3bce1bfd1a63ab80de4e4eaf777bf24356cea914..ff4355c0aaf2a2d210d35b5231a592d929bace8f 100644 --- a/c++/src/dynamixel_sdk/PortHandler.cpp +++ b/c++/src/dynamixel_sdk/PortHandler.cpp @@ -2,8 +2,11 @@ * PortHandler.cpp * * Created on: 2016. 2. 5. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include "dynamixel_sdk/PortHandler.h" @@ -27,5 +30,3 @@ PortHandler *PortHandler::GetPortHandler(const char *port_name) return (PortHandler *)(new PortHandlerWindows(port_name)); #endif } - - diff --git a/c++/src/dynamixel_sdk/Protocol1PacketHandler.cpp b/c++/src/dynamixel_sdk/Protocol1PacketHandler.cpp index 630afe09b66659349129e8b743cb96f8d5dc4d72..4004f457d3c88322214977aab8cbffcfbe62a65c 100644 --- a/c++/src/dynamixel_sdk/Protocol1PacketHandler.cpp +++ b/c++/src/dynamixel_sdk/Protocol1PacketHandler.cpp @@ -2,8 +2,11 @@ * Protocol1PacketHandler.cpp * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif #include <string.h> #include <stdlib.h> @@ -660,4 +663,3 @@ int Protocol1PacketHandler::BulkWriteTxOnly(PortHandler *port, UINT8_T *param, U { return COMM_NOT_AVAILABLE; } - diff --git a/c++/src/dynamixel_sdk/Protocol2PacketHandler.cpp b/c++/src/dynamixel_sdk/Protocol2PacketHandler.cpp index 39cba41f197e2466eae41e70baeff8986e13d78a..f835eea1212273eef415387f0530fdcfbd469959 100644 --- a/c++/src/dynamixel_sdk/Protocol2PacketHandler.cpp +++ b/c++/src/dynamixel_sdk/Protocol2PacketHandler.cpp @@ -2,9 +2,13 @@ * Protocol2PacketHandler.cpp * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ +#if defined(_WIN32) || defined(_WIN64) +#define WINDLLEXPORT +#endif + #include <stdio.h> #include <string.h> #include <stdlib.h> diff --git a/c++/src/dynamixel_sdk_linux/PortHandlerLinux.cpp b/c++/src/dynamixel_sdk_linux/PortHandlerLinux.cpp index 8fb8b02aef9d2dcd34d78584ac4a6459e53de7a6..96c3f75c0ea3d661d1ee557780a2875c8f6a71fe 100644 --- a/c++/src/dynamixel_sdk_linux/PortHandlerLinux.cpp +++ b/c++/src/dynamixel_sdk_linux/PortHandlerLinux.cpp @@ -2,7 +2,7 @@ * PortHandlerLinux.cpp * * Created on: 2016. 1. 26. - * Author: zerom + * Author: zerom, leon */ #include <stdio.h> diff --git a/manual/DynamixelSDK_Manual_EN_160308.docx b/manual/DynamixelSDK_Manual_EN_160308.docx deleted file mode 100644 index b3222761c5a66592d625b67de79c912f243e3555..0000000000000000000000000000000000000000 Binary files a/manual/DynamixelSDK_Manual_EN_160308.docx and /dev/null differ diff --git a/manual/DynamixelSDK_ODROID_EN_160308.pptx b/manual/DynamixelSDK_ODROID_EN_160308.pptx deleted file mode 100644 index 46e3adad59840b10fb6d11014e1b2a419f57677e..0000000000000000000000000000000000000000 Binary files a/manual/DynamixelSDK_ODROID_EN_160308.pptx and /dev/null differ