From f488ad7c38b08cdf4f76ac10790067858ebfbd65 Mon Sep 17 00:00:00 2001 From: Duncan Calvert Date: Wed, 21 Aug 2024 14:33:22 -0500 Subject: [PATCH] Disable ROS 1 support, removing all transitive dependencies but keeping old code compiling. --- .../sandia/SandiaHandManualControlUI.java | 6 +- .../AtlasHeightMapTopicConverter.java | 20 +- .../ros/ROSiRobotCommandDispatcher.java | 55 - .../avatar/ros/ROSiRobotCommunicator.java | 93 - .../ihmc/avatar/ros/RosCameraBenchmarker.java | 85 - .../RosArmJointTrajectorySubscriber.java | 107 -- .../multisense/MultiSenseParamaterSetter.java | 56 +- .../ros1/camera/ROSHeadTransformFrame.java | 17 +- ihmc-ros-tools/build.gradle.kts | 42 +- .../CorrectPoseRequest.java | 8 - .../GetBoundedMapResponse.java | 8 - .../MatchCloudsRequest.java | 10 - .../grid_map_msg/GetGridMap.java | 6 - .../grid_map_msg/GetGridMapRequest.java | 16 - .../grid_map_msg/GetGridMapResponse.java | 8 - .../generated-java/grid_map_msg/GridMap.java | 16 - .../grid_map_msg/GridMapInfo.java | 18 - .../handle_msgs/CableTension.java | 10 - .../generated-java/handle_msgs/Collision.java | 18 - .../generated-java/handle_msgs/Finger.java | 10 - .../handle_msgs/HandleCollisions.java | 10 - .../handle_msgs/HandleSensors.java | 44 - .../handle_msgs/HandleSensorsCalibrated.java | 18 - .../RelativeJointCommands.java | 4 +- .../dynamic_reconfigure/BoolParameter.java | 16 + .../main/java/dynamic_reconfigure/Config.java | 29 + .../dynamic_reconfigure/DoubleParameter.java | 16 + .../java/dynamic_reconfigure/GroupState.java | 24 + .../java/dynamic_reconfigure/Reconfigure.java | 8 + .../ReconfigureRequest.java | 12 + .../ReconfigureResponse.java | 12 + .../dynamic_reconfigure/StrParameter.java | 16 + .../src/main/java/geometry_msgs/Point.java | 20 + .../src/main/java/geometry_msgs/Point32.java | 20 + .../src/main/java/geometry_msgs/Pose.java | 16 + .../main/java/geometry_msgs/PoseStamped.java | 17 + .../geometry_msgs/PoseWithCovariance.java | 16 + .../PoseWithCovarianceStamped.java | 17 + .../main/java/geometry_msgs/Quaternion.java | 24 + .../main/java/geometry_msgs/Transform.java | 21 + .../java/geometry_msgs/TransformStamped.java | 26 + .../src/main/java/geometry_msgs/Twist.java | 16 + .../geometry_msgs/TwistWithCovariance.java | 16 + .../src/main/java/geometry_msgs/Vector3.java | 25 + .../src/main/java/geometry_msgs/Wrench.java | 16 + .../java/geometry_msgs/WrenchStamped.java | 17 + .../handle_msgs/HandleControl.java | 2 +- .../main/java/multisense_ros/StampedPps.java | 17 + .../src/main/java/nav_msgs/Odometry.java | 27 + .../org/jboss/netty/buffer/ChannelBuffer.java | 1515 +++++++++++++++++ .../netty/buffer/ChannelBufferFactory.java | 104 ++ .../org/ros/exception/RemoteException.java | 21 + .../ros/exception/RosRuntimeException.java | 15 + .../org/ros/exception/ServiceException.java | 15 + .../org/ros/internal/message/Message.java | 6 + .../org/ros/internal/message/RawMessage.java | 145 ++ .../main/java/org/ros/message/Duration.java | 145 ++ .../java/org/ros/message/MessageFactory.java | 5 + .../java/org/ros/message/MessageListener.java | 5 + .../src/main/java/org/ros/message/Time.java | 114 ++ .../java/org/ros/namespace/GraphName.java | 161 ++ .../java/org/ros/node/AbstractNodeMain.java | 18 + .../main/java/org/ros/node/ConnectedNode.java | 42 + .../src/main/java/org/ros/node/Node.java | 39 + .../java/org/ros/node/NodeConfiguration.java | 293 ++++ .../main/java/org/ros/node/NodeListener.java | 11 + .../src/main/java/org/ros/node/NodeMain.java | 7 + .../java/org/ros/node/NodeMainExecutor.java | 16 + .../ros/node/parameter/ParameterListener.java | 5 + .../org/ros/node/parameter/ParameterTree.java | 103 ++ .../org/ros/node/service/ServiceClient.java | 18 + .../node/service/ServiceResponseBuilder.java | 7 + .../node/service/ServiceResponseListener.java | 9 + .../org/ros/node/service/ServiceServer.java | 14 + .../node/service/ServiceServerListener.java | 7 + .../java/org/ros/node/topic/Publisher.java | 24 + .../org/ros/node/topic/PublisherListener.java | 4 + .../java/org/ros/node/topic/Subscriber.java | 20 + .../ros/node/topic/SubscriberListener.java | 4 + .../main/java/org/ros/time/TimeProvider.java | 7 + .../src/main/java/people_msgs/Person.java | 34 + .../src/main/java/rosgraph_msgs/Clock.java | 13 + .../src/main/java/sensor_msgs/CameraInfo.java | 53 + .../java/sensor_msgs/CompressedImage.java | 22 + .../src/main/java/sensor_msgs/Image.java | 38 + .../src/main/java/sensor_msgs/Imu.java | 39 + .../src/main/java/sensor_msgs/JointState.java | 30 + .../src/main/java/sensor_msgs/LaserScan.java | 49 + .../main/java/sensor_msgs/PointCloud2.java | 52 + .../src/main/java/sensor_msgs/PointField.java | 37 + .../java/sensor_msgs/RegionOfInterest.java | 28 + .../src/main/java/std_msgs/Bool.java | 12 + .../src/main/java/std_msgs/Empty.java | 8 + .../src/main/java/std_msgs/Float64.java | 12 + .../src/main/java/std_msgs/Header.java | 26 + .../src/main/java/std_msgs/Int32.java | 12 + .../src/main/java/std_msgs/Int64.java | 12 + .../src/main/java/std_msgs/String.java | 17 + .../src/main/java/std_msgs/Time.java | 12 + .../src/main/java/std_srvs/Empty.java | 8 + .../src/main/java/std_srvs/EmptyRequest.java | 8 + .../src/main/java/std_srvs/EmptyResponse.java | 8 + .../src/main/java/tf/tfMessage.java | 14 + .../src/main/java/tf2_msgs/TFMessage.java | 14 + .../us/ihmc/utilities/ros/ROS1Helper.java | 107 +- .../utilities/ros/RosDynamicReconfigure.java | 283 +-- .../us/ihmc/utilities/ros/RosMainNode.java | 291 ++-- .../ihmc/utilities/ros/RosServiceClient.java | 48 +- .../ihmc/utilities/ros/RosServiceServer.java | 56 +- .../us/ihmc/utilities/ros/RosTopicList.java | 14 +- .../apps/RosPointCloudFilterRepublisher.java | 2 +- .../MessageAndServiceInterfaceGenerator.java | 6 +- .../bootstrap/SpoofROSDirectoryCreator.java | 20 +- .../ros/publisher/PrintStreamToRosBridge.java | 58 - .../ros/publisher/RosCameraInfoPublisher.java | 2 +- .../publisher/RosEmptyMessagePublisher.java | 19 - .../ros/publisher/RosImagePublisher.java | 66 +- .../ros/publisher/RosImuPublisher.java | 10 +- .../ros/publisher/RosJointStatePublisher.java | 2 +- .../ros/publisher/RosLidarPublisher.java | 68 +- .../ros/publisher/RosLogPublisher.java | 30 - .../ros/publisher/RosOdometryPublisher.java | 2 +- .../ros/publisher/RosPointCloudPublisher.java | 82 +- .../ros/publisher/RosTf1Publisher.java | 98 +- .../ros/publisher/RosTf2Publisher.java | 78 +- .../ros/publisher/RosTopicPublisher.java | 18 +- .../ros/publisher/RosUInt8Publisher.java | 23 - .../AbstractRosTopicSubscriber.java | 2 +- .../RosFloat32MultiArraySubscriber.java | 17 - .../ros/subscriber/RosImuSubscriber.java | 22 +- .../ihmc/utilities/ros/types/PointType.java | 24 +- .../utilities/ros/AddTwoIntsServiceTest.java | 2 + .../utilities/ros/IHMCRosTestWithRosCore.java | 42 +- 133 files changed, 4644 insertions(+), 1436 deletions(-) delete mode 100644 ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommandDispatcher.java delete mode 100644 ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommunicator.java delete mode 100644 ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/RosCameraBenchmarker.java delete mode 100644 ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/subscriber/RosArmJointTrajectorySubscriber.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/CorrectPoseRequest.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/GetBoundedMapResponse.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/MatchCloudsRequest.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMap.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapRequest.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapResponse.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMap.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMapInfo.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/CableTension.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/Collision.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/Finger.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleCollisions.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensors.java delete mode 100644 ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensorsCalibrated.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/BoolParameter.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/Config.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/DoubleParameter.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/GroupState.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/Reconfigure.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureRequest.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureResponse.java create mode 100644 ihmc-ros-tools/src/main/java/dynamic_reconfigure/StrParameter.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Point.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Point32.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Pose.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/PoseStamped.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovariance.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovarianceStamped.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Quaternion.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Transform.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/TransformStamped.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Twist.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/TwistWithCovariance.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Vector3.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/Wrench.java create mode 100644 ihmc-ros-tools/src/main/java/geometry_msgs/WrenchStamped.java rename ihmc-ros-tools/src/main/{generated-java => java}/handle_msgs/HandleControl.java (99%) create mode 100644 ihmc-ros-tools/src/main/java/multisense_ros/StampedPps.java create mode 100644 ihmc-ros-tools/src/main/java/nav_msgs/Odometry.java create mode 100644 ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java create mode 100644 ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/exception/RemoteException.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/exception/RosRuntimeException.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/exception/ServiceException.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/internal/message/Message.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/internal/message/RawMessage.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/message/Duration.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/message/MessageFactory.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/message/MessageListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/message/Time.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/namespace/GraphName.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/AbstractNodeMain.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/ConnectedNode.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/Node.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/NodeConfiguration.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/NodeListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/NodeMain.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/NodeMainExecutor.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/parameter/ParameterListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/parameter/ParameterTree.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/service/ServiceClient.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/service/ServiceResponseBuilder.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/service/ServiceResponseListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/service/ServiceServer.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/service/ServiceServerListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/topic/Publisher.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/topic/PublisherListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/topic/Subscriber.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/node/topic/SubscriberListener.java create mode 100644 ihmc-ros-tools/src/main/java/org/ros/time/TimeProvider.java create mode 100644 ihmc-ros-tools/src/main/java/people_msgs/Person.java create mode 100644 ihmc-ros-tools/src/main/java/rosgraph_msgs/Clock.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/CameraInfo.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/CompressedImage.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/Image.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/Imu.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/JointState.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/LaserScan.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/PointCloud2.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/PointField.java create mode 100644 ihmc-ros-tools/src/main/java/sensor_msgs/RegionOfInterest.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Bool.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Empty.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Float64.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Header.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Int32.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Int64.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/String.java create mode 100644 ihmc-ros-tools/src/main/java/std_msgs/Time.java create mode 100644 ihmc-ros-tools/src/main/java/std_srvs/Empty.java create mode 100644 ihmc-ros-tools/src/main/java/std_srvs/EmptyRequest.java create mode 100644 ihmc-ros-tools/src/main/java/std_srvs/EmptyResponse.java create mode 100644 ihmc-ros-tools/src/main/java/tf/tfMessage.java create mode 100644 ihmc-ros-tools/src/main/java/tf2_msgs/TFMessage.java delete mode 100644 ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/PrintStreamToRosBridge.java delete mode 100644 ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosEmptyMessagePublisher.java delete mode 100644 ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosLogPublisher.java delete mode 100644 ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/publisher/RosUInt8Publisher.java delete mode 100644 ihmc-ros-tools/src/main/java/us/ihmc/utilities/ros/subscriber/RosFloat32MultiArraySubscriber.java diff --git a/atlas/src/main/java/us/ihmc/atlas/handControl/sandia/SandiaHandManualControlUI.java b/atlas/src/main/java/us/ihmc/atlas/handControl/sandia/SandiaHandManualControlUI.java index 91c3c9579b9..fec1c374c67 100644 --- a/atlas/src/main/java/us/ihmc/atlas/handControl/sandia/SandiaHandManualControlUI.java +++ b/atlas/src/main/java/us/ihmc/atlas/handControl/sandia/SandiaHandManualControlUI.java @@ -25,7 +25,7 @@ import org.ros.namespace.GraphName; import org.ros.node.AbstractNodeMain; import org.ros.node.ConnectedNode; -import org.ros.node.DefaultNodeMainExecutor; +//import org.ros.node.DefaultNodeMainExecutor; import org.ros.node.NodeConfiguration; import org.ros.node.NodeMainExecutor; import org.ros.node.topic.Publisher; @@ -393,8 +393,8 @@ public static void main(String[] args) throws URISyntaxException master = new URI(MASTER_URI); NodeConfiguration nodeConfiguration = RosTools.createNodeConfiguration(master); - NodeMainExecutor nodeMainExecutor = DefaultNodeMainExecutor.newDefault(); - nodeMainExecutor.execute(new SandiaHandManualControlUI(), nodeConfiguration); +// NodeMainExecutor nodeMainExecutor = DefaultNodeMainExecutor.newDefault(); +// nodeMainExecutor.execute(new SandiaHandManualControlUI(), nodeConfiguration); } class FingerJointSliderMouseListener implements MouseListener 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 6317a2378ed..db895adadb3 100644 --- a/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java +++ b/atlas/src/main/java/us/ihmc/atlas/jfxvisualizer/AtlasHeightMapTopicConverter.java @@ -4,7 +4,7 @@ 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.jboss.netty.buffer.LittleEndianHeapChannelBuffer; import org.ros.message.Duration; import org.ros.message.Time; import sensor_msgs.PointCloud2; @@ -237,15 +237,15 @@ private static PointCloud2 packMessage(PointCloud2 message, Point3D[] points) message.setIsDense(true); message.setFields(pointType.getPointField()); - ChannelBuffer buffer = new LittleEndianHeapChannelBuffer(dataLength); - for (int i = 0; i < points.length; i++) - { - buffer.writeFloat((float) points[i].getX()); - buffer.writeFloat((float) points[i].getY()); - buffer.writeFloat((float) points[i].getZ()); - buffer.writeFloat(100.0f); - } - message.setData(buffer); +// ChannelBuffer buffer = new LittleEndianHeapChannelBuffer(dataLength); +// for (int i = 0; i < points.length; i++) +// { +// buffer.writeFloat((float) points[i].getX()); +// buffer.writeFloat((float) points[i].getY()); +// buffer.writeFloat((float) points[i].getZ()); +// buffer.writeFloat(100.0f); +// } +// message.setData(buffer); return message; } diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommandDispatcher.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommandDispatcher.java deleted file mode 100644 index d0f88f4b32e..00000000000 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommandDispatcher.java +++ /dev/null @@ -1,55 +0,0 @@ -package us.ihmc.avatar.ros; - -import java.net.URI; -import java.net.URISyntaxException; - -import org.ros.node.DefaultNodeMainExecutor; -import org.ros.node.NodeConfiguration; -import org.ros.node.NodeMainExecutor; - -import controller_msgs.msg.dds.HandDesiredConfigurationMessage; -import us.ihmc.communication.HumanoidControllerAPI; -import us.ihmc.humanoidRobotics.communication.subscribers.HandDesiredConfigurationMessageSubscriber; -import us.ihmc.ros2.RealtimeROS2Node; -import us.ihmc.utilities.ros.RosTools; - -public class ROSiRobotCommandDispatcher implements Runnable -{ - private final HandDesiredConfigurationMessageSubscriber handDesiredConfigurationMessageSubscriber = new HandDesiredConfigurationMessageSubscriber(null); - - private final ROSiRobotCommunicator rosHandCommunicator; - - public ROSiRobotCommandDispatcher(String robotName, RealtimeROS2Node realtimeROS2Node, String rosHostIP) - { - realtimeROS2Node.createSubscription(HumanoidControllerAPI.getInputTopic(robotName).withTypeName(HandDesiredConfigurationMessage.class), - handDesiredConfigurationMessageSubscriber); - - String rosURI = "http://" + rosHostIP + ":11311"; - - rosHandCommunicator = new ROSiRobotCommunicator(rosURI); - - try - { - NodeConfiguration nodeConfiguration = RosTools.createNodeConfiguration(new URI(rosURI)); - NodeMainExecutor nodeMainExecutor = DefaultNodeMainExecutor.newDefault(); - nodeMainExecutor.execute(rosHandCommunicator, nodeConfiguration); - } - catch (URISyntaxException e) - { - e.printStackTrace(); - } - } - - @Override - public void run() - { - while (true) - { - if (handDesiredConfigurationMessageSubscriber.isNewDesiredConfigurationAvailable()) - { - HandDesiredConfigurationMessage ihmcMessage = handDesiredConfigurationMessageSubscriber.pollMessage(); - rosHandCommunicator.sendHandCommand(ihmcMessage); - } - } - } -} diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommunicator.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommunicator.java deleted file mode 100644 index 789b270aa17..00000000000 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/ROSiRobotCommunicator.java +++ /dev/null @@ -1,93 +0,0 @@ -package us.ihmc.avatar.ros; - -import java.net.URI; -import java.net.URISyntaxException; - -import org.ros.namespace.GraphName; -import org.ros.node.AbstractNodeMain; -import org.ros.node.ConnectedNode; -import org.ros.node.topic.Publisher; - -import controller_msgs.msg.dds.HandDesiredConfigurationMessage; -import handle_msgs.HandleControl; -import us.ihmc.robotics.robotSide.RobotSide; -import us.ihmc.robotics.robotSide.SideDependentList; - -public class ROSiRobotCommunicator extends AbstractNodeMain -{ - private static final String MASTER_URI = "http://localhost:11311"; - - private URI master; - - private final SideDependentList> handCommandPublishers = new SideDependentList>(); - private final SideDependentList handControlMessages = new SideDependentList(); - - private Publisher leftHandPublisher, rightHandPublisher; - private handle_msgs.HandleControl leftHandControlMessage, rightHandControlMessage; - - private ConnectedNode connectedNode; - - public ROSiRobotCommunicator() - { - try - { - master = new URI(MASTER_URI); - } - catch (URISyntaxException e) - { - e.printStackTrace(); - } - } - - public ROSiRobotCommunicator(String uri) - { - try - { - master = new URI(uri); - } - catch (URISyntaxException e) - { - e.printStackTrace(); - } - } - - @Override - public GraphName getDefaultNodeName() - { - return GraphName.of("darpaRoboticsChallenge/iRobotROSCommunicator"); - } - - @Override - public void onStart(ConnectedNode connectedNode) - { - this.connectedNode = connectedNode; - - setupPublishers(); - - setupMessages(); - } - - private void setupPublishers() - { - leftHandPublisher = connectedNode.newPublisher("/left_hand/control", handle_msgs.HandleControl._TYPE); - rightHandPublisher = connectedNode.newPublisher("/right_hand/control", handle_msgs.HandleControl._TYPE); - - handCommandPublishers.put(RobotSide.LEFT, leftHandPublisher); - handCommandPublishers.put(RobotSide.RIGHT, rightHandPublisher); - } - - private void setupMessages() - { - leftHandControlMessage = leftHandPublisher.newMessage(); - rightHandControlMessage = rightHandPublisher.newMessage(); - - handControlMessages.put(RobotSide.LEFT, leftHandControlMessage); - handControlMessages.put(RobotSide.RIGHT, rightHandControlMessage); - } - - public void sendHandCommand(HandDesiredConfigurationMessage packet) - { - HandDesiredConfigurationMessageToHandleControlMessageConverter.convertHandDesiredConfigurationMessage(packet, handControlMessages.get(RobotSide.fromByte(packet.getRobotSide()))); - handCommandPublishers.get(RobotSide.fromByte(packet.getRobotSide())).publish(handControlMessages.get(RobotSide.fromByte(packet.getRobotSide()))); - } -} diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/RosCameraBenchmarker.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/RosCameraBenchmarker.java deleted file mode 100644 index 315fb5a4f31..00000000000 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/RosCameraBenchmarker.java +++ /dev/null @@ -1,85 +0,0 @@ -package us.ihmc.avatar.ros; - -import java.net.URI; -import java.net.URISyntaxException; - -import org.ros.message.MessageListener; -import org.ros.namespace.GraphName; -import org.ros.node.AbstractNodeMain; -import org.ros.node.ConnectedNode; -import org.ros.node.DefaultNodeMainExecutor; -import org.ros.node.NodeConfiguration; -import org.ros.node.NodeMainExecutor; -import org.ros.node.topic.Subscriber; - -import us.ihmc.tools.inputDevices.keyboard.linux.RepeatingReleasedEventsFixer; -import us.ihmc.utilities.ros.RosTools; - -public class RosCameraBenchmarker extends AbstractNodeMain -{ - private Subscriber cameraSubscriber; - private String topicName; - - private long initialTime; - private double framesReceived = 0.0; - - public RosCameraBenchmarker(String topicName) - { - new RepeatingReleasedEventsFixer().install(); - - this.topicName = topicName; - } - - public GraphName getDefaultNodeName() { - return GraphName.of("darpaRoboticsChallenge/RosCameraBenchmarker" + topicName); - } - - public void onStart(ConnectedNode connectedNode) - { - setupSubscriber(connectedNode); - - setupCameraSubscriberListener(); - } - - private void setupCameraSubscriberListener() - { - cameraSubscriber.addMessageListener(new MessageListener() - { - public void onNewMessage(sensor_msgs.CompressedImage message) - { - if (framesReceived == 0.0) - initialTime = System.currentTimeMillis(); - else - { - System.out.println("FPS: "+(framesReceived*1000.0)/(System.currentTimeMillis()-initialTime)); - } - ++framesReceived; - } - - }); - } - - private void setupSubscriber(ConnectedNode connectedNode) - { - cameraSubscriber = connectedNode.newSubscriber(topicName, sensor_msgs.CompressedImage._TYPE); - } - - public static void main(String[] args) throws URISyntaxException - { - String MASTER = "http://localhost:11311"; - String TOPIC_NAME = "/camera/image_raw/compressed"; - URI master = new URI(MASTER); - - try - { - RosCameraBenchmarker externalCamera = new RosCameraBenchmarker(TOPIC_NAME); - NodeConfiguration nodeConfiguration = RosTools.createNodeConfiguration(master); - NodeMainExecutor nodeMainExecutor = DefaultNodeMainExecutor.newDefault(); - nodeMainExecutor.execute(externalCamera, nodeConfiguration); - } - catch (Exception e) - { - e.printStackTrace(); - } - } -} diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/subscriber/RosArmJointTrajectorySubscriber.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/subscriber/RosArmJointTrajectorySubscriber.java deleted file mode 100644 index b42c428b3b3..00000000000 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/ros/subscriber/RosArmJointTrajectorySubscriber.java +++ /dev/null @@ -1,107 +0,0 @@ -package us.ihmc.avatar.ros.subscriber; - -import java.util.ArrayList; - -import controller_msgs.msg.dds.ArmTrajectoryMessage; -import controller_msgs.msg.dds.OneDoFJointTrajectoryMessage; -import trajectory_msgs.JointTrajectory; -import us.ihmc.commons.Conversions; -import us.ihmc.communication.packetCommunicator.PacketCommunicator; -import us.ihmc.communication.packets.PacketDestination; -import us.ihmc.humanoidRobotics.communication.packets.HumanoidMessageTools; -import us.ihmc.commons.lists.RecyclingArrayList; -import us.ihmc.robotModels.FullHumanoidRobotModel; -import us.ihmc.robotics.partNames.ArmJointName; -import us.ihmc.robotics.robotSide.RobotSide; -import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; - -public class RosArmJointTrajectorySubscriber extends AbstractRosTopicSubscriber -{ - private final PacketCommunicator packetCommunicator; - private final ArrayList leftArmNames = new ArrayList(); - private final ArrayList rightArmNames = new ArrayList(); - - public RosArmJointTrajectorySubscriber(PacketCommunicator controllerCommunicationBridge, FullHumanoidRobotModel fullRobotModel) - { - super(trajectory_msgs.JointTrajectory._TYPE); - this.packetCommunicator = controllerCommunicationBridge; - - ArmJointName[] armJointNames = fullRobotModel.getRobotSpecificJointNames().getArmJointNames(); - - for (int i = 0; i < armJointNames.length; i++) - { - ArmJointName jointName = armJointNames[i]; - leftArmNames.add(fullRobotModel.getArmJoint(RobotSide.LEFT, jointName).getName()); - rightArmNames.add(fullRobotModel.getArmJoint(RobotSide.RIGHT, jointName).getName()); - } - } - - @Override - public void onNewMessage(JointTrajectory rosMessage) - { - RobotSide robotSide; - if (leftArmNames.equals(rosMessage.getJointNames())) - { - robotSide = RobotSide.LEFT; - } - else if (rightArmNames.equals(rosMessage.getJointNames())) - { - robotSide = RobotSide.RIGHT; - } - else - { - System.out.println(getHelp()); - System.err.println(getHelp()); - return; - } - - int numberOfJoints = rosMessage.getJointNames().size(); - int numberOfWaypoints = rosMessage.getPoints().size(); - - ArmTrajectoryMessage ihmcMessage = HumanoidMessageTools.createArmTrajectoryMessage(robotSide); - RecyclingArrayList jointTrajectoryMessages = ihmcMessage.getJointspaceTrajectory().getJointTrajectoryMessages(); - for (int i = 0; i < numberOfJoints; i++) - jointTrajectoryMessages.add(); - - for (int waypointIndex = 0; waypointIndex < numberOfWaypoints; waypointIndex++) - { - double[] positions = rosMessage.getPoints().get(waypointIndex).getPositions(); - double[] velocities = rosMessage.getPoints().get(waypointIndex).getVelocities(); - - if (positions.length != numberOfJoints || positions.length != velocities.length) - { - String msg = "Number of joints positions or velocities in JointTrajectoryPoint inconsistent with expected number of joints " + numberOfJoints; - System.out.println(msg); - System.err.println(msg); - } - - long nsecs = rosMessage.getPoints().get(waypointIndex).getTimeFromStart().totalNsecs(); - double time = Conversions.nanosecondsToSeconds(nsecs); - - for (int jointIndex = 0; jointIndex < numberOfJoints; jointIndex++) - { - jointTrajectoryMessages.get(jointIndex).getTrajectoryPoints().add().set(HumanoidMessageTools.createTrajectoryPoint1DMessage(time, positions[jointIndex], velocities[jointIndex])); - } - } - - ihmcMessage.setDestination(PacketDestination.CONTROLLER.ordinal()); - packetCommunicator.send(ihmcMessage); - } - - private String getHelp() - { - String helpText = "Expected arm joint names for the left side are:\n"; - for (int i = 0; i < leftArmNames.size(); i++) - { - helpText += leftArmNames.get(i) + " "; - } - helpText += "\nFor a right side trajectory please provide:\n"; - for (int i = 0; i < rightArmNames.size(); i++) - { - helpText += rightArmNames.get(i) + " "; - } - helpText += "\nIt is required to provide the full list of joint angles in the correct order."; - - return helpText; - } -} diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/multisense/MultiSenseParamaterSetter.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/multisense/MultiSenseParamaterSetter.java index ffded923843..1e0358732f7 100644 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/multisense/MultiSenseParamaterSetter.java +++ b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/sensors/multisense/MultiSenseParamaterSetter.java @@ -6,11 +6,11 @@ import java.io.PrintStream; import java.nio.charset.StandardCharsets; -import org.ros.exception.RemoteException; +//import org.ros.exception.RemoteException; import org.ros.node.NodeConfiguration; import org.ros.node.parameter.ParameterListener; import org.ros.node.parameter.ParameterTree; -import org.ros.node.service.ServiceResponseListener; +//import org.ros.node.service.ServiceResponseListener; import perception_msgs.msg.dds.MultisenseParameterPacket; import dynamic_reconfigure.BoolParameter; @@ -321,19 +321,19 @@ public void run() gainParam.setValue(3.2); request.getConfig().getDoubles().add(gainParam); - multiSenseClient.call(request, new ServiceResponseListener() - { - - public void onSuccess(ReconfigureResponse response) - { - System.out.println("Set resolution to " + response.getConfig().getStrs().get(0).getValue()); - } - - public void onFailure(RemoteException e) - { - e.printStackTrace(); - } - }); +// multiSenseClient.call(request, new ServiceResponseListener() +// { +// +// public void onSuccess(ReconfigureResponse response) +// { +// System.out.println("Set resolution to " + response.getConfig().getStrs().get(0).getValue()); +// } +// +// public void onFailure(RemoteException e) +// { +// e.printStackTrace(); +// } +// }); } }; @@ -421,19 +421,19 @@ public void setMultisenseParameters(MultisenseParameterPacket object) @Override public void run() { - multiSenseClient.call(request, new ServiceResponseListener() - { - - public void onSuccess(ReconfigureResponse response) - { - System.out.println("successful" + response.getConfig().getDoubles().get(0).getValue()); - } - - public void onFailure(RemoteException e) - { - e.printStackTrace(); - } - }); +// multiSenseClient.call(request, new ServiceResponseListener() +// { +// +// public void onSuccess(ReconfigureResponse response) +// { +// System.out.println("successful" + response.getConfig().getDoubles().get(0).getValue()); +// } +// +// public void onFailure(RemoteException e) +// { +// e.printStackTrace(); +// } +// }); } }.start(); diff --git a/ihmc-perception/src/main/java/us/ihmc/perception/ros1/camera/ROSHeadTransformFrame.java b/ihmc-perception/src/main/java/us/ihmc/perception/ros1/camera/ROSHeadTransformFrame.java index 4fd390bca8b..816bd7988c9 100644 --- a/ihmc-perception/src/main/java/us/ihmc/perception/ros1/camera/ROSHeadTransformFrame.java +++ b/ihmc-perception/src/main/java/us/ihmc/perception/ros1/camera/ROSHeadTransformFrame.java @@ -1,15 +1,10 @@ package us.ihmc.perception.ros1.camera; -import org.ros.message.Time; - -import geometry_msgs.Transform; import transform_provider.TransformProvider; import transform_provider.TransformProviderRequest; import transform_provider.TransformProviderResponse; import us.ihmc.euclid.referenceFrame.ReferenceFrame; import us.ihmc.euclid.transform.RigidBodyTransform; -import us.ihmc.euclid.tuple3D.Vector3D; -import us.ihmc.euclid.tuple4D.Quaternion; import us.ihmc.sensorProcessing.parameters.AvatarRobotSensorParameters; import us.ihmc.commons.thread.ThreadTools; import us.ihmc.utilities.ros.RosMainNode; @@ -38,19 +33,19 @@ public void run() { ThreadTools.sleep(1); // Don't hog CPU TransformProviderRequest request = client.getMessage(); - request.setTime(new Time(0)); +// request.setTime(new Time(0)); request.setSrc(cameraParameters.getBaseFrameForRosTransform()); request.setDest(cameraParameters.getEndFrameForRosTransform()); response = client.call(request); } - Transform transform = response.getTransform().getTransform(); - Vector3D translation = new Vector3D(transform.getTranslation().getX(), transform.getTranslation().getY(), transform.getTranslation().getZ()); - Quaternion rotation = new Quaternion(transform.getRotation().getX(), transform.getRotation().getY(), transform.getRotation().getZ(), transform.getRotation() - .getW()); +// Transform transform = response.getTransform().getTransform(); +// Vector3D translation = new Vector3D(transform.getTranslation().getX(), transform.getTranslation().getY(), transform.getTranslation().getZ()); +// Quaternion rotation = new Quaternion(transform.getRotation().getX(), transform.getRotation().getY(), transform.getRotation().getZ(), transform.getRotation() +// .getW()); synchronized (headToCameraTransform) { - headToCameraTransform.set(rotation, translation); +// headToCameraTransform.set(rotation, translation); System.out.println("Got head to camera transform"); System.out.println(headToCameraTransform); } diff --git a/ihmc-ros-tools/build.gradle.kts b/ihmc-ros-tools/build.gradle.kts index 81f839188ae..113c38aeaeb 100644 --- a/ihmc-ros-tools/build.gradle.kts +++ b/ihmc-ros-tools/build.gradle.kts @@ -14,28 +14,28 @@ ihmc { } mainDependencies { - api("io.netty:netty:3.5.8.Final") - api("org.apache.commons:com.springsource.org.apache.commons.io:1.4.0") +// api("io.netty:netty:3.5.8.Final") +// api("org.apache.commons:com.springsource.org.apache.commons.io:1.4.0") - api("org.apache.logging.log4j:log4j-1.2-api:2.17.0") // required for rosjava to log stuff - api("org.ros.rosjava_core:rosjava:0.2.1") { - exclude(group = "junit", module = "junit") - exclude(group = "org.ros.rosjava_messages", module = "rosjava_test_msgs") - exclude(group = "org.ros.rosjava_messages", module = "test_rosmaster") - } - api("org.ros.rosjava_bootstrap:message_generation:0.3.3") - api("org.ros.rosjava_messages:std_msgs:0.5.10") - api("org.ros.rosjava_messages:std_srvs:1.11.1") - api("org.ros.rosjava_messages:people_msgs:1.0.4") - api("org.ros.rosjava_messages:sensor_msgs:1.11.7") - api("org.ros.rosjava_messages:dynamic_reconfigure:1.5.38") - api("org.ros.rosjava_messages:multisense_ros:3.4.2") - api("org.ros.rosjava_messages:rosgraph_msgs:1.11.1") - api("org.ros.rosjava_messages:geometry_msgs:1.11.7") - api("org.ros.rosjava_messages:trajectory_msgs:1.11.7") - api("org.ros.rosjava_messages:nav_msgs:1.11.7") - api("org.ros.rosjava_messages:tf2_msgs:0.5.9") - api("org.ros.rosjava_messages:tf:1.10.8") +// api("org.apache.logging.log4j:log4j-1.2-api:2.17.0") // required for rosjava to log stuff +// api("org.ros.rosjava_core:rosjava:0.2.1") { +// exclude(group = "junit", module = "junit") +// exclude(group = "org.ros.rosjava_messages", module = "rosjava_test_msgs") +// exclude(group = "org.ros.rosjava_messages", module = "test_rosmaster") +// } +// api("org.ros.rosjava_bootstrap:message_generation:0.3.3") +// api("org.ros.rosjava_messages:std_msgs:0.5.10") +// api("org.ros.rosjava_messages:std_srvs:1.11.1") +// api("org.ros.rosjava_messages:people_msgs:1.0.4") +// api("org.ros.rosjava_messages:sensor_msgs:1.11.7") +// api("org.ros.rosjava_messages:dynamic_reconfigure:1.5.38") +// api("org.ros.rosjava_messages:multisense_ros:3.4.2") +// api("org.ros.rosjava_messages:rosgraph_msgs:1.11.1") +// api("org.ros.rosjava_messages:geometry_msgs:1.11.7") +// api("org.ros.rosjava_messages:trajectory_msgs:1.11.7") +// api("org.ros.rosjava_messages:nav_msgs:1.11.7") +// api("org.ros.rosjava_messages:tf2_msgs:0.5.9") +// api("org.ros.rosjava_messages:tf:1.10.8") api("us.ihmc:ihmc-communication:source") } diff --git a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/CorrectPoseRequest.java b/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/CorrectPoseRequest.java deleted file mode 100644 index 67794362419..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/CorrectPoseRequest.java +++ /dev/null @@ -1,8 +0,0 @@ -package ethz_asl_icp_mapper; - -public interface CorrectPoseRequest extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "ethz_asl_icp_mapper/CorrectPoseRequest"; - static final java.lang.String _DEFINITION = "nav_msgs/Odometry odom\n"; - nav_msgs.Odometry getOdom(); - void setOdom(nav_msgs.Odometry value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/GetBoundedMapResponse.java b/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/GetBoundedMapResponse.java deleted file mode 100644 index 917fd07cf2a..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/GetBoundedMapResponse.java +++ /dev/null @@ -1,8 +0,0 @@ -package ethz_asl_icp_mapper; - -public interface GetBoundedMapResponse extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "ethz_asl_icp_mapper/GetBoundedMapResponse"; - static final java.lang.String _DEFINITION = "sensor_msgs/PointCloud2 boundedMap"; - sensor_msgs.PointCloud2 getBoundedMap(); - void setBoundedMap(sensor_msgs.PointCloud2 value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/MatchCloudsRequest.java b/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/MatchCloudsRequest.java deleted file mode 100644 index 580f70fcd9e..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/ethz_asl_icp_mapper/MatchCloudsRequest.java +++ /dev/null @@ -1,10 +0,0 @@ -package ethz_asl_icp_mapper; - -public interface MatchCloudsRequest extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "ethz_asl_icp_mapper/MatchCloudsRequest"; - static final java.lang.String _DEFINITION = "sensor_msgs/PointCloud2 reference\nsensor_msgs/PointCloud2 readings\n"; - sensor_msgs.PointCloud2 getReference(); - void setReference(sensor_msgs.PointCloud2 value); - sensor_msgs.PointCloud2 getReadings(); - void setReadings(sensor_msgs.PointCloud2 value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMap.java b/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMap.java deleted file mode 100644 index 22117138202..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMap.java +++ /dev/null @@ -1,6 +0,0 @@ -package grid_map_msg; - -public interface GetGridMap extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "grid_map_msg/GetGridMap"; - static final java.lang.String _DEFINITION = "# Requested submap position in x-direction [m].\nfloat64 positionX\n \n# Requested submap position in y-direction [m].\nfloat64 positionY\n\n# Requested submap length in x-direction [m].\nfloat64 lengthX\n \n# Requested submap width in y-direction [m].\nfloat64 lengthY\n\n# Requested data. If empty, get all available data.\nstd_msgs/String[] dataDefinition\n\n---\n\n# Submap\ngrid_map_msg/GridMap gridMap"; -} diff --git a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapRequest.java b/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapRequest.java deleted file mode 100644 index 8661bc29802..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapRequest.java +++ /dev/null @@ -1,16 +0,0 @@ -package grid_map_msg; - -public interface GetGridMapRequest extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "grid_map_msg/GetGridMapRequest"; - static final java.lang.String _DEFINITION = "# Requested submap position in x-direction [m].\nfloat64 positionX\n \n# Requested submap position in y-direction [m].\nfloat64 positionY\n\n# Requested submap length in x-direction [m].\nfloat64 lengthX\n \n# Requested submap width in y-direction [m].\nfloat64 lengthY\n\n# Requested data. If empty, get all available data.\nstd_msgs/String[] dataDefinition\n\n"; - double getPositionX(); - void setPositionX(double value); - double getPositionY(); - void setPositionY(double value); - double getLengthX(); - void setLengthX(double value); - double getLengthY(); - void setLengthY(double value); - java.util.List getDataDefinition(); - void setDataDefinition(java.util.List value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapResponse.java b/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapResponse.java deleted file mode 100644 index c052d5e97e0..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GetGridMapResponse.java +++ /dev/null @@ -1,8 +0,0 @@ -package grid_map_msg; - -public interface GetGridMapResponse extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "grid_map_msg/GetGridMapResponse"; - static final java.lang.String _DEFINITION = "\n# Submap\ngrid_map_msg/GridMap gridMap"; - grid_map_msg.GridMap getGridMap(); - void setGridMap(grid_map_msg.GridMap value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMap.java b/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMap.java deleted file mode 100644 index 0e39e08d1f3..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMap.java +++ /dev/null @@ -1,16 +0,0 @@ -package grid_map_msg; - -public interface GridMap extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "grid_map_msg/GridMap"; - static final java.lang.String _DEFINITION = "# Grid map header\nGridMapInfo info\n\n# Grid map data definition.\nstd_msgs/String[] dataDefinition\n\n# Grid map data.\nstd_msgs/Float32MultiArray[] data\n\n# Row start index (default 0).\nuint16 outerStartIndex\n\n# Column start index (default 0).\nuint16 innerStartIndex"; - grid_map_msg.GridMapInfo getInfo(); - void setInfo(grid_map_msg.GridMapInfo value); - java.util.List getDataDefinition(); - void setDataDefinition(java.util.List value); - java.util.List getData(); - void setData(java.util.List value); - short getOuterStartIndex(); - void setOuterStartIndex(short value); - short getInnerStartIndex(); - void setInnerStartIndex(short value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMapInfo.java b/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMapInfo.java deleted file mode 100644 index 2387ce7264c..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/grid_map_msg/GridMapInfo.java +++ /dev/null @@ -1,18 +0,0 @@ -package grid_map_msg; - -public interface GridMapInfo extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "grid_map_msg/GridMapInfo"; - static final java.lang.String _DEFINITION = "# Header (time and frame)\nHeader header\n\n# Resolution of the grid [m/cell].\nfloat64 resolution\n\n# Length in x-direction [m].\nfloat64 lengthX\n\n# Width in y-direction [m].\nfloat64 lengthY\n\n# Position of the grid map in x-direction in the parent frame [m].\nfloat64 positionX\n\n# Position of the grid map in y-direction in the parent frame [m].\nfloat64 positionY"; - std_msgs.Header getHeader(); - void setHeader(std_msgs.Header value); - double getResolution(); - void setResolution(double value); - double getLengthX(); - void setLengthX(double value); - double getLengthY(); - void setLengthY(double value); - double getPositionX(); - void setPositionX(double value); - double getPositionY(); - void setPositionY(double value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/CableTension.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/CableTension.java deleted file mode 100644 index 6b964a3c030..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/CableTension.java +++ /dev/null @@ -1,10 +0,0 @@ -package handle_msgs; - -public interface CableTension extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/CableTension"; - static final java.lang.String _DEFINITION = "# The cable tension in one finger of the HANDLE hand.\n\nfloat32 sensor1\nfloat32 sensor2\n"; - float getSensor1(); - void setSensor1(float value); - float getSensor2(); - void setSensor2(float value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/Collision.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/Collision.java deleted file mode 100644 index e3c177b021a..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/Collision.java +++ /dev/null @@ -1,18 +0,0 @@ -package handle_msgs; - -public interface Collision extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/Collision"; - static final java.lang.String _DEFINITION = "# This is basic collision message\n# it is used in HandleCollisions to build an array\n\nstring frame_id\n# finger[0]/proximal_link\n# finger[0]/distal_link\n# finger[1]/proximal_link\n# finger[1]/distal_link\n# finger[2]/proximal_link\n# finger[2]/distal_link\n# base_link\n\nint32 sensor_id\n# index of sensor\n\nfloat32 intensity\n\n# location of sensor on the surface of the finger in the link frame\nfloat32 x\nfloat32 y\nfloat32 z\n"; - java.lang.String getFrameId(); - void setFrameId(java.lang.String value); - int getSensorId(); - void setSensorId(int value); - float getIntensity(); - void setIntensity(float value); - float getX(); - void setX(float value); - float getY(); - void setY(float value); - float getZ(); - void setZ(float value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/Finger.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/Finger.java deleted file mode 100644 index 5ef39e42be4..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/Finger.java +++ /dev/null @@ -1,10 +0,0 @@ -package handle_msgs; - -public interface Finger extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/Finger"; - static final java.lang.String _DEFINITION = "# This finger definition is used for different sensors in the HandleSensors \n# message type. \n\nfloat32[] proximal\nfloat32[] distal\n\n"; - float[] getProximal(); - void setProximal(float[] value); - float[] getDistal(); - void setDistal(float[] value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleCollisions.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleCollisions.java deleted file mode 100644 index f494fd989b1..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleCollisions.java +++ /dev/null @@ -1,10 +0,0 @@ -package handle_msgs; - -public interface HandleCollisions extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/HandleCollisions"; - static final java.lang.String _DEFINITION = "# This is sensors of the HANDLE hand after calibration and data manipulation\n# published from the package sensors, by the sensors_publisher\n\n# not all the sensors were included, but only the one which were addressed at the moment\n\n# Currently only used for time stamp. \nHeader header\n\nCollision[] collisions\n"; - std_msgs.Header getHeader(); - void setHeader(std_msgs.Header value); - java.util.List getCollisions(); - void setCollisions(java.util.List value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensors.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensors.java deleted file mode 100644 index 107f3d7ec75..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensors.java +++ /dev/null @@ -1,44 +0,0 @@ -package handle_msgs; - -public interface HandleSensors extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/HandleSensors"; - static final java.lang.String _DEFINITION = "# All of the sensors on the HANDLE hand.\n#\n# NOTE: In general, the order of the arrays is: [F1, F2, F3, F3 Ant., Spread].\n# Where: F1 is analogous to your right hand index finger, F2 is analogous to \n# your right middle finger, F3 is analogous to your right thumb, F3 Ant. is \n# the antagonistic motor for F3, and Spread is the motor which controls the \n# rotation of F1 and F2.\n#\n\n# Currently only used for time stamp. Time stamp set from Overo\'s clock.\n# Not guaranteed to be in sync with the current time.\nHeader header\n\n# The hall effect sensor on the finger motors. \n# 24 counts per motor revolution x 300 motor revolutions for one full spindle\n# rotation. \n# 3500 to put finger at approx. 90 degrees\n# 6000 to close finger gently\n# 7000 to close finger tightly\n#\n# [F1, F2, F3, F3 Ant.]\nint32[4] motorHallEncoder\n\n# The temperature of the finger motor windings, in Celsius.\n#\n# [F1, F2, F3, F3 Ant.]\nfloat32[4] motorWindingTemp\n\n# The air temperature as measured inside the housing, in Celsius.\nfloat32 airTemp\n\n# The motor velocity in RPM. (Hall encoder ticks per minute)\n#\n# [F1, F2, F3, F3 Ant.]\nint32[4] motorVelocity\n\n# The temperature of the motor housing, in Celsius.\n# Note that the housing temp for the Spread motor is not populated, so will\n# not have a logical value.\n#\n# [F1, F2, F3, F3 Ant., Spread]\nfloat32[5] motorHousingTemp\n\n# The motor current in amps.\n#\n# [F1, F2, F3, F3 Ant., Spread]\nfloat32[5] motorCurrent\n\n# The tactile array for each finger. In units of ADC counts.\n# Note there are 12 proximal and 10 distal sensors.\n#\n# [F1, F2, F3]\nFinger[3] fingerTactile\n\n# The tactile temperature array for each finger, in Celsius.\n# Note there are 12 proximal and 10 distal sensors.\n#\n# [F1, F2, F3]\nFinger[3] fingerTactileTemp\n\n# The tactile array for the palm. In units of ADC counts.\nfloat32[48] palmTactile\n\n# The tactile temperature array for the palm, in Celsius.\nfloat32[48] palmTactileTemp\n\n# The encoder on the F1 / F2 rotation. 8.533 ticks per degree.\n# 3072 ticks per 180 degree rotation. (not possible).\n# 768 ticks to rotate the fingers 90 degrees for a \"T\" grasp.\n# 512 ticks to rotate the fingers 60 degrees for a spherical grasp.\nint32 fingerSpread\n\n# The proximal joint angle. Approx 2.84 ticks per degree.\n# 1024 ticks per full revolution. (not possible)\n# 256 ticks to put finger at approx. 90 degrees\n# 435 ticks to close finger gently\n# 445 ticks to close finger tightly\n#\n# [F1, F2, F3]\nint32[3] proximalJointAngle\n\n# The finger distal joint flexture angle\n# [F1, F2, F3]\n# Note there are 4 readings on either side of the joint.\nFinger[3] distalJointAngle\n\n# The accelerometer in the proximal link of each finger. In G\'s.\n# This sensor is not populated at this time.\n#\n# [F1, F2, F3]\ngeometry_msgs/Vector3[3] proximalAcceleration\n\n# The accelerometer in the distal link of each finger. In G\'s.\n# Z axis points out the back of the finger.\n# Y axis points out the finger tip.\n# X axis points to the left when looking at the finger pad.\n#\n# [F1, F2, F3]\ngeometry_msgs/Vector3[3] distalAcceleration\n\n# In this sensor message, which devices actually contributed data.\n# The order of the array is:\n# 0: Palm (Traffic Cop)\n# 1: Finger 1 Proximal\n# 2: Finger 1 Distal\n# 3: Finger 2 Proximal\n# 4: Finger 2 Distal\n# 5: Finger 3 Proximal\n# 6: Finger 3 Distal\n# 7: Motor for Finger 1\n# 8: Motor for Finger 2\n# 9: Motor for Finger 3\n# 10: Motor for Finger 3 Antagonist\n# 11: Tactile Palm\nbool[12] responses\n\n# How many of the the last 100 messages had data from each device.\n# This gives a good indication of communication quality between the devices.\n# Note that this only counts sensor message history. If you have a motor that\n# is in thermal shutdown and non-responsive, the device may look fine here.\n# However there will be errors in the motorError array below.\n# The order of the array is:\n# 0: Palm (Traffic Cop)\n# 1: Finger 1 Proximal\n# 2: Finger 1 Distal\n# 3: Finger 2 Proximal\n# 4: Finger 2 Distal\n# 5: Finger 3 Proximal\n# 6: Finger 3 Distal\n# 7: Motor for Finger 1\n# 8: Motor for Finger 2\n# 9: Motor for Finger 3\n# 10: Motor for Finger 3 Antagonist\n# 11: Tactile Palm\nint8[12] responseHistory\n\n# The last received error from each motor.\n# The order of the motors in the array:\n# [F1, F2, F3, F3 Ant., Spread]\n# The error codes are:\n# 0 = No Error\n# 1 = Traffic Cop checksum error\n# 2 = Unknown Command\n# 3 = Bad Address\n# 4 = Traffic Cop timeout waiting for response\n# 17 = Overo checksum error\n# 18 = Overo data length error\n# 20 = Overo timout waiting for response\n# 128 = Thermal Protection Delay\n# 129 = Mandatory Cool Down \n# 130 = Request out of range\nint16[5] motorError\n"; - std_msgs.Header getHeader(); - void setHeader(std_msgs.Header value); - int[] getMotorHallEncoder(); - void setMotorHallEncoder(int[] value); - float[] getMotorWindingTemp(); - void setMotorWindingTemp(float[] value); - float getAirTemp(); - void setAirTemp(float value); - int[] getMotorVelocity(); - void setMotorVelocity(int[] value); - float[] getMotorHousingTemp(); - void setMotorHousingTemp(float[] value); - float[] getMotorCurrent(); - void setMotorCurrent(float[] value); - java.util.List getFingerTactile(); - void setFingerTactile(java.util.List value); - java.util.List getFingerTactileTemp(); - void setFingerTactileTemp(java.util.List value); - float[] getPalmTactile(); - void setPalmTactile(float[] value); - float[] getPalmTactileTemp(); - void setPalmTactileTemp(float[] value); - int getFingerSpread(); - void setFingerSpread(int value); - int[] getProximalJointAngle(); - void setProximalJointAngle(int[] value); - java.util.List getDistalJointAngle(); - void setDistalJointAngle(java.util.List value); - java.util.List getProximalAcceleration(); - void setProximalAcceleration(java.util.List value); - java.util.List getDistalAcceleration(); - void setDistalAcceleration(java.util.List value); - boolean[] getResponses(); - void setResponses(boolean[] value); - org.jboss.netty.buffer.ChannelBuffer getResponseHistory(); - void setResponseHistory(org.jboss.netty.buffer.ChannelBuffer value); - short[] getMotorError(); - void setMotorError(short[] value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensorsCalibrated.java b/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensorsCalibrated.java deleted file mode 100644 index 862f257580b..00000000000 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleSensorsCalibrated.java +++ /dev/null @@ -1,18 +0,0 @@ -package handle_msgs; - -public interface HandleSensorsCalibrated extends org.ros.internal.message.Message { - static final java.lang.String _TYPE = "handle_msgs/HandleSensorsCalibrated"; - static final java.lang.String _DEFINITION = "# This is sensors of the HANDLE hand after calibration and data manipulation\n# published from the package sensors, by the sensors_publisher\n\n# not all the sensors were included, but only the one which were addressed at the moment\n\n# Currently only used for time stamp. \nHeader header\n\n# The tactile array for each finger. In units of kPa.\n# [F1, F2, F3]\n# Note there are 12 proximal and 10 distal sensors.\nFinger[3] fingerTactile\n\n# The tactile array for the palm. In units of kPa.\nfloat32[48] palmTactile\n\n# The encoder on the F1 / F2 rotation.\n# Approx. 768 ticks to rotate the fingers 90 degrees.\nfloat32 fingerSpread\n\n# The proximal joint angle. Angle in radians\n# [F1, F2, F3]\nfloat32[3] proximalJointAngle\n\n# The finger distal joint flexture angle\n# [F1, F2, F3]\n# Note there are 4 readings on either side of the joint.\nFinger[3] distalJointAngle\n\n"; - std_msgs.Header getHeader(); - void setHeader(std_msgs.Header value); - java.util.List getFingerTactile(); - void setFingerTactile(java.util.List value); - float[] getPalmTactile(); - void setPalmTactile(float[] value); - float getFingerSpread(); - void setFingerSpread(float value); - float[] getProximalJointAngle(); - void setProximalJointAngle(float[] value); - java.util.List getDistalJointAngle(); - void setDistalJointAngle(java.util.List value); -} diff --git a/ihmc-ros-tools/src/main/generated-java/sandia_hand_msgs/RelativeJointCommands.java b/ihmc-ros-tools/src/main/generated-java/sandia_hand_msgs/RelativeJointCommands.java index ae7b3318231..ac9ccc6a855 100644 --- a/ihmc-ros-tools/src/main/generated-java/sandia_hand_msgs/RelativeJointCommands.java +++ b/ihmc-ros-tools/src/main/generated-java/sandia_hand_msgs/RelativeJointCommands.java @@ -7,6 +7,6 @@ public interface RelativeJointCommands extends org.ros.internal.message.Message void setHeader(std_msgs.Header value); float[] getPosition(); void setPosition(float[] value); - org.jboss.netty.buffer.ChannelBuffer getMaxEffort(); - void setMaxEffort(org.jboss.netty.buffer.ChannelBuffer value); +// org.jboss.netty.buffer.ChannelBuffer getMaxEffort(); +// void setMaxEffort(org.jboss.netty.buffer.ChannelBuffer value); } diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/BoolParameter.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/BoolParameter.java new file mode 100644 index 00000000000..08d2ddb119f --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/BoolParameter.java @@ -0,0 +1,16 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface BoolParameter extends Message { + String _TYPE = "dynamic_reconfigure/BoolParameter"; + String _DEFINITION = "string name\nbool value\n"; + + String getName(); + + void setName(String var1); + + boolean getValue(); + + void setValue(boolean var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Config.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Config.java new file mode 100644 index 00000000000..7fd471397b9 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Config.java @@ -0,0 +1,29 @@ +package dynamic_reconfigure; + +import java.util.List; +import org.ros.internal.message.Message; + +public interface Config extends Message { + String _TYPE = "dynamic_reconfigure/Config"; + String _DEFINITION = "BoolParameter[] bools\nIntParameter[] ints\nStrParameter[] strs\nDoubleParameter[] doubles\nGroupState[] groups\n"; + + List getBools(); + + void setBools(List var1); + +// List getInts(); +// +// void setInts(List var1); + + List getStrs(); + +// void setStrs(List var1); + + List getDoubles(); + + void setDoubles(List var1); + + List getGroups(); + + void setGroups(List var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/DoubleParameter.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/DoubleParameter.java new file mode 100644 index 00000000000..9464951a5ee --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/DoubleParameter.java @@ -0,0 +1,16 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface DoubleParameter extends Message { + String _TYPE = "dynamic_reconfigure/DoubleParameter"; + String _DEFINITION = "string name\nfloat64 value\n"; + + String getName(); + + void setName(String var1); + + double getValue(); + + void setValue(double var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/GroupState.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/GroupState.java new file mode 100644 index 00000000000..8c4b1200b3a --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/GroupState.java @@ -0,0 +1,24 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface GroupState extends Message { + String _TYPE = "dynamic_reconfigure/GroupState"; + String _DEFINITION = "string name\nbool state\nint32 id\nint32 parent\n"; + + String getName(); + + void setName(String var1); + + boolean getState(); + + void setState(boolean var1); + + int getId(); + + void setId(int var1); + + int getParent(); + + void setParent(int var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Reconfigure.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Reconfigure.java new file mode 100644 index 00000000000..d6329332f8c --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/Reconfigure.java @@ -0,0 +1,8 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface Reconfigure extends Message { + String _TYPE = "dynamic_reconfigure/Reconfigure"; + String _DEFINITION = "Config config\n---\nConfig config\n"; +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureRequest.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureRequest.java new file mode 100644 index 00000000000..fa7ae7f8325 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureRequest.java @@ -0,0 +1,12 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface ReconfigureRequest extends Message { + String _TYPE = "dynamic_reconfigure/ReconfigureRequest"; + String _DEFINITION = "Config config\n"; + + Config getConfig(); + + void setConfig(Config var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureResponse.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureResponse.java new file mode 100644 index 00000000000..aa9e7433ccb --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/ReconfigureResponse.java @@ -0,0 +1,12 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface ReconfigureResponse extends Message { + String _TYPE = "dynamic_reconfigure/ReconfigureResponse"; + String _DEFINITION = "Config config"; + + Config getConfig(); + + void setConfig(Config var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/dynamic_reconfigure/StrParameter.java b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/StrParameter.java new file mode 100644 index 00000000000..0ccb251179f --- /dev/null +++ b/ihmc-ros-tools/src/main/java/dynamic_reconfigure/StrParameter.java @@ -0,0 +1,16 @@ +package dynamic_reconfigure; + +import org.ros.internal.message.Message; + +public interface StrParameter extends Message { + String _TYPE = "dynamic_reconfigure/StrParameter"; + String _DEFINITION = "string name\nstring value\n"; + + String getName(); + + void setName(String var1); + + String getValue(); + + void setValue(String var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Point.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Point.java new file mode 100644 index 00000000000..4f87f570ed0 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Point.java @@ -0,0 +1,20 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Point extends Message { + String _TYPE = "geometry_msgs/Point"; + String _DEFINITION = "# This contains the position of a point in free space\nfloat64 x\nfloat64 y\nfloat64 z\n"; + + double getX(); + + void setX(double var1); + + double getY(); + + void setY(double var1); + + double getZ(); + + void setZ(double var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Point32.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Point32.java new file mode 100644 index 00000000000..e3e4130414e --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Point32.java @@ -0,0 +1,20 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Point32 extends Message { + String _TYPE = "geometry_msgs/Point32"; + String _DEFINITION = "# This contains the position of a point in free space(with 32 bits of precision).\n# It is recommeded to use Point wherever possible instead of Point32. \n# \n# This recommendation is to promote interoperability. \n#\n# This message is designed to take up less space when sending\n# lots of points at once, as in the case of a PointCloud. \n\nfloat32 x\nfloat32 y\nfloat32 z"; + + float getX(); + + void setX(float var1); + + float getY(); + + void setY(float var1); + + float getZ(); + + void setZ(float var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Pose.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Pose.java new file mode 100644 index 00000000000..a64ece9fc5b --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Pose.java @@ -0,0 +1,16 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Pose extends Message { + String _TYPE = "geometry_msgs/Pose"; + String _DEFINITION = "# A representation of pose in free space, composed of postion and orientation. \nPoint position\nQuaternion orientation\n"; + + Point getPosition(); + + void setPosition(Point var1); + + Quaternion getOrientation(); + + void setOrientation(Quaternion var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/PoseStamped.java b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseStamped.java new file mode 100644 index 00000000000..52fa694d821 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseStamped.java @@ -0,0 +1,17 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; +import std_msgs.Header; + +public interface PoseStamped extends Message { + String _TYPE = "geometry_msgs/PoseStamped"; + String _DEFINITION = "# A Pose with reference coordinate frame and timestamp\nHeader header\nPose pose\n"; + + Header getHeader(); + + void setHeader(Header var1); + + Pose getPose(); + + void setPose(Pose var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovariance.java b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovariance.java new file mode 100644 index 00000000000..6d1ed9959b4 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovariance.java @@ -0,0 +1,16 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface PoseWithCovariance extends Message { + String _TYPE = "geometry_msgs/PoseWithCovariance"; + String _DEFINITION = "# This represents a pose in free space with uncertainty.\n\nPose pose\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n"; + + Pose getPose(); + + void setPose(Pose var1); + + double[] getCovariance(); + + void setCovariance(double[] var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovarianceStamped.java b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovarianceStamped.java new file mode 100644 index 00000000000..39a4475134e --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/PoseWithCovarianceStamped.java @@ -0,0 +1,17 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; +import std_msgs.Header; + +public interface PoseWithCovarianceStamped extends Message { + String _TYPE = "geometry_msgs/PoseWithCovarianceStamped"; + String _DEFINITION = "# This expresses an estimated pose with a reference coordinate frame and timestamp\n\nHeader header\nPoseWithCovariance pose\n"; + + Header getHeader(); + + void setHeader(Header var1); + + PoseWithCovariance getPose(); + + void setPose(PoseWithCovariance var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Quaternion.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Quaternion.java new file mode 100644 index 00000000000..2f5fe0257d7 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Quaternion.java @@ -0,0 +1,24 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Quaternion extends Message { + String _TYPE = "geometry_msgs/Quaternion"; + String _DEFINITION = "# This represents an orientation in free space in quaternion form.\n\nfloat64 x\nfloat64 y\nfloat64 z\nfloat64 w\n"; + + double getX(); + + void setX(double var1); + + double getY(); + + void setY(double var1); + + double getZ(); + + void setZ(double var1); + + double getW(); + + void setW(double var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Transform.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Transform.java new file mode 100644 index 00000000000..6a48dc53d95 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Transform.java @@ -0,0 +1,21 @@ +// +// Source code recreated from a .class file by IntelliJ IDEA +// (powered by FernFlower decompiler) +// + +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Transform extends Message { + String _TYPE = "geometry_msgs/Transform"; + String _DEFINITION = "# This represents the transform between two coordinate frames in free space.\n\nVector3 translation\nQuaternion rotation\n"; + + Vector3 getTranslation(); + + void setTranslation(Vector3 var1); + + Quaternion getRotation(); + + void setRotation(Quaternion var1); +} diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/TransformStamped.java b/ihmc-ros-tools/src/main/java/geometry_msgs/TransformStamped.java new file mode 100644 index 00000000000..a1d9d04948a --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/TransformStamped.java @@ -0,0 +1,26 @@ +// +// Source code recreated from a .class file by IntelliJ IDEA +// (powered by FernFlower decompiler) +// + +package geometry_msgs; + +import org.ros.internal.message.Message; +import std_msgs.Header; + +public interface TransformStamped extends Message { + String _TYPE = "geometry_msgs/TransformStamped"; + String _DEFINITION = "# This expresses a transform from coordinate frame header.frame_id\n# to the coordinate frame child_frame_id\n#\n# This message is mostly used by the \n# tf package. \n# See its documentation for more information.\n\nHeader header\nstring child_frame_id # the frame id of the child frame\nTransform transform\n"; + + Header getHeader(); + + void setHeader(Header var1); + + String getChildFrameId(); + + void setChildFrameId(String var1); + + Transform getTransform(); + + void setTransform(Transform var1); +} diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Twist.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Twist.java new file mode 100644 index 00000000000..02c6e077a59 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Twist.java @@ -0,0 +1,16 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Twist extends Message { + String _TYPE = "geometry_msgs/Twist"; + String _DEFINITION = "# This expresses velocity in free space broken into its linear and angular parts.\nVector3 linear\nVector3 angular\n"; + + Vector3 getLinear(); + + void setLinear(Vector3 var1); + + Vector3 getAngular(); + + void setAngular(Vector3 var1); +} diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/TwistWithCovariance.java b/ihmc-ros-tools/src/main/java/geometry_msgs/TwistWithCovariance.java new file mode 100644 index 00000000000..8b8c0d575b1 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/TwistWithCovariance.java @@ -0,0 +1,16 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface TwistWithCovariance extends Message { + String _TYPE = "geometry_msgs/TwistWithCovariance"; + String _DEFINITION = "# This expresses velocity in free space with uncertainty.\n\nTwist twist\n\n# Row-major representation of the 6x6 covariance matrix\n# The orientation parameters use a fixed-axis representation.\n# In order, the parameters are:\n# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\nfloat64[36] covariance\n"; + + Twist getTwist(); + + void setTwist(Twist var1); + + double[] getCovariance(); + + void setCovariance(double[] var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Vector3.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Vector3.java new file mode 100644 index 00000000000..23d7db44bc4 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Vector3.java @@ -0,0 +1,25 @@ +// +// Source code recreated from a .class file by IntelliJ IDEA +// (powered by FernFlower decompiler) +// + +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Vector3 extends Message { + String _TYPE = "geometry_msgs/Vector3"; + String _DEFINITION = "# This represents a vector in free space. \n\nfloat64 x\nfloat64 y\nfloat64 z"; + + double getX(); + + void setX(double var1); + + double getY(); + + void setY(double var1); + + double getZ(); + + void setZ(double var1); +} diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/Wrench.java b/ihmc-ros-tools/src/main/java/geometry_msgs/Wrench.java new file mode 100644 index 00000000000..4f3f17c2375 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/Wrench.java @@ -0,0 +1,16 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; + +public interface Wrench extends Message { + String _TYPE = "geometry_msgs/Wrench"; + String _DEFINITION = "# This represents force in free space, separated into\n# its linear and angular parts.\nVector3 force\nVector3 torque\n"; + + Vector3 getForce(); + + void setForce(Vector3 var1); + + Vector3 getTorque(); + + void setTorque(Vector3 var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/geometry_msgs/WrenchStamped.java b/ihmc-ros-tools/src/main/java/geometry_msgs/WrenchStamped.java new file mode 100644 index 00000000000..842f89089af --- /dev/null +++ b/ihmc-ros-tools/src/main/java/geometry_msgs/WrenchStamped.java @@ -0,0 +1,17 @@ +package geometry_msgs; + +import org.ros.internal.message.Message; +import std_msgs.Header; + +public interface WrenchStamped extends Message { + String _TYPE = "geometry_msgs/WrenchStamped"; + String _DEFINITION = "# A wrench with reference coordinate frame and timestamp\nHeader header\nWrench wrench\n"; + + Header getHeader(); + + void setHeader(Header var1); + + Wrench getWrench(); + + void setWrench(Wrench var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleControl.java b/ihmc-ros-tools/src/main/java/handle_msgs/HandleControl.java similarity index 99% rename from ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleControl.java rename to ihmc-ros-tools/src/main/java/handle_msgs/HandleControl.java index 3f94adbc0bb..d1225f4ab1e 100644 --- a/ihmc-ros-tools/src/main/generated-java/handle_msgs/HandleControl.java +++ b/ihmc-ros-tools/src/main/java/handle_msgs/HandleControl.java @@ -14,4 +14,4 @@ public interface HandleControl extends org.ros.internal.message.Message { void setValue(int[] value); boolean[] getValid(); void setValid(boolean[] value); -} +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/multisense_ros/StampedPps.java b/ihmc-ros-tools/src/main/java/multisense_ros/StampedPps.java new file mode 100644 index 00000000000..7bc5c4293c4 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/multisense_ros/StampedPps.java @@ -0,0 +1,17 @@ +package multisense_ros; + +import org.ros.internal.message.Message; +import org.ros.message.Time; + +public interface StampedPps extends Message { + String _TYPE = "multisense_ros/StampedPps"; + String _DEFINITION = "time data\ntime host_time\n"; + + Time getData(); + + void setData(Time var1); + + Time getHostTime(); + + void setHostTime(Time var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/nav_msgs/Odometry.java b/ihmc-ros-tools/src/main/java/nav_msgs/Odometry.java new file mode 100644 index 00000000000..6b5527b9c9f --- /dev/null +++ b/ihmc-ros-tools/src/main/java/nav_msgs/Odometry.java @@ -0,0 +1,27 @@ +package nav_msgs; + +import geometry_msgs.PoseWithCovariance; +import geometry_msgs.TwistWithCovariance; +import org.ros.internal.message.Message; +import std_msgs.Header; + +public interface Odometry extends Message { + String _TYPE = "nav_msgs/Odometry"; + String _DEFINITION = "# This represents an estimate of a position and velocity in free space. \n# The pose in this message should be specified in the coordinate frame given by header.frame_id.\n# The twist in this message should be specified in the coordinate frame given by the child_frame_id\nHeader header\nstring child_frame_id\ngeometry_msgs/PoseWithCovariance pose\ngeometry_msgs/TwistWithCovariance twist\n"; + + Header getHeader(); + + void setHeader(Header var1); + + String getChildFrameId(); + + void setChildFrameId(String var1); + + PoseWithCovariance getPose(); + + void setPose(PoseWithCovariance var1); + + TwistWithCovariance getTwist(); + + void setTwist(TwistWithCovariance var1); +} \ No newline at end of file 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 new file mode 100644 index 00000000000..4c77f6a794c --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBuffer.java @@ -0,0 +1,1515 @@ +/* + * 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: + *

    + *
  • a non-dynamic buffer will throw an {@link IndexOutOfBoundsException}.
  • + *
  • a dynamic buffer will expand its capacity so that the number of the + * {@link #writableBytes() writable bytes} becomes equal to or greater + * than the specified value. The expansion involves the reallocation of + * the internal buffer and consequently memory copy.
  • + *
+ * + * @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: + *

    + *
  • the size of the contents of the two buffers are same and
  • + *
  • every single byte of the content of the two buffers are same.
  • + *
+ * 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 new file mode 100644 index 00000000000..fa53b98db6e --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/jboss/netty/buffer/ChannelBufferFactory.java @@ -0,0 +1,104 @@ +/* + * 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/org/ros/exception/RemoteException.java b/ihmc-ros-tools/src/main/java/org/ros/exception/RemoteException.java new file mode 100644 index 00000000000..ae80072308d --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/exception/RemoteException.java @@ -0,0 +1,21 @@ +package org.ros.exception; + +//import org.ros.internal.node.response.StatusCode; + +public class RemoteException extends RosRuntimeException { +// private final StatusCode statusCode; +// +// public RemoteException(StatusCode statusCode, String message) { +// super(message); +// this.statusCode = statusCode; +// } + + public RemoteException(String message) + { + super(message); + } + + // public StatusCode getStatusCode() { +// return this.statusCode; +// } +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/exception/RosRuntimeException.java b/ihmc-ros-tools/src/main/java/org/ros/exception/RosRuntimeException.java new file mode 100644 index 00000000000..56487d4edca --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/exception/RosRuntimeException.java @@ -0,0 +1,15 @@ +package org.ros.exception; + +public class RosRuntimeException extends RuntimeException { + public RosRuntimeException(Throwable throwable) { + super(throwable); + } + + public RosRuntimeException(String message, Throwable throwable) { + super(message, throwable); + } + + public RosRuntimeException(String message) { + super(message); + } +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/exception/ServiceException.java b/ihmc-ros-tools/src/main/java/org/ros/exception/ServiceException.java new file mode 100644 index 00000000000..b4bdd69b861 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/exception/ServiceException.java @@ -0,0 +1,15 @@ +package org.ros.exception; + +public class ServiceException extends Exception { + public ServiceException(Throwable throwable) { + super(throwable); + } + + public ServiceException(String message, Throwable throwable) { + super(message, throwable); + } + + public ServiceException(String message) { + super(message); + } +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/internal/message/Message.java b/ihmc-ros-tools/src/main/java/org/ros/internal/message/Message.java new file mode 100644 index 00000000000..0f39939851f --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/internal/message/Message.java @@ -0,0 +1,6 @@ +package org.ros.internal.message; + +public interface Message +{ + RawMessage toRawMessage(); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/internal/message/RawMessage.java b/ihmc-ros-tools/src/main/java/org/ros/internal/message/RawMessage.java new file mode 100644 index 00000000000..53a1dbda464 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/internal/message/RawMessage.java @@ -0,0 +1,145 @@ +package org.ros.internal.message; + +import java.util.List; + +public interface RawMessage extends Message { + boolean getBool(String var1); + + boolean[] getBoolArray(String var1); + + /** @deprecated */ + byte getByte(String var1); + + /** @deprecated */ + byte[] getByteArray(String var1); + + /** @deprecated */ + short getChar(String var1); + + /** @deprecated */ + short[] getCharArray(String var1); + + String getDefinition(); + + + float getFloat32(String var1); + + float[] getFloat32Array(String var1); + + double getFloat64(String var1); + + double[] getFloat64Array(String var1); + + + short getInt16(String var1); + + short[] getInt16Array(String var1); + + int getInt32(String var1); + + int[] getInt32Array(String var1); + + long getInt64(String var1); + + long[] getInt64Array(String var1); + + byte getInt8(String var1); + + + T getMessage(String var1); + + List getMessageList(String var1); + + String getName(); + + String getPackage(); + + String getString(String var1); + + List getStringList(String var1); + + + String getType(); + + short getUInt16(String var1); + + short[] getUInt16Array(String var1); + + int getUInt32(String var1); + + int[] getUInt32Array(String var1); + + long getUInt64(String var1); + + long[] getUInt64Array(String var1); + + short getUInt8(String var1); + + short[] getUInt8Array(String var1); + + void setBool(String var1, boolean var2); + + void setBoolArray(String var1, boolean[] var2); + + /** @deprecated */ + void setByte(String var1, byte var2); + + /** @deprecated */ + void setByteArray(String var1, byte[] var2); + + /** @deprecated */ + void setChar(String var1, short var2); + + /** @deprecated */ + void setCharArray(String var1, short[] var2); + + + void setFloat32(String var1, float var2); + + void setFloat32Array(String var1, float[] var2); + + void setFloat64(String var1, double var2); + + void setFloat64Array(String var1, double[] var2); + + void setInt16(String var1, short var2); + + void setInt16Array(String var1, short[] var2); + + void setInt32(String var1, int var2); + + void setInt32Array(String var1, int[] var2); + + void setInt64(String var1, long var2); + + void setInt64Array(String var1, long[] var2); + + void setInt8(String var1, byte var2); + + void setInt8Array(String var1, byte[] var2); + + void setMessage(String var1, Message var2); + + void setMessageList(String var1, List var2); + + void setString(String var1, String var2); + + void setStringList(String var1, List var2); + + + void setUInt16(String var1, short var2); + + void setUInt16Array(String var1, short[] var2); + + void setUInt32(String var1, int var2); + + void setUInt32Array(String var1, int[] var2); + + void setUInt64(String var1, long var2); + + void setUInt64Array(String var1, long[] var2); + + void setUInt8(String var1, byte var2); + + void setUInt8Array(String var1, byte[] var2); +} diff --git a/ihmc-ros-tools/src/main/java/org/ros/message/Duration.java b/ihmc-ros-tools/src/main/java/org/ros/message/Duration.java new file mode 100644 index 00000000000..2b623f98e41 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/message/Duration.java @@ -0,0 +1,145 @@ +package org.ros.message; + +public class Duration implements Comparable +{ + public static final Duration MAX_VALUE = new Duration(Integer.MAX_VALUE, 999999999); + public int secs; + public int nsecs; + + public Duration() + { + } + + public Duration(int secs, int nsecs) + { + this.secs = secs; + this.nsecs = nsecs; + this.normalize(); + } + + public Duration(double secs) + { + this.secs = (int) secs; + this.nsecs = (int) ((secs - (double) this.secs) * 1.0E9); + this.normalize(); + } + + public Duration(Duration t) + { + this.secs = t.secs; + this.nsecs = t.nsecs; + } + + public Duration add(Duration d) + { + return new Duration(this.secs + d.secs, this.nsecs + d.nsecs); + } + + public Duration subtract(Duration d) + { + return new Duration(this.secs - d.secs, this.nsecs - d.nsecs); + } + + public static Duration fromMillis(long durationInMillis) + { + int secs = (int) (durationInMillis / 1000L); + int nsecs = (int) (durationInMillis % 1000L) * 1000000; + return new Duration(secs, nsecs); + } + + public static Duration fromNano(long durationInNs) + { + int secs = (int) (durationInNs / 1000000000L); + int nsecs = (int) (durationInNs % 1000000000L); + return new Duration(secs, nsecs); + } + + public void normalize() + { + while (this.nsecs < 0) + { + this.nsecs += 1000000000; + --this.secs; + } + + while (this.nsecs >= 1000000000) + { + this.nsecs -= 1000000000; + ++this.secs; + } + } + + public long totalNsecs() + { + return (long) this.secs * 1000000000L + (long) this.nsecs; + } + + public boolean isZero() + { + return this.totalNsecs() == 0L; + } + + public boolean isPositive() + { + return this.totalNsecs() > 0L; + } + + public boolean isNegative() + { + return this.totalNsecs() < 0L; + } + + public String toString() + { + return this.secs + ":" + this.nsecs; + } + + public int hashCode() + { + int prime = 0; + int result = 1; + result = 31 * result + this.nsecs; + result = 31 * result + this.secs; + return result; + } + + public boolean equals(Object obj) + { + if (this == obj) + { + return true; + } + else if (obj == null) + { + return false; + } + else if (this.getClass() != obj.getClass()) + { + return false; + } + else + { + Duration other = (Duration) obj; + if (this.nsecs != other.nsecs) + { + return false; + } + else + { + return this.secs == other.secs; + } + } + } + + public int compareTo(Duration d) + { + if (this.secs <= d.secs && (this.secs != d.secs || this.nsecs <= d.nsecs)) + { + return this.secs == d.secs && this.nsecs == d.nsecs ? 0 : -1; + } + else + { + return 1; + } + } +} diff --git a/ihmc-ros-tools/src/main/java/org/ros/message/MessageFactory.java b/ihmc-ros-tools/src/main/java/org/ros/message/MessageFactory.java new file mode 100644 index 00000000000..027621dde98 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/message/MessageFactory.java @@ -0,0 +1,5 @@ +package org.ros.message; + +public interface MessageFactory { + T newFromType(String var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/message/MessageListener.java b/ihmc-ros-tools/src/main/java/org/ros/message/MessageListener.java new file mode 100644 index 00000000000..dead76cfdc2 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/message/MessageListener.java @@ -0,0 +1,5 @@ +package org.ros.message; + +public interface MessageListener { + void onNewMessage(T var1); +} \ No newline at end of file diff --git a/ihmc-ros-tools/src/main/java/org/ros/message/Time.java b/ihmc-ros-tools/src/main/java/org/ros/message/Time.java new file mode 100644 index 00000000000..63418448084 --- /dev/null +++ b/ihmc-ros-tools/src/main/java/org/ros/message/Time.java @@ -0,0 +1,114 @@ +package org.ros.message; + +public class Time implements Comparable