Compare commits
9 Commits
0839b19c09
...
4cd994cf7a
| Author | SHA1 | Date | |
|---|---|---|---|
| 4cd994cf7a | |||
| 9dee466e0e | |||
| 43da8a3a37 | |||
| 5e2cc0b5af | |||
| 6cc4ce01d4 | |||
| f973dfc9d8 | |||
| fbab22835b | |||
| a409150ea6 | |||
| b1492b4c5d |
@ -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;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user