protocol1_packet_handler.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
21 
22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
24 
25 
26 #include "packet_handler.h"
27 
28 namespace dynamixel
29 {
30 
34 class WINDECLSPEC Protocol1PacketHandler : public PacketHandler
35 {
36  private:
38 
40 
41  public:
46  static Protocol1PacketHandler *getInstance() { return unique_instance_; }
47 
49 
54  float getProtocolVersion() { return 1.0; }
55 
61  const char *getTxRxResult (int result);
62 
68  const char *getRxPacketError (uint8_t error);
69 
85  int txPacket (PortHandler *port, uint8_t *txpacket);
86 
106  int rxPacket (PortHandler *port, uint8_t *rxpacket);
107 
122  int txRxPacket (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
123 
133  int ping (PortHandler *port, uint8_t id, uint8_t *error = 0);
134 
151  int ping (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0);
152 
159  int broadcastPing (PortHandler *port, std::vector<uint8_t> &id_list);
160 
170  int action (PortHandler *port, uint8_t id);
171 
179  int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0);
180 
188  int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0);
189 
201  int factoryReset (PortHandler *port, uint8_t id, uint8_t option, uint8_t *error = 0);
202 
217  int readTx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length);
218 
229  int readRx (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0);
230 
248  int readTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
249 
258  int read1ByteTx (PortHandler *port, uint8_t id, uint16_t address);
259 
269  int read1ByteRx (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0);
270 
283  int read1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0);
284 
293  int read2ByteTx (PortHandler *port, uint8_t id, uint16_t address);
294 
304  int read2ByteRx (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0);
305 
318  int read2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0);
319 
328  int read4ByteTx (PortHandler *port, uint8_t id, uint16_t address);
329 
339  int read4ByteRx (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0);
340 
353  int read4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0);
354 
366  int writeTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
367 
381  int writeTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
382 
392  int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data);
393 
405  int write1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0);
406 
416  int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data);
417 
429  int write2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0);
430 
440  int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data);
441 
453  int write4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0);
454 
467  int regWriteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
468 
483  int regWriteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
484 
494  int syncReadTx (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
495  // SyncReadRx -> GroupSyncRead class
496  // SyncReadTxRx -> GroupSyncRead class
497 
509  int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
510 
520  int bulkReadTx (PortHandler *port, uint8_t *param, uint16_t param_length);
521  // BulkReadRx -> GroupBulkRead class
522  // BulkReadTxRx -> GroupBulkRead class
523 
531  int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length);
532 };
533 
534 }
535 
536 
537 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_ */
dynamixel::Protocol1PacketHandler::getProtocolVersion
float getProtocolVersion()
The function that returns Protocol version used in Protocol1PacketHandler (1.0)
Definition: protocol1_packet_handler.h:54
dynamixel
Definition: group_bulk_read.h:31
dynamixel::PortHandler
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition: port_handler.h:56
dynamixel::Protocol1PacketHandler::getInstance
static Protocol1PacketHandler * getInstance()
The function that returns Protocol1PacketHandler instance.
Definition: protocol1_packet_handler.h:46
dynamixel::Protocol1PacketHandler
The class for control Dynamixel by using Protocol1.0.
Definition: protocol1_packet_handler.h:34
dynamixel::Protocol1PacketHandler::~Protocol1PacketHandler
virtual ~Protocol1PacketHandler()
Definition: protocol1_packet_handler.h:48
dynamixel::Protocol1PacketHandler::unique_instance_
static Protocol1PacketHandler * unique_instance_
Definition: protocol1_packet_handler.h:37
packet_handler.h
dynamixel::PacketHandler
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
Definition: packet_handler.h:82


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Wed Mar 2 2022 00:13:50