9 Commits

Author SHA1 Message Date
4cd994cf7a Fixed services for parameter adjusting not working 2025-02-28 21:47:23 +01:00
9dee466e0e Fixed service name confilict 2025-02-28 21:47:23 +01:00
43da8a3a37 Added dwm rotate 2025-02-28 21:47:23 +01:00
5e2cc0b5af Added rotate action 2025-02-28 21:47:23 +01:00
6cc4ce01d4 Added Zero and SetWidth services 2025-02-28 21:47:23 +01:00
f973dfc9d8 Added SetWidth service 2025-02-28 21:47:23 +01:00
fbab22835b Added more missing dependencies 2025-02-28 21:47:23 +01:00
a409150ea6 Added mg_msgs as requirement to magrob 2025-02-28 21:47:23 +01:00
b1492b4c5d Changed the way we communicate with the stepper driver 2025-02-28 20:48:58 +01:00

View File

@ -66,14 +66,18 @@ hardware_interface::return_type mg::MgStepperInterface::read(const rclcpp::Time&
}
hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time&, const rclcpp::Duration&) {
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));
union {
std::array<u_char, sizeof(double)> bytes;
double data;
} value{};
try {
odrive_serial_interface.Write(cmd_left + cmd_right);
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); }
} catch (const std::runtime_error& e) { return hardware_interface::return_type::ERROR; }
return hardware_interface::return_type::OK;
}