Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 0 additions & 8 deletions geometry_msgs/TwistMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions geometry_msgs/Vector3Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions sensor_msgs/CompressedImageMsg.cs.meta

This file was deleted.

113 changes: 83 additions & 30 deletions sensor_msgs/PointCloud2Msg.cs
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@
using ROSBridgeLib.std_msgs;
using UnityEngine;
using PointCloud;
using System.Text;

/**
* Define a PointCloud2 message.
*
* @author Miquel Massot Campos
* @author Miquel Massot Campos; Yuzhou Liu
*
*/

namespace ROSBridgeLib {
Expand All @@ -28,29 +30,30 @@ public PointCloud2Msg(JSONNode msg) {
_height = uint.Parse(msg ["height"]);
_width = uint.Parse(msg ["width"]);
_is_bigendian = msg["is_bigendian"].AsBool;
_is_dense = msg["is_dense"].AsBool;
_point_step = uint.Parse(msg ["point_step"]);
_row_step = uint.Parse(msg ["row_step"]);
_fields = new PointFieldMsg[msg["fields"].Count];
for (int i = 0; i < _fields.Length; i++)
{
_fields[i] = new PointFieldMsg(msg["fields"][i]);
}
_point_step = uint.Parse(msg["point_step"]);
_row_step = uint.Parse(msg["row_step"]);
_data = System.Convert.FromBase64String(msg["data"]);
_cloud = ReadData(_data);
}
//_cloud = ReadData(_data);
_is_dense = msg["is_dense"].AsBool;
}

public PointCloud2Msg(HeaderMsg header, uint height, uint width, PointFieldMsg fields, bool is_bigendian, uint point_step, uint row_step, byte[] data, bool is_dense) {
public PointCloud2Msg(HeaderMsg header, uint height, uint width, PointFieldMsg[] fields, bool is_bigendian, uint point_step, uint row_step, byte[] data, bool is_dense) {
_header = header;
_height = height;
_width = width;
//_fields = fields;
_is_dense = is_dense;
_fields = fields;
_is_bigendian = is_bigendian;
_point_step = point_step;
_row_step = row_step;
_cloud = ReadData(data);
}
_data = data;
//_cloud = ReadData(data);
_is_dense = is_dense;
}

private PointCloud<PointXYZRGB> ReadData(byte[] byteArray) {
PointCloud<PointXYZRGB> cloud = new PointCloud<PointXYZRGB> ();
Expand Down Expand Up @@ -89,35 +92,85 @@ public uint GetRowStep() {
return _row_step;
}

public PointCloud<PointXYZRGB> GetCloud() {
return _cloud;
}
//public PointCloud<PointXYZRGB> GetCloud() {
//return _cloud;
//}

public static string GetMessageType() {
return "sensor_msgs/PointCloud2";
}

public override string ToString() {
return "PointCloud2 [header=" + _header.ToString() +
"height=" + _height +
"width=" + _width +
//"fields=" + _fields.ToString() +
"is_bigendian=" + _is_bigendian +
"is_dense=" + _is_dense +
"point_step=" + _point_step +
"row_step=" + _row_step + "]";
", height=" + _height +
", width=" + _width +
", fields=" + _fields.ToString() +
", is_bigendian=" + _is_bigendian +
", point_step=" + _point_step +
", row_step=" + _row_step +
", data=" + _data.ToString() +
", is_dense=" + _is_dense + "]";
}

public override string ToYAMLString() {
return "{\"header\" :" + _header.ToYAMLString() +
"\"height\" :" + _height +
"\"width\" :" + _width +
//"\"fields\" :" + _fields.ToYAMLString() +
"\"is_bigendian\" :" + _is_bigendian +
"\"is_dense\" :" + _is_dense +
"\"point_step\" :" + _point_step +
"\"row_step\" :" + _row_step + "}";

string fields_array = "[";
for (int i = 0; i < _fields.Length; i++)
{
fields_array = fields_array + _fields[i].ToYAMLString();
if (_fields.Length - i > 1)
fields_array += ",";
}
fields_array += "]";

/*string data_array = "[";
for (int i = 0; i < _data.Length; i++)
{
data_array = data_array + _data[i];
if (_data.Length - i > 1)
data_array += ",";
}
data_array += "]";*/
StringBuilder data_sb = new StringBuilder();
data_sb.Append("[");
for (int i = 0; i < _data.Length; i++)
{
data_sb.Append(_data[i]);
if (_data.Length - i > 1)
data_sb.Append(",");
}
data_sb.Append("]");

string is_bigendian_string;
if (_is_bigendian == true){
is_bigendian_string = "true";
}
else{
is_bigendian_string = "false";
}

string _is_dense_string;
if (_is_dense == true)
{
_is_dense_string = "true";
}
else
{
_is_dense_string = "false";
}


return "{\"header\" : " + _header.ToYAMLString() +
", \"height\" : " + _height +
", \"width\" : " + _width +
", \"fields\" : " + fields_array +
", \"is_bigendian\" : " + is_bigendian_string +
", \"point_step\" : " + _point_step +
", \"row_step\" : " + _row_step +
", \"data\" : " + data_sb +
", \"is_dense\" : " + _is_dense_string +
"}";
}
}
}
}
}
12 changes: 0 additions & 12 deletions sensor_msgs/PointCloudMsg.cs.meta

This file was deleted.

2 changes: 1 addition & 1 deletion sensor_msgs/PointFieldMsg.cs
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ public override string ToString() {
}

public override string ToYAMLString() {
return "{\"name\" : " + "\"" + _name + "\", \"offset\" : \"" + _offset + "\", \"datatype\" : " + _datatype + "\", \"count\" : " + _count + "}";
return "{\"name\" : " + "\"" + _name + "\", \"offset\" : " + _offset + ", \"datatype\" : " + _datatype + ", \"count\" : " + _count + "}";
}
}
}
Expand Down
8 changes: 0 additions & 8 deletions std_msgs/HeaderMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int32Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int32MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int64Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int64MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int8Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/Int8MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/MultiArrayDimensionMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/MultiArrayLayoutMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/StringMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/TimeMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt16Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt16MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt32Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt32MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt64Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt64MultiArrayMsg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt8Msg.cs.meta

This file was deleted.

8 changes: 0 additions & 8 deletions std_msgs/UInt8MultiArrayMsg.cs.meta

This file was deleted.