From 3454ea25b057ae969a0290470cf2b4dc546035d2 Mon Sep 17 00:00:00 2001 From: UMDLoop Jetson Orin NX Date: Sat, 9 May 2026 09:03:34 -0400 Subject: [PATCH 1/2] give_jetson_internet_framework.sh --- .../scripts/give_jetson_internet_framework.sh | 22 +++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100755 src/tools/scripts/give_jetson_internet_framework.sh diff --git a/src/tools/scripts/give_jetson_internet_framework.sh b/src/tools/scripts/give_jetson_internet_framework.sh new file mode 100755 index 00000000..8ab18f15 --- /dev/null +++ b/src/tools/scripts/give_jetson_internet_framework.sh @@ -0,0 +1,22 @@ +#!/bin/bash +set -e + +INET_IF="wlp5s0" +JETSON_IF="enx9cbf0d007947" + +sudo sysctl -w net.ipv4.ip_forward=1 + +if ! grep -q '^net.ipv4.ip_forward=1$' /etc/sysctl.conf; then + echo "net.ipv4.ip_forward=1" | sudo tee -a /etc/sysctl.conf +fi + +sudo iptables -t nat -C POSTROUTING -o "$INET_IF" -j MASQUERADE 2>/dev/null || \ +sudo iptables -t nat -A POSTROUTING -o "$INET_IF" -j MASQUERADE + +sudo iptables -C FORWARD -i "$JETSON_IF" -o "$INET_IF" -j ACCEPT 2>/dev/null || \ +sudo iptables -A FORWARD -i "$JETSON_IF" -o "$INET_IF" -j ACCEPT + +sudo iptables -C FORWARD -i "$INET_IF" -o "$JETSON_IF" -m conntrack --ctstate RELATED,ESTABLISHED -j ACCEPT 2>/dev/null || \ +sudo iptables -A FORWARD -i "$INET_IF" -o "$JETSON_IF" -m conntrack --ctstate RELATED,ESTABLISHED -j ACCEPT + +echo "Done. IP forwarding and NAT are configured." From 36fb3f9c705dac3940828e0eaeb9a0bbde91fecb Mon Sep 17 00:00:00 2001 From: UMDLoop Jetson Orin NX Date: Sat, 9 May 2026 18:07:34 -0400 Subject: [PATCH 2/2] latest fixes from drive --- .../drive/drive.odrive.ros2_control.xacro | 2 +- .../drive/drive.rmd.ros2_control.xacro | 14 +++++++------- .../ros_odrive/odrive_node/src/odrive_can_node.cpp | 2 +- .../src/odrive_hardware_interface.cpp | 2 +- .../umdloop_can_library/src/SocketCanBus.cpp | 2 +- 5 files changed, 11 insertions(+), 11 deletions(-) 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