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

portenta h7 m7 ethernet support #852

Merged
merged 10 commits into from
Mar 21, 2022
Merged
Show file tree
Hide file tree
Changes from 6 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
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
#include <micro_ros_arduino.h>

#include <stdio.h>
#include <rcl/rcl.h>
#include <rcl/error_handling.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <std_msgs/msg/int32.h>

#if !defined(TARGET_STM32F4) || !defined(ARDUINO_TEENSY41) || !defined(TARGET_PORTENTA_H7_M7)
#error This example is only avaible for Arduino Portenta, Arduino Teensy41 and STM32F4
Jenifen marked this conversation as resolved.
Show resolved Hide resolved
#endif

rcl_publisher_t publisher;
std_msgs__msg__Int32 msg;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;

#define LED_PIN 13

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){error_loop();}}
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}



void error_loop(){
while(1){
digitalWrite(LED_PIN, !digitalRead(LED_PIN));
delay(100);
}
}

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL) {
RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
msg.data++;
}
}

void setup() {
byte arduino_mac[] = { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xED };
Jenifen marked this conversation as resolved.
Show resolved Hide resolved
// The IP address will be dependent on your local network
IPAddress arduino_ip(192, 168, 1, 177);
IPAddress agent_ip(192, 168, 1, 113);
Jenifen marked this conversation as resolved.
Show resolved Hide resolved
set_microros_native_ethernet_udp_transports(arduino_mac, arduino_ip, agent_ip, 9999);

pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, HIGH);

delay(2000);

allocator = rcl_get_default_allocator();

//create init_options
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));

// create node
RCCHECK(rclc_node_init_default(&node, "micro_ros_arduino_ethernet_node", "namespace", &support));

// create publisher
RCCHECK(rclc_publisher_init_best_effort(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
"topic_name"));

msg.data = 0;
}

void loop() {
RCSOFTCHECK(rcl_publish(&publisher, &msg, NULL));
msg.data++;
delay(100);
}
12 changes: 10 additions & 2 deletions src/micro_ros_arduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,14 @@ static inline void set_microros_transports(){
#include <NativeEthernet.h>
#endif

#if defined(TARGET_STM32F4) || defined(ARDUINO_TEENSY41)
#if defined(TARGET_PORTENTA_H7_M7)
#include <EthernetUdp.h>
#include <PortentaEthernet.h>
#include <uxr/client/transport.h>
Jenifen marked this conversation as resolved.
Show resolved Hide resolved
#include <rmw_microros/rmw_microros.h>
#endif

#if defined(TARGET_STM32F4) || defined(ARDUINO_TEENSY41) || defined(TARGET_PORTENTA_H7_M7)
extern "C" bool arduino_native_ethernet_udp_transport_open(struct uxrCustomTransport * transport);
extern "C" bool arduino_native_ethernet_udp_transport_close(struct uxrCustomTransport * transport);
extern "C" size_t arduino_native_ethernet_udp_transport_write(struct uxrCustomTransport* transport, const uint8_t * buf, size_t len, uint8_t * err);
Expand Down Expand Up @@ -95,11 +102,12 @@ extern "C" bool arduino_wifi_transport_open(struct uxrCustomTransport * transpor
extern "C" bool arduino_wifi_transport_close(struct uxrCustomTransport * transport);
extern "C" size_t arduino_wifi_transport_write(struct uxrCustomTransport* transport, const uint8_t * buf, size_t len, uint8_t * err);
extern "C" size_t arduino_wifi_transport_read(struct uxrCustomTransport* transport, uint8_t* buf, size_t len, int timeout, uint8_t* err);

#if not defined(TARGET_PORTENTA_H7_M7)
Jenifen marked this conversation as resolved.
Show resolved Hide resolved
struct micro_ros_agent_locator {
IPAddress address;
int port;
};
#endif

static inline void set_microros_wifi_transports(char * ssid, char * pass, char * agent_ip, uint agent_port){

Expand Down
7 changes: 6 additions & 1 deletion src/native_ethernet_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,13 @@
#include <NativeEthernet.h>
#include <micro_ros_arduino.h>
#endif
#ifdef TARGET_PORTENTA_H7_M7
#include <Arduino.h>
#include <EthernetUdp.h>
#include <micro_ros_arduino.h>
#endif

#if defined(TARGET_STM32F4) || defined(ARDUINO_TEENSY41)
#if defined(TARGET_STM32F4) || defined(ARDUINO_TEENSY41) || defined(TARGET_PORTENTA_H7_M7)
extern "C" {

#include <stdbool.h>
Expand Down