arduinoteensyros2

What is rosidl_runtime_c__double__Sequence type?


I'm trying to use a teensy 4.1 as an interface between an encoder and ROS thanks to micro-ros (arduino version).

I would like to publish position of a wheel to the /jointState topic with the teensy but there is no example on the micro-ros arduino Github repo.

I've tried to inspect the sensormsgs/msg/jointState message struct but everything is a bit fuzzy and I don't understand how to make it works. I can't understand what is rosidl_runtime_c__double__Sequence type.

I've tried several things but I always get an error about operand types

no match for 'operator=' (operand types are 'rosidl_runtime_c__String' and 'const char [18]')
 msg.name.data[0] = "drivewhl_1g_joint";

Here is my arduino code

#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 <sensor_msgs/msg/joint_state.h>

rcl_publisher_t publisher;
sensor_msgs__msg__JointState msg;
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;

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

    //Do not work
    //msg.name=["drivewhl_1g_joint","drivewhl_1d_joint","drivewhl_2g_joint","drivewhl_2d_joint"];
    //msg.position=["1.3","0.2", "0","0"];
    msg.name.size = 1;
    msg.name.data[0] = "drivewhl_1g_joint";
    msg.position.size = 1;
    msg.position.data[0] = 1.85;
    
  
  }
}

void setup() {
  set_microros_transports();
  
  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_node", "", &support));

  // create publisher
  RCCHECK(rclc_publisher_init_default(
    &publisher,
    &node,
    ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, JointState),
    "JointState"));

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

  // create executor
  RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
  RCCHECK(rclc_executor_add_timer(&executor, &timer));

}

void loop() {
  delay(100);
  RCSOFTCHECK(rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)));
}

I'm a beginner with Ros and C, it may be a very dumb question but I don't know how to solve it. Thanks for your help !


Solution

  • I also spent quite some time trying to get publishing JointState message from my esp32 running microros, and also couldn't find working example. Finally, i was successful, maybe it will help someone.

    In simple words:

    This is my code that allocates memory for 12 joints, named j0-j11. Good luck!

    ...
    // Declarations
    rcl_publisher_t pub_joint;
    sensor_msgs__msg__JointState joint_state_msg;
    ...
    // Create publisher
    RCCHECK(rclc_publisher_init_default(&pub_joint, &node,
        ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, JointState), 
        "/hexapod/joint_state"));
    
    //Allocate memory
        joint_state_msg.name.capacity = 12;
        joint_state_msg.name.size = 12;
        joint_state_msg.name.data = (std_msgs__msg__String*) malloc(joint_state_msg.name.capacity*sizeof(std_msgs__msg__String));
    
        for(int i=0;i<12;i++) {
            joint_state_msg.name.data[i].data = malloc(5);
            joint_state_msg.name.data[i].capacity = 5;
            sprintf(joint_state_msg.name.data[i].data,"j%d",i);
            joint_state_msg.name.data[i].size = strlen(joint_state_msg.name.data[i].data);
        }
    
        joint_state_msg.position.size=12;
        joint_state_msg.position.capacity=12;
        joint_state_msg.position.data = malloc(joint_state_msg.position.capacity*sizeof(double));
        joint_state_msg.velocity.size=12;
        joint_state_msg.velocity.capacity=12;
        joint_state_msg.velocity.data = malloc(joint_state_msg.velocity.capacity*sizeof(double));
        joint_state_msg.effort.size=12;
        joint_state_msg.effort.capacity=12;
        joint_state_msg.effort.data = malloc(joint_state_msg.effort.capacity*sizeof(double));
    
        for(int i=0;i<12;i++) {
            joint_state_msg.position.data[i]=0.0;
            joint_state_msg.velocity.data[i]=0.0;
            joint_state_msg.effort.data[i]=0.0;
        }
    
    ....
    //Publish
    RCSOFTCHECK(rcl_publish(&pub_joint, &joint_state_msg, NULL));