modified.

This commit is contained in:
ROBOTIS-zerom
2016-04-29 16:18:25 +09:00
parent 738b68b6e4
commit c72bab42ba
59 changed files with 1987 additions and 789 deletions

View File

@@ -7,7 +7,7 @@ find_package(catkin REQUIRED COMPONENTS
catkin_package(
INCLUDE_DIRS include
# LIBRARIES dynamixel_sdk
LIBRARIES dynamixel_sdk
# CATKIN_DEPENDS roscpp
# DEPENDS system_lib
)

View File

@@ -2,7 +2,7 @@
* DynamixelSDK.h
*
* Created on: 2016. 3. 8.
* Author: zerom
* Author: zerom, leon
*/
#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_DYNAMIXELSDK_H_

View File

@@ -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_;
@@ -51,9 +51,8 @@ public:
int RxPacket();
int TxRxPacket();
bool GetData(UINT8_T id, UINT16_T address, UINT8_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT16_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data);
bool IsAvailable (UINT8_T id, UINT16_T address, UINT16_T data_length);
UINT32_T GetData (UINT8_T id, UINT16_T address, UINT16_T data_length);
};
}

View File

@@ -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_;

View File

@@ -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_;
@@ -51,9 +51,8 @@ public:
int RxPacket();
int TxRxPacket();
bool GetData(UINT8_T id, UINT16_T address, UINT8_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT16_T *data);
bool GetData(UINT8_T id, UINT16_T address, UINT32_T *data);
bool IsAvailable (UINT8_T id, UINT16_T address, UINT16_T data_length);
UINT32_T GetData (UINT8_T id, UINT16_T address, UINT16_T data_length);
};
}

View File

@@ -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_;

View File

@@ -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() { }

View File

@@ -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;

View File

@@ -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_;

View File

@@ -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_;

View File

@@ -2,7 +2,7 @@
* RobotisDef.h
*
* Created on: 2016. 1. 27.
* Author: zerom
* Author: zerom, leon
*/
#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ROBOTISDEF_H_

View File

@@ -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_

View File

@@ -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>
@@ -155,7 +158,7 @@ int GroupBulkRead::TxRxPacket()
return RxPacket();
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
bool GroupBulkRead::IsAvailable(UINT8_T id, UINT16_T address, UINT16_T data_length)
{
UINT16_T _start_addr, _data_length;
@@ -165,48 +168,32 @@ bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
_start_addr = address_list_[id];
_data_length = length_list_[id];
if(address < _start_addr || _start_addr + _data_length - 1 < address)
if(address < _start_addr || _start_addr + _data_length - data_length < address)
return false;
*data = data_list_[id][address - _start_addr];
return true;
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data)
UINT32_T GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT16_T data_length)
{
UINT16_T _start_addr, _data_length;
if(IsAvailable(id, address, data_length) == false)
return 0;
if(last_result_ == false || data_list_.find(id) == data_list_.end())
return false;
UINT16_T _start_addr = address_list_[id];
_start_addr = address_list_[id];
_data_length = length_list_[id];
switch(data_length)
{
case 1:
return data_list_[id][address - _start_addr];
if(address < _start_addr || _start_addr + _data_length - 2 < address)
return false;
case 2:
return DXL_MAKEWORD(data_list_[id][address - _start_addr], data_list_[id][address - _start_addr + 1]);
*data = DXL_MAKEWORD(data_list_[id][address - _start_addr], data_list_[id][address - _start_addr + 1]);
case 4:
return DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - _start_addr + 0], data_list_[id][address - _start_addr + 1]),
DXL_MAKEWORD(data_list_[id][address - _start_addr + 2], data_list_[id][address - _start_addr + 3]));
return true;
default:
return 0;
}
}
bool GroupBulkRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data)
{
UINT16_T _start_addr, _data_length;
if(last_result_ == false || data_list_.find(id) == data_list_.end())
return false;
_start_addr = address_list_[id];
_data_length = length_list_[id];
if(address < _start_addr || _start_addr + _data_length - 4 < address)
return false;
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - _start_addr + 0], data_list_[id][address - _start_addr + 1]),
DXL_MAKEWORD(data_list_[id][address - _start_addr + 2], data_list_[id][address - _start_addr + 3]));
return true;
}

View File

@@ -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"

View File

@@ -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"
@@ -138,50 +141,35 @@ int GroupSyncRead::TxRxPacket()
return RxPacket();
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT8_T *data)
bool GroupSyncRead::IsAvailable(UINT8_T id, UINT16_T address, UINT16_T data_length)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
if(ph_->GetProtocolVersion() == 1.0 || last_result_ == false || data_list_.find(id) == data_list_.end())
return false;
if(data_list_.find(id) == data_list_.end())
if(address < start_address_ || start_address_ + data_length_ - data_length < address)
return false;
if(address < start_address_ || start_address_ + data_length_ - 1 < address)
return false;
*data = data_list_[id][address - start_address_];
return true;
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T *data)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
return false;
if(data_list_.find(id) == data_list_.end())
return false;
if(address < start_address_ || start_address_ + data_length_ - 2 < address)
return false;
*data = DXL_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
return true;
}
bool GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT32_T *data)
{
if(last_result_ == false || ph_->GetProtocolVersion() == 1.0)
return false;
if(data_list_.find(id) == data_list_.end())
return false;
if(address < start_address_ || start_address_ + data_length_ - 4 < address)
return false;
*data = DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
DXL_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
return true;
}
UINT32_T GroupSyncRead::GetData(UINT8_T id, UINT16_T address, UINT16_T data_length)
{
if(IsAvailable(id, address, data_length) == false)
return 0;
switch(data_length)
{
case 1:
return data_list_[id][address - start_address_];
case 2:
return DXL_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
case 4:
return DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
DXL_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
default:
return 0;
}
}

View File

@@ -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"

View File

@@ -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"

View File

@@ -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
}

View File

@@ -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>
@@ -180,7 +183,12 @@ int Protocol1PacketHandler::RxPacket(PortHandler *port, UINT8_T *rxpacket)
}
// re-calculate the exact length of the rx packet
_wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1;
if(_wait_length != rxpacket[PKT_LENGTH] + PKT_LENGTH + 1)
{
_wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1;
continue;
}
if(_rx_length < _wait_length)
{
// check timeout
@@ -660,4 +668,3 @@ int Protocol1PacketHandler::BulkWriteTxOnly(PortHandler *port, UINT8_T *param, U
{
return COMM_NOT_AVAILABLE;
}

View File

@@ -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>
@@ -326,7 +330,12 @@ int Protocol2PacketHandler::RxPacket(PortHandler *port, UINT8_T *rxpacket)
}
// re-calculate the exact length of the rx packet
_wait_length = DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) + PKT_LENGTH_H + 1;
if(_wait_length != DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) + PKT_LENGTH_H + 1)
{
_wait_length = DXL_MAKEWORD(rxpacket[PKT_LENGTH_L], rxpacket[PKT_LENGTH_H]) + PKT_LENGTH_H + 1;
continue;
}
if(_rx_length < _wait_length)
{
// check timeout

View File

@@ -2,7 +2,7 @@
* PortHandlerLinux.cpp
*
* Created on: 2016. 1. 26.
* Author: zerom
* Author: zerom, leon
*/
#include <stdio.h>