Skip to content

Commit 22209a4

Browse files
Manually merged changes from old branch (#56)
Signed-off-by: Andy Blight <andy.blight@gmail.com> Co-authored-by: Andy Blight <andy.blight@gmail.com>
1 parent d843dbb commit 22209a4

7 files changed

Lines changed: 160 additions & 0 deletions

File tree

examples/int32_sub_pub/.gitignore

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
build
2+
sdkconfig
3+
sdkconfig.old
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
3+
set (EXTRA_COMPONENT_DIRS "./../../.")
4+
5+
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
6+
project(int32_pub_sub)
7+
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
idf_component_register(SRCS main.c
2+
INCLUDE_DIRS ""
3+
)
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
menu "micro-ROS example-app settings"
2+
3+
config MICRO_ROS_APP_STACK
4+
int "Stack the micro-ROS app (Bytes)"
5+
default 16000
6+
help
7+
Stack size in Bytes of the micro-ROS app
8+
9+
config MICRO_ROS_APP_TASK_PRIO
10+
int "Priority of the micro-ROS app"
11+
default 5
12+
help
13+
Priority of micro-ros task higher value means higher priority
14+
15+
endmenu
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
#
2+
# "main" pseudo-component makefile.
3+
#
4+
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
5+

examples/int32_sub_pub/main/main.c

Lines changed: 124 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,124 @@
1+
#include <string.h>
2+
#include <stdio.h>
3+
#include <unistd.h>
4+
5+
#include "freertos/FreeRTOS.h"
6+
#include "freertos/task.h"
7+
#include "esp_log.h"
8+
#include "esp_system.h"
9+
10+
#include <uros_network_interfaces.h>
11+
#include <rcl/rcl.h>
12+
#include <rcl/error_handling.h>
13+
#include <std_msgs/msg/int32.h>
14+
#include <rclc/rclc.h>
15+
#include <rclc/executor.h>
16+
#include <rmw_uros/options.h>
17+
#include "uxr/client/config.h"
18+
19+
#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Aborting.\n",__LINE__,(int)temp_rc);vTaskDelete(NULL);}}
20+
#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){printf("Failed status on line %d: %d. Continuing.\n",__LINE__,(int)temp_rc);}}
21+
22+
rcl_publisher_t publisher;
23+
rcl_subscription_t subscriber;
24+
std_msgs__msg__Int32 send_msg;
25+
std_msgs__msg__Int32 recv_msg;
26+
27+
void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
28+
{
29+
(void) last_call_time;
30+
if (timer != NULL) {
31+
RCSOFTCHECK(rcl_publish(&publisher, &send_msg, NULL));
32+
printf("Sent: %d\n", send_msg.data);
33+
send_msg.data++;
34+
}
35+
}
36+
37+
void subscription_callback(const void * msgin)
38+
{
39+
const std_msgs__msg__Int32 * msg = (const std_msgs__msg__Int32 *)msgin;
40+
printf("Received: %d\n", msg->data);
41+
}
42+
43+
void micro_ros_task(void * arg)
44+
{
45+
rcl_allocator_t allocator = rcl_get_default_allocator();
46+
rclc_support_t support;
47+
48+
// Create init_options.
49+
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
50+
RCCHECK(rcl_init_options_init(&init_options, allocator));
51+
rmw_init_options_t* rmw_options = rcl_init_options_get_rmw_init_options(&init_options);
52+
// Use static agent IP and port.
53+
RCCHECK(rmw_uros_options_set_udp_address(CONFIG_MICRO_ROS_AGENT_IP, CONFIG_MICRO_ROS_AGENT_PORT, rmw_options));
54+
55+
// Setup support structure.
56+
RCCHECK(rclc_support_init_with_options(&support, 0, NULL, &init_options, &allocator));
57+
58+
// Create node.
59+
rcl_node_t node = rcl_get_zero_initialized_node();
60+
RCCHECK(rclc_node_init_default(&node, "int32_publisher_subscriber_rclc", "", &support));
61+
62+
// Create publisher.
63+
RCCHECK(rclc_publisher_init_default(
64+
&publisher,
65+
&node,
66+
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
67+
"int32_publisher"));
68+
69+
// Create subscriber.
70+
RCCHECK(rclc_subscription_init_default(
71+
&subscriber,
72+
&node,
73+
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
74+
"int32_subscriber"));
75+
76+
// Create timer.
77+
rcl_timer_t timer = rcl_get_zero_initialized_timer();
78+
const unsigned int timer_timeout = 1000;
79+
RCCHECK(rclc_timer_init_default(
80+
&timer,
81+
&support,
82+
RCL_MS_TO_NS(timer_timeout),
83+
timer_callback));
84+
85+
// Create executor.
86+
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
87+
RCCHECK(rclc_executor_init(&executor, &support.context, 2, &allocator));
88+
unsigned int rcl_wait_timeout = 1000; // in ms
89+
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
90+
91+
// Add timer and subscriber to executor.
92+
RCCHECK(rclc_executor_add_timer(&executor, &timer));
93+
RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &recv_msg, &subscription_callback, ON_NEW_DATA));
94+
95+
// Spin forever.
96+
send_msg.data = 0;
97+
while(1){
98+
rclc_executor_spin_some(&executor, 100);
99+
usleep(100000);
100+
}
101+
102+
// Free resources.
103+
RCCHECK(rcl_subscription_fini(&subscriber, &node));
104+
RCCHECK(rcl_publisher_fini(&publisher, &node));
105+
RCCHECK(rcl_node_fini(&node));
106+
107+
vTaskDelete(NULL);
108+
}
109+
110+
void app_main(void)
111+
{
112+
#ifdef UCLIENT_PROFILE_UDP
113+
// Start the networking if required
114+
ESP_ERROR_CHECK(uros_network_interface_initialize());
115+
#endif // UCLIENT_PROFILE_UDP
116+
117+
//pin micro-ros task in APP_CPU to make PRO_CPU to deal with wifi:
118+
xTaskCreate(micro_ros_task,
119+
"uros_task",
120+
CONFIG_MICRO_ROS_APP_STACK,
121+
NULL,
122+
CONFIG_MICRO_ROS_APP_TASK_PRIO,
123+
NULL);
124+
}
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3000
2+
CONFIG_ESP_TASK_WDT=n
3+

0 commit comments

Comments
 (0)