27 using ::std::ostringstream;
28 using ::std::shared_ptr;
40 : AbstractTtlDriver(std::move(portHandler), std::move(packetHandler))
56 std::string hardware_message;
58 if (hw_state & 1 << 0)
60 hardware_message +=
"Input Voltage";
62 if (hw_state & 1 << 2)
64 if (!hardware_message.empty())
65 hardware_message +=
", ";
66 hardware_message +=
"OverHeating";
68 if (hw_state & 1 << 7)
70 if (!hardware_message.empty())
71 hardware_message +=
", ";
72 hardware_message +=
"Disconnection";
75 if (!hardware_message.empty())
76 hardware_message +=
" Error";
78 return hardware_message;
87 auto v_major =
static_cast<uint8_t
>(fw_version >> 24);
88 auto v_minor =
static_cast<uint16_t
>(fw_version >> 8);
89 auto v_patch =
static_cast<uint8_t
>(fw_version >> 0);
91 std::ostringstream ss;
92 ss << std::to_string(v_major) <<
"." << std::to_string(v_minor) <<
"." << std::to_string(v_patch);
93 std::string version = ss.str();
105 common::model::EActionType action = common::model::EActionType::NO_ACTION;
111 action = common::model::EActionType::SINGLE_PUSH_ACTION;
113 else if (value & 1 << 1)
115 action = common::model::EActionType::DOUBLE_PUSH_ACTION;
117 else if (value & 1 << 2)
119 action = common::model::EActionType::LONG_PUSH_ACTION;
121 else if (value & 1 << 3)
123 action = common::model::EActionType::HANDLE_HELD_ACTION;
135 if (cmd && cmd->isValid())
137 switch (common::model::EEndEffectorCommandType(cmd->getCmdType()))
139 case common::model::EEndEffectorCommandType::CMD_TYPE_DIGITAL_OUTPUT:
142 case common::model::EEndEffectorCommandType::CMD_TYPE_PING:
145 case common::model::EEndEffectorCommandType::CMD_TYPE_SET_COLLISION_THRESH:
148 case common::model::EEndEffectorCommandType::CMD_TYPE_SET_COLLISION_THRESH_ALGO_2:
152 std::cout <<
"Command not implemented" << std::endl;
165 std::cout <<
"Synchronized cmd not implemented for end effector" << std::endl;