18 #include "common/model/stepper_command_type_enum.hpp"
28 using ::common::model::EStepperCalibrationStatus;
29 using ::common::model::EStepperCommandType;
56 if (cmd->isValid() && cmd->isStepperCmd())
58 switch (EStepperCommandType(cmd->getCmdType()))
60 case EStepperCommandType::CMD_TYPE_VELOCITY:
62 case EStepperCommandType::CMD_TYPE_POSITION:
64 case EStepperCommandType::CMD_TYPE_TORQUE:
66 case EStepperCommandType::CMD_TYPE_LEARNING_MODE:
68 case EStepperCommandType::CMD_TYPE_CALIBRATION:
70 case EStepperCommandType::CMD_TYPE_FACTORY_CALIBRATION:
72 case EStepperCommandType::CMD_TYPE_CALIBRATION_SETUP:
73 return writeHomingSetup(cmd->getId(),
static_cast<uint8_t
>(cmd->getParams().at(0)),
static_cast<uint8_t
>(cmd->getParams().at(1)));
74 case EStepperCommandType::CMD_TYPE_PING:
75 return ping(cmd->getId());
76 case EStepperCommandType::CMD_TYPE_CONVEYOR:
78 std::vector<uint32_t> params = cmd->getParams();
85 uint32_t dir =
static_cast<uint32_t
>(cmd->getParams().at(2));
86 uint32_t speed_percent = std::clamp(
static_cast<uint32_t
>(cmd->getParams().at(1)), 0u, 100u);
89 ROS_INFO(
"AbstractStepperDriver::writeSingleCmd: speed = %d", speed);
92 case EStepperCommandType::CMD_TYPE_VELOCITY_PROFILE:
94 case EStepperCommandType::CMD_TYPE_OPERATING_MODE:
95 return writeControlMode(cmd->getId(),
static_cast<uint8_t
>(cmd->getParam()));
97 std::cout <<
"Command not implemented " << cmd->getCmdType() << std::endl;
101 std::cout <<
"AbstractStepperDriver::writeSingleCmd: Command not validated : " << cmd->str() << std::endl;
113 assert(!ids.empty() &&
"AbstractStepperDriver::writeSyncCmdwriteSyncCmd: ids is empty");
114 assert(!params.empty() &&
"AbstractStepperDriver::writeSyncCmdwriteSyncCmd: params is empty");
116 switch (EStepperCommandType(type))
118 case EStepperCommandType::CMD_TYPE_POSITION:
120 case EStepperCommandType::CMD_TYPE_VELOCITY:
122 case EStepperCommandType::CMD_TYPE_TORQUE:
124 std::vector<uint8_t> params_conv;
125 params_conv.reserve(params.size());
126 for (
auto const &p : params)
128 params_conv.emplace_back(
static_cast<uint8_t
>(p));
132 case EStepperCommandType::CMD_TYPE_LEARNING_MODE:
134 std::vector<uint8_t> params_inv;
135 params_inv.reserve(params.size());
136 for (
auto const &p : params)
138 params_inv.emplace_back(!p);
142 case EStepperCommandType::CMD_TYPE_WRITE_HOMING_ABS_POSITION:
145 std::cout <<
"Command not implemented " << type << std::endl;
148 std::cout <<
"AbstractStepperDriver::writeSyncCmd : Command not validated : " << type << std::endl;
159 auto v_major =
static_cast<uint8_t
>(fw_version >> 24);
160 auto v_minor =
static_cast<uint16_t
>(fw_version >> 8);
161 auto v_patch =
static_cast<uint8_t
>(fw_version >> 0);
163 std::ostringstream ss;
164 ss << std::to_string(v_major) <<
"." << std::to_string(v_minor) <<
"." << std::to_string(v_patch);
165 std::string version = ss.str();
177 std::string hardware_message;
179 if (hw_state & 1 << 0)
181 hardware_message +=
"Input Voltage";
183 if (hw_state & 1 << 2)
185 if (!hardware_message.empty())
186 hardware_message +=
", ";
187 hardware_message +=
"OverHeating";
189 if (hw_state & 1 << 3)
191 if (!hardware_message.empty())
192 hardware_message +=
", ";
193 hardware_message +=
"Motor Encoder";
195 if (hw_state & 1 << 7)
197 if (!hardware_message.empty())
198 hardware_message +=
", ";
199 hardware_message +=
"Disconnection";
202 if (!hardware_message.empty())
203 hardware_message +=
" Error";
205 return hardware_message;
215 EStepperCalibrationStatus homing_status{EStepperCalibrationStatus::UNINITIALIZED};
220 homing_status = EStepperCalibrationStatus::UNINITIALIZED;
223 homing_status = EStepperCalibrationStatus::IN_PROGRESS;
226 homing_status = EStepperCalibrationStatus::OK;
229 homing_status = EStepperCalibrationStatus::FAIL;
232 homing_status = EStepperCalibrationStatus::FAIL;
236 return homing_status;
246 ROS_WARN(
"AbstractStepperDriver::factoryCalibration - not implemented");
256 uint32_t unsigned_present_velocity = 0;
258 if (res != COMM_SUCCESS )
260 ROS_ERROR(
"AbstractStepperDriver::readConveyorVelocity: readVelocity failed with error %d", res);
266 int32_t present_velocity =
static_cast<int32_t
>(unsigned_present_velocity);
269 auto velocity_rpms = present_velocity * velocity_unit;
270 direction = present_velocity > 0 ? 1 : -1;
271 velocity_percent =
static_cast<int32_t
>(std::abs(velocity_rpms * 100 /
MAX_CONVEYOR_RPM));