-
Notifications
You must be signed in to change notification settings - Fork 376
User_App_DotNet_Fibonacci_Action
This section provides a comprehensive guide to implementing both the Fibonacci Client and Fibonacci Server for ROS 1 and ROS 2 in .NET. It includes detailed explanations and code examples for setting up the action communication between the client and server, handling goals, processing feedback, and receiving results. The examples are designed to give you a deeper understanding of the concepts, methods, and flow of action-based communication in both ROS 1 and ROS 2 environments.
The FibonacciClient and FibonacciServer sections offer practical insights, with code snippets that demonstrate the core functionality. To understand the underlying action middleware implementation in more detail, please refer to the Action Middleware Implementation. For an in-depth look at the action server state machine model and its states, transitions, and behavior, visit the Action Server State Machine Model page.
- 4.4.1 Fibonacci Client
- 4.4.1.1 Class Definition and Constructor
- 4.4.1.2 Overriden Methods
- 4.4.1.3 Custom Methods
- 4.4.1.4 Console Example
- 4.4.2 Fibonacci Server
- 4.4.2.1 Class Definition and Constructor
- 4.4.2.2 Overriden Methods
- 4.4.2.3 Custom Methods
- 4.4.2.4 Console Example
ROS2 Humble
This section explains the implementation of the FibonacciActionClient for ROS 2. The client allows interaction with the Fibonacci action server, enabling users to send goals, receive feedback, and obtain results.
The FibonacciActionClient
class derives from ActionClient<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
and provides specific functionality for the Fibonacci action. For more information about the abstract class, please see Action Middleware Implementation
The constructor initializes the action client and sets up necessary attributes:
public class FibonacciActionClient : ActionClient<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
{
public FibonacciActionClient(string actionName, RosSocket rosSocket)
{
this.actionName = actionName;
this.rosSocket = rosSocket;
action = new FibonacciAction();
goalStatus = new GoalStatus();
}
}
-
Parameters:
-
actionName
: The name of the Fibonacci action server (e.g.,/fibonacci
). -
rosSocket
: The ROS socket for communication with the server.
-
-
Data Members:
-
action
: Represents the full Fibonacci action structure, including goal, feedback, and result. -
goalStatus
: Tracks the current goal's status.
-
This client overrides the following methods to implement action-specific behavior:
-
SetActionGoal
Configures the action goal, specifying the Fibonacci sequence order and communication settings.public override void SetActionGoal(FibonacciGoal fibonacciOrder, bool feedback = true, int fragmentSize = int.MaxValue, string compression = "none") { action.action_goal.action = actionName; action.action_goal.args = fibonacciOrder; action.action_goal.feedback = feedback; action.action_goal.fragment_size = fragmentSize; action.action_goal.compression = compression; }
-
Parameters:
-
fibonacciOrder
: Specifies the desired Fibonacci sequence order. -
feedback
: Enables feedback messages if set totrue
. -
fragmentSize
: Configures fragment size for large messages. -
compression
: Specifies message compression format.
-
-
Parameters:
-
GetActionGoal
Returns the current action goal.public override FibonacciActionGoal GetActionGoal() { return action.action_goal; }
-
OnStatusUpdated
Handles status updates from the server. For this application, it is not implemented.protected override void OnStatusUpdated() { // Not implemented for this particular application }
-
OnFeedbackReceived
Processes feedback received from the action server.protected override void OnFeedbackReceived() { Console.WriteLine("Feedback received: " + GetFeedbackString()); }
-
OnResultReceived
Handles the final result received from the server and prints relevant information.protected override void OnResultReceived() { Console.WriteLine("Result received: " + GetResultString()); Console.WriteLine("Status: " + GetStatusString()); Console.WriteLine("Result (success?): " + lastResultSuccess); Console.WriteLine("Frame ID: " + action.action_result.id); }
The class includes additional methods for extracting and displaying feedback, status, and result information.
-
GetStatusString
Retrieves a string representation of the current goal status.public string GetStatusString() { if (goalStatus != null) { return ((ActionStatus)(goalStatus.status)).ToString(); } return ""; }
-
GetFeedbackString
Returns the feedback received from the server as a formatted string.public string GetFeedbackString() { if (action != null) return String.Join(", ", action.action_feedback.values.partial_sequence); return ""; }
-
GetResultString
Returns the final result received from the server as a formatted string.public string GetResultString() { if (action != null) return String.Join(", ", action.action_result.values.sequence); return ""; }
The following example demonstrates how to use the FibonacciActionClient
in a console application.
-
Initialize the Client
Begin by creating an instance of theFibonacciActionClient
and initializing it:rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol("ws://localhost:9090")); fibonacciActionClient = new FibonacciActionClient("/fibonacci", rosSocket); fibonacciActionClient.Initialize();
-
Send a Goal
Set the desired Fibonacci order usingSetActionGoal
and send the goal to the server:fibonacciActionClient.SetActionGoal(new FibonacciGoal { order = 5 }); fibonacciActionClient.SendGoal();
-
Cancel a Goal
If wanted, check whether the action is completed (success or not) ,and cancel the current goal:if (!fibonacciActionClient.lastResultSuccess) { Console.WriteLine("Action not completed. Cancelling..."); fibonacciActionClient.CancelGoal(); Console.ReadKey(true); } else { Console.WriteLine("Action completed."); }
-
Terminate
After completing the operation, close the ROS socket:rosSocket.Close();
This section explains the implementation of the FibonacciActionClient for ROS 2. The client allows interaction with the Fibonacci action server, enabling users to send goals, receive feedback, and obtain results.
The FibonacciActionServer
class derives from ActionServer<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
and provides specific functionality for the Fibonacci action. For more information about the abstract class, please see Action Middleware Implementation
The constructor initializes the action client and sets up necessary attributes:
public class FibonacciActionServer : ActionServer<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
{
private ManualResetEvent isProcessingGoal = new ManualResetEvent(false);
private Thread goalHandler;
public FibonacciActionServer(string actionName, RosSocket rosSocket, Log log)
{
this.actionName = actionName;
this.rosSocket = rosSocket;
this.log = log;
action = new FibonacciAction();
}
-
Parameters:
-
actionName
: The name of the Fibonacci action server (e.g.,/fibonacci
). -
rosSocket
: The ROS socket for communication with the server. -
log
: Logging function (Debug.Log or Console.WriteLine)
-
-
Data Members:
-
action
: Represents the full Fibonacci action structure, including goal, feedback, and result. -
goalStatus
: Tracks the current goal's status. -
isProcessingGoal
: ManuelResetEvent to handle race conditions. -
goalHanlder
: Thread in which the actual server calculations handled.
-
Here is the documentation for the overridden methods and custom methods in the FibonacciActionServer class, similar to what we did for the client:
Thank you for providing the correct script! Based on the updated ROS2 Fibonacci action server code, here's the documentation for the ROS2-specific methods and functionality with code snippets where applicable:
These methods are overridden to implement server-specific behavior for the FibonacciActionServer in ROS2.
-
OnGoalReceived
This method is invoked when the server receives a goal. The goal is validated by checking if the Fibonacci order is greater than or equal to 1. If valid, the goal moves to the "executing" state; otherwise, it is aborted.
protected override void OnGoalReceived() { if (IsGoalValid()) { SetExecuting(); // The goal is valid, proceed to execution } else { SetAborted(); // Reject the goal if it's invalid log("Fibonacci Action Server: Cannot generate fibonacci sequence of order less than 1."); } }
-
OnGoalExecuting
This method is invoked when the goal is actively being executed. It logs the status and initiates the
goalHandler
thread to compute the Fibonacci sequence in the background.protected override void OnGoalExecuting() { log("Fibonacci Action Server: Accepted, executing."); goalHandler = new Thread(ExecuteFibonacciGoal); goalHandler.Start(); }
-
OnGoalCanceling
This method is invoked when the goal is being canceled. It stops the Fibonacci sequence computation and ensures that the goal handler is properly joined (i.e., completion or termination).
protected override void OnGoalCanceling() { log("Fibonacci Action Server: Cancelling."); isProcessingGoal.Reset(); // Reset goal processing flag goalHandler.Join(); // Wait for the goal processing to complete }
-
OnGoalSucceeded
This method is invoked when the goal has been successfully executed. It logs the success status, resets the goal processing, and updates the action status to "SUCCEEDED."
protected override void OnGoalSucceeded() { log("Fibonacci Action Server: Succeeded."); isProcessingGoal.Reset(); UpdateAndPublishStatus(ActionStatus.STATUS_SUCCEEDED); }
-
OnGoalAborted
This method is invoked when the goal is aborted. It stops the goal execution, sets the result to
false
, and publishes the result.protected override void OnGoalAborted() { log("Fibonacci Action Server: Aborted."); isProcessingGoal.Reset(); // Reset goal processing goalHandler.Join(); // Ensure goal handler is completed action.action_result.result = false; // Set the result to false (aborted) PublishResult(); // Publish the result }
-
OnGoalCanceled
This method is invoked when the goal is canceled. It logs the cancellation status and publishes the result with the action result set to
true
.protected override void OnGoalCanceled() { log("Fibonacci Action Server: Canceled."); action.action_result.result = true; // Set result to true (canceled) PublishResult(); // Publish the result }
These custom methods implement server-specific behavior for goal validation, execution, and result feedback.
-
IsGoalValid
This method checks whether the Fibonacci goal is valid by verifying that the Fibonacci order is greater than or equal to 1. If the order is valid, it returns
true
; otherwise, it returnsfalse
.protected bool IsGoalValid() { return action.action_goal.args.order >= 1; }
-
ExecuteFibonacciGoal
This method executes the Fibonacci goal. It calculates the Fibonacci sequence and provides feedback at each step. If the goal is canceled or preempted, the sequence calculation stops. The final result is published after the sequence is completed.
private void ExecuteFibonacciGoal() { isProcessingGoal.Set(); Thread.Sleep(500); // Simulate some delay List<int> sequence = new List<int> { 0, 1 }; action.action_feedback.values.partial_sequence = sequence.ToArray(); PublishFeedback(); // Publish feedback to the client for (int i = 1; i < action.action_goal.args.order; i++) { if (!isProcessingGoal.WaitOne(0)) { action.action_result.values.sequence = sequence.ToArray(); if (this.GetStatus() != ActionStatus.STATUS_ABORTED) { SetCanceled(); // If goal was preempted, cancel the goal } return; } sequence.Add(sequence[i] + sequence[i - 1]); action.action_feedback.values.partial_sequence = sequence.ToArray(); PublishFeedback(); // Publish feedback to the client log("Fibonacci Action Server: Publishing feedback: " + GetFeedbackSequenceString()); Thread.Sleep(500); // Simulate delay between calculations } action.action_result.values.sequence = sequence.ToArray(); // Final sequence action.action_result.result = true; // Goal succeeded SetSucceeded(); log("Final result: " + GetResultSequenceString()); }
-
GetFeedbackSequenceString
This method retrieves the current feedback sequence as a comma-separated string, which provides a snapshot of the Fibonacci sequence up to the current point.
public string GetFeedbackSequenceString() { if (action != null) return String.Join(", ", action.action_feedback.values.partial_sequence); return ""; }
-
GetResultSequenceString
This method retrieves the final sequence result as a comma-separated string, which represents the full Fibonacci sequence calculated by the server.
public string GetResultSequenceString() { if (action != null) return String.Join(", ", action.action_result.values.sequence); return ""; }
- Initialize the Client
In this part of the code, the WebSocket connection (rosSocket
) is established to communicate with the ROS bridge at the specified URI
. We then initialize the FibonacciActionServer
with the provided action name (/fibonacci) and the WebSocket connection. The fibonacciActionServer.Initialize()
method sets up the server and prepares it to handle incoming goals. A log handler (Log(x => Console.WriteLine(x))
) ensures that logs are printed to the console, providing feedback during the server’s operation.
static readonly string uri = "ws://localhost:9090";
static readonly string actionName = "/fibonacci";
private static RosSocket rosSocket;
private static FibonacciActionServer fibonacciActionServer;
public static void Main(string[] args)
{
rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol(uri));
fibonacciActionServer = new FibonacciActionServer(actionName, rosSocket, new Log(x => Console.WriteLine(x)));
fibonacciActionServer.Initialize();
...
- Terminate
Once the action server has finished processing goals and is no longer needed, we proceed to clean up and close the connection. This involves calling the Terminate()
method on the fibonacciActionServer
to gracefully stop the server and calling rosSocket.Close()
to terminate the WebSocket connection to the ROS bridge.
...
fibonacciActionServer.Terminate();
rosSocket.Close();
}
ROS1 Noetic
This section explains the implementation of the FibonacciActionClient for ROS 1. The client allows interaction with the Fibonacci action server, enabling users to send goals, receive feedback, and obtain results.
The FibonacciActionClient
class inherits from ActionClient<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
, specifically designed for ROS 1.
The constructor initializes the action client and sets up required attributes:
public class FibonacciActionClient : ActionClient<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
{
public int fibonacciOrder;
public string status = "";
public string feedback = "";
public string result = "";
public FibonacciActionClient(string actionName, RosSocket rosSocket)
{
this.actionName = actionName;
this.rosSocket = rosSocket;
action = new FibonacciAction();
goalStatus = new MessageTypes.Actionlib.GoalStatus();
}
}
-
Parameters:
-
actionName
: The name of the Fibonacci action server (e.g.,/fibonacci
). -
rosSocket
: The ROS socket for communication with the server.
-
-
Data Members:
-
fibonacciOrder
: The order of the Fibonacci sequence to be computed. -
status
: Holds the status of the action. -
feedback
: Stores feedback from the server. -
result
: Stores the result received from the server.
-
This class overrides several methods to provide the necessary behavior for interacting with the Fibonacci action server.
-
GetActionGoal
This method sets the Fibonacci order in the goal and returns it.protected override FibonacciActionGoal GetActionGoal() { action.action_goal.goal.order = fibonacciOrder; return action.action_goal; }
-
OnStatusUpdated
This method is overridden but not implemented for this specific client. It's meant to handle status updates when implemented.protected override void OnStatusUpdated() { // Not implemented for this particular application }
-
OnFeedbackReceived
Similar toOnStatusUpdated
, this method is not implemented for this client. It is meant to handle feedback received from the server.protected override void OnFeedbackReceived() { // Not implemented for this particular application since get string directly returns stored feedback }
-
OnResultReceived
This method is not implemented but can be used to handle the result once it is received from the server.protected override void OnResultReceived() { // Not implemented for this particular application since get string directly returns stored result }
The class includes additional methods for retrieving and displaying feedback, status, and result information.
-
GetStatusString
Returns a string representation of the current goal's status.public string GetStatusString() { if (goalStatus != null) { return ((ActionStatus)(goalStatus.status)).ToString(); } return ""; }
-
GetFeedbackString
Retrieves the feedback string, which is the Fibonacci sequence generated so far.public string GetFeedbackString() { if (action != null) return String.Join(",", action.action_feedback.feedback.sequence); return ""; }
-
GetResultString
Retrieves the final result as a string, showing the complete Fibonacci sequence.public string GetResultString() { if (action != null) return String.Join(",", action.action_result.result.sequence); return ""; }
Below is a sample usage of the Fibonacci client in a console application:
-
Initialize the Client:
rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol(uri)); fibonacciActionClient = new FibonacciActionClient(actionName, rosSocket);
-
Send a Goal:
fibonacciActionClient.fibonacciOrder = 5; fibonacciActionClient.SendGoal();
-
Receive Feedback and Result:
do { Console.WriteLine(fibonacciActionClient.GetFeedbackString()); Console.WriteLine(fibonacciActionClient.GetStatusString()); Thread.Sleep(100); } while (fibonacciActionClient.goalStatus.status != GoalStatus.SUCCEEDED); Thread.Sleep(500); Console.WriteLine(fibonacciActionClient.GetResultString()); Console.WriteLine(fibonacciActionClient.GetStatusString());
-
Cancel the Goal:
fibonacciActionClient.CancelGoal();
-
Close the Socket:
rosSocket.Close();
The FibonacciActionServer
class derives from ActionServer<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
and provides specific functionality for the Fibonacci action. For more information about the abstract class, please see Action Middleware Implementation
The constructor initializes the action client and sets up necessary attributes:
public class FibonacciActionServer : ActionServer<FibonacciAction, FibonacciActionGoal, FibonacciActionResult, FibonacciActionFeedback, FibonacciGoal, FibonacciResult, FibonacciFeedback>
{
private ManualResetEvent isProcessingGoal = new ManualResetEvent(false);
private Thread goalHandler;
public FibonacciActionServer(string actionName, RosSocket rosSocket, Log log)
{
this.actionName = actionName;
this.rosSocket = rosSocket;
this.log = log;
action = new FibonacciAction();
}
-
Parameters:
-
actionName
: The name of the Fibonacci action server (e.g.,/fibonacci
). -
rosSocket
: The ROS socket for communication with the server. -
log
: Logging function (Debug.Log or Console.WriteLine)
-
-
Data Members:
-
action
: Represents the full Fibonacci action structure, including goal, feedback, and result. -
goalStatus
: Tracks the current goal's status. -
isProcessingGoal
: ManuelResetEvent to handle race conditions. -
goalHanlder
: Thread in which the actual server calculations handled.
-
This server overrides the following methods to implement server-specific behavior:
-
OnGoalReceived
This method is called when a new goal is received by the server. It checks if the goal is valid, i.e., the Fibonacci order is greater than or equal to 1. If the goal is valid, it accepts the goal; otherwise, it rejects the goal.
protected override void OnGoalReceived() { if (IsGoalValid()) { SetAccepted("Fibonacci Action Server: The goal has been accepted"); } else { SetRejected("Fibonacci Action Server: Cannot generate fibonacci sequence of order less than 1"); } }
-
OnGoalRecalling
This method is invoked when a goal is being recalled. In this implementation, it is left empty for this example, but you could customize it to perform actions when a goal is recalled.
protected override void OnGoalRecalling(GoalID goalID) { // Left blank for this example }
-
OnGoalRejected
This method is called when a goal is rejected due to an invalid request. In this case, it logs the reason for the rejection, such as when the Fibonacci order is less than 1.
protected override void OnGoalRejected() { log("Cannot generate fibonacci sequence of order less than 1. Goal Rejected"); }
-
OnGoalActive
This method is invoked when the goal transitions to the "active" state. It starts a new thread (
goalHandler
) to execute the Fibonacci sequence generation asynchronously.protected override void OnGoalActive() { goalHandler = new Thread(ExecuteFibonacciGoal); goalHandler.Start(); }
-
OnGoalPreempting
This method is called when a goal is preempted (i.e., interrupted before completion). It resets the goal processing and ensures that the current goal thread is properly joined (i.e., completed or terminated).
protected override void OnGoalPreempting() { isProcessingGoal.Reset(); goalHandler.Join(); }
-
OnGoalSucceeded
This method is invoked when the goal is successfully completed. It resets the goal processing flag and simulates a time delay (defined by
timeStep
) before publishing the success status of the action.protected override void OnGoalSucceeded() { isProcessingGoal.Reset(); Thread.Sleep((int)timeStep * 1000); UpdateAndPublishStatus(ActionStatus.SUCCEEDED); }
-
OnGoalAborted
This method is triggered when the goal is aborted. For this example, it is left empty, but it could be used to handle any necessary cleanup when the goal fails prematurely.
protected override void OnGoalAborted() { // Left blank for this example }
-
OnGoalCanceled
This method is called when the goal is canceled. It ensures that the result of the action is published after cancellation.
protected override void OnGoalCanceled() { PublishResult(); }
These are custom methods specific to the behavior of the Fibonacci action server:
-
IsGoalValid
This method checks whether the received goal is valid. It ensures that the Fibonacci order specified in the goal is greater than or equal to 1. If the goal order is valid, the method returns
true
; otherwise, it returnsfalse
.protected bool IsGoalValid() { return action.action_goal.goal.order >= 1; }
-
ExecuteFibonacciGoal
This method handles the execution of the Fibonacci goal. It calculates the Fibonacci sequence up to the specified order, providing feedback at each step. It runs the calculation asynchronously and sleeps for 1 second between iterations. If the goal is preempted during execution, the calculation stops, and the goal is canceled.
private void ExecuteFibonacciGoal() { isProcessingGoal.Set(); List<int> sequence = new List<int> { 0, 1 }; action.action_feedback.feedback.sequence = sequence.ToArray(); PublishFeedback(); for (int i = 1; i < action.action_goal.goal.order; i++) { if (!isProcessingGoal.WaitOne(0)) { action.action_result.result.sequence = sequence.ToArray(); SetCanceled(); return; } sequence.Add(sequence[i] + sequence[i - 1]); action.action_feedback.feedback.sequence = sequence.ToArray(); PublishFeedback(); Thread.Sleep(1000); } action.action_result.result.sequence = sequence.ToArray(); SetSucceeded(); }
-
GetFeedbackSequenceString
This method returns the Fibonacci sequence as a comma-separated string. It accesses the current feedback sequence stored in the action server and formats it for easy display.
public string GetFeedbackSequenceString() { if (action != null) return String.Join(",", action.action_feedback.feedback.sequence); return ""; }
- Initialize the Client
In this step, we start by setting up the connection to the action server using a RosSocket. The server is initialized using the FibonacciActionServer, which will handle the communication. Additionally, we pass in a logging delegate to print messages to the console. We also create an event, isWaitingForGoal
, that will help manage the process of waiting for goals and controlling the flow of the application.
static readonly string uri = "ws://localhost:9090";
static readonly string actionName = "/fibonacci";
private static RosSocket rosSocket;
private static FibonacciActionServer fibonacciActionServer;
private static ManualResetEvent isWaitingForGoal = new ManualResetEvent(false);
public static void Main(string[] args)
{
rosSocket = new RosSocket(new RosBridgeClient.Protocols.WebSocketNetProtocol(uri));
// Initialize server
fibonacciActionServer = new FibonacciActionServer(actionName, rosSocket, new Log(x => Console.WriteLine(x)));
fibonacciActionServer.Initialize();
...
In this code, we establish the WebSocket connection to the ROS bridge using the provided uri
and create an instance of FibonacciActionServer
to communicate with the ROS action server. The rosSocket
object handles the communication, while the fibonacciActionServer
will manage the action requests. After initializing the server with Initialize()
, we indicate that the action server is ready to handle incoming goals.
- Wait for Goal
Here, we introduce the functionality that allows the program to wait for an incoming goal from a client. The main thread sets the isWaitingForGoal
event, which signals the program to start a background thread (waitForGoal
) that continuously polls the action server to publish its status while waiting for the goal.
...
isWaitingForGoal.Set();
Console.WriteLine("Waiting for goal");
Thread waitForGoal = new Thread(WaitForGoal);
waitForGoal.Start();
...
In this section, we set the isWaitingForGoal
flag, which indicates to the program that it is ready to handle incoming goals. The waitForGoal
thread is then started, which will continually publish the status of the action server while waiting for a goal to arrive. This allows the program to remain responsive and handle status updates while awaiting input.
private static void WaitForGoal()
{
while (isWaitingForGoal.WaitOne(0))
{
fibonacciActionServer.PublishStatus();
Thread.Sleep(50);
}
}
The WaitForGoal
method is where the background thread performs the actual polling. It keeps the thread running while the isWaitingForGoal
flag is set, ensuring the action server continuously publishes status updates. The Thread.Sleep(50)
ensures the polling isn't too aggressive, which helps in managing CPU resources.
- Terminate
In this final part of the code, we reset the isWaitingForGoal
event, signaling that we no longer want to wait for further goals. We then call waitForGoal.Join()
to ensure the background thread has finished its operation. After the thread completes, we clean up the resources by calling Terminate()
on the fibonacciActionServer to properly stop the server and close the connection using rosSocket.Close()
.
...
isWaitingForGoal.Reset();
waitForGoal.Join();
fibonacciActionServer.Terminate();
rosSocket.Close();
}
© Siemens AG, 2017-2025
-
- 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
- 4.1 Introduction to RosBridgeClient
- 4.2 Image Publication
- 4.3 URDF Transfer
- 4.4 Fibonacci Action Client/Server
- 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
- Actions in ROS#
- Action Server State Machine Model
© Siemens AG, 2017-2025