19 #include "common/model/dxl_command_type_enum.hpp"
20 #include "common/model/single_motor_cmd.hpp"
29 using ::common::model::EDxlCommandType;
38 std::shared_ptr<dynamixel::PacketHandler> packetHandler)
54 if (cmd && cmd->isValid() && cmd->isDxlCmd())
56 switch (EDxlCommandType(cmd->getCmdType()))
58 case EDxlCommandType::CMD_TYPE_VELOCITY:
60 case EDxlCommandType::CMD_TYPE_POSITION:
62 case EDxlCommandType::CMD_TYPE_EFFORT:
63 return writeTorqueGoal(cmd->getId(),
static_cast<uint16_t
>(cmd->getParam()));
64 case EDxlCommandType::CMD_TYPE_TORQUE:
66 case EDxlCommandType::CMD_TYPE_LEARNING_MODE:
68 case EDxlCommandType::CMD_TYPE_PING:
69 return ping(cmd->getId());
70 case EDxlCommandType::CMD_TYPE_PID: {
71 std::vector<uint16_t> params_conv;
72 for (
auto p : cmd->getParams())
74 params_conv.emplace_back(
static_cast<uint16_t
>(p));
76 return writePID(cmd->getId(), params_conv);
78 case EDxlCommandType::CMD_TYPE_PROFILE:
80 case EDxlCommandType::CMD_TYPE_CONTROL_MODE:
81 return writeControlMode(cmd->getId(),
static_cast<uint8_t
>(cmd->getParam()));
82 case EDxlCommandType::CMD_TYPE_LED_STATE:
83 return writeLed(cmd->getId(),
static_cast<uint8_t
>(cmd->getParam()));
84 case EDxlCommandType::CMD_TYPE_STARTUP:
86 case EDxlCommandType::CMD_TYPE_TEMPERATURE_LIMIT:
88 case EDxlCommandType::CMD_TYPE_SHUTDOWN:
91 std::cout <<
"Command not implemented " << cmd->getCmdType() << std::endl;
95 std::cout <<
"AbstractDxlDriver::writeSingleCmd : Command not validated: " << cmd->str() << std::endl;
96 return COMM_RX_CORRUPT;
107 assert(!ids.empty() &&
"AbstractDxlDriver::writeSyncCmd: ids is empty");
108 assert(!params.empty() &&
"AbstractDxlDriver::writeSyncCmd: params is empty");
110 switch (EDxlCommandType(type))
112 case EDxlCommandType::CMD_TYPE_POSITION:
114 case EDxlCommandType::CMD_TYPE_VELOCITY:
116 case EDxlCommandType::CMD_TYPE_EFFORT: {
117 std::vector<uint16_t> params_conv;
118 params_conv.reserve(params.size());
119 for (
auto const &p : params)
121 params_conv.emplace_back(
static_cast<uint16_t
>(p));
125 case EDxlCommandType::CMD_TYPE_TORQUE: {
126 std::vector<uint8_t> params_conv;
127 params_conv.reserve(params.size());
128 for (
auto const &p : params)
130 params_conv.emplace_back(
static_cast<uint8_t
>(p));
134 case EDxlCommandType::CMD_TYPE_LEARNING_MODE: {
135 std::vector<uint8_t> params_inv;
136 params_inv.reserve(params.size());
137 for (
auto const &p : params)
139 params_inv.emplace_back(!p);
144 std::cout <<
"Command not implemented " << type << std::endl;
147 std::cout <<
"AbstractDxlDriver::writeSyncCmd : Command not validated: " << type << std::endl;