abstract_end_effector_driver.hpp
Go to the documentation of this file.
1 /*
2 abstract_ttl_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_END_EFFECTOR_DRIVER_HPP
18 #define ABSTRACT_END_EFFECTOR_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 
25 #include "abstract_ttl_driver.hpp"
26 
27 #include "dynamixel_sdk/dynamixel_sdk.h"
28 #include "common/common_defs.hpp"
29 #include "common/model/hardware_type_enum.hpp"
30 #include "common/model/single_motor_cmd.hpp"
31 #include "common/model/abstract_synchronize_motor_cmd.hpp"
32 
33 #include "common/model/action_type_enum.hpp"
34 
35 namespace ttl_driver
36 {
37 
42 {
43 
44 public:
45  AbstractEndEffectorDriver() = default;
46  AbstractEndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
47  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
48 
49 public:
50  virtual int readButton0Status(uint8_t id, common::model::EActionType& action) = 0;
51  virtual int readButton1Status(uint8_t id, common::model::EActionType& action) = 0;
52  virtual int readButton2Status(uint8_t id, common::model::EActionType& action) = 0;
53  virtual int syncReadButtonsStatus(const uint8_t& id, std::vector<common::model::EActionType>& action_list) = 0;
54 
55  virtual int readAccelerometerXValue(uint8_t id, uint32_t& x_value) = 0;
56  virtual int readAccelerometerYValue(uint8_t id, uint32_t& y_value) = 0;
57  virtual int readAccelerometerZValue(uint8_t id, uint32_t& z_value) = 0;
58 
59  virtual int readCollisionStatus(uint8_t id, bool& status) = 0;
60 
61  virtual int readDigitalInput(uint8_t id, bool& in) = 0;
62  virtual int writeDigitalOutput(uint8_t id, bool out) = 0;
63 
64  virtual int writeCollisionThresh(uint8_t id, int thresh) = 0;
65  virtual int writeCollisionThreshAlgo2(uint8_t id, int thresh) = 0;
66 
67  std::string interpretErrorState(uint32_t hw_state) const override;
68 
69  common::model::EActionType interpretActionValue(uint32_t value) const;
70 
71  // AbstractTtlDriver interface
72 protected:
73  std::string str() const override;
74  std::string interpretFirmwareVersion(uint32_t fw_version) const override;
75 
76  // AbstractTtlDriver interface
77 public:
78  int writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd) override;
79  int writeSyncCmd(int type, const std::vector<uint8_t> &ids, const std::vector<uint32_t> &params) override;
80 };
81 
82 } // ttl_driver
83 
84 #endif // ABSTRACT_END_EFFECTOR_DRIVER_HPP
ttl_driver::AbstractEndEffectorDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
MockEndEffectorDriver::interpretErrorState.
Definition: abstract_end_effector_driver.cpp:54
ttl_driver::AbstractEndEffectorDriver::writeCollisionThresh
virtual int writeCollisionThresh(uint8_t id, int thresh)=0
ttl_driver::AbstractTtlDriver
The AbstractTtlDriver class.
Definition: abstract_ttl_driver.hpp:37
ttl_driver::AbstractEndEffectorDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockEndEffectorDriver::interpretFirmawreVersion.
Definition: abstract_end_effector_driver.cpp:85
ttl_driver::AbstractEndEffectorDriver::readButton1Status
virtual int readButton1Status(uint8_t id, common::model::EActionType &action)=0
ttl_driver::AbstractEndEffectorDriver::interpretActionValue
common::model::EActionType interpretActionValue(uint32_t value) const
MockEndEffectorDriver::interpretActionValue.
Definition: abstract_end_effector_driver.cpp:103
ttl_driver::AbstractEndEffectorDriver::syncReadButtonsStatus
virtual int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list)=0
ttl_driver::AbstractEndEffectorDriver::readDigitalInput
virtual int readDigitalInput(uint8_t id, bool &in)=0
ttl_driver::AbstractEndEffectorDriver::str
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_end_effector_driver.cpp:48
ttl_driver::AbstractEndEffectorDriver::readButton2Status
virtual int readButton2Status(uint8_t id, common::model::EActionType &action)=0
ttl_driver::AbstractEndEffectorDriver::writeCollisionThreshAlgo2
virtual int writeCollisionThreshAlgo2(uint8_t id, int thresh)=0
ttl_driver::AbstractEndEffectorDriver::AbstractEndEffectorDriver
AbstractEndEffectorDriver()=default
ttl_driver::AbstractEndEffectorDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
MockEndEffectorDriver::writeSingleCmd.
Definition: abstract_end_effector_driver.cpp:133
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractEndEffectorDriver::readButton0Status
virtual int readButton0Status(uint8_t id, common::model::EActionType &action)=0
ttl_driver::AbstractEndEffectorDriver::readAccelerometerZValue
virtual int readAccelerometerZValue(uint8_t id, uint32_t &z_value)=0
abstract_ttl_driver.hpp
ttl_driver::AbstractEndEffectorDriver
The AbstractEndEffectorDriver class.
Definition: abstract_end_effector_driver.hpp:41
ttl_driver::AbstractEndEffectorDriver::readAccelerometerYValue
virtual int readAccelerometerYValue(uint8_t id, uint32_t &y_value)=0
ttl_driver::AbstractEndEffectorDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
MockEndEffectorDriver::writeSyncCmd.
Definition: abstract_end_effector_driver.cpp:163
ttl_driver::AbstractEndEffectorDriver::readCollisionStatus
virtual int readCollisionStatus(uint8_t id, bool &status)=0
ttl_driver::AbstractEndEffectorDriver::readAccelerometerXValue
virtual int readAccelerometerXValue(uint8_t id, uint32_t &x_value)=0
ttl_driver::AbstractEndEffectorDriver::writeDigitalOutput
virtual int writeDigitalOutput(uint8_t id, bool out)=0


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