diff --git a/src/description/ros2_control/drive/drive.odrive.ros2_control.xacro b/src/description/ros2_control/drive/drive.odrive.ros2_control.xacro index e584d59e..2551097d 100644 --- a/src/description/ros2_control/drive/drive.odrive.ros2_control.xacro +++ b/src/description/ros2_control/drive/drive.odrive.ros2_control.xacro @@ -6,7 +6,7 @@ odrive_ros2_control_plugin/ODriveHardwareInterface - can0 + can1 diff --git a/src/description/ros2_control/drive/drive.rmd.ros2_control.xacro b/src/description/ros2_control/drive/drive.rmd.ros2_control.xacro index 3bdd541d..9b2a21bf 100644 --- a/src/description/ros2_control/drive/drive.rmd.ros2_control.xacro +++ b/src/description/ros2_control/drive/drive.rmd.ros2_control.xacro @@ -7,11 +7,11 @@ 30 5 0 - can0 + can1 - 0x142 + 0x14A 1 -1.0 150 @@ -24,7 +24,7 @@ - 0x145 + 0x141 1 1.0 150 @@ -37,9 +37,9 @@ - 0x144 + 0x15E 1 - -1.0 + 1.0 150 @@ -50,9 +50,9 @@ - 0x141 + 0x159 1 - 1.0 + -1.0 150 diff --git a/src/hardware_interfaces/ros_odrive/odrive_node/src/odrive_can_node.cpp b/src/hardware_interfaces/ros_odrive/odrive_node/src/odrive_can_node.cpp index eaa85708..b27d8535 100644 --- a/src/hardware_interfaces/ros_odrive/odrive_node/src/odrive_can_node.cpp +++ b/src/hardware_interfaces/ros_odrive/odrive_node/src/odrive_can_node.cpp @@ -30,7 +30,7 @@ enum ControlMode : uint64_t { ODriveCanNode::ODriveCanNode(const std::string& node_name) : rclcpp::Node(node_name) { - rclcpp::Node::declare_parameter("interface", "can0"); + rclcpp::Node::declare_parameter("interface", "can1"); rclcpp::Node::declare_parameter("node_id", 0); rclcpp::Node::declare_parameter("axis_idle_on_shutdown", false); diff --git a/src/hardware_interfaces/ros_odrive/odrive_ros2_control/src/odrive_hardware_interface.cpp b/src/hardware_interfaces/ros_odrive/odrive_ros2_control/src/odrive_hardware_interface.cpp index b7bd4cf0..d19a19c7 100644 --- a/src/hardware_interfaces/ros_odrive/odrive_ros2_control/src/odrive_hardware_interface.cpp +++ b/src/hardware_interfaces/ros_odrive/odrive_ros2_control/src/odrive_hardware_interface.cpp @@ -116,7 +116,7 @@ CallbackReturn ODriveHardwareInterface::on_init(const hardware_interface::Hardwa return CallbackReturn::ERROR; } - can_intf_name_ = info_.hardware_parameters["can"]; + can_intf_name_ = "can1"; for (auto& joint : info_.joints) { axes_.emplace_back(&can_intf_, std::stoi(joint.parameters.at("node_id")), std::stoi(joint.parameters.at("gear_ratio"))); diff --git a/src/infrastructure/umdloop_can_library/src/SocketCanBus.cpp b/src/infrastructure/umdloop_can_library/src/SocketCanBus.cpp index 0b153200..15755d6a 100644 --- a/src/infrastructure/umdloop_can_library/src/SocketCanBus.cpp +++ b/src/infrastructure/umdloop_can_library/src/SocketCanBus.cpp @@ -205,4 +205,4 @@ void SocketCanBus::receiveLoop_() { } } -} // namespace CANLib \ No newline at end of file +} // namespace CANLib