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

Feature/ros2 tcp #185

Merged
merged 10 commits into from
Nov 5, 2024
Merged
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
32 changes: 32 additions & 0 deletions config/buildmode.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
; ********************************************************************************
; Build mode log configurations
; * debug: Standard debugging purposes during development.
; * release: The release build contains only the relevant user informations.
; * trace: Hardcore debugging by following e.g. method call hierarchy.
; ********************************************************************************
[mode:debug_log]
build_flags =
-D LOG_DEBUG_ENABLE=1
-D LOG_TRACE_ENABLE=0
-D CONFIG_LOG_SEVERITY=Logging::LOG_LEVEL_DEBUG

[mode:release_log]
build_flags =
-D LOG_DEBUG_ENABLE=0
-D LOG_TRACE_ENABLE=0
-D CONFIG_LOG_SEVERITY=Logging::LOG_LEVEL_INFO

[mode:trace_log]
build_flags =
-D LOG_DEBUG_ENABLE=1
-D LOG_TRACE_ENABLE=1
-D CONFIG_LOG_SEVERITY=Logging::LOG_LEVEL_TRACE

[mode:debug_native]
build_flags =
-O0
-ggdb

[mode:release_native]
build_flags =
-O2
28 changes: 27 additions & 1 deletion doc/ROS2/setup/Agent.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ Sources: [here](https://micro-xrce-dds.docs.eprosima.com/en/latest/index.html)
* [Installation](#installation)
* [Using the agent with the serial interface](#using-the-agent-with-the-serial-interface)
* [Using the agent with the UDP interface](#using-the-agent-with-the-udp-interface)
* [Using the agent with the TCP interface](#using-the-agent-with-the-tcp-interface)
* [Troubleshooting on WSL environment](#troubleshooting-on-wsl-environment)
* [Testing the node](#testing-the-node)

Expand Down Expand Up @@ -37,9 +38,32 @@ Once the Agent and the Client are connected, the terminal should show something
[1723186868.574254] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x64C59DFF, datawriter_id: 0x000(5), publisher_id: 0x000(3)
```

## Using the agent with the TCP interface

Start the MicroXRCEAgent binary to listen to **TCP** connections:

```bash
./MicroXRCEAgent tcp4 -p 8888 -v 6
[1730295182.773705] info | TCPv4AgentLinux.cpp | init | running... | port: 8888
[1730295182.774347] info | Root.cpp | set_verbose_level | logger setup | verbose_level: 6
[1730295187.775068] debug | TCPv4AgentLinux.cpp | recv_message | [==>> TCP <<==] | client_key: 0x00000000, len: 16, data:
0000: 80 00 00 00 02 01 08 00 00 0A FF FD 02 00 00 00
[1730295187.775861] debug | TCPv4AgentLinux.cpp | send_message | [** <<TCP>> **] | client_key: 0x00000000, len: 36, data:
0000: 80 00 00 00 06 01 1C 00 00 0A FF FD 00 00 01 0D 58 52 43 45 01 00 01 0F 00 01 0D 00 01 00 00 00
0020: 00 00 00 00
[1730295188.777062] debug | TCPv4AgentLinux.cpp | recv_message | [==>> TCP <<==] | client_key: 0x00000000, len: 24, data:
...
```

## Using the agent with the UDP interface

Start the MicroXRCEAgent binary to listen to UDP connections
> [!WARNING]
> Note: UDP ports on WSL are not working properly if you need to access them outside of the WSL VM (Status 2024-10-31). Use TCP with WSL instead.
> See [https://github.com/micro-ROS/micro-ROS-Agent/issues/194](https://github.com/micro-ROS/micro-ROS-Agent/issues/194) for further details.
> The mentioned ```netsh`` tool for port proxy forwarding only supports TCP.

Start the MicroXRCEAgent binary to listen to UDP connections:

```bash
./MicroXRCEAgent udp4 -p 8888 -v 6
[1724834512.980210] info | UDPv4AgentLinux.cpp | init | running... | port: 8888
Expand All @@ -56,6 +80,8 @@ Start the MicroXRCEAgent binary to listen to UDP connections

UDP connections [setup wsl](./wsl.md#exposing-wsl-udp-ports-to-the-network) (Requires Win 11).

Update: 2024-10-30: TCP transport is available in DroidControlShip, making UDP usage optional. Use TCP on WSL to avoid the trouble.

## Testing the node

In order to test your node, you can use `ros2 topic list` to list all topics used, or `ros2 topic echo <topic_name>` to listen to incoming data in a specific topic.
Expand Down
188 changes: 7 additions & 181 deletions lib/APPTurtle/src/CustomRosTransport.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@
DESCRIPTION
*******************************************************************************/
/**
* @brief Custom Micro-ROS transport.
* @author Gabryel Reyes <[email protected]>
* @brief Custom Micro-ROS transport class selector.
* @author Norbert Schulz <[email protected]>
*
* @addtogroup Application
*
Expand All @@ -38,185 +38,11 @@
/******************************************************************************
* Compile Switches
*****************************************************************************/

/******************************************************************************
* Includes
*****************************************************************************/
#include <IPAddress.h>
#include <rmw_microros/rmw_microros.h>
#include <WiFiUdp.h>

/******************************************************************************
* Macros
*****************************************************************************/

/******************************************************************************
* Types and Classes
*****************************************************************************/

/**
* Micro-ROS custom transport adaption.
*
* The static functions are used as these are called from C-language
*/
class CustomRosTransport
{
public:
/**
* Constructs a custom Micro-ROS transport.
*/
CustomRosTransport() : m_udpClient(), m_address(), m_port(DEFAULT_PORT)
{
}

/**
* Destroys custom Micro-ROS transport.
*
*/
~CustomRosTransport()
{
}

/**
* Initialize custom ROS transport with agent address and port.
*
* @param[in] addr Micro-ROS agent IP-address
* @param[in] port Micro-ROS agent port
*/
void init(const IPAddress& addr, uint16_t port)
{
m_address = addr;
m_port = port;
}

/**
* Get IP-address of Micro-ROS agent.
*
* @return IP-address
*/
const IPAddress& getIPAddress() const
{
return m_address;
}

/**
* Get IP-address of Micro-ROS agent as string
*
* @return IP-address as string
*/
const String getIPAddressAsStr() const
{
return m_address.toString();
}

/**
* Get port of Micro-ROS agent.
*
* @return Port
*/
uint16_t getPort() const
{
return m_port;
}

/**
* Open and initialize the custom transport (C-Entry Point).
* https://micro.ros.org/docs/tutorials/advanced/create_custom_transports/
*
* @param[in] transport The arguments passed through uxr_init_custom_transport.
*
* @return A boolean indicating if the opening was successful.
*/
static bool open(uxrCustomTransport* transport);

/**
* Close the custom transport (C-Entry Point).
* https://micro.ros.org/docs/tutorials/advanced/create_custom_transports/
*
* @param[in] transport The arguments passed through uxr_init_custom_transport.
*
* @return A boolean indicating if the closing was successful.
*/
static bool close(uxrCustomTransport* transport);

/**
* Write data to the custom transport (C-Entry Point).
* https://micro.ros.org/docs/tutorials/advanced/create_custom_transports/
*
* @param[in] transport The arguments passed through uxr_init_custom_transport.
* @param[in] buffer The buffer to write.
* @param[in] size The size of the buffer.
* @param[out] errorCode The error code.
*
* @return The number of bytes written.
*/
static size_t write(uxrCustomTransport* transport, const uint8_t* buffer, size_t size, uint8_t* errorCode);

/**
* Read data from the custom transport (C-Entry Point).
* https://micro.ros.org/docs/tutorials/advanced/create_custom_transports/
*
* @param[in] transport The arguments passed through uxr_init_custom_transport.
* @param[out] buffer The buffer to read into.
* @param[in] size The size of the buffer.
* @param[in] timeout The timeout in milliseconds.
* @param[out] errorCode The error code.
*
* @return The number of bytes read.
*/
static size_t read(uxrCustomTransport* transport, uint8_t* buffer, size_t size, int timeout, uint8_t* errorCode);

private:
/**
* Open and initialize the custom transport.
*
* @return A boolean indicating if the opening was successful.
*/
bool open(void);

/**
* Close the custom transport.
*
* @return A boolean indicating if the closing was successful.
*/
bool close(void);

/**
* Write data to the custom transport.
*
* @param[in] buffer The buffer to write.
* @param[in] size The size of the buffer.
* @param[out] errorCode The error code.
*
* @return The number of bytes written.
*/
size_t write(const uint8_t* buffer, size_t size, uint8_t* errorCode);

/**
* Read data from the custom transport.
*
* @param[out] buffer The buffer to read into.
* @param[in] size The size of the buffer.
* @param[in] timeout The timeout in milliseconds.
* @param[out] errorCode The error code.
*
* @return The number of bytes read.
*/
size_t read(uint8_t* buffer, size_t size, int timeout, uint8_t* errorCode);

/**
* Default Micro-ROS agent port.
*/
static const int DEFAULT_PORT = 8888;

WiFiUDP m_udpClient; /**< UDP client */
IPAddress m_address; /**< IP address of the Micro-ROS agent */
uint16_t m_port; /**< Port of the Micro-ROS agent */
};

/******************************************************************************
* Functions
*****************************************************************************/
#if defined(TRANSPORT_USE_TCP) && TRANSPORT_USE_TCP != 0
#include "Transports/CustomRosTransportTcp.h"
#else
#include "Transports/CustomRosTransportUdp.h"
#endif /* else defined(TRANSPORT_USE_TCP) && TRANSPORT_USE_TCP != 0 */

#endif /* CUSTOM_ROS_TRANSPORT_H */
/** @} */
27 changes: 20 additions & 7 deletions lib/APPTurtle/src/MicroRosClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,9 +171,13 @@ bool MicroRosClient::setupCustomTransport(const IPAddress& ipAddress, uint16_t p

m_customRosTransport.init(ipAddress, port);

if (RCL_RET_OK != rmw_uros_set_custom_transport(false, (void*)&m_customRosTransport, CustomRosTransport::open,
CustomRosTransport::close, CustomRosTransport::write,
CustomRosTransport::read))
if (RCL_RET_OK != rmw_uros_set_custom_transport(
false,
&m_customRosTransport,
CustomRosTransportBase::open,
CustomRosTransportBase::close,
CustomRosTransportBase::write,
CustomRosTransportBase::read))
{
LOG_ERROR("Failed to set custom transport for Micro-ROS.");
}
Expand Down Expand Up @@ -284,7 +288,10 @@ void MicroRosClient::waitingForAgentState()
if ((false == m_timer.isTimerRunning()) || (true == m_timer.isTimeout()))
{
String ipAddStr = m_customRosTransport.getIPAddressAsStr();
LOG_INFO("Ping Micro-ROS agent %s:%u ...", ipAddStr.c_str(), m_customRosTransport.getPort());
LOG_INFO("Ping Micro-ROS agent %s:%s:%u ...",
m_customRosTransport.getProtocolName().c_str(),
ipAddStr.c_str(),
m_customRosTransport.getPort());

if (RMW_RET_OK == rmw_uros_ping_agent(MICRO_ROS_AGENT_PING_TIMEOUT, MICRO_ROS_AGENT_PING_ATTEMPTS))
{
Expand All @@ -307,16 +314,22 @@ void MicroRosClient::connectingState()
{
String ipAddStr = m_customRosTransport.getIPAddressAsStr();

LOG_INFO("Connecting to Micro-ROS agent %s:%u ...", ipAddStr.c_str(), m_customRosTransport.getPort());
LOG_INFO("Connecting to Micro-ROS agent %s:%s:%u ...",
m_customRosTransport.getProtocolName().c_str(),
ipAddStr.c_str(),
m_customRosTransport.getPort());

if (false == createEntities())
{
m_state = STATE_WAIT_FOR_AGENT;
}
else
{
LOG_INFO("Connected with Micro-ROS agent %s:%u.", ipAddStr.c_str(), m_customRosTransport.getPort());

LOG_INFO("Connected with Micro-ROS agent %s:%s:%u ...",
m_customRosTransport.getProtocolName().c_str(),
ipAddStr.c_str(),
m_customRosTransport.getPort());

subscribe();

/* Periodically verify that the connection is still established. */
Expand Down
2 changes: 1 addition & 1 deletion lib/APPTurtle/src/MicroRosClient.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class MicroRosClient
/**
* The Micro-ROS agent ping operation timeout is ms.
*/
static const int32_t MICRO_ROS_AGENT_PING_TIMEOUT = 100;
static const int32_t MICRO_ROS_AGENT_PING_TIMEOUT = 200;

/**
* The Micro-ROS agent ping operation attempts. Keep 1, because the
Expand Down
Loading