diff --git a/include/openarm/can/socket/openarm.hpp b/include/openarm/can/socket/openarm.hpp index 5f7b8e5..666e259 100644 --- a/include/openarm/can/socket/openarm.hpp +++ b/include/openarm/can/socket/openarm.hpp @@ -28,6 +28,9 @@ public: OpenArm(const std::string& can_interface, bool enable_fd = false); ~OpenArm() = default; + std::string can_interface() const noexcept { return can_interface_; } + bool can_fd_enabled() const noexcept { return enable_fd_; } + // Component initialization void init_arm_motors(const std::vector& motor_types, const std::vector& send_can_ids, diff --git a/src/openarm/damiao_motor/dm_motor_device_collection.cpp b/src/openarm/damiao_motor/dm_motor_device_collection.cpp index 3ec8e05..eca9027 100644 --- a/src/openarm/damiao_motor/dm_motor_device_collection.cpp +++ b/src/openarm/damiao_motor/dm_motor_device_collection.cpp @@ -55,7 +55,7 @@ void DMDeviceCollection::set_zero_all() { } void DMDeviceCollection::refresh_one(int i) { - auto dm_device = get_dm_devices()[i]; + auto dm_device = get_dm_devices().at(i); auto& motor = dm_device->get_motor(); CANPacket refresh_packet = CanPacketEncoder::create_refresh_command(motor); send_command_to_device(dm_device, refresh_packet);