Open bit-pirate opened 11 years ago
This should work (for instance, I know we've used JointState message (which includes an array of string names). Can you attach both your .msg file, and the exported header file.
Hmm, Github doesn't allow me to attach this file type. Hence, I'll add the code:
Message description:
# Modified version of sensor_msgs/Range.msg
Header header # time stamp in the header is the time the ranger returned the distance reading
string name
string[] names
int16[] ranges # distance measured by the rangers
And generated header file:
#ifndef _ROS_kobuki_arduino_msgs_Rangers_h
#define _ROS_kobuki_arduino_msgs_Rangers_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"
#include "std_msgs/Header.h"
namespace kobuki_arduino_msgs
{
class Rangers : public ros::Msg
{
public:
std_msgs::Header header;
char * name;
uint8_t names_length;
char* st_names;
char* * names;
uint8_t ranges_length;
int16_t st_ranges;
int16_t * ranges;
virtual int serialize(unsigned char *outbuffer) const
{
int offset = 0;
offset += this->header.serialize(outbuffer + offset);
uint32_t * length_name = (uint32_t *)(outbuffer + offset);
*length_name = strlen( (const char*) this->name);
offset += 4;
memcpy(outbuffer + offset, this->name, *length_name);
offset += *length_name;
*(outbuffer + offset++) = names_length;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
for( uint8_t i = 0; i < names_length; i++){
uint32_t * length_namesi = (uint32_t *)(outbuffer + offset);
*length_namesi = strlen( (const char*) this->names[i]);
offset += 4;
memcpy(outbuffer + offset, this->names[i], *length_namesi);
offset += *length_namesi;
}
*(outbuffer + offset++) = ranges_length;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
*(outbuffer + offset++) = 0;
for( uint8_t i = 0; i < ranges_length; i++){
union {
int16_t real;
uint16_t base;
} u_rangesi;
u_rangesi.real = this->ranges[i];
*(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF;
*(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF;
offset += sizeof(this->ranges[i]);
}
return offset;
}
virtual int deserialize(unsigned char *inbuffer)
{
int offset = 0;
offset += this->header.deserialize(inbuffer + offset);
uint32_t length_name = *(uint32_t *)(inbuffer + offset);
offset += 4;
for(unsigned int k= offset; k< offset+length_name; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_name-1]=0;
this->name = (char *)(inbuffer + offset-1);
offset += length_name;
uint8_t names_lengthT = *(inbuffer + offset++);
if(names_lengthT > names_length)
this->names = (char**)realloc(this->names, names_lengthT * sizeof(char*));
offset += 3;
names_length = names_lengthT;
for( uint8_t i = 0; i < names_length; i++){
uint32_t length_st_names = *(uint32_t *)(inbuffer + offset);
offset += 4;
for(unsigned int k= offset; k< offset+length_st_names; ++k){
inbuffer[k-1]=inbuffer[k];
}
inbuffer[offset+length_st_names-1]=0;
this->st_names = (char *)(inbuffer + offset-1);
offset += length_st_names;
memcpy( &(this->names[i]), &(this->st_names), sizeof(char*));
}
uint8_t ranges_lengthT = *(inbuffer + offset++);
if(ranges_lengthT > ranges_length)
this->ranges = (int16_t*)realloc(this->ranges, ranges_lengthT * sizeof(int16_t));
offset += 3;
ranges_length = ranges_lengthT;
for( uint8_t i = 0; i < ranges_length; i++){
union {
int16_t real;
uint16_t base;
} u_st_ranges;
u_st_ranges.base = 0;
u_st_ranges.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
u_st_ranges.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
this->st_ranges = u_st_ranges.real;
offset += sizeof(this->st_ranges);
memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(int16_t));
}
return offset;
}
const char * getType(){ return "kobuki_arduino_msgs/Rangers"; };
const char * getMD5(){ return "b1e667a4c5373e22f15a5704e4c57c59"; };
};
}
#endif
I noticed that I only got the communication working when I reduced the size of the arrays a lot. I guess that's due to the limited message size. So, finally I removed the strings completely. Unfortunately I ended up with other errors regarding arrays. I will open up a new ticket for that.
Maybe this issue is related: https://github.com/ros-drivers/rosserial/issues/45
Ugh, I'm actually getting something which might be this issue. I can send an array of strings just fine, but receiving one causes a segfault— seems like the length of the string is getting garbled up with the length of the array, and the part of the deserializer that shifts the string over to make room for a null is making a big mess.
Now investigating further.
@mikeferguson @mikepurvis I think I've fixed the underlying issue that causes the above issues in PR #222
Not sure, if this is a bug or I am missing sth. Here is what I am doing: I have created a custom message, which works except the array of strings. My test message contains a normal string, a string array and a float32 array.