micro-ROS / micro_ros_renesas_demos

Demo code for Renesas e2 studio
Apache License 2.0
4 stars 5 forks source link

Issue with pub/sub modification of micro_ros_freertos example #112

Closed samiamlabs closed 1 year ago

samiamlabs commented 1 year ago

Issue template

Steps to reproduce the issue

Replace microros_app.c in the micro_ros_udp_freertos with this:

#include "./utils.h"

#include <time.h>

#include <rclc/rclc.h>
#include <rclc/executor.h>

#include <std_msgs/msg/int32.h>

#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){bool l = true; while(1){set_led_status(LED_RED, l = !l); sleep_ms(100);}}}

void microros_app(void);

rcl_publisher_t publisher;
rcl_subscription_t subscriber;
std_msgs__msg__Int32 msg;
std_msgs__msg__Int32 recv_msg;

void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
{
    (void) last_call_time;
    if (timer != NULL) {
        rcl_publish(&publisher, &msg, NULL);
        // printf("Sent: %d\n", msg.data);
        msg.data++;
    }
}

void subscription_callback(const void * msgin)
{
    const std_msgs__msg__Int32 * new_msg = (const std_msgs__msg__Int32 *)msgin;
    msg.data = new_msg->data;
    //printf("Received: %d\n", msg->data);
}

void microros_app(void)
{
    rcl_allocator_t allocator = rcl_get_default_allocator();

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

    // create nodes
    rcl_node_t node;
    RCCHECK(rclc_node_init_default(&node, "my_renesas_node", "", &support));

    // create publisher
    RCCHECK(rclc_publisher_init_default(
        &publisher,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
        "int_publisher"));

    // create subscriber
    RCCHECK(rclc_subscription_init_default(
        &subscriber,
        &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
        "int_subscriber"));

    // create timer,
    rcl_timer_t timer;
    const unsigned int timer_timeout = 1000;
    RCCHECK(rclc_timer_init_default(
        &timer,
        &support,
        RCL_MS_TO_NS(timer_timeout),
        timer_callback));

    // create executor
    rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
    RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
    RCCHECK(rclc_executor_add_timer(&executor, &timer));
    RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &recv_msg, &subscription_callback, ON_NEW_DATA));

    msg.data = 0;

    rclc_executor_spin(&executor);

    RCCHECK(rcl_subscription_fini(&subscriber, &node));
    RCCHECK(rcl_publisher_fini(&publisher, &node));
    RCCHECK(rcl_node_fini(&node));
}

Expected behavior

The subscription_callback should run when publishing to it through the agent on my PC.

Actual behavior

The subscription callback does not run when you publish to the node. (The timer callback and publisher seem to work though.)

pablogs9 commented 1 year ago

Your executor only has one handle:

RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));

The add timer method shall work but you shouldn't be able to add the subscription.

Just increase the number of handles in rclc_executor_init

samiamlabs commented 1 year ago

Ok, thanks! I'm pretty sure I learned that last time I tried micro-ROS last time but it is apparently pretty easy to forget about.