micro-ROS / micro_ros_espidf_component

micro-ROS ESP32 IDF component and sample code
Apache License 2.0
254 stars 60 forks source link

cant find CONFIG_MICRO_ROS_APP_STACK and CONFIG_MICRO_ROS_APP_TASK_PRIO during build #201

Open Vulcan758 opened 1 year ago

Vulcan758 commented 1 year ago

Issue template

Steps to reproduce the issue

I went to example directory of the cloned repository. I ran the export.sh for the esp-idf (. $IDF_PATH/export.sh ) Created a new project named twist_node --> idf.py create-project -p . twist_node in the twist_node.c file I copied the contents of the int32_publisher/main/main.c file into the twist_node.c


`#include <string.h>
#include <stdio.h>
#include <unistd.h>

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_log.h"
#include "esp_system.h"

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

#include <geometry_msgs/msg/twist.h>

#ifdef CONFIG_MICRO_ROS_ESP_XRCE_DDS_MIDDLEWARE
#include <rmw_microros/rmw_microros.h>
#endif

#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);}}
#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);}}

rcl_subscription_t twist_sub;

geometry_msgs__msg__Twist twist_msg;

void cmdvelCallback(const void * msgin){
    const geometry_msgs__msg__Twist *msg = (const geometry_msgs__msg__Twist *) msgin; 
}

void micro_ros_task(void * arg)
{
    rcl_allocator_t allocator = rcl_get_default_allocator();
    rclc_support_t support;

    rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
    RCCHECK(rcl_init_options_init(&init_options, allocator));

#ifdef CONFIG_MICRO_ROS_ESP_XRCE_DDS_MIDDLEWARE
    rmw_init_options_t* rmw_options = rcl_init_options_get_rmw_init_options(&init_options);

    // Static Agent IP and port can be used instead of autodisvery.
    RCCHECK(rmw_uros_options_set_udp_address(CONFIG_MICRO_ROS_AGENT_IP, CONFIG_MICRO_ROS_AGENT_PORT, rmw_options));
    //RCCHECK(rmw_uros_discover_agent(rmw_options));
#endif

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

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

    const rosidl_message_type_support_t * my_type_support = ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist);

    //create subscriber
    RCCHECK(rclc_subscription_init_best_effort(
        &twist_sub,
        &node,
        &my_type_support,
        "cmd_vel"));

    //create executor
    rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
    RCCHECK(rclc_executor_init(
        &executor,
        &support.context,
        2,
        &allocator));

    RCCHECK(rclc_executor_add_subscription(
        &executor,
        &twist_sub,
        &twist_msg,
        &cmdvelCallback,
        ON_NEW_DATA));

    while(1){
        rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
        usleep(1000);
    }

    RCCHECK(rclc_executor_fini(&executor));
    RCCHECK(rcl_subscription_fini(&twist_sub, &node));
    RCCHECK(rcl_node_fini(&node));
    vTaskDelete(NULL);
}

void app_main(void)
{
#if defined(CONFIG_MICRO_ROS_ESP_NETIF_WLAN) || defined(CONFIG_MICRO_ROS_ESP_NETIF_ENET)
    ESP_ERROR_CHECK(uros_network_interface_initialize());
#endif

    //pin micro-ros task in APP_CPU to make PRO_CPU to deal with wifi:
    xTaskCreate(micro_ros_task,
            "uros_task",
            CONFIG_MICRO_ROS_APP_STACK,
            NULL,
            CONFIG_MICRO_ROS_APP_TASK_PRIO,
            NULL);
}

Edited the CMakelist,.txt to make it look like this


# For more information about build system see
# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html
# The following five lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)

set (EXTRA_COMPONENT_DIRS "./../../.")

include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(twist_node)

I did this in order to mimic the cmakelist file in that of the int32_publlisher

Expected behavior


Project build complete. To flash, run this command:
/home/mahir/.espressif/python_env/idf5.0_py3.10_env/bin/python ../../../../../../../esp/esp-idf/components/esptool_py/esptool/esptool.py -p (PORT) -b 460800 --before default_reset --after hard_reset --chip esp32  write_flash --flash_mode dio --flash_size 2MB --flash_freq 40m 0x1000 build/bootloader/bootloader.bin 0x8000 build/partition_table/partition-table.bin 0x10000 build/int32_publisher.bin
or run 'idf.py -p (PORT) flash

`

Actual behavior


/home/mahir/esp/esp-idf/tools/check_python_dependencies.py:12: DeprecationWarning: pkg_resources is deprecated as an API. See https://setuptools.pypa.io/en/latest/pkg_resources.html
  import pkg_resources
Executing action: all (aliases: build)
Running ninja in directory /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/build
Executing "ninja all"...
[1/1] cd /home/mahir/uros_esp32_ws/src...t_node/build/bootloader/bootloader.binBootloader binary size 0x6700 bytes. 0x900 bytes (8%) free.
[3/9] Building C object esp-idf/main/CMakeFiles/__idf_main.dir/twist_node.c.objFAILED: esp-idf/main/CMakeFiles/__idf_main.dir/twist_node.c.obj 
/home/mahir/.espressif/tools/xtensa-esp32-elf/esp-2022r1-11.2.0/xtensa-esp32-elf/bin/xtensa-esp32-elf-gcc -DMBEDTLS_CONFIG_FILE=\"mbedtls/esp_config.h\" -DSOC_MMU_PAGE_SIZE=CONFIG_MMU_PAGE_SIZE -DUNITY_INCLUDE_CONFIG_H -I/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/build/config -I/home/mahir/esp/esp-idf/components/newlib/platform_include -I/home/mahir/esp/esp-idf/components/freertos/FreeRTOS-Kernel/include -I/home/mahir/esp/esp-idf/components/freertos/esp_additions/include/freertos -I/home/mahir/esp/esp-idf/components/freertos/FreeRTOS-Kernel/portable/xtensa/include -I/home/mahir/esp/esp-idf/components/freertos/esp_additions/include -I/home/mahir/esp/esp-idf/components/esp_hw_support/include -I/home/mahir/esp/esp-idf/components/esp_hw_support/include/soc -I/home/mahir/esp/esp-idf/components/esp_hw_support/include/soc/esp32 -I/home/mahir/esp/esp-idf/components/esp_hw_support/port/esp32/. -I/home/mahir/esp/esp-idf/components/esp_hw_support/port/esp32/private_include -I/home/mahir/esp/esp-idf/components/heap/include -I/home/mahir/esp/esp-idf/components/log/include -I/home/mahir/esp/esp-idf/components/soc/include -I/home/mahir/esp/esp-idf/components/soc/esp32/. -I/home/mahir/esp/esp-idf/components/soc/esp32/include -I/home/mahir/esp/esp-idf/components/hal/esp32/include -I/home/mahir/esp/esp-idf/components/hal/include -I/home/mahir/esp/esp-idf/components/hal/platform_port/include -I/home/mahir/esp/esp-idf/components/esp_rom/include -I/home/mahir/esp/esp-idf/components/esp_rom/include/esp32 -I/home/mahir/esp/esp-idf/components/esp_rom/esp32 -I/home/mahir/esp/esp-idf/components/esp_common/include -I/home/mahir/esp/esp-idf/components/esp_system/include -I/home/mahir/esp/esp-idf/components/esp_system/port/soc -I/home/mahir/esp/esp-idf/components/esp_system/port/include/private -I/home/mahir/esp/esp-idf/components/xtensa/include -I/home/mahir/esp/esp-idf/components/xtensa/esp32/include -I/home/mahir/esp/esp-idf/components/lwip/include -I/home/mahir/esp/esp-idf/components/lwip/include/apps -I/home/mahir/esp/esp-idf/components/lwip/include/apps/sntp -I/home/mahir/esp/esp-idf/components/lwip/lwip/src/include -I/home/mahir/esp/esp-idf/components/lwip/port/esp32/include -I/home/mahir/esp/esp-idf/components/lwip/port/esp32/include/arch -I/home/mahir/esp/esp-idf/components/esp_ringbuf/include -I/home/mahir/esp/esp-idf/components/efuse/include -I/home/mahir/esp/esp-idf/components/efuse/esp32/include -I/home/mahir/esp/esp-idf/components/driver/include -I/home/mahir/esp/esp-idf/components/driver/deprecated -I/home/mahir/esp/esp-idf/components/driver/esp32/include -I/home/mahir/esp/esp-idf/components/esp_pm/include -I/home/mahir/esp/esp-idf/components/mbedtls/port/include -I/home/mahir/esp/esp-idf/components/mbedtls/mbedtls/include -I/home/mahir/esp/esp-idf/components/mbedtls/mbedtls/library -I/home/mahir/esp/esp-idf/components/mbedtls/esp_crt_bundle/include -I/home/mahir/esp/esp-idf/components/esp_app_format/include -I/home/mahir/esp/esp-idf/components/bootloader_support/include -I/home/mahir/esp/esp-idf/components/bootloader_support/bootloader_flash/include -I/home/mahir/esp/esp-idf/components/esp_partition/include -I/home/mahir/esp/esp-idf/components/app_update/include -I/home/mahir/esp/esp-idf/components/spi_flash/include -I/home/mahir/esp/esp-idf/components/pthread/include -I/home/mahir/esp/esp-idf/components/esp_timer/include -I/home/mahir/esp/esp-idf/components/app_trace/include -I/home/mahir/esp/esp-idf/components/esp_event/include -I/home/mahir/esp/esp-idf/components/nvs_flash/include -I/home/mahir/esp/esp-idf/components/esp_phy/include -I/home/mahir/esp/esp-idf/components/esp_phy/esp32/include -I/home/mahir/esp/esp-idf/components/vfs/include -I/home/mahir/esp/esp-idf/components/esp_netif/include -I/home/mahir/esp/esp-idf/components/wpa_supplicant/include -I/home/mahir/esp/esp-idf/components/wpa_supplicant/port/include -I/home/mahir/esp/esp-idf/components/wpa_supplicant/esp_supplicant/include -I/home/mahir/esp/esp-idf/components/esp_wifi/include -I/home/mahir/esp/esp-idf/components/unity/include -I/home/mahir/esp/esp-idf/components/unity/unity/src -I/home/mahir/esp/esp-idf/components/cmock/CMock/src -I/home/mahir/esp/esp-idf/components/console -I/home/mahir/esp/esp-idf/components/http_parser -I/home/mahir/esp/esp-idf/components/esp-tls -I/home/mahir/esp/esp-idf/components/esp-tls/esp-tls-crypto -I/home/mahir/esp/esp-idf/components/esp_adc/include -I/home/mahir/esp/esp-idf/components/esp_adc/interface -I/home/mahir/esp/esp-idf/components/esp_adc/esp32/include -I/home/mahir/esp/esp-idf/components/esp_adc/deprecated/include -I/home/mahir/esp/esp-idf/components/esp_eth/include -I/home/mahir/esp/esp-idf/components/esp_gdbstub/include -I/home/mahir/esp/esp-idf/components/esp_gdbstub/xtensa -I/home/mahir/esp/esp-idf/components/esp_gdbstub/esp32 -I/home/mahir/esp/esp-idf/components/esp_hid/include -I/home/mahir/esp/esp-idf/components/tcp_transport/include -I/home/mahir/esp/esp-idf/components/esp_http_client/include -I/home/mahir/esp/esp-idf/components/esp_http_server/include -I/home/mahir/esp/esp-idf/components/esp_https_ota/include -I/home/mahir/esp/esp-idf/components/esp_lcd/include -I/home/mahir/esp/esp-idf/components/esp_lcd/interface -I/home/mahir/esp/esp-idf/components/protobuf-c/protobuf-c -I/home/mahir/esp/esp-idf/components/protocomm/include/common -I/home/mahir/esp/esp-idf/components/protocomm/include/security -I/home/mahir/esp/esp-idf/components/protocomm/include/transports -I/home/mahir/esp/esp-idf/components/esp_local_ctrl/include -I/home/mahir/esp/esp-idf/components/esp_psram/include -I/home/mahir/esp/esp-idf/components/espcoredump/include -I/home/mahir/esp/esp-idf/components/espcoredump/include/port/xtensa -I/home/mahir/esp/esp-idf/components/wear_levelling/include -I/home/mahir/esp/esp-idf/components/sdmmc/include -I/home/mahir/esp/esp-idf/components/fatfs/diskio -I/home/mahir/esp/esp-idf/components/fatfs/vfs -I/home/mahir/esp/esp-idf/components/fatfs/src -I/home/mahir/esp/esp-idf/components/idf_test/include -I/home/mahir/esp/esp-idf/components/idf_test/include/esp32 -I/home/mahir/esp/esp-idf/components/ieee802154/include -I/home/mahir/esp/esp-idf/components/json/cJSON -I/home/mahir/esp/esp-idf/components/mqtt/esp-mqtt/include -I/home/mahir/esp/esp-idf/components/perfmon/include -I/home/mahir/esp/esp-idf/components/spiffs/include -I/home/mahir/esp/esp-idf/components/ulp/ulp_common/include -I/home/mahir/esp/esp-idf/components/ulp/ulp_common/include/esp32 -I/home/mahir/esp/esp-idf/components/wifi_provisioning/include -I/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/network_interfaces -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/action_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/actionlib_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/builtin_interfaces -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/composition_interfaces -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/diagnostic_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/example_interfaces -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/geometry_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/include -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/lifecycle_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/micro_ros_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/micro_ros_utilities -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/nav_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcl -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcl_action -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcl_interfaces -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcl_lifecycle -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcl_logging_interface -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rclc -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rclc_lifecycle -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rclc_parameter -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rcutils -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rmw -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rmw_microros -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rmw_microxrcedds_c -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosgraph_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosidl_runtime_c -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosidl_typesupport_c -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosidl_typesupport_interface -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosidl_typesupport_introspection_c -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rosidl_typesupport_microxrcedds_c -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/sensor_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/shape_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/statistics_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/std_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/std_srvs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/stereo_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/test_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/tracetools -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/trajectory_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/ucdr -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/unique_identifier_msgs -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/uxr -isystem /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/visualization_msgs -mlongcalls -Wno-frame-address  -ffunction-sections -fdata-sections -Wall -Werror=all -Wno-error=unused-function -Wno-error=unused-variable -Wno-error=deprecated-declarations -Wextra -Wno-unused-parameter -Wno-sign-compare -Wno-enum-conversion -gdwarf-4 -ggdb -Og -fmacro-prefix-map=/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node=. -fmacro-prefix-map=/home/mahir/esp/esp-idf=/IDF -fstrict-volatile-bitfields -Wno-error=unused-but-set-variable -fno-jump-tables -fno-tree-switch-conversion -DconfigENABLE_FREERTOS_DEBUG_OCDAWARE=1 -std=gnu17 -Wno-old-style-declaration -D_GNU_SOURCE -DIDF_VER=\"v5.0.2\" -DESP_PLATFORM -D_POSIX_READER_WRITER_LOCKS -MD -MT esp-idf/main/CMakeFiles/__idf_main.dir/twist_node.c.obj -MF esp-idf/main/CMakeFiles/__idf_main.dir/twist_node.c.obj.d -o esp-idf/main/CMakeFiles/__idf_main.dir/twist_node.c.obj -c /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c: In function 'cmdvelCallback':
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:31:38: warning: unused variable 'msg' [-Wunused-variable]
   31 |     const geometry_msgs__msg__Twist *msg = (const geometry_msgs__msg__Twist *) msgin;
      |                                      ^~~
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c: In function 'micro_ros_task':
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:63:9: warning: passing argument 3 of 'rclc_subscription_init_best_effort' from incompatible pointer type [-Wincompatible-pointer-types]
   63 |         &my_type_support,
      |         ^~~~~~~~~~~~~~~~
      |         |
      |         const rosidl_message_type_support_t **
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:23:43: note: in definition of macro 'RCCHECK'
   23 | #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);}}
      |                                           ^~
In file included from /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rclc/rclc.h:31,
                 from /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:14:
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/include/rclc/subscription.h:78:41: note: expected 'const rosidl_message_type_support_t *' but argument is of type 'const rosidl_message_type_support_t **'
   78 |   const rosidl_message_type_support_t * type_support,
      |   ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c: In function 'app_main':
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:102:13: error: 'CONFIG_MICRO_ROS_APP_STACK' undeclared (first use in this function); did you mean 'CONFIG_MICRO_ROS_AGENT_IP'?
  102 |             CONFIG_MICRO_ROS_APP_STACK,
      |             ^~~~~~~~~~~~~~~~~~~~~~~~~~
      |             CONFIG_MICRO_ROS_AGENT_IP
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:102:13: note: each undeclared identifier is reported only once for each function it appears in
/home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/main/twist_node.c:104:13: error: 'CONFIG_MICRO_ROS_APP_TASK_PRIO' undeclared (first use in this function); did you mean 'CONFIG_MICRO_ROS_AGENT_IP'?
  104 |             CONFIG_MICRO_ROS_APP_TASK_PRIO,
      |             ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
      |             CONFIG_MICRO_ROS_AGENT_IP
ninja: build stopped: subcommand failed.
ninja failed with exit code 1, output of the command is in the /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/build/log/idf_py_stderr_output_6529 and /home/mahir/uros_esp32_ws/src/twist_node/components/micro_ros_espidf_component/examples/twist_node/build/log/idf_py_stdout_output_6529

```#### Additional information
I am trying to write a microROS project for making a differential drive robot but I can't even get the example to work on a new project. The example however works by default, I just cant get it to work as a new project. I created the project on the example directory to mimic the example/int32_publisher as best I can but Im not getting anywhere. Help would be appreciated
Vulcan758 commented 1 year ago

The whole creating a project in the example directory was done so that I could mimic the int32_publisher (or any of the example projects which build and work properly for that matter) as best i can.

I have tried creating a project and doing things in a seperate file with similar changes (different path for EXTRA_COMPONENTS_DIR) but I face this same issue