abstract_motor_driver.hpp
Go to the documentation of this file.
1 /*
2 ttl_motor_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_MOTOR_DRIVER_HPP
18 #define ABSTRACT_MOTOR_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 
25 #include "dynamixel_sdk/dynamixel_sdk.h"
26 #include "common/common_defs.hpp"
27 #include "common/model/hardware_type_enum.hpp"
28 
30 
31 namespace ttl_driver
32 {
33 
37 // CC add list of associated motors ? this would remove the need for a map and for some params
39 {
40 public:
41  AbstractMotorDriver() = default;
42  AbstractMotorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
43  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
44 
45 public:
46  // AbstractTtlDriver interface
47  std::string str() const override;
48 
49 public:
50  // here are only common TTL commands found in both Steppers and DXl
51 
52  // eeprom write
53  virtual int changeId(uint8_t id, uint8_t new_id) = 0;
54 
55  // eeprom read
56  virtual int readMinPosition(uint8_t id, uint32_t& min_pos) = 0;
57  virtual int readMaxPosition(uint8_t id, uint32_t& max_pos) = 0;
58 
59  // ram write
60 
61  virtual int writeControlMode(uint8_t id, uint8_t mode) = 0;
62  virtual int writeVelocityProfile(uint8_t id, const std::vector<uint32_t>& data_list) = 0;
63 
64  virtual int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) = 0;
65  virtual int writePositionGoal(uint8_t id, uint32_t position) = 0;
66  virtual int writeVelocityGoal(uint8_t id, uint32_t velocity) = 0;
67 
68  virtual int syncWriteTorquePercentage(const std::vector<uint8_t>& id_list, const std::vector<uint8_t>& torque_percentage_list) = 0;
69  virtual int syncWritePositionGoal(const std::vector<uint8_t>& id_list, const std::vector<uint32_t>& position_list) = 0;
70  virtual int syncWriteVelocityGoal(const std::vector<uint8_t>& id_list, const std::vector<uint32_t>& velocity_list) = 0;
71 
72  // ram read
73  virtual int readControlMode(uint8_t id, uint8_t& mode) = 0;
74  virtual int readVelocityProfile(uint8_t id, std::vector<uint32_t>& data_list) = 0;
75 
76  virtual int readPosition(uint8_t id, uint32_t& present_position) = 0;
77  virtual int readVelocity(uint8_t id, uint32_t& present_velocity) = 0;
78 
79  virtual int syncReadPosition(const std::vector<uint8_t>& id_list, std::vector<uint32_t>& position_list) = 0;
80  virtual int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t>& velocity_list) = 0;
81  virtual int syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2> >& data_array_list) = 0;
82 };
83 
84 } // ttl_driver
85 
86 #endif // ABSTRACT_MOTOR_DRIVER_HPP
ttl_driver::AbstractMotorDriver::syncReadJointStatus
virtual int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array_list)=0
ttl_driver::AbstractTtlDriver
The AbstractTtlDriver class.
Definition: abstract_ttl_driver.hpp:37
ttl_driver::AbstractMotorDriver::changeId
virtual int changeId(uint8_t id, uint8_t new_id)=0
ttl_driver::AbstractMotorDriver::readPosition
virtual int readPosition(uint8_t id, uint32_t &present_position)=0
ttl_driver::AbstractMotorDriver::syncWritePositionGoal
virtual int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list)=0
ttl_driver::AbstractMotorDriver::readMinPosition
virtual int readMinPosition(uint8_t id, uint32_t &min_pos)=0
ttl_driver::AbstractMotorDriver::writeControlMode
virtual int writeControlMode(uint8_t id, uint8_t mode)=0
ttl_driver::AbstractMotorDriver::writeVelocityProfile
virtual int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data_list)=0
ttl_driver::AbstractMotorDriver::syncReadPosition
virtual int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list)=0
ttl_driver::AbstractMotorDriver::readVelocityProfile
virtual int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list)=0
ttl_driver::AbstractMotorDriver::writePositionGoal
virtual int writePositionGoal(uint8_t id, uint32_t position)=0
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractMotorDriver::syncReadVelocity
virtual int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list)=0
ttl_driver::AbstractMotorDriver
The XDriver class.
Definition: abstract_motor_driver.hpp:38
ttl_driver::AbstractMotorDriver::str
std::string str() const override
AbstractMotorDriver::str.
Definition: abstract_motor_driver.cpp:44
abstract_ttl_driver.hpp
ttl_driver::AbstractMotorDriver::readVelocity
virtual int readVelocity(uint8_t id, uint32_t &present_velocity)=0
ttl_driver::AbstractMotorDriver::syncWriteVelocityGoal
virtual int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list)=0
ttl_driver::AbstractMotorDriver::readControlMode
virtual int readControlMode(uint8_t id, uint8_t &mode)=0
ttl_driver::AbstractMotorDriver::writeTorquePercentage
virtual int writeTorquePercentage(uint8_t id, uint8_t torque_percentage)=0
ttl_driver::AbstractMotorDriver::syncWriteTorquePercentage
virtual int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list)=0
ttl_driver::AbstractMotorDriver::writeVelocityGoal
virtual int writeVelocityGoal(uint8_t id, uint32_t velocity)=0
ttl_driver::AbstractMotorDriver::AbstractMotorDriver
AbstractMotorDriver()=default
ttl_driver::AbstractMotorDriver::readMaxPosition
virtual int readMaxPosition(uint8_t id, uint32_t &max_pos)=0


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