-
Notifications
You must be signed in to change notification settings - Fork 373
Dev_FileServer
The ROS# File Server package is an essential utility in the ROS# framework, providing a mechanism for transferring files between ROS and external environments such as .NET applications. This is particularly useful for sharing URDF files between ROS packages and Unity Engine.
Note: This page includes examples from the file_server2 (ROS2) package as they are easier to read. The logic behind is the same with the file_server (ROS1) package.
- File Retrieval: Retrieve binary files stored within ROS packages using a ROS service.
- File Saving: Save binary files into ROS package directories through another ROS service.
- URDF Transfer: Critical for transferring URDF files, allowing external systems to dynamically visualize and interact with ROS-defined robot models.
- Multi-Threaded Execution: Utilizes ROS 2's multi-threaded executor to handle multiple requests simultaneously.
The file server node is implemented in C++ and is responsible for the core functionality of the package. It handles requests to retrieve and save files using ROS services. Below is a detailed walkthrough of this implementation.
class FileServerNode : public rclcpp::Node
{
public:
FileServerNode() : Node("file_server")
{
get_file_service_ = this->create_service<file_server2::srv::GetBinaryFile>(
"/file_server/get_file",
std::bind(&FileServerNode::get_file_callback, this, _1, _2));
save_file_service_ = this->create_service<file_server2::srv::SaveBinaryFile>(
"/file_server/save_file",
std::bind(&FileServerNode::save_file_callback, this, _1, _2));
RCLCPP_INFO(this->get_logger(), "ROS2 File Server initialized.");
}
-
Service Definitions: The node sets up two services,
/file_server/get_file
and/file_server/save_file
, for retrieving and saving binary files respectively. These services are associated with their respective callback functions (get_file_callback
andsave_file_callback
).
The get_file_callback
handles requests to retrieve files. This function reads a file from a specified path within a ROS package and returns its contents as a binary array.
void get_file_callback(
const std::shared_ptr<file_server2::srv::GetBinaryFile::Request> request,
std::shared_ptr<file_server2::srv::GetBinaryFile::Response> response)
{
if (request->name.compare(0, 10, "package://") != 0)
{
RCLCPP_INFO(this->get_logger(), "Only \"package://\" addresses allowed.");
return;
}
std::string address = request->name.substr(10);
std::string package = address.substr(0, address.find("/"));
std::string filepath = address.substr(package.length());
std::string directory = ament_index_cpp::get_package_share_directory(package);
directory += filepath;
std::ifstream inputfile(directory.c_str(), std::ios::binary);
if (!inputfile.is_open())
{
RCLCPP_INFO(this->get_logger(), "File \"%s\" not found.", request->name.c_str());
return;
}
response->value.assign(
std::istreambuf_iterator<char>(inputfile),
std::istreambuf_iterator<char>());
RCLCPP_INFO(this->get_logger(), "get_file request: %s", request->name.c_str());
}
Detailed Steps:
-
Path Validation: Ensures the requested file path starts with
package://
, a standard for ROS package paths. - Package and File Extraction: Extracts the package name and the relative file path.
-
Directory Resolution: Uses
ament_index_cpp::get_package_share_directory
to locate the package's directory on the filesystem. - File Reading: Opens the file in binary mode and reads its contents into the response object.
The save_file_callback
handles requests to save binary data as a file within a ROS package. This service allows external applications to upload files to the ROS environment.
void save_file_callback(
const std::shared_ptr<file_server2::srv::SaveBinaryFile::Request> request,
std::shared_ptr<file_server2::srv::SaveBinaryFile::Response> response)
{
std::lock_guard<std::mutex> guard(save_file_mutex_);
RCLCPP_INFO(this->get_logger(), "save_file request: %s", request->name.c_str());
if (request->name.compare(0, 10, "package://") != 0)
{
RCLCPP_INFO(this->get_logger(), "Only \"package://\" addresses allowed.");
return;
}
std::string address = request->name.substr(10);
std::string package = address.substr(0, address.find("/"));
std::string filepath = address.substr(package.length());
std::string directory;
try {
directory = ament_index_cpp::get_package_share_directory(package);
} catch (const std::exception &e) {
RCLCPP_INFO(this->get_logger(), "Package \"%s\" not found. Creating a new package.", package.c_str());
directory = generate_ros_package(package);
}
create_directories(directory, filepath.substr(0, filepath.find_last_of("/")));
directory += filepath;
std::ofstream file_to_save(directory.c_str(), std::ios::binary);
if (!file_to_save.is_open())
{
RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", directory.c_str());
return;
}
file_to_save.write(reinterpret_cast<const char*>(request->value.data()), request->value.size());
file_to_save.close();
response->name = request->name;
RCLCPP_INFO(this->get_logger(), "save_file request completed: %s", request->name.c_str());
}
Detailed Steps:
- Mutex Locking: A mutex ensures that multiple threads do not interfere with each other when saving files.
-
Path Validation: Verifies that the file path starts with
package://
. - Directory Resolution: Attempts to locate the package directory. If the package does not exist, a new ROS package structure is created.
-
Directory Creation: The function
create_directories
is used to recursively create the necessary directories if they don't exist. - File Writing: The binary data from the request is written to the specified file path.
-
Directory Creation: The
create_directories
function recursively creates the necessary directory structure.
void create_directories(const std::string& packagePath, const std::string& filePath)
{
if (filePath.empty())
{
return;
}
create_directories(packagePath, filePath.substr(0, filePath.find_last_of("/")));
struct stat sb;
if (!(stat((packagePath + filePath).c_str(), &sb) == 0 && S_ISDIR(sb.st_mode)))
{
mkdir((packagePath + filePath).c_str(), S_IRWXU | S_IRWXG | S_IROTH | S_IXOTH);
}
}
-
Package Generation: The
generate_ros_package
function creates a new ROS package if the requested package does not exist. This is particularly useful for dynamically saving files to new packages. This utility has not been updated for colcon type packages, yet; thus, be sure to create your ROS2 package before using file server.
std::string generate_ros_package(const std::string& packageName)
{
std::string package_share_dir = ament_index_cpp::get_package_share_directory(packageName);
std::string directory = package_share_dir;
// NOT Colcon
std::string packageXmlContents = "<?xml version=\"1.0\"?>\n<package format=\"2\">\n <name>" + packageName + "</name>\n <version>0.0.0</version>\n <description>The " + packageName + " package</description>\n\n <maintainer email=\"ros-sharp.ct@siemens.com\">Ros#</maintainer>\n\n <license>Apache 2.0</license>\n\n <buildtool_depend>ament_cmake</buildtool_depend>\n <build_depend>rclcpp</build_depend>\n <exec_depend>rclcpp</exec_depend>\n\n <export>\n
</export>\n</package>";
create_directories(directory, "");
std::ofstream packageXmlFile(directory + "/package.xml");
packageXmlFile << packageXmlContents;
packageXmlFile.close();
return directory;
}
ROS services define the communication protocol between nodes. In this package, two services are defined: GetBinaryFile.srv
and SaveBinaryFile.srv
.
-
GetBinaryFile.srv: Retrieves binary files from a package.
string name --- uint8[] value
-
SaveBinaryFile.srv: Saves binary files to a package.
string name uint8[] value --- string name
The package includes several launch files that simplify the configuration and deployment of the file server node and related components, particulary for ROS# tutorials.
This launch file initializes the ROS# communication layer (including the rosbridge_server) and starts the file server node. A very important parameter is the max_message_size
. If your files are larger than this limit, rosbridge_server will shut down silenty without giving any errors.
def generate_launch_description():
return LaunchDescription([
Node(
package='file_server2',
executable='file_server2_node',
name='file_server',
output='screen'
),
Node(
package='rosbridge_server',
executable='rosbridge_websocket',
name='rosbridge_websocket',
output='screen',
parameters=[
{"use_compression": True},
{"fragment_timeout": 600}, # Timeout for fragment reassembly in seconds (default: 600)
{"unregister_timeout": 10.0}, # Timeout for unregistering in seconds (default: 10.0)
{"max_message_size": 100000000}, # Maximum message size in bytes (default: 10000000)
{"port": 9090},
]
)
])
Used in:
Sets up the environment for basic visualization of a robot model using RVIZ. By default, this launcher file is configured to work out of the box with the [Transferring a URDF from Unity to ROS] tutorial (User_App_ROS_TransferURDFToROS). Instead of reading the /robot_description topic for the model, it loads the exported .urdf file directly from your package's share directory, thus the called joint_state_publisher node has no physical meaning but just for demonstration.
# Read the RViz config file, replace the placeholder with the actual path, and write to a temporary file
with open(rviz_config_file_path, 'r') as infp:
rviz_config_content = infp.read().replace('Description File:', 'Description File: ' + urdf_file_path)
tmp_rviz_config_file = NamedTemporaryFile(delete=False, suffix='.rviz')
with open(tmp_rviz_config_file.name, 'w') as outfp:
outfp.write(rviz_config_content)
# Define nodes
joint_state_publisher_node = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui'
)
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': robot_description}]
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', rviz_config_file_path]
)
Publishes the URDF description of a custom robot and establishes communication with ROS#. Used in the tutorial. Transfer a URDF from ROS to Unity. Notice that the file_server2 package comes bundled with two additional launch files that publish TurtleBot4 lite and standard. And of course they need the TurtleBot4 ROS Humble package installed (turtlebot4_bringup, specifically) to work. Again, we will only use R2D2; and TurtleBot4 files are included for convenience.
The File Server package is particularly used in the following applications:
- Transfer a URDF from ROS to Unity
- Transfer a URDF from Unity to ROS
- Unity Simulation Scene Example
- Gazebo Simulation Scene Example
© Siemens AG, 2017-2024
-
- 1.3.1 R2D2 Setup
- 1.3.2 Gazebo Setup on VM
- 1.3.3 TurtleBot Setup (Optional for ROS2)
-
- 2.1 Quick Start
- 2.2 Transfer a URDF from ROS to Unity
- 2.3 Transfer a URDF from Unity to ROS
- 2.4 Unity Simulation Scene Example
- 2.5 Gazebo Simulation Scene Example
- 2.6 Fibonacci Action Client
- 2.7 Fibonacci Action Server
- 3.1 Import a URDF on Windows
- 3.2 Create, Modify and Export a URDF Model
- 3.3 Animate a Robot Model in Unity
- Message Handling: Readers & Writers
- Thread Safety for Message Reception
- File Server Package
- ROS-Unity Coordinate System Conversions
- Post Build Events
- Preprocessor Directives in ROS#
- Adding New Message Types
- RosBridgeClient Protocols
- RosBridgeClient Serializers
- Action Server State Machine Model
© Siemens AG, 2017-2024