From 47cd5b358d1e204920e9e1fcec9a640f38939b81 Mon Sep 17 00:00:00 2001 From: Duncan Calvert Date: Wed, 21 Aug 2024 17:02:26 -0500 Subject: [PATCH] Remove vendored netty classes, because we actually use Netty in some places. --- .../AtlasHeightMapTopicConverter.java | 1 - .../AtlasD435ToMultiSenseLeftEyeBridge.java | 60 +- ...erL515ZED2FusedColoredROS1ToREABridge.java | 14 +- ...sZED2LeftEyeToMultiSenseLeftEyeBridge.java | 13 +- .../realsense/RealsenseVideoROS1Bridge.java | 62 +- .../org/jboss/netty/buffer/ChannelBuffer.java | 1515 ----------------- .../netty/buffer/ChannelBufferFactory.java | 104 -- .../java/sensor_msgs/CompressedImage.java | 7 +- .../src/main/java/sensor_msgs/Image.java | 8 +- .../main/java/sensor_msgs/PointCloud2.java | 8 +- .../java/us/ihmc/utilities/ros/RosTools.java | 78 +- .../ros/publisher/RosImagePublisher.java | 40 +- .../ros/publisher/RosPointCloudPublisher.java | 2 +- .../subscriber/RosPointCloudSubscriber.java | 74 +- .../hardware/MultisenseImageROS1Bridge.java | 40 +- ...ointCloud2ToLidarScanMessageConverter.java | 32 +- 16 files changed, 214 insertions(+), 1844 deletions(-) delete mode 100644 ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java delete mode 100644 ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java diff --git a/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java b/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java index db895adadb3..1745e0b1e4b 100644 --- a/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java +++ b/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java @@ -3,7 +3,6 @@ import perception_msgs.msg.dds.PlanarRegionsListMessage; import map_sense.RawGPUPlanarRegionList; import org.apache.commons.lang3.mutable.MutableInt; -import org.jboss.netty.buffer.ChannelBuffer; //import org.jboss.netty.buffer.LittleEndianHeapChannelBuffer; import org.ros.message.Duration; import org.ros.message.Time; diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java index c5d7f8c5bd2..bb0adfc2f29 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java @@ -70,36 +70,36 @@ public void onNewMessage(sensor_msgs.CompressedImage ros1Image) syncedRobot.update(); // if (syncedRobot.getDataReceptionTimerSnapshot().isRunning(3.0)) { - try - { - byte[] payload = ros1Image.getData().array(); - int offset = ros1Image.getData().arrayOffset(); - BufferedImage bufferedImage = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); - - YUVPicture picture = converter.fromBufferedImage(bufferedImage, YUVPicture.YUVSubsamplingType.YUV420); - ByteBuffer buffer = encoder.encode(picture, 75); - - byte[] data = new byte[buffer.remaining()]; - buffer.get(data); - - FramePose3DReadOnly ousterPose = syncedRobot.getFramePoseReadOnly(HumanoidReferenceFrames::getOusterLidarFrame); - ousterPose.get(transformToWorld); - - VideoPacket message = new VideoPacket(); - message.setTimestamp(System.nanoTime()); - message.getData().add(data); - message.getPosition().set(ousterPose.getPosition()); - message.getOrientation().set(ousterPose.getOrientation()); - message.setVideoSource(VideoPacket.VIDEO_SOURCE_MULTISENSE_LEFT_EYE); - message.getIntrinsicParameters().set(HumanoidMessageTools.toIntrinsicParametersMessage(depthCameraIntrinsics)); - - ros2Helper.publish(PerceptionAPI.VIDEO, message); - } - catch (Exception e) - { - LogTools.error(e.getMessage()); - e.printStackTrace(); - } +// try +// { +// byte[] payload = ros1Image.getData().array(); +// int offset = ros1Image.getData().arrayOffset(); +// BufferedImage bufferedImage = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); +// +// YUVPicture picture = converter.fromBufferedImage(bufferedImage, YUVPicture.YUVSubsamplingType.YUV420); +// ByteBuffer buffer = encoder.encode(picture, 75); +// +// byte[] data = new byte[buffer.remaining()]; +// buffer.get(data); +// +// FramePose3DReadOnly ousterPose = syncedRobot.getFramePoseReadOnly(HumanoidReferenceFrames::getOusterLidarFrame); +// ousterPose.get(transformToWorld); +// +// VideoPacket message = new VideoPacket(); +// message.setTimestamp(System.nanoTime()); +// message.getData().add(data); +// message.getPosition().set(ousterPose.getPosition()); +// message.getOrientation().set(ousterPose.getOrientation()); +// message.setVideoSource(VideoPacket.VIDEO_SOURCE_MULTISENSE_LEFT_EYE); +// message.getIntrinsicParameters().set(HumanoidMessageTools.toIntrinsicParametersMessage(depthCameraIntrinsics)); +// +// ros2Helper.publish(PerceptionAPI.VIDEO, message); +// } +// catch (Exception e) +// { +// LogTools.error(e.getMessage()); +// e.printStackTrace(); +// } } }); } diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java index 74383f05e7d..c5687789b39 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java @@ -2,8 +2,6 @@ import perception_msgs.msg.dds.LidarScanMessage; import controller_msgs.msg.dds.StereoVisionPointCloudMessage; -import org.bytedeco.javacpp.BytePointer; -import org.jboss.netty.buffer.ChannelBuffer; import sensor_msgs.Image; import sensor_msgs.PointCloud2; import us.ihmc.atlas.AtlasRobotModel; @@ -94,12 +92,12 @@ public void onNewMessage(PointCloud2 pointCloud2) Point3D[] l515Points = null; if (latestL515PointCloud2 != null && zed2Image != null) { - ChannelBuffer l515NettyImageData = latestL515PointCloud2.getData(); - ByteBuffer l515DataByteBuffer = l515NettyImageData.toByteBuffer(); - int arrayOffset = l515NettyImageData.arrayOffset(); - l515DataByteBuffer.position(arrayOffset); - ByteBuffer offsetByteBuffer = l515DataByteBuffer.slice(); - BytePointer imageDataPointer = new BytePointer(offsetByteBuffer); +// ChannelBuffer l515NettyImageData = latestL515PointCloud2.getData(); +// ByteBuffer l515DataByteBuffer = l515NettyImageData.toByteBuffer(); +// int arrayOffset = l515NettyImageData.arrayOffset(); +// l515DataByteBuffer.position(arrayOffset); +// ByteBuffer offsetByteBuffer = l515DataByteBuffer.slice(); +// BytePointer imageDataPointer = new BytePointer(offsetByteBuffer); // l515 is 4 float 32s, X,Y,Z,RGB // Point4fVector l515Point3fVector = new Point4fVector(imageDataPointer); diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java index 350586986b2..156ad6f0f7e 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java @@ -8,7 +8,6 @@ import org.bytedeco.opencv.global.opencv_imgcodecs; import org.bytedeco.opencv.global.opencv_imgproc; import org.bytedeco.opencv.opencv_core.Mat; -import org.jboss.netty.buffer.ChannelBuffer; import us.ihmc.atlas.AtlasRobotModel; import us.ihmc.atlas.AtlasRobotVersion; import us.ihmc.avatar.drcRobot.ROS2SyncedRobotModel; @@ -95,18 +94,18 @@ public void onNewMessage(sensor_msgs.Image ros1Image) try { - ChannelBuffer nettyImageData = ros1Image.getData(); - ByteBuffer dataByteBuffer = nettyImageData.toByteBuffer(); - int arrayOffset = nettyImageData.arrayOffset(); - dataByteBuffer.position(arrayOffset); - ByteBuffer offsetByteBuffer = dataByteBuffer.slice(); +// ChannelBuffer nettyImageData = ros1Image.getData(); +// ByteBuffer dataByteBuffer = nettyImageData.toByteBuffer(); +// int arrayOffset = nettyImageData.arrayOffset(); +// dataByteBuffer.position(arrayOffset); +// ByteBuffer offsetByteBuffer = dataByteBuffer.slice(); // byte[] nettyBackingArray = nettyImageData.array(); // int dataLength = nettyBackingArray.length - arrayOffset; // ByteBuffer offsetByteBuffer = ByteBuffer.wrap(nettyBackingArray, arrayOffset, dataLength); // ByteBuffer offsetByteBuffer = new ByteBuffer(0, 0, dataLength, dataLength, nettyBackingArray, arrayOffset); // System.out.println(dataByteBuffer.isDirect()); - BytePointer imageDataPointer = new BytePointer(offsetByteBuffer); + BytePointer imageDataPointer = null; inputImageMat.data(imageDataPointer); opencv_imgproc.cvtColor(inputImageMat, decodedImageMat, opencv_imgproc.COLOR_BGR2YUV_I420); diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/realsense/RealsenseVideoROS1Bridge.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/realsense/RealsenseVideoROS1Bridge.java index 30c54ec97fa..297147cf6d6 100644 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/realsense/RealsenseVideoROS1Bridge.java +++ b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/realsense/RealsenseVideoROS1Bridge.java @@ -74,38 +74,38 @@ private void waitThenAct(sensor_msgs.CompressedImage ros1Image) private void compute(sensor_msgs.CompressedImage ros1Image) { - try - { - byte[] payload = ros1Image.getData().array(); - int offset = ros1Image.getData().arrayOffset(); - BufferedImage bufferedImage = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); - - YUVPicture picture = converter.fromBufferedImage(bufferedImage, YUVPicture.YUVSubsamplingType.YUV420); - ByteBuffer buffer = encoder.encode(picture, 75); - - byte[] data = new byte[buffer.remaining()]; - buffer.get(data); - - VideoPacket message = new VideoPacket(); - message.setTimestamp(System.nanoTime()); - message.getData().add(data); - - publisher.publish(message); - } - catch (Exception e) - { - LogTools.error(e.getMessage()); - e.printStackTrace(); - } +// try +// { +// byte[] payload = ros1Image.getData().array(); +// int offset = ros1Image.getData().arrayOffset(); +// BufferedImage bufferedImage = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); +// +// YUVPicture picture = converter.fromBufferedImage(bufferedImage, YUVPicture.YUVSubsamplingType.YUV420); +// ByteBuffer buffer = encoder.encode(picture, 75); +// +// byte[] data = new byte[buffer.remaining()]; +// buffer.get(data); +// +// VideoPacket message = new VideoPacket(); +// message.setTimestamp(System.nanoTime()); +// message.getData().add(data); +// +// publisher.publish(message); +// } +// catch (Exception e) +// { +// LogTools.error(e.getMessage()); +// e.printStackTrace(); +// } } // Eventually it would be nice to use Compressed Image - private void createROS2CompressedImage(sensor_msgs.CompressedImage ros1Image) - { - CompressedImage ros2Image = new CompressedImage(); - byte[] data = ros1Image.getData().array(); - int dataOffset = ros1Image.getData().arrayOffset(); - int length = data.length; - ros2Image.getData().add(data, dataOffset, length - dataOffset); - } +// private void createROS2CompressedImage(sensor_msgs.CompressedImage ros1Image) +// { +// CompressedImage ros2Image = new CompressedImage(); +// byte[] data = ros1Image.getData().array(); +// int dataOffset = ros1Image.getData().arrayOffset(); +// int length = data.length; +// ros2Image.getData().add(data, dataOffset, length - dataOffset); +// } } diff --git a/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java b/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java deleted file mode 100644 index 4c77f6a794c..00000000000 --- a/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java +++ /dev/null @@ -1,1515 +0,0 @@ -/* - * Copyright 2012 The Netty Project - * - * The Netty Project licenses this file to you under the Apache License, - * version 2.0 (the "License"); you may not use this file except in compliance - * with the License. You may obtain a copy of the License at: - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the - * License for the specific language governing permissions and limitations - * under the License. - */ -package org.jboss.netty.buffer; - -import java.io.IOException; -import java.io.InputStream; -import java.io.OutputStream; -import java.nio.ByteBuffer; -import java.nio.ByteOrder; -import java.nio.channels.GatheringByteChannel; -import java.nio.channels.ScatteringByteChannel; -import java.nio.charset.Charset; -import java.nio.charset.UnsupportedCharsetException; - -public interface ChannelBuffer extends Comparable { - - /** - * Returns the factory which creates a {@link ChannelBuffer} whose - * type and default {@link ByteOrder} are same with this buffer. - */ -// ChannelBufferFactory factory(); - - /** - * Returns the number of bytes (octets) this buffer can contain. - */ - int capacity(); - - /** - * Returns the endianness - * of this buffer. - */ - ByteOrder order(); - - /** - * Returns {@code true} if and only if this buffer is backed by an - * NIO direct buffer. - */ - boolean isDirect(); - - /** - * Returns the {@code readerIndex} of this buffer. - */ - int readerIndex(); - - /** - * Sets the {@code readerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code readerIndex} is - * less than {@code 0} or - * greater than {@code this.writerIndex} - */ - void readerIndex(int readerIndex); - - /** - * Returns the {@code writerIndex} of this buffer. - */ - int writerIndex(); - - /** - * Sets the {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code writerIndex} is - * less than {@code this.readerIndex} or - * greater than {@code this.capacity} - */ - void writerIndex(int writerIndex); - - void setIndex(int readerIndex, int writerIndex); - - /** - * Returns the number of readable bytes which is equal to - * {@code (this.writerIndex - this.readerIndex)}. - */ - int readableBytes(); - - /** - * Returns the number of writable bytes which is equal to - * {@code (this.capacity - this.writerIndex)}. - */ - int writableBytes(); - - /** - * Returns {@code true} - * if and only if {@code (this.writerIndex - this.readerIndex)} is greater - * than {@code 0}. - */ - boolean readable(); - - /** - * Returns {@code true} - * if and only if {@code (this.capacity - this.writerIndex)} is greater - * than {@code 0}. - */ - boolean writable(); - - /** - * Sets the {@code readerIndex} and {@code writerIndex} of this buffer to - * {@code 0}. - * This method is identical to {@link #setIndex(int, int) setIndex(0, 0)}. - *

- * Please note that the behavior of this method is different - * from that of NIO buffer, which sets the {@code limit} to - * the {@code capacity} of the buffer. - */ - void clear(); - - /** - * Marks the current {@code readerIndex} in this buffer. You can - * reposition the current {@code readerIndex} to the marked - * {@code readerIndex} by calling {@link #resetReaderIndex()}. - * The initial value of the marked {@code readerIndex} is {@code 0}. - */ - void markReaderIndex(); - - /** - * Repositions the current {@code readerIndex} to the marked - * {@code readerIndex} in this buffer. - * - * @throws IndexOutOfBoundsException - * if the current {@code writerIndex} is less than the marked - * {@code readerIndex} - */ - void resetReaderIndex(); - - /** - * Marks the current {@code writerIndex} in this buffer. You can - * reposition the current {@code writerIndex} to the marked - * {@code writerIndex} by calling {@link #resetWriterIndex()}. - * The initial value of the marked {@code writerIndex} is {@code 0}. - */ - void markWriterIndex(); - - /** - * Repositions the current {@code writerIndex} to the marked - * {@code writerIndex} in this buffer. - * - * @throws IndexOutOfBoundsException - * if the current {@code readerIndex} is greater than the marked - * {@code writerIndex} - */ - void resetWriterIndex(); - - /** - * Discards the bytes between the 0th index and {@code readerIndex}. - * It moves the bytes between {@code readerIndex} and {@code writerIndex} - * to the 0th index, and sets {@code readerIndex} and {@code writerIndex} - * to {@code 0} and {@code oldWriterIndex - oldReaderIndex} respectively. - *

- * Please refer to the class documentation for more detailed explanation. - */ - void discardReadBytes(); - - /** - * Makes sure the number of {@linkplain #writableBytes() the writable bytes} - * is equal to or greater than the specified value. If there is enough - * writable bytes in this buffer, this method returns with no side effect. - * Otherwise: - *

- * - * @param writableBytes - * the expected minimum number of writable bytes - * @throws IndexOutOfBoundsException - * if {@linkplain #writableBytes() the writable bytes} of this - * buffer is less than the specified value and if this buffer is - * not a dynamic buffer - */ - void ensureWritableBytes(int writableBytes); - - /** - * Gets a byte at the specified absolute {@code index} in this buffer. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 1} is greater than {@code this.capacity} - */ - byte getByte(int index); - - /** - * Gets an unsigned byte at the specified absolute {@code index} in this - * buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 1} is greater than {@code this.capacity} - */ - short getUnsignedByte(int index); - - /** - * Gets a 16-bit short integer at the specified absolute {@code index} in - * this buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 2} is greater than {@code this.capacity} - */ - short getShort(int index); - - /** - * Gets an unsigned 16-bit short integer at the specified absolute - * {@code index} in this buffer. This method does not modify - * {@code readerIndex} or {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 2} is greater than {@code this.capacity} - */ - int getUnsignedShort(int index); - - /** - * Gets a 24-bit medium integer at the specified absolute {@code index} in - * this buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 3} is greater than {@code this.capacity} - */ - int getMedium(int index); - - /** - * Gets an unsigned 24-bit medium integer at the specified absolute - * {@code index} in this buffer. This method does not modify - * {@code readerIndex} or {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 3} is greater than {@code this.capacity} - */ - int getUnsignedMedium(int index); - - /** - * Gets a 32-bit integer at the specified absolute {@code index} in - * this buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 4} is greater than {@code this.capacity} - */ - int getInt(int index); - - /** - * Gets an unsigned 32-bit integer at the specified absolute {@code index} - * in this buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 4} is greater than {@code this.capacity} - */ - long getUnsignedInt(int index); - - /** - * Gets a 64-bit long integer at the specified absolute {@code index} in - * this buffer. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 8} is greater than {@code this.capacity} - */ - long getLong(int index); - - /** - * Gets a 2-byte UTF-16 character at the specified absolute - * {@code index} in this buffer. This method does not modify - * {@code readerIndex} or {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 2} is greater than {@code this.capacity} - */ - char getChar(int index); - - /** - * Gets a 32-bit floating point number at the specified absolute - * {@code index} in this buffer. This method does not modify - * {@code readerIndex} or {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 4} is greater than {@code this.capacity} - */ - float getFloat(int index); - - /** - * Gets a 64-bit floating point number at the specified absolute - * {@code index} in this buffer. This method does not modify - * {@code readerIndex} or {@code writerIndex} of this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 8} is greater than {@code this.capacity} - */ - double getDouble(int index); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index} until the destination becomes - * non-writable. This method is basically same with - * {@link #getBytes(int, ChannelBuffer, int, int)}, except that this - * method increases the {@code writerIndex} of the destination by the - * number of the transferred bytes while - * {@link #getBytes(int, ChannelBuffer, int, int)} does not. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * the source buffer (i.e. {@code this}). - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + dst.writableBytes} is greater than - * {@code this.capacity} - */ - void getBytes(int index, ChannelBuffer dst); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index}. This method is basically same - * with {@link #getBytes(int, ChannelBuffer, int, int)}, except that this - * method increases the {@code writerIndex} of the destination by the - * number of the transferred bytes while - * {@link #getBytes(int, ChannelBuffer, int, int)} does not. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * the source buffer (i.e. {@code this}). - * - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code length} is greater than {@code dst.writableBytes} - */ - void getBytes(int index, ChannelBuffer dst, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} - * of both the source (i.e. {@code this}) and the destination. - * - * @param dstIndex the first index of the destination - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if the specified {@code dstIndex} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code dstIndex + length} is greater than - * {@code dst.capacity} - */ - void getBytes(int index, ChannelBuffer dst, int dstIndex, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + dst.length} is greater than - * {@code this.capacity} - */ - void getBytes(int index, byte[] dst); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} - * of this buffer. - * - * @param dstIndex the first index of the destination - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if the specified {@code dstIndex} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code dstIndex + length} is greater than - * {@code dst.length} - */ - void getBytes(int index, byte[] dst, int dstIndex, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the specified absolute {@code index} until the destination's position - * reaches its limit. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer while the destination's {@code position} will be increased. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + dst.remaining()} is greater than - * {@code this.capacity} - */ - void getBytes(int index, ByteBuffer dst); - - /** - * Transfers this buffer's data to the specified stream starting at the - * specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + length} is greater than - * {@code this.capacity} - * @throws IOException - * if the specified stream threw an exception during I/O - */ - void getBytes(int index, OutputStream out, int length) throws IOException; - - /** - * Transfers this buffer's data to the specified channel starting at the - * specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @param length the maximum number of bytes to transfer - * - * @return the actual number of bytes written out to the specified channel - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + length} is greater than - * {@code this.capacity} - * @throws IOException - * if the specified channel threw an exception during I/O - */ - int getBytes(int index, GatheringByteChannel out, int length) throws IOException; - - /** - * Sets the specified byte at the specified absolute {@code index} in this - * buffer. The 24 high-order bits of the specified value are ignored. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 1} is greater than {@code this.capacity} - */ - void setByte(int index, int value); - - /** - * Sets the specified 16-bit short integer at the specified absolute - * {@code index} in this buffer. The 16 high-order bits of the specified - * value are ignored. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 2} is greater than {@code this.capacity} - */ - void setShort(int index, int value); - - /** - * Sets the specified 24-bit medium integer at the specified absolute - * {@code index} in this buffer. Please note that the most significant - * byte is ignored in the specified value. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 3} is greater than {@code this.capacity} - */ - void setMedium(int index, int value); - - /** - * Sets the specified 32-bit integer at the specified absolute - * {@code index} in this buffer. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 4} is greater than {@code this.capacity} - */ - void setInt(int index, int value); - - /** - * Sets the specified 64-bit long integer at the specified absolute - * {@code index} in this buffer. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 8} is greater than {@code this.capacity} - */ - void setLong(int index, long value); - - /** - * Sets the specified 2-byte UTF-16 character at the specified absolute - * {@code index} in this buffer. - * The 16 high-order bits of the specified value are ignored. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 2} is greater than {@code this.capacity} - */ - void setChar(int index, int value); - - /** - * Sets the specified 32-bit floating-point number at the specified - * absolute {@code index} in this buffer. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 4} is greater than {@code this.capacity} - */ - void setFloat(int index, float value); - - /** - * Sets the specified 64-bit floating-point number at the specified - * absolute {@code index} in this buffer. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * {@code index + 8} is greater than {@code this.capacity} - */ - void setDouble(int index, double value); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the specified absolute {@code index} until the source buffer becomes - * unreadable. This method is basically same with - * {@link #setBytes(int, ChannelBuffer, int, int)}, except that this - * method increases the {@code readerIndex} of the source buffer by - * the number of the transferred bytes while - * {@link #setBytes(int, ChannelBuffer, int, int)} does not. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * the source buffer (i.e. {@code this}). - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + src.readableBytes} is greater than - * {@code this.capacity} - */ - void setBytes(int index, ChannelBuffer src); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the specified absolute {@code index}. This method is basically same - * with {@link #setBytes(int, ChannelBuffer, int, int)}, except that this - * method increases the {@code readerIndex} of the source buffer by - * the number of the transferred bytes while - * {@link #setBytes(int, ChannelBuffer, int, int)} does not. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * the source buffer (i.e. {@code this}). - * - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code length} is greater than {@code src.readableBytes} - */ - void setBytes(int index, ChannelBuffer src, int length); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} - * of both the source (i.e. {@code this}) and the destination. - * - * @param srcIndex the first index of the source - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if the specified {@code srcIndex} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code srcIndex + length} is greater than - * {@code src.capacity} - */ - void setBytes(int index, ChannelBuffer src, int srcIndex, int length); - - /** - * Transfers the specified source array's data to this buffer starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + src.length} is greater than - * {@code this.capacity} - */ - void setBytes(int index, byte[] src); - - /** - * Transfers the specified source array's data to this buffer starting at - * the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0}, - * if the specified {@code srcIndex} is less than {@code 0}, - * if {@code index + length} is greater than - * {@code this.capacity}, or - * if {@code srcIndex + length} is greater than {@code src.length} - */ - void setBytes(int index, byte[] src, int srcIndex, int length); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the specified absolute {@code index} until the source buffer's position - * reaches its limit. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + src.remaining()} is greater than - * {@code this.capacity} - */ - void setBytes(int index, ByteBuffer src); - - /** - * Transfers the content of the specified source stream to this buffer - * starting at the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @param length the number of bytes to transfer - * - * @return the actual number of bytes read in from the specified channel. - * {@code -1} if the specified channel is closed. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + length} is greater than {@code this.capacity} - * @throws IOException - * if the specified stream threw an exception during I/O - */ - int setBytes(int index, InputStream in, int length) throws IOException; - - /** - * Transfers the content of the specified source channel to this buffer - * starting at the specified absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @param length the maximum number of bytes to transfer - * - * @return the actual number of bytes read in from the specified channel. - * {@code -1} if the specified channel is closed. - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + length} is greater than {@code this.capacity} - * @throws IOException - * if the specified channel threw an exception during I/O - */ - int setBytes(int index, ScatteringByteChannel in, int length) throws IOException; - - /** - * Fills this buffer with NUL (0x00) starting at the specified - * absolute {@code index}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @param length the number of NULs to write to the buffer - * - * @throws IndexOutOfBoundsException - * if the specified {@code index} is less than {@code 0} or - * if {@code index + length} is greater than {@code this.capacity} - */ - void setZero(int index, int length); - - /** - * Gets a byte at the current {@code readerIndex} and increases - * the {@code readerIndex} by {@code 1} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 1} - */ - byte readByte(); - - /** - * Gets an unsigned byte at the current {@code readerIndex} and increases - * the {@code readerIndex} by {@code 1} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 1} - */ - short readUnsignedByte(); - - /** - * Gets a 16-bit short integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 2} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 2} - */ - short readShort(); - - /** - * Gets an unsigned 16-bit short integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 2} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 2} - */ - int readUnsignedShort(); - - /** - * Gets a 24-bit medium integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 3} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 3} - */ - int readMedium(); - - /** - * Gets an unsigned 24-bit medium integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 3} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 3} - */ - int readUnsignedMedium(); - - /** - * Gets a 32-bit integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 4} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 4} - */ - int readInt(); - - /** - * Gets an unsigned 32-bit integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 4} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 4} - */ - long readUnsignedInt(); - - /** - * Gets a 64-bit integer at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 8} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 8} - */ - long readLong(); - - /** - * Gets a 2-byte UTF-16 character at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 2} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 2} - */ - char readChar(); - - /** - * Gets a 32-bit floating point number at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 4} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 4} - */ - float readFloat(); - - /** - * Gets a 64-bit floating point number at the current {@code readerIndex} - * and increases the {@code readerIndex} by {@code 8} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.readableBytes} is less than {@code 8} - */ - double readDouble(); - - /** - * Transfers this buffer's data to a newly created buffer starting at - * the current {@code readerIndex} and increases the {@code readerIndex} - * by the number of the transferred bytes (= {@code length}). - * The returned buffer's {@code readerIndex} and {@code writerIndex} are - * {@code 0} and {@code length} respectively. - * - * @param length the number of bytes to transfer - * - * @return the newly created buffer which contains the transferred bytes - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - */ - ChannelBuffer readBytes(int length); - -// /** -// * @deprecated Use {@link #bytesBefore(ChannelBufferIndexFinder)} and {@link #readBytes(int)} instead. -// */ -// @Deprecated -// ChannelBuffer readBytes(ChannelBufferIndexFinder indexFinder); - - /** - * Returns a new slice of this buffer's sub-region starting at the current - * {@code readerIndex} and increases the {@code readerIndex} by the size - * of the new slice (= {@code length}). - * - * @param length the size of the new slice - * - * @return the newly created slice - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - */ - ChannelBuffer readSlice(int length); - -// /** -// * @deprecated Use {@link #bytesBefore(ChannelBufferIndexFinder)} and {@link #readSlice(int)} instead. -// */ -// @Deprecated -// ChannelBuffer readSlice(ChannelBufferIndexFinder indexFinder); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} until the destination becomes - * non-writable, and increases the {@code readerIndex} by the number of the - * transferred bytes. This method is basically same with - * {@link #readBytes(ChannelBuffer, int, int)}, except that this method - * increases the {@code writerIndex} of the destination by the number of - * the transferred bytes while {@link #readBytes(ChannelBuffer, int, int)} - * does not. - * - * @throws IndexOutOfBoundsException - * if {@code dst.writableBytes} is greater than - * {@code this.readableBytes} - */ - void readBytes(ChannelBuffer dst); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} and increases the {@code readerIndex} - * by the number of the transferred bytes (= {@code length}). This method - * is basically same with {@link #readBytes(ChannelBuffer, int, int)}, - * except that this method increases the {@code writerIndex} of the - * destination by the number of the transferred bytes (= {@code length}) - * while {@link #readBytes(ChannelBuffer, int, int)} does not. - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} or - * if {@code length} is greater than {@code dst.writableBytes} - */ - void readBytes(ChannelBuffer dst, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} and increases the {@code readerIndex} - * by the number of the transferred bytes (= {@code length}). - * - * @param dstIndex the first index of the destination - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code dstIndex} is less than {@code 0}, - * if {@code length} is greater than {@code this.readableBytes}, or - * if {@code dstIndex + length} is greater than - * {@code dst.capacity} - */ - void readBytes(ChannelBuffer dst, int dstIndex, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} and increases the {@code readerIndex} - * by the number of the transferred bytes (= {@code dst.length}). - * - * @throws IndexOutOfBoundsException - * if {@code dst.length} is greater than {@code this.readableBytes} - */ - void readBytes(byte[] dst); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} and increases the {@code readerIndex} - * by the number of the transferred bytes (= {@code length}). - * - * @param dstIndex the first index of the destination - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code dstIndex} is less than {@code 0}, - * if {@code length} is greater than {@code this.readableBytes}, or - * if {@code dstIndex + length} is greater than {@code dst.length} - */ - void readBytes(byte[] dst, int dstIndex, int length); - - /** - * Transfers this buffer's data to the specified destination starting at - * the current {@code readerIndex} until the destination's position - * reaches its limit, and increases the {@code readerIndex} by the - * number of the transferred bytes. - * - * @throws IndexOutOfBoundsException - * if {@code dst.remaining()} is greater than - * {@code this.readableBytes} - */ - void readBytes(ByteBuffer dst); - - /** - * Transfers this buffer's data to the specified stream starting at the - * current {@code readerIndex}. - * - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - * @throws IOException - * if the specified stream threw an exception during I/O - */ - void readBytes(OutputStream out, int length) throws IOException; - - /** - * Transfers this buffer's data to the specified stream starting at the - * current {@code readerIndex}. - * - * @param length the maximum number of bytes to transfer - * - * @return the actual number of bytes written out to the specified channel - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - * @throws IOException - * if the specified channel threw an exception during I/O - */ - int readBytes(GatheringByteChannel out, int length) throws IOException; - - /** - * Increases the current {@code readerIndex} by the specified - * {@code length} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - */ - void skipBytes(int length); - -// /** -// * @deprecated Use {@link #bytesBefore(ChannelBufferIndexFinder)} and {@link #skipBytes(int)} instead. -// */ -// @Deprecated -// int skipBytes(ChannelBufferIndexFinder indexFinder); - - /** - * Sets the specified byte at the current {@code writerIndex} - * and increases the {@code writerIndex} by {@code 1} in this buffer. - * The 24 high-order bits of the specified value are ignored. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 1} - */ - void writeByte(int value); - - /** - * Sets the specified 16-bit short integer at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 2} - * in this buffer. The 16 high-order bits of the specified value are ignored. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 2} - */ - void writeShort(int value); - - /** - * Sets the specified 24-bit medium integer at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 3} - * in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 3} - */ - void writeMedium(int value); - - /** - * Sets the specified 32-bit integer at the current {@code writerIndex} - * and increases the {@code writerIndex} by {@code 4} in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 4} - */ - void writeInt(int value); - - /** - * Sets the specified 64-bit long integer at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 8} - * in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 8} - */ - void writeLong(long value); - - /** - * Sets the specified 2-byte UTF-16 character at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 2} - * in this buffer. The 16 high-order bits of the specified value are ignored. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 2} - */ - void writeChar(int value); - - /** - * Sets the specified 32-bit floating point number at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 4} - * in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 4} - */ - void writeFloat(float value); - - /** - * Sets the specified 64-bit floating point number at the current - * {@code writerIndex} and increases the {@code writerIndex} by {@code 8} - * in this buffer. - * - * @throws IndexOutOfBoundsException - * if {@code this.writableBytes} is less than {@code 8} - */ - void writeDouble(double value); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the current {@code writerIndex} until the source buffer becomes - * unreadable, and increases the {@code writerIndex} by the number of - * the transferred bytes. This method is basically same with - * {@link #writeBytes(ChannelBuffer, int, int)}, except that this method - * increases the {@code readerIndex} of the source buffer by the number of - * the transferred bytes while {@link #writeBytes(ChannelBuffer, int, int)} - * does not. - * - * @throws IndexOutOfBoundsException - * if {@code src.readableBytes} is greater than - * {@code this.writableBytes} - */ - void writeBytes(ChannelBuffer src); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the current {@code writerIndex} and increases the {@code writerIndex} - * by the number of the transferred bytes (= {@code length}). This method - * is basically same with {@link #writeBytes(ChannelBuffer, int, int)}, - * except that this method increases the {@code readerIndex} of the source - * buffer by the number of the transferred bytes (= {@code length}) while - * {@link #writeBytes(ChannelBuffer, int, int)} does not. - * - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.writableBytes} or - * if {@code length} is greater then {@code src.readableBytes} - */ - void writeBytes(ChannelBuffer src, int length); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the current {@code writerIndex} and increases the {@code writerIndex} - * by the number of the transferred bytes (= {@code length}). - * - * @param srcIndex the first index of the source - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code srcIndex} is less than {@code 0}, - * if {@code srcIndex + length} is greater than - * {@code src.capacity}, or - * if {@code length} is greater than {@code this.writableBytes} - */ - void writeBytes(ChannelBuffer src, int srcIndex, int length); - - /** - * Transfers the specified source array's data to this buffer starting at - * the current {@code writerIndex} and increases the {@code writerIndex} - * by the number of the transferred bytes (= {@code src.length}). - * - * @throws IndexOutOfBoundsException - * if {@code src.length} is greater than {@code this.writableBytes} - */ - void writeBytes(byte[] src); - - /** - * Transfers the specified source array's data to this buffer starting at - * the current {@code writerIndex} and increases the {@code writerIndex} - * by the number of the transferred bytes (= {@code length}). - * - * @param srcIndex the first index of the source - * @param length the number of bytes to transfer - * - * @throws IndexOutOfBoundsException - * if the specified {@code srcIndex} is less than {@code 0}, - * if {@code srcIndex + length} is greater than - * {@code src.length}, or - * if {@code length} is greater than {@code this.writableBytes} - */ - void writeBytes(byte[] src, int srcIndex, int length); - - /** - * Transfers the specified source buffer's data to this buffer starting at - * the current {@code writerIndex} until the source buffer's position - * reaches its limit, and increases the {@code writerIndex} by the - * number of the transferred bytes. - * - * @throws IndexOutOfBoundsException - * if {@code src.remaining()} is greater than - * {@code this.writableBytes} - */ - void writeBytes(ByteBuffer src); - - /** - * Transfers the content of the specified stream to this buffer - * starting at the current {@code writerIndex} and increases the - * {@code writerIndex} by the number of the transferred bytes. - * - * @param length the number of bytes to transfer - * - * @return the actual number of bytes read in from the specified stream - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.writableBytes} - * @throws IOException - * if the specified stream threw an exception during I/O - */ - int writeBytes(InputStream in, int length) throws IOException; - - /** - * Transfers the content of the specified channel to this buffer - * starting at the current {@code writerIndex} and increases the - * {@code writerIndex} by the number of the transferred bytes. - * - * @param length the maximum number of bytes to transfer - * - * @return the actual number of bytes read in from the specified channel - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.writableBytes} - * @throws IOException - * if the specified channel threw an exception during I/O - */ - int writeBytes(ScatteringByteChannel in, int length) throws IOException; - - /** - * Fills this buffer with NUL (0x00) starting at the current - * {@code writerIndex} and increases the {@code writerIndex} by the - * specified {@code length}. - * - * @param length the number of NULs to write to the buffer - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.writableBytes} - */ - void writeZero(int length); - - /** - * Locates the first occurrence of the specified {@code value} in this - * buffer. The search takes place from the specified {@code fromIndex} - * (inclusive) to the specified {@code toIndex} (exclusive). - *

- * If {@code fromIndex} is greater than {@code toIndex}, the search is - * performed in a reversed order. - *

- * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @return the absolute index of the first occurrence if found. - * {@code -1} otherwise. - */ - int indexOf(int fromIndex, int toIndex, byte value); - -// /** -// * Locates the first place where the specified {@code indexFinder} -// * returns {@code true}. The search takes place from the specified -// * {@code fromIndex} (inclusive) to the specified {@code toIndex} -// * (exclusive). -// *

-// * If {@code fromIndex} is greater than {@code toIndex}, the search is -// * performed in a reversed order. -// *

-// * This method does not modify {@code readerIndex} or {@code writerIndex} of -// * this buffer. -// * -// * @return the absolute index where the specified {@code indexFinder} -// * returned {@code true}. {@code -1} if the {@code indexFinder} -// * did not return {@code true} at all. -// */ -// int indexOf(int fromIndex, int toIndex, ChannelBufferIndexFinder indexFinder); - - /** - * Locates the first occurrence of the specified {@code value} in this - * buffer. The search takes place from the current {@code readerIndex} - * (inclusive) to the current {@code writerIndex} (exclusive). - *

- * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @return the number of bytes between the current {@code readerIndex} - * and the first occurrence if found. {@code -1} otherwise. - */ - int bytesBefore(byte value); - -// /** -// * Locates the first place where the specified {@code indexFinder} returns -// * {@code true}. The search takes place from the current {@code readerIndex} -// * (inclusive) to the current {@code writerIndex}. -// *

-// * This method does not modify {@code readerIndex} or {@code writerIndex} of -// * this buffer. -// * -// * @return the number of bytes between the current {@code readerIndex} -// * and the first place where the {@code indexFinder} returned -// * {@code true}. {@code -1} if the {@code indexFinder} did not -// * return {@code true} at all. -// */ -// int bytesBefore(ChannelBufferIndexFinder indexFinder); - - /** - * Locates the first occurrence of the specified {@code value} in this - * buffer. The search starts from the current {@code readerIndex} - * (inclusive) and lasts for the specified {@code length}. - *

- * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @return the number of bytes between the current {@code readerIndex} - * and the first occurrence if found. {@code -1} otherwise. - * - * @throws IndexOutOfBoundsException - * if {@code length} is greater than {@code this.readableBytes} - */ - int bytesBefore(int length, byte value); - -// /** -// * Locates the first place where the specified {@code indexFinder} returns -// * {@code true}. The search starts the current {@code readerIndex} -// * (inclusive) and lasts for the specified {@code length}. -// *

-// * This method does not modify {@code readerIndex} or {@code writerIndex} of -// * this buffer. -// * -// * @return the number of bytes between the current {@code readerIndex} -// * and the first place where the {@code indexFinder} returned -// * {@code true}. {@code -1} if the {@code indexFinder} did not -// * return {@code true} at all. -// * -// * @throws IndexOutOfBoundsException -// * if {@code length} is greater than {@code this.readableBytes} -// */ -// int bytesBefore(int length, ChannelBufferIndexFinder indexFinder); - - /** - * Locates the first occurrence of the specified {@code value} in this - * buffer. The search starts from the specified {@code index} (inclusive) - * and lasts for the specified {@code length}. - *

- * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @return the number of bytes between the specified {@code index} - * and the first occurrence if found. {@code -1} otherwise. - * - * @throws IndexOutOfBoundsException - * if {@code index + length} is greater than {@code this.capacity} - */ - int bytesBefore(int index, int length, byte value); - -// /** -// * Locates the first place where the specified {@code indexFinder} returns -// * {@code true}. The search starts the specified {@code index} (inclusive) -// * and lasts for the specified {@code length}. -// *

-// * This method does not modify {@code readerIndex} or {@code writerIndex} of -// * this buffer. -// * -// * @return the number of bytes between the specified {@code index} -// * and the first place where the {@code indexFinder} returned -// * {@code true}. {@code -1} if the {@code indexFinder} did not -// * return {@code true} at all. -// * -// * @throws IndexOutOfBoundsException -// * if {@code index + length} is greater than {@code this.capacity} -// */ -// int bytesBefore(int index, int length, ChannelBufferIndexFinder indexFinder); - - /** - * Returns a copy of this buffer's readable bytes. Modifying the content - * of the returned buffer or this buffer does not affect each other at all. - * This method is identical to {@code buf.copy(buf.readerIndex(), buf.readableBytes())}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ChannelBuffer copy(); - - /** - * Returns a copy of this buffer's sub-region. Modifying the content of - * the returned buffer or this buffer does not affect each other at all. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ChannelBuffer copy(int index, int length); - - /** - * Returns a slice of this buffer's readable bytes. Modifying the content - * of the returned buffer or this buffer affects each other's content - * while they maintain separate indexes and marks. This method is - * identical to {@code buf.slice(buf.readerIndex(), buf.readableBytes())}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ChannelBuffer slice(); - - /** - * Returns a slice of this buffer's sub-region. Modifying the content of - * the returned buffer or this buffer affects each other's content while - * they maintain separate indexes and marks. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ChannelBuffer slice(int index, int length); - - /** - * Returns a buffer which shares the whole region of this buffer. - * Modifying the content of the returned buffer or this buffer affects - * each other's content while they maintain separate indexes and marks. - * This method is identical to {@code buf.slice(0, buf.capacity())}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ChannelBuffer duplicate(); - - /** - * Converts this buffer's readable bytes into a NIO buffer. The returned - * buffer might or might not share the content with this buffer, while - * they have separate indexes and marks. This method is identical to - * {@code buf.toByteBuffer(buf.readerIndex(), buf.readableBytes())}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ByteBuffer toByteBuffer(); - - /** - * Converts this buffer's sub-region into a NIO buffer. The returned - * buffer might or might not share the content with this buffer, while - * they have separate indexes and marks. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ByteBuffer toByteBuffer(int index, int length); - - /** - * Converts this buffer's readable bytes into an array of NIO buffers. - * The returned buffers might or might not share the content with this - * buffer, while they have separate indexes and marks. This method is - * identical to {@code buf.toByteBuffers(buf.readerIndex(), buf.readableBytes())}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ByteBuffer[] toByteBuffers(); - - /** - * Converts this buffer's sub-region into an array of NIO buffers. - * The returned buffers might or might not share the content with this - * buffer, while they have separate indexes and marks. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - */ - ByteBuffer[] toByteBuffers(int index, int length); - - /** - * Returns {@code true} if and only if this buffer has a backing byte array. - * If this method returns true, you can safely call {@link #array()} and - * {@link #arrayOffset()}. - */ - boolean hasArray(); - - /** - * Returns the backing byte array of this buffer. - * - * @throws UnsupportedOperationException - * if there no accessible backing byte array - */ - byte[] array(); - - /** - * Returns the offset of the first byte within the backing byte array of - * this buffer. - * - * @throws UnsupportedOperationException - * if there no accessible backing byte array - */ - int arrayOffset(); - - /** - * Decodes this buffer's readable bytes into a string with the specified - * character set name. This method is identical to - * {@code buf.toString(buf.readerIndex(), buf.readableBytes(), charsetName)}. - * This method does not modify {@code readerIndex} or {@code writerIndex} of - * this buffer. - * - * @throws UnsupportedCharsetException - * if the specified character set name is not supported by the - * current VM - */ - String toString(Charset charset); - - /** - * Decodes this buffer's sub-region into a string with the specified - * character set. This method does not modify {@code readerIndex} or - * {@code writerIndex} of this buffer. - */ - String toString(int index, int length, Charset charset); - - /** - * @deprecated Use {@link #toString(Charset)} instead. - */ - @Deprecated - String toString(String charsetName); - -// @Deprecated -// String toString( -// String charsetName, ChannelBufferIndexFinder terminatorFinder); - - @Deprecated - String toString(int index, int length, String charsetName); - -// /** -// * @deprecated Use {@link #bytesBefore(int, int, ChannelBufferIndexFinder)} and -// * {@link #toString(int, int, Charset)} instead. -// */ -// @Deprecated -// String toString( -// int index, int length, String charsetName, -// ChannelBufferIndexFinder terminatorFinder); - - /** - * Returns a hash code which was calculated from the content of this - * buffer. If there's a byte array which is - * {@linkplain #equals(Object) equal to} this array, both arrays should - * return the same value. - */ - int hashCode(); - - /** - * Determines if the content of the specified buffer is identical to the - * content of this array. 'Identical' here means: - *

- * Please note that it does not compare {@link #readerIndex()} nor - * {@link #writerIndex()}. This method also returns {@code false} for - * {@code null} and an object which is not an instance of - * {@link ChannelBuffer} type. - */ - boolean equals(Object obj); - - /** - * Compares the content of the specified buffer to the content of this - * buffer. Comparison is performed in the same manner with the string - * comparison functions of various languages such as {@code strcmp}, - * {@code memcmp} and {@link String#compareTo(String)}. - */ - int compareTo(ChannelBuffer buffer); - - /** - * Returns the string representation of this buffer. This method does not - * necessarily return the whole content of the buffer but returns - * the values of the key properties such as {@link #readerIndex()}, - * {@link #writerIndex()} and {@link #capacity()}. - */ - String toString(); -} diff --git a/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java b/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java deleted file mode 100644 index fa53b98db6e..00000000000 --- a/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java +++ /dev/null @@ -1,104 +0,0 @@ -/* - * Copyright 2012 The Netty Project - * - * The Netty Project licenses this file to you under the Apache License, - * version 2.0 (the "License"); you may not use this file except in compliance - * with the License. You may obtain a copy of the License at: - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the - * License for the specific language governing permissions and limitations - * under the License. - */ -package org.jboss.netty.buffer; - -import java.nio.ByteBuffer; -import java.nio.ByteOrder; - -/** - * A factory that creates or pools {@link ChannelBuffer}s. - */ -public interface ChannelBufferFactory { - - /** - * Returns a {@link ChannelBuffer} with the specified {@code capacity}. - * This method is identical to {@code getBuffer(getDefaultOrder(), capacity)}. - * - * @param capacity the capacity of the returned {@link ChannelBuffer} - * @return a {@link ChannelBuffer} with the specified {@code capacity}, - * whose {@code readerIndex} and {@code writerIndex} are {@code 0} - */ - ChannelBuffer getBuffer(int capacity); - - /** - * Returns a {@link ChannelBuffer} with the specified {@code endianness} - * and {@code capacity}. - * - * @param endianness the endianness of the returned {@link ChannelBuffer} - * @param capacity the capacity of the returned {@link ChannelBuffer} - * @return a {@link ChannelBuffer} with the specified {@code endianness} and - * {@code capacity}, whose {@code readerIndex} and {@code writerIndex} - * are {@code 0} - */ - ChannelBuffer getBuffer(ByteOrder endianness, int capacity); - - /** - * Returns a {@link ChannelBuffer} whose content is equal to the sub-region - * of the specified {@code array}. Depending on the factory implementation, - * the returned buffer could wrap the {@code array} or create a new copy of - * the {@code array}. - * This method is identical to {@code getBuffer(getDefaultOrder(), array, offset, length)}. - * - * @param array the byte array - * @param offset the offset of the byte array - * @param length the length of the byte array - * - * @return a {@link ChannelBuffer} with the specified content, - * whose {@code readerIndex} and {@code writerIndex} - * are {@code 0} and {@code (length - offset)} respectively - */ - ChannelBuffer getBuffer(byte[] array, int offset, int length); - - /** - * Returns a {@link ChannelBuffer} whose content is equal to the sub-region - * of the specified {@code array}. Depending on the factory implementation, - * the returned buffer could wrap the {@code array} or create a new copy of - * the {@code array}. - * - * @param endianness the endianness of the returned {@link ChannelBuffer} - * @param array the byte array - * @param offset the offset of the byte array - * @param length the length of the byte array - * - * @return a {@link ChannelBuffer} with the specified content, - * whose {@code readerIndex} and {@code writerIndex} - * are {@code 0} and {@code (length - offset)} respectively - */ - ChannelBuffer getBuffer(ByteOrder endianness, byte[] array, int offset, int length); - - /** - * Returns a {@link ChannelBuffer} whose content is equal to the sub-region - * of the specified {@code nioBuffer}. Depending on the factory - * implementation, the returned buffer could wrap the {@code nioBuffer} or - * create a new copy of the {@code nioBuffer}. - * - * @param nioBuffer the NIO {@link ByteBuffer} - * - * @return a {@link ChannelBuffer} with the specified content, - * whose {@code readerIndex} and {@code writerIndex} - * are {@code 0} and {@code nioBuffer.remaining()} respectively - */ - ChannelBuffer getBuffer(ByteBuffer nioBuffer); - - /** - * Returns the default endianness of the {@link ChannelBuffer} which is - * returned by {@link #getBuffer(int)}. - * - * @return the default endianness of the {@link ChannelBuffer} which is - * returned by {@link #getBuffer(int)} - */ - ByteOrder getDefaultOrder(); -} diff --git a/ihmc-ros-tools/src/main/java/sensor_msgs/CompressedImage.java b/ihmc-ros-tools/src/main/java/sensor_msgs/CompressedImage.java index 35d2db5bea1..1d48451c336 100644 --- a/ihmc-ros-tools/src/main/java/sensor_msgs/CompressedImage.java +++ b/ihmc-ros-tools/src/main/java/sensor_msgs/CompressedImage.java @@ -1,6 +1,5 @@ package sensor_msgs; -import org.jboss.netty.buffer.ChannelBuffer; import org.ros.internal.message.Message; import std_msgs.Header; @@ -16,7 +15,7 @@ public interface CompressedImage extends Message { void setFormat(String var1); - ChannelBuffer getData(); - - void setData(ChannelBuffer var1); +// ChannelBuffer getData(); +// +// void setData(ChannelBuffer var1); } \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/sensor_msgs/Image.java b/ihmc-ros-tools/src/main/java/sensor_msgs/Image.java index c10d8ed0ab5..6572a45c560 100644 --- a/ihmc-ros-tools/src/main/java/sensor_msgs/Image.java +++ b/ihmc-ros-tools/src/main/java/sensor_msgs/Image.java @@ -1,6 +1,6 @@ package sensor_msgs; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; import org.ros.internal.message.Message; import std_msgs.Header; @@ -32,7 +32,7 @@ public interface Image extends Message { void setStep(int var1); - ChannelBuffer getData(); - - void setData(ChannelBuffer var1); +// ChannelBuffer getData(); +// +// void setData(ChannelBuffer var1); } \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/sensor_msgs/PointCloud2.java b/ihmc-ros-tools/src/main/java/sensor_msgs/PointCloud2.java index 09dccd658dd..387e0f5f753 100644 --- a/ihmc-ros-tools/src/main/java/sensor_msgs/PointCloud2.java +++ b/ihmc-ros-tools/src/main/java/sensor_msgs/PointCloud2.java @@ -6,7 +6,7 @@ package sensor_msgs; import java.util.List; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; import org.ros.internal.message.Message; import std_msgs.Header; @@ -42,9 +42,9 @@ public interface PointCloud2 extends Message { void setRowStep(int var1); - ChannelBuffer getData(); - - void setData(ChannelBuffer var1); +// ChannelBuffer getData(); +// +// void setData(ChannelBuffer var1); boolean getIsDense(); diff --git a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/RosTools.java b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/RosTools.java index 95e228f5859..f982e23e3d3 100644 --- a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/RosTools.java +++ b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/RosTools.java @@ -20,7 +20,7 @@ import javax.imageio.ImageIO; import boofcv.struct.calib.CameraPinholeBrown; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; import org.ros.node.NodeConfiguration; import geometry_msgs.Point; @@ -111,13 +111,13 @@ public static BufferedImage bufferedImageFromRosMessageRaw(ColorModel colorModel int width = imageMessage.getWidth(); int height = imageMessage.getHeight(); - byte[] payload = imageMessage.getData().array(); +// byte[] payload = imageMessage.getData().array(); BufferedImage ret = new BufferedImage(width, height, BufferedImage.TYPE_3BYTE_BGR); - DataBuffer dataBuffer = new DataBufferByte(payload, payload.length, imageMessage.getData().arrayOffset()); - SampleModel sampleModel = colorModel.createCompatibleSampleModel(width, height); - - WritableRaster raster = Raster.createWritableRaster(sampleModel, dataBuffer, null); - ret.setData(raster); +// DataBuffer dataBuffer = new DataBufferByte(payload, payload.length, imageMessage.getData().arrayOffset()); +// SampleModel sampleModel = colorModel.createCompatibleSampleModel(width, height); +// +// WritableRaster raster = Raster.createWritableRaster(sampleModel, dataBuffer, null); +// ret.setData(raster); return ret; } @@ -131,16 +131,16 @@ public static BufferedImage bufferedImageFromRosMessageJpeg(sensor_msgs.Compress { BufferedImage ret = null; - byte[] payload = imageMessage.getData().array(); - try - { - int offset = imageMessage.getData().arrayOffset(); - ret = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); - } - catch (IOException e) - { - e.printStackTrace(); - } +// byte[] payload = imageMessage.getData().array(); +// try +// { +// int offset = imageMessage.getData().arrayOffset(); +// ret = ImageIO.read(new ByteArrayInputStream(payload, offset, payload.length - offset)); +// } +// catch (IOException e) +// { +// e.printStackTrace(); +// } return ret; } @@ -148,13 +148,13 @@ public static BufferedImage bufferedImageFromRosMessageJpeg(sensor_msgs.Compress /** * Returns a ByteBuffer that starts with the data part. */ - public static ByteBuffer sliceNettyBuffer(ChannelBuffer channelBuffer) - { - ByteBuffer originalByteBuffer = channelBuffer.toByteBuffer(); - int arrayOffset = channelBuffer.arrayOffset(); - originalByteBuffer.position(arrayOffset); - return originalByteBuffer.slice(); - } +// public static ByteBuffer sliceNettyBuffer(ChannelBuffer channelBuffer) +// { +// ByteBuffer originalByteBuffer = channelBuffer.toByteBuffer(); +// int arrayOffset = channelBuffer.arrayOffset(); +// originalByteBuffer.position(arrayOffset); +// return originalByteBuffer.slice(); +// } public static CameraPinholeBrown cameraIntrisicsFromCameraInfo(CameraInfo cameraInfo) { @@ -254,21 +254,21 @@ public static InetAddress getMyIP(String rosMasterURI) } } - public static ByteBuffer wrapPointCloud2Array(PointCloud2 pointCloud2) - { - int numberOfPoints = pointCloud2.getWidth() * pointCloud2.getHeight(); - int offset = pointCloud2.getData().arrayOffset(); - int pointStep = pointCloud2.getPointStep(); - - ByteBuffer byteBuffer = ByteBuffer.wrap(pointCloud2.getData().array(), offset, numberOfPoints * pointStep); - - if (pointCloud2.getIsBigendian()) - byteBuffer.order(ByteOrder.BIG_ENDIAN); - else - byteBuffer.order(ByteOrder.LITTLE_ENDIAN); - - return byteBuffer; - } +// public static ByteBuffer wrapPointCloud2Array(PointCloud2 pointCloud2) +// { +//// int numberOfPoints = pointCloud2.getWidth() * pointCloud2.getHeight(); +//// int offset = pointCloud2.getData().arrayOffset(); +//// int pointStep = pointCloud2.getPointStep(); +//// +//// ByteBuffer byteBuffer = ByteBuffer.wrap(pointCloud2.getData().array(), offset, numberOfPoints * pointStep); +//// +//// if (pointCloud2.getIsBigendian()) +//// byteBuffer.order(ByteOrder.BIG_ENDIAN); +//// else +//// byteBuffer.order(ByteOrder.LITTLE_ENDIAN); +// +// return byteBuffer; +// } public static void printPointCloud2Info(String name, PointCloud2 pointCloud2) { diff --git a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosImagePublisher.java b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosImagePublisher.java index 1f7103ded4a..8d510254942 100644 --- a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosImagePublisher.java +++ b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosImagePublisher.java @@ -4,8 +4,7 @@ //import java.awt.image.DataBufferByte; //import java.nio.ByteOrder; -import org.jboss.netty.buffer.ChannelBuffer; -import org.jboss.netty.buffer.ChannelBufferFactory; +//import org.jboss.netty.buffer.ChannelBuffer; //import org.jboss.netty.buffer.HeapChannelBufferFactory; import org.ros.message.Time; @@ -60,22 +59,22 @@ public void publish(String frameID, BufferedImage img, Time t) // publish(message); } - public Image createMessage(int width, int height, int bytesPerValue, String encoding, ChannelBuffer channelBuffer) - { - Image message = getMessage(); - Header header = message.getHeader(); - - header.setSeq(seq++); - - message.setIsBigendian((byte) 0); - message.setStep(width * bytesPerValue); - message.setHeight(height); - message.setWidth(width); - message.setEncoding(encoding); - - message.setData(channelBuffer); - return message; - } +// public Image createMessage(int width, int height, int bytesPerValue, String encoding, ChannelBuffer channelBuffer) +// { +// Image message = getMessage(); +// Header header = message.getHeader(); +// +// header.setSeq(seq++); +// +// message.setIsBigendian((byte) 0); +// message.setStep(width * bytesPerValue); +// message.setHeight(height); +// message.setWidth(width); +// message.setEncoding(encoding); +// +// message.setData(channelBuffer); +// return message; +// } public void publish(Image message) { @@ -108,9 +107,4 @@ public static int floatTo16BitInt(float fval) + (0x800000 >>> val - 102) // round depending on cut off >>> 126 - val); // div by 2^(1-(exp-127+15)) and >> 13 | exp=0 } - - public ChannelBufferFactory getChannelBufferFactory() - { - return null; - } } diff --git a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosPointCloudPublisher.java b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosPointCloudPublisher.java index 92781dbaed1..dbe159c3a01 100644 --- a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosPointCloudPublisher.java +++ b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosPointCloudPublisher.java @@ -1,6 +1,6 @@ package us.ihmc.utilities.ros.publisher; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; //import org.jboss.netty.buffer.LittleEndianHeapChannelBuffer; import org.ros.message.Time; diff --git a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/subscriber/RosPointCloudSubscriber.java b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/subscriber/RosPointCloudSubscriber.java index 5adcf8de378..e26b3df6596 100644 --- a/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/subscriber/RosPointCloudSubscriber.java +++ b/ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/subscriber/RosPointCloudSubscriber.java @@ -142,43 +142,43 @@ public static UnpackedPointCloud unpackPointsAndIntensities(PointCloud2 pointClo break; } - int offset = pointCloud.getData().arrayOffset(); - int pointStep = pointCloud.getPointStep(); - - ByteBuffer byteBuffer = ByteBuffer.wrap(pointCloud.getData().array(), offset, numberOfPoints * pointStep); - - if (pointCloud.getIsBigendian()) - byteBuffer.order(ByteOrder.BIG_ENDIAN); - else - byteBuffer.order(ByteOrder.LITTLE_ENDIAN); - - for (int i = 0; i < numberOfPoints; i++) - { - byteBuffer.position(i * pointStep + offset); - float x = byteBuffer.getFloat(); - float y = byteBuffer.getFloat(); - float z = byteBuffer.getFloat(); - - packet.points[i] = new Point3D(x, y, z); - - switch (packet.pointType) - { - case XYZI: - packet.intensities[i] = byteBuffer.getFloat(); - break; - - case XYZRGB: - int b = byteToUnsignedInt(byteBuffer.get()); - int g = byteToUnsignedInt(byteBuffer.get()); - int r = byteToUnsignedInt(byteBuffer.get()); - int a = byteToUnsignedInt(byteBuffer.get()); - packet.pointColors[i] = toRGB(r, g, b); - break; - - case XYZ: - break; - } - } +// int offset = pointCloud.getData().arrayOffset(); +// int pointStep = pointCloud.getPointStep(); +// +// ByteBuffer byteBuffer = ByteBuffer.wrap(pointCloud.getData().array(), offset, numberOfPoints * pointStep); +// +// if (pointCloud.getIsBigendian()) +// byteBuffer.order(ByteOrder.BIG_ENDIAN); +// else +// byteBuffer.order(ByteOrder.LITTLE_ENDIAN); + +// for (int i = 0; i < numberOfPoints; i++) +// { +// byteBuffer.position(i * pointStep + offset); +// float x = byteBuffer.getFloat(); +// float y = byteBuffer.getFloat(); +// float z = byteBuffer.getFloat(); +// +// packet.points[i] = new Point3D(x, y, z); +// +// switch (packet.pointType) +// { +// case XYZI: +// packet.intensities[i] = byteBuffer.getFloat(); +// break; +// +// case XYZRGB: +// int b = byteToUnsignedInt(byteBuffer.get()); +// int g = byteToUnsignedInt(byteBuffer.get()); +// int r = byteToUnsignedInt(byteBuffer.get()); +// int a = byteToUnsignedInt(byteBuffer.get()); +// packet.pointColors[i] = toRGB(r, g, b); +// break; +// +// case XYZ: +// break; +// } +// } return packet; } diff --git a/robot-environment-awareness/src/application/java/us/ihmc/robotEnvironmentAwareness/hardware/MultisenseImageROS1Bridge.java b/robot-environment-awareness/src/application/java/us/ihmc/robotEnvironmentAwareness/hardware/MultisenseImageROS1Bridge.java index f9b7c55824f..4c3e33872c7 100644 --- a/robot-environment-awareness/src/application/java/us/ihmc/robotEnvironmentAwareness/hardware/MultisenseImageROS1Bridge.java +++ b/robot-environment-awareness/src/application/java/us/ihmc/robotEnvironmentAwareness/hardware/MultisenseImageROS1Bridge.java @@ -10,7 +10,7 @@ import javax.imageio.ImageIO; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; import perception_msgs.msg.dds.Image32; import sensor_msgs.CameraInfo; @@ -94,25 +94,25 @@ public void onNewMessage(Image image) message.setHeight(height); message.setWidth(width); - ChannelBuffer data = image.getData(); - byte[] array = data.array(); - int dataIndex = data.arrayOffset(); - for (int i = 0; i < height; i++) - { - for (int j = 0; j < width; j++) - { - int b = array[dataIndex]; - dataIndex++; - int g = array[dataIndex]; - dataIndex++; - int r = array[dataIndex]; - dataIndex++; - - int rgbColor = convertBGR2RGB(b, g, r); - message.getRgbdata().add(rgbColor); - bufferedImage.setRGB(j, i, rgbColor); - } - } +// ChannelBuffer data = image.getData(); +// byte[] array = data.array(); +// int dataIndex = data.arrayOffset(); +// for (int i = 0; i < height; i++) +// { +// for (int j = 0; j < width; j++) +// { +// int b = array[dataIndex]; +// dataIndex++; +// int g = array[dataIndex]; +// dataIndex++; +// int r = array[dataIndex]; +// dataIndex++; +// +// int rgbColor = convertBGR2RGB(b, g, r); +// message.getRgbdata().add(rgbColor); +// bufferedImage.setRGB(j, i, rgbColor); +// } +// } imagePublisher.publish(message); diff --git a/robot-environment-awareness/src/main/java/us/ihmc/robotEnvironmentAwareness/communication/converters/PointCloud2ToLidarScanMessageConverter.java b/robot-environment-awareness/src/main/java/us/ihmc/robotEnvironmentAwareness/communication/converters/PointCloud2ToLidarScanMessageConverter.java index dd752185a01..079c25386c3 100644 --- a/robot-environment-awareness/src/main/java/us/ihmc/robotEnvironmentAwareness/communication/converters/PointCloud2ToLidarScanMessageConverter.java +++ b/robot-environment-awareness/src/main/java/us/ihmc/robotEnvironmentAwareness/communication/converters/PointCloud2ToLidarScanMessageConverter.java @@ -13,7 +13,7 @@ import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.subscriber.RosPointCloudSubscriber; import sensor_msgs.PointCloud2; -import org.jboss.netty.buffer.ChannelBuffer; +//import org.jboss.netty.buffer.ChannelBuffer; import java.net.URI; import java.net.URISyntaxException; @@ -98,14 +98,14 @@ public void onNewMessage(sensor_msgs.PointCloud2 pointCloud) for (int i = 0; i < numberOfPoints; i++) { int startIndex = (int) pointStep * i; - packBytes(bytes, startIndex + 0, pointCloud.getData()); - float x = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); - packBytes(bytes, startIndex + 4, pointCloud.getData()); - float y = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); - packBytes(bytes, startIndex + 8, pointCloud.getData()); - float z = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); - - Pose3D dataPoint = new Pose3D(x, y, z, 0.0, 0.0, 0.0); +// packBytes(bytes, startIndex + 0, pointCloud.getData()); +// float x = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); +// packBytes(bytes, startIndex + 4, pointCloud.getData()); +// float y = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); +// packBytes(bytes, startIndex + 8, pointCloud.getData()); +// float z = ByteBuffer.wrap(bytes).order(byteOrder).getFloat(); + + Pose3D dataPoint = null; dataPoint.applyTransform(transform); points[3 * i + 0] = (float) dataPoint.getX(); @@ -128,13 +128,13 @@ public void onNewMessage(sensor_msgs.PointCloud2 pointCloud) pointCloudSubscriber.wailTillRegistered(); } - private static void packBytes(byte[] bytes, int startIndex, ChannelBuffer data) - { - for (int i = 0; i < 4; i++) - { - bytes[i] = data.getByte(startIndex + i); - } - } +// private static void packBytes(byte[] bytes, int startIndex, ChannelBuffer data) +// { +// for (int i = 0; i < 4; i++) +// { +// bytes[i] = data.getByte(startIndex + i); +// } +// } public static void main(String[] args) {