8 Commits

Author SHA1 Message Date
0839b19c09 Fixed services for parameter adjusting not working 2025-02-28 19:43:00 +01:00
e46b336357 Fixed service name confilict 2025-02-26 16:47:58 +01:00
4576703012 Added dwm rotate 2025-02-26 16:41:16 +01:00
74c5bc77cc Added rotate action 2025-02-26 16:26:35 +01:00
4835dd8eda Added Zero and SetWidth services 2025-02-26 02:07:30 +01:00
7311085be0 Added SetWidth service 2025-02-26 02:07:07 +01:00
447d9a5fa6 Added more missing dependencies 2025-02-26 02:06:50 +01:00
b28463635c Added mg_msgs as requirement to magrob 2025-02-25 19:17:42 +01:00

View File

@ -66,18 +66,14 @@ hardware_interface::return_type mg::MgStepperInterface::read(const rclcpp::Time&
}
hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time&, const rclcpp::Duration&) {
union {
std::array<u_char, sizeof(double)> bytes;
double data;
} value{};
std::string cmd_left;
std::string cmd_right;
cmd_left = std::to_string(left_wheel_vel_cmd / (2 * M_PI)) + " ";
cmd_right = std::to_string(-right_wheel_vel_cmd / (2 * M_PI));
try {
odrive_serial_interface.Write("s;");
value.data = left_wheel_vel_cmd / (2 * M_PI);
for (const auto& bt : value.bytes) { odrive_serial_interface.WriteByte(bt); }
value.data = -right_wheel_vel_cmd / (2 * M_PI);
for (const auto& bt : value.bytes) { odrive_serial_interface.WriteByte(bt); }
odrive_serial_interface.Write(cmd_left + cmd_right);
} catch (const std::runtime_error& e) { return hardware_interface::return_type::ERROR; }
return hardware_interface::return_type::OK;
}