abstract_dxl_driver.hpp
Go to the documentation of this file.
1 /*
2 abstract_dxl_driver.hpp
3 Copyright (C) 2020 Niryo
4 All rights reserved.
5 This program is free software: you can redistribute it and/or modify
6 it under the terms of the GNU General Public License as published by
7 the Free Software Foundation, either version 3 of the License, or
8 (at your option) any later version.
9 This program is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 GNU General Public License for more details.
13 You should have received a copy of the GNU General Public License
14 along with this program. If not, see <http:// www.gnu.org/licenses/>.
15 */
16 
17 #ifndef ABSTRACT_DXL_DRIVER_HPP
18 #define ABSTRACT_DXL_DRIVER_HPP
19 
20 // ttl
22 
23 // std
24 #include <memory>
25 
26 // common
27 #include "common/model/single_motor_cmd.hpp"
28 #include "common/model/synchronize_motor_cmd.hpp"
29 
30 namespace ttl_driver
31 {
32 
34  {
35  public:
36  AbstractDxlDriver() = default;
37  AbstractDxlDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
38  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
39 
40  public:
41  // AbstractMotorDriver interface
42  std::string str() const override;
43 
44  int writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd) override;
45  int writeSyncCmd(int type, const std::vector<uint8_t> &ids, const std::vector<uint32_t> &params) override;
46 
47  public:
48  // specific DXL commands
49 
50  // eeprom write
51  virtual int writeStartupConfiguration(uint8_t id, uint8_t config) = 0;
52  virtual int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit) = 0;
53  virtual int writeShutdownConfiguration(uint8_t id, uint8_t configuration) = 0;
54 
55  // ram read
56  virtual int readLoad(uint8_t id, uint16_t &present_load) = 0;
57  virtual int syncReadLoad(const std::vector<uint8_t> &id_list, std::vector<uint16_t> &load_list) = 0;
58 
59  virtual int readPID(uint8_t id, std::vector<uint16_t> &data) = 0;
60 
61  virtual int readMoving(uint8_t id, uint8_t &status) = 0;
62 
63  // ram write
64  virtual int writePID(uint8_t id, const std::vector<uint16_t> &data) = 0;
65 
66  virtual int writeLed(uint8_t id, uint8_t led_value) = 0;
67  virtual int syncWriteLed(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &led_list) = 0;
68 
69  virtual int writeTorqueGoal(uint8_t id, uint16_t torque) = 0;
70  virtual int syncWriteTorqueGoal(const std::vector<uint8_t> &id_list, const std::vector<uint16_t> &torque_list) = 0;
71  };
72 
73 } // ttl_driver
74 
75 #endif // ABSTRACT_DXL_DRIVER_HPP
ttl_driver::AbstractDxlDriver::syncReadLoad
virtual int syncReadLoad(const std::vector< uint8_t > &id_list, std::vector< uint16_t > &load_list)=0
ttl_driver::AbstractDxlDriver::writeLed
virtual int writeLed(uint8_t id, uint8_t led_value)=0
ttl_driver::AbstractDxlDriver::readMoving
virtual int readMoving(uint8_t id, uint8_t &status)=0
ttl_driver::AbstractDxlDriver::readLoad
virtual int readLoad(uint8_t id, uint16_t &present_load)=0
ttl_driver::AbstractDxlDriver::writeTemperatureLimit
virtual int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit)=0
ttl_driver::AbstractDxlDriver
Definition: abstract_dxl_driver.hpp:33
ttl_driver::AbstractDxlDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
AbstractDxlDriver::writeSingleCmd.
Definition: abstract_dxl_driver.cpp:48
abstract_motor_driver.hpp
ttl_driver::AbstractDxlDriver::readPID
virtual int readPID(uint8_t id, std::vector< uint16_t > &data)=0
ttl_driver::AbstractDxlDriver::writeShutdownConfiguration
virtual int writeShutdownConfiguration(uint8_t id, uint8_t configuration)=0
ttl_driver::AbstractDxlDriver::AbstractDxlDriver
AbstractDxlDriver()=default
ttl_driver::AbstractDxlDriver::syncWriteLed
virtual int syncWriteLed(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &led_list)=0
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractMotorDriver
The XDriver class.
Definition: abstract_motor_driver.hpp:38
ttl_driver::AbstractDxlDriver::writeStartupConfiguration
virtual int writeStartupConfiguration(uint8_t id, uint8_t config)=0
ttl_driver::AbstractDxlDriver::writePID
virtual int writePID(uint8_t id, const std::vector< uint16_t > &data)=0
ttl_driver::AbstractDxlDriver::str
std::string str() const override
AbstractTtlDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_dxl_driver.cpp:42
ttl_driver::AbstractDxlDriver::writeTorqueGoal
virtual int writeTorqueGoal(uint8_t id, uint16_t torque)=0
ttl_driver::AbstractDxlDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
AbstractDxlDriver::writeSyncCmd.
Definition: abstract_dxl_driver.cpp:102
ttl_driver::AbstractDxlDriver::syncWriteTorqueGoal
virtual int syncWriteTorqueGoal(const std::vector< uint8_t > &id_list, const std::vector< uint16_t > &torque_list)=0


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14