micro-ROS/micro_ros_stm32cubemx_utils

is micro_ros_utilities_create_message_memory available?

elgarbe opened this issue · 10 comments

Hi, I've read this and would like to use micro_ros_utilities_create_message_memory, but it seems that it's not available on libmicroros.

Thank

So, I need to clone this repo into microros_static_library/library_generation/extra_packages/ folder and rebuild the library?

Yes

I recompile the library but now I have a new error:

//  Assigning dynamic memory to the frame_id char sequence
	IMU_msg.header.frame_id.capacity = 10;	// 9 for "base_link" + 1 for null terminated string???
	IMU_msg.header.frame_id.data = (char*) malloc(IMU_msg.values.capacity * sizeof(char));
	IMU_msg.header.frame_id.size = 0;

	// Assigning value to the frame_id char sequence
	strcpy(IMU_msg.header.frame_id.data, "base_link");
	IMU_msg.header.frame_id.size = strlen(IMU_msg.header.frame_id.data);

IMU_msg is a Vecto3Stamped type. I don't fully understand capacity and size fields of header.frame.
The error is on (char*) malloc(IMU_msg.values.capacity * sizeof(char));
'geometry_msgs__msg__Vector3Stamped' has no member named 'values'

Thank for the help!

Let me see if I understand correctly:
IMU_msg.header is a compund data type it's members are stamp and frame_id.
frame_id is a sequence data type (a sequence of chars) and thereare for it has capacity, data and size members.
I don't fully understand this:
"The pointer should have memory for storing up to capacity values and size member shows how many element are currently in the sequence"

maybe I could understand with an example. If I want to store "base_link" on data member, then I have to use:
IMU_msg.header.frame_id.capacity = 10; becouse I need the null symbol as string termination, right?
then I need to reserve memory for the data member:
IMU_msg.header.frame_id.data = (char*) malloc(IMU_msg.header.frame_id.capacity * sizeof(char));
next I can fill data member with:
strcpy(IMU_msg.header.frame_id.data, "base_link");
here I'm not sure about the static string "base_link" and the null terminated frame_id.data
Finally I should use IMU_msg.header.frame_id.size = strlen(IMU_msg.header.frame_id.data);
am I right? or do I miss something?

That's it

Ok and I can replace that code with this:


	static micro_ros_utilities_memory_conf_t conf = {0};
	bool success = micro_ros_utilities_create_message_memory(
		ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Vector3Stamped),
		&IMU_msg,
		conf
		);
	IMU_msg.header.frame_id = micro_ros_string_utilities_set(IMU_msg.header.frame_id, "base_link");
	if (success)
		printf("[INFO] imu msg init OK!\r\n");
	else
	{
		printf("[ERROR]imu msg init failed!\r\n");

using micro_ros_utilities, right?

It should be possible, yes

Thank a lot for the help!