abstract_stepper_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_STEPPER_DRIVER_HPP
18 #define ABSTRACT_STEPPER_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 #include "common/model/stepper_calibration_status_enum.hpp"
30 
31 namespace ttl_driver
32 {
33 
35  {
36  public:
37  AbstractStepperDriver() = default;
38  AbstractStepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
39  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
40 
41  public:
42  // AbstractMotorDriver interface
43  std::string str() const override;
44 
45  int writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd) override;
46  int writeSyncCmd(int type, const std::vector<uint8_t> &ids, const std::vector<uint32_t> &params) override;
47 
48  virtual common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const;
49  std::string interpretErrorState(uint32_t hw_state) const override;
50 
51  protected:
52  // AbstractTtlDriver interface
53  std::string interpretFirmwareVersion(uint32_t fw_version) const override;
54 
55  public:
56  // specific Stepper commands
57 
58  // ram write
59  virtual int startHoming(uint8_t id) = 0;
60  virtual int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) = 0;
61  virtual int factoryCalibration(const uint8_t id, const uint32_t &command);
62 
63  // read
64  virtual int readHomingStatus(uint8_t id, uint8_t &status) = 0;
65  virtual int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list) = 0;
66 
67  virtual int readFirmwareRunning(uint8_t id, bool &is_running) = 0;
68 
69  virtual int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position) = 0;
70  virtual int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position) = 0;
71 
72  // Important Remark: It is weird to have conveyor specific functions in a stepper driver
73  // This is temporary waiting for a new driver abstraction design
74  int readConveyorVelocity(uint8_t id, int32_t &velocity, int32_t &direction);
75 
76  // parameters
77 
81  virtual float velocityUnit() const = 0;
82  };
83 
84 } // ttl_driver
85 
86 #endif // ABSTRACT_STEPPER_DRIVER_HPP
ttl_driver::AbstractStepperDriver::interpretHomingData
virtual common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const
AbstractStepperDriver::interpretHomingData.
Definition: abstract_stepper_driver.cpp:213
ttl_driver::AbstractStepperDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
AbstractStepperDriver::interpretErrorState.
Definition: abstract_stepper_driver.cpp:175
ttl_driver::AbstractStepperDriver::factoryCalibration
virtual int factoryCalibration(const uint8_t id, const uint32_t &command)
AbstractStepperDriver::factoryCalibration.
Definition: abstract_stepper_driver.cpp:244
ttl_driver::AbstractStepperDriver::writeHomingSetup
virtual int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)=0
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:48
ttl_driver::AbstractStepperDriver::syncReadHomingStatus
virtual int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)=0
ttl_driver::AbstractStepperDriver::syncWriteHomingAbsPosition
virtual int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)=0
ttl_driver::AbstractStepperDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
AbstractStepperDriver::writeSingleCmd.
Definition: abstract_stepper_driver.cpp:54
ttl_driver::AbstractStepperDriver::AbstractStepperDriver
AbstractStepperDriver()=default
ttl_driver::AbstractStepperDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
AbstractStepperDriver::interpretFirmwareVersion.
Definition: abstract_stepper_driver.cpp:157
ttl_driver::AbstractStepperDriver::readHomingStatus
virtual int readHomingStatus(uint8_t id, uint8_t &status)=0
abstract_motor_driver.hpp
ttl_driver::AbstractStepperDriver::velocityUnit
virtual float velocityUnit() const =0
writeVelocityGoal: define the unit of the velocity in RPM
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractStepperDriver::readFirmwareRunning
virtual int readFirmwareRunning(uint8_t id, bool &is_running)=0
ttl_driver::AbstractStepperDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
AbstractStepperDriver::writeSyncCmd.
Definition: abstract_stepper_driver.cpp:111
ttl_driver::AbstractStepperDriver::readConveyorVelocity
int readConveyorVelocity(uint8_t id, int32_t &velocity, int32_t &direction)
Returns the velocity of the conveyor in percentage.
Definition: abstract_stepper_driver.cpp:254
ttl_driver::AbstractStepperDriver::syncReadHomingAbsPosition
virtual int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)=0
ttl_driver::AbstractMotorDriver
The XDriver class.
Definition: abstract_motor_driver.hpp:38
ttl_driver::AbstractStepperDriver
Definition: abstract_stepper_driver.hpp:34
ttl_driver::AbstractStepperDriver::startHoming
virtual int startHoming(uint8_t id)=0


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