Hi Everyone, Due to having no Arduino, but willing to test the connection from an embedded system to a ros-host, i have written a message generator, generating C message-header files compatible to standard ros_serial messages. Also I have written a small version of ros lib, containing types and function mechanisms to build up a simple node on an embedded system, in the same style its written on host-machines. Following Code is part of my example project running on a STM32F3Discovery, containing accelerometers, magnetometers and gyroscopes, it represents a ROS-IMU sensor. The board is available for 15-20$ I think, me got it from embeddedWorld fair this year. int main(void) { /* init hardware */ hardwareInit(); /* initialize IMU */ imuInit(); /* initialize ROS, namespace "imu_sensor*/ rosInit("imu_sensor"); /* get pointer to global nodehandle */ rosNodeHandle_t* nh = rosNodeHandle(); /* setup ROS IMU message */ Imu_t imu_msg = rosCreateImu_t(); /* advertise imu msg */ rosPublisher_t *imu_pub = nh->advertise(&imu_msg.mh, "/Imu", 512); /* set frame id */ imu_msg.header.frame_id = "/base_link"; /* enter loop */ while (rosOk()) { /* update IMU data */ imuUpdate(); /* set data to imu message */ float* acc = imuGetAcc(); float* mag = imuGetMag(); float* gyr = imuGetGyr(); float* ori = imuGetOrientation(); imu_msg.angular_velocity.x = gyr[X]; imu_msg.angular_velocity.y = gyr[Y]; imu_msg.angular_velocity.z = gyr[Z]; imu_msg.linear_acceleration.x = acc[X]; imu_msg.linear_acceleration.y = acc[Y]; imu_msg.linear_acceleration.z = acc[Z]; imu_msg.orientation.w = ori[W]; imu_msg.orientation.x = ori[X]; imu_msg.orientation.y = ori[Y]; imu_msg.orientation.z = ori[Z]; /* set timestamp */ imu_msg.header.stamp = rosTimeNow(); /* publish message */ imu_pub->publish(&imu_msg); /* spin nodehandle */ rosSpinOnce(); /* sleep 50 milliseconds */ rosSleep(50); } } Library code and generated code are at least C99 compatible. Heap size used is determined by in-/out-buffer lengths like its done in standard ros_serial. Input is bufferd by a fifo-queue and processed via rosSpin() or rosSpinOnce() function (same way ros_serial does). Therefor the code could be usable for any controller understanding C, having a U(S)ART and at least 4K memory. Currently I'm trying to bring up a FreeRTOS-ROS system, to have another way to implement sensors or something else. Now my question is, what shall i do? Put it into ros_serial? Or shall i make a new ros_embedded package? Or are there already plans to build up an embedded distribution on RTOS systems, like FreeRTOS? Regards, Peter