Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Now the branch ROS2 works with distro Humble #6

Open
wants to merge 3 commits into
base: ROS2
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 11 additions & 17 deletions ros2-network-analysis/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,22 +18,16 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(ros2_network_analysis_interface REQUIRED)
find_package(ament_cmake_python REQUIRED)
## System dependencies are found with CMake's conventions
find_package(Boost REQUIRED COMPONENTS system)
find_package(rosidl_default_generators REQUIRED)
# find_package(rosidl_default_generators REQUIRED)
find_package(rclpy REQUIRED)

rosidl_generate_interfaces( ${PROJECT_NAME}
"msg/WirelessLink.msg"
"msg/LinkUtilization.msg"
"msg/NetworkErrors.msg"
"msg/NetworkDelay.msg"
"msg/NetworkAnalysis.msg"
"msg/WirelessLinkVector.msg"
"action/Ping.srv"
DEPENDENCIES builtin_interfaces std_msgs
)
# rosidl_generate_interfaces( ${PROJECT_NAME}
# DEPENDENCIES builtin_interfaces std_msgs
# )

ament_export_dependencies(rosidl_default_runtime)

Expand All @@ -43,23 +37,23 @@ ament_export_dependencies(rosidl_default_runtime)

add_executable(network_ping_client src/ping_client.cpp)
# add_dependencies(${target}${target_suffix} ${PROJECT_NAME})
ament_target_dependencies(network_ping_client rclcpp std_msgs)
ament_target_dependencies(network_ping_client rclcpp std_msgs ros2_network_analysis_interface)

add_executable(network_ping_service src/ping_service.cpp)
# add_dependencies(${target}${target_suffix} ${PROJECT_NAME})
ament_target_dependencies(network_ping_service rclcpp std_msgs)
ament_target_dependencies(network_ping_service rclcpp std_msgs ros2_network_analysis_interface)


install(TARGETS
network_ping_client
network_ping_service
DESTINATION lib/${PROJECT_NAME})

rosidl_target_interfaces(network_ping_client
${PROJECT_NAME} "rosidl_typesupport_cpp")
# rosidl_target_interfaces(network_ping_client
# ${PROJECT_NAME} "rosidl_typesupport_cpp")

rosidl_target_interfaces(network_ping_service
${PROJECT_NAME} "rosidl_typesupport_cpp")
# rosidl_target_interfaces(network_ping_service
# ${PROJECT_NAME} "rosidl_typesupport_cpp")

ament_python_install_package(${PROJECT_NAME})

Expand Down
5 changes: 3 additions & 2 deletions ros2-network-analysis/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,12 @@
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>std_msgs</depend>
<depend>ros2_network_analysis_interface</depend>

<!-- Action -->
<buildtool_depend>rosidl_default_generators</buildtool_depend>
<!-- <buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<member_of_group>rosidl_interface_packages</member_of_group> -->

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
35 changes: 24 additions & 11 deletions ros2-network-analysis/scripts/link_utilization.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@

import rclpy
from subprocess import Popen, PIPE
from ros2_network_analysis.msg import LinkUtilization
from ros2_network_analysis_interface.msg import LinkUtilization
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
import std_msgs.msg
import threading

Expand Down Expand Up @@ -37,17 +38,29 @@ def getparameters():

def linkutilization_publisher():
node = rclpy.create_node('link_utilization')
node.declare_parameter('interface_name',
value="wlan0",
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_STRING,
description="The Wi-Fi interface id (e.g. wlan0)",
),
)
node.declare_parameter('update_rate_link_utilization',
value=1.0,
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_DOUBLE,
description="Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation",
),
)
spin_thread = threading.Thread(target=rclpy.spin, args=(node, ), daemon=True)
spin_thread.start()
interfacename = node.get_parameter_or('~INTERFACE_NAME', 'wlan0') # The Wi-Fi interface id wlan0
if type(interfacename) == "Parameter":
interfacename = interfacename.value
updaterate = node.get_parameter_or('~update_rate_link_utilization', 1) # Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation.
if type(updaterate) == "Parameter":
updaterate = updaterate.value
if updaterate <= 0:
node.get_logger().error("Update rate should be greater than 0. Setting to 10 hz")
updaterate = 10
interfacename = node.get_parameter("interface_name").get_parameter_value().string_value # The Wi-Fi interface id wlan0
node.get_logger().info(f"Wi-Fi Interface Name: {interfacename}")
updaterate = node.get_parameter("update_rate_link_utilization").get_parameter_value().double_value # Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation.
node.get_logger().info(f"Update Frequency: {updaterate} Hz")
if updaterate <= 0:
node.get_logger().error("Update rate should be greater than 0. Setting to 10 hz")
updaterate = 10
global cmd,cmd_netstat_tcp,cmd_netstat_udp,msg
cmd ="cat /proc/net/dev | grep " + interfacename
cmd_netstat_tcp = "cat /proc/net/snmp | grep Tcp:"
Expand All @@ -73,7 +86,7 @@ def linkutilization_publisher():
rate.sleep()
fout = getparameters()
if (fout == 0):
print("The interface %s does not exist or is disconnected",interfacename)
print(f"The interface {interfacename} does not exist or is disconnected")
continue
msg.total_tx_mbps = (8 * (msg.total_tx_bytes - previous_total_tx_bytes) / float(1000*1000))
msg.total_rx_mbps = (8 * (msg.total_rx_bytes - previous_total_rx_bytes) / float(1000*1000))
Expand Down
35 changes: 23 additions & 12 deletions ros2-network-analysis/scripts/network_errors.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,38 @@

from subprocess import Popen, PIPE
import rclpy
from ros2_network_analysis.msg import NetworkErrors
from ros2_network_analysis_interface.msg import NetworkErrors
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
import std_msgs.msg
import threading


def network_errors_publisher():
node = rclpy.create_node('NetworkErrors_publisher')
node.declare_parameter('interface_name',
value="wlan0",
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_STRING,
description="The Wi-Fi interface id (e.g. wlan0)",
),
)
node.declare_parameter('update_rate_network_errors',
value=1.0,
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_DOUBLE,
description="Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation",
),
)
spin_thread = threading.Thread(
target=rclpy.spin, args=(node, ), daemon=True)
spin_thread.start()
interfacename = node.get_parameter_or(
'~INTERFACE_NAME', 'wlan0')
if type(interfacename) == "Parameter":
interfacename = interfacename.value
# Update frequency in Hz.
updaterate = node.get_parameter_or('~update_rate_network_errors', 1)
if type(updaterate) == "Parameter":
updaterate = updaterate.value
if updaterate <= 0:
node.get_logger().error("Update rate should be greater than 0. Setting to 10 hz")
updaterate = 10
interfacename = node.get_parameter("interface_name").get_parameter_value().string_value # The Wi-Fi interface id wlan0
node.get_logger().info(f"Wi-Fi Interface Name: {interfacename}")
updaterate = node.get_parameter("update_rate_network_errors").get_parameter_value().double_value # Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation.
node.get_logger().info(f"Update Frequency: {updaterate} Hz")
if updaterate <= 0:
node.get_logger().error("Update rate should be greater than 0. Setting to 10 hz")
updaterate = 10
pub = node.create_publisher(
NetworkErrors, 'network_analysis/network_errors', 10)
msg = NetworkErrors()
Expand Down
41 changes: 27 additions & 14 deletions ros2-network-analysis/scripts/wireless_quality.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@

import os
import rclpy
from ros2_network_analysis.msg import WirelessLink
from ros2_network_analysis_interface.msg import WirelessLink
from rcl_interfaces.msg import ParameterDescriptor, ParameterType
import std_msgs.msg
import threading

Expand All @@ -25,9 +26,9 @@ def get_rssi_from_os(interface_name, node):
cmd_output = f.read()
ans = cmd_output.split()

msg.rssi = int(ans[3]) # there is a problem here when i use my interface (wlp0s20f3). Not sure what it is though
msg.rssi = int(float(ans[3])) # there is a problem here when i use my interface (wlp0s20f3). Not sure what it is though
msg.lqi = float(ans[2])
msg.noise = float(ans[4])
msg.noise = int(ans[4])
msg.iface = interface_name
msg.status = True

Expand All @@ -42,20 +43,32 @@ def get_rssi_from_os(interface_name, node):
if __name__ == '__main__':
rclpy.init()
node = rclpy.create_node('wireless_quality')
node.declare_parameter('interface_name',
value="wlan0",
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_STRING,
description="The Wi-Fi interface id (e.g. wlan0)",
),
)
node.declare_parameter('update_rate_wireless_quality',
value=1.0,
descriptor=ParameterDescriptor(
type=ParameterType.PARAMETER_DOUBLE,
description="Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation",
),
)
spin_thread = threading.Thread(
target=rclpy.spin, args=(node, ), daemon=True)
spin_thread.start()
interfacename = node.get_parameter_or('~INTERFACE_NAME', 'wlan0wlp0s20f3')
if type(interfacename) == "Parameter":
interfacename = interfacename.value
update_rate = node.get_parameter_or(
'~update_rate_wireless_quality', 10)
if type(update_rate) == "Parameter":
update_rate = update_rate.value
if update_rate <= 0:
node.get_logger().error(
"Update rate must be greater than 0. Setting to 10 Hz")
update_rate = 10
interfacename = node.get_parameter("interface_name").get_parameter_value().string_value # The Wi-Fi interface id wlan0
node.get_logger().info(f"Wi-Fi Interface Name: {interfacename}")
update_rate = node.get_parameter("update_rate_wireless_quality").get_parameter_value().double_value # Update frequency in Hz. Note: more than 1 Hz will not be effective in throughput calculation.
node.get_logger().info(f"Update Frequency: {update_rate} Hz")

if update_rate <= 0:
node.get_logger().error(
"Update rate must be greater than 0. Setting to 10 Hz")
update_rate = 10

pub_rssi = node.create_publisher(
WirelessLink, 'network_analysis/wireless_quality', 10)
Expand Down
12 changes: 6 additions & 6 deletions ros2-network-analysis/src/ping_client.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <rclcpp/rclcpp.hpp>
#include <sys/time.h>
#include <ros2_network_analysis/srv/ping.hpp>
#include <ros2_network_analysis/msg/network_delay.hpp>
#include <ros2_network_analysis_interface/srv/ping.hpp>
#include <ros2_network_analysis_interface/msg/network_delay.hpp>
#include <iostream>
#include <chrono>
#include <cstdlib>
Expand Down Expand Up @@ -30,10 +30,10 @@ int main(int argc, char *argv[])
return 0;
}

auto client = node->create_client<ros2_network_analysis::srv::Ping>("network_analysis/ping");
auto request = std::make_shared<ros2_network_analysis::srv::Ping::Request>();
ros2_network_analysis::msg::NetworkDelay msg;
auto delayPub = node->create_publisher<ros2_network_analysis::msg::NetworkDelay>("network_analysis/network_delay", 10);
auto client = node->create_client<ros2_network_analysis_interface::srv::Ping>("network_analysis/ping");
auto request = std::make_shared<ros2_network_analysis_interface::srv::Ping::Request>();
ros2_network_analysis_interface::msg::NetworkDelay msg;
auto delayPub = node->create_publisher<ros2_network_analysis_interface::msg::NetworkDelay>("network_analysis/network_delay", 10);
request->inp = true;
rclcpp::Rate rate(updateRate);
while (!client->wait_for_service(std::chrono::seconds(1)))
Expand Down
10 changes: 5 additions & 5 deletions ros2-network-analysis/src/ping_service.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
#include <rclcpp/rclcpp.hpp>
#include <ros2_network_analysis/srv/ping.hpp>
#include <ros2_network_analysis/msg/network_delay.hpp>
#include <ros2_network_analysis_interface/srv/ping.hpp>
#include <ros2_network_analysis_interface/msg/network_delay.hpp>




void respond(std::shared_ptr<ros2_network_analysis::srv::Ping::Request> request,
std::shared_ptr<ros2_network_analysis::srv::Ping::Response> response)
void respond(std::shared_ptr<ros2_network_analysis_interface::srv::Ping::Request> request,
std::shared_ptr<ros2_network_analysis_interface::srv::Ping::Response> response)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ping service received request");
if(request->inp)
Expand All @@ -25,7 +25,7 @@ int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("ping_service");
auto service = node->create_service<ros2_network_analysis::srv::Ping>("network_analysis/ping", &respond);
auto service = node->create_service<ros2_network_analysis_interface::srv::Ping>("network_analysis/ping", &respond);
while(rclcpp::ok()){
rclcpp::spin_some(node);
}
Expand Down
50 changes: 50 additions & 0 deletions ros2_network_analysis_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
cmake_minimum_required(VERSION 3.5)
project(ros2_network_analysis_interface)

# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(std_msgs REQUIRED)

find_package(rosidl_default_generators REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/LinkUtilization.msg"
"msg/NetworkAnalysis.msg"
"msg/NetworkDelay.msg"
"msg/NetworkErrors.msg"
"msg/WirelessLink.msg"
"msg/WirelessLinkVector.msg"
"action/Ping.srv"
DEPENDENCIES std_msgs
)


if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
26 changes: 26 additions & 0 deletions ros2_network_analysis_interface/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros2_network_analysis_interface</name>
<version>0.1.0</version>
<description>Custom messages for ros2_aruco</description>
<maintainer email="[email protected]">Nathan Sprague</maintainer>
<license>TODO: License declaration</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>std_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<build_depend>rosidl_default_generators</build_depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>