Go to the documentation of this file.
   36 #include "std_msgs/String.h" 
   37 #include "dynamixel_sdk_examples/SyncGetPosition.h" 
   38 #include "dynamixel_sdk_examples/SyncSetPosition.h" 
   44 #define ADDR_TORQUE_ENABLE    64 
   45 #define ADDR_PRESENT_POSITION 132 
   46 #define ADDR_GOAL_POSITION    116 
   49 #define PROTOCOL_VERSION      2.0             // Default Protocol version of DYNAMIXEL X series. 
   52 #define DXL1_ID               1               // DXL1 ID 
   53 #define DXL2_ID               2               // DXL2 ID 
   54 #define BAUDRATE              57600           // Default Baudrate of DYNAMIXEL X series 
   55 #define DEVICE_NAME           "/dev/ttyUSB0"  // [Linux] To find assigned port, use "$ ls /dev/ttyUSB*" command 
   64   dynamixel_sdk_examples::SyncGetPosition::Request & req,
 
   65   dynamixel_sdk_examples::SyncGetPosition::Response & res)
 
   67   uint8_t dxl_error = 0;
 
   69   int dxl_addparam_result = 
false;
 
   72   int32_t position1 = 0;
 
   73   int32_t position2 = 0;
 
   78   if (dxl_addparam_result != 
true) {
 
   79     ROS_ERROR(
"Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id1);
 
   84   if (dxl_addparam_result != 
true) {
 
   85     ROS_ERROR(
"Failed to addparam to groupSyncRead for Dynamixel ID %d", req.id2);
 
   93     ROS_INFO(
"getPosition : [POSITION:%d]", position1);
 
   94     ROS_INFO(
"getPosition : [POSITION:%d]", position2);
 
   95     res.position1 = position1;
 
   96     res.position2 = position2;
 
  100     ROS_ERROR(
"Failed to get position! Result: %d", dxl_comm_result);
 
  108   uint8_t dxl_error = 0;
 
  110   int dxl_addparam_result = 
false;
 
  111   uint8_t param_goal_position1[4];
 
  112   uint8_t param_goal_position2[4];
 
  115   uint32_t position1 = (
unsigned int)msg->position1; 
 
  120   uint32_t position2 = (
unsigned int)msg->position2; 
 
  129   if (dxl_addparam_result != 
true) {
 
  130     ROS_ERROR( 
"Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id1);
 
  134   if (dxl_addparam_result != 
true) {
 
  135     ROS_ERROR( 
"Failed to addparam to groupSyncWrite for Dynamixel ID %d", msg->id2);
 
  140     ROS_INFO(
"setPosition : [ID:%d] [POSITION:%d]", msg->id1, msg->position1);
 
  141     ROS_INFO(
"setPosition : [ID:%d] [POSITION:%d]", msg->id2, msg->position2);
 
  143     ROS_ERROR(
"Failed to set position! Result: %d", dxl_comm_result);
 
  149 int main(
int argc, 
char ** argv)
 
  151   uint8_t dxl_error = 0;
 
  160     ROS_ERROR(
"Failed to set the baudrate!");
 
  178   ros::init(argc, argv, 
"sync_read_write_node");
 
  
#define ADDR_GOAL_POSITION
PacketHandler * packetHandler
bool addParam(uint8_t id)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
virtual bool setBaudRate(const int baudrate)=0
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void syncSetPositionCallback(const dynamixel_sdk_examples::SyncSetPosition::ConstPtr &msg)
bool addParam(uint8_t id, uint8_t *data)
static PacketHandler * getPacketHandler(float protocol_version=2.0)
#define ADDR_PRESENT_POSITION
GroupSyncWrite groupSyncWrite(portHandler, packetHandler, ADDR_GOAL_POSITION, 4)
static PortHandler * getPortHandler(const char *port_name)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
virtual bool openPort()=0
virtual int write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
#define ADDR_TORQUE_ENABLE
GroupSyncRead groupSyncRead(portHandler, packetHandler, ADDR_PRESENT_POSITION, 4)
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
virtual void closePort()=0
bool syncGetPresentPositionCallback(dynamixel_sdk_examples::SyncGetPosition::Request &req, dynamixel_sdk_examples::SyncGetPosition::Response &res)
PortHandler * portHandler