├── .gitignore
├── Assets
├── ROS.meta
├── ROS
│ ├── Plugins.meta
│ └── Plugins
│ │ ├── Messages.meta
│ │ ├── Messages
│ │ ├── Interfaces.cs
│ │ ├── Interfaces.cs.meta
│ │ ├── MessageTypes.cs
│ │ ├── MessageTypes.cs.meta
│ │ ├── SerializationHelper.cs
│ │ ├── SerializationHelper.cs.meta
│ │ ├── ServiceTest.meta
│ │ ├── ServiceTest
│ │ │ ├── AddTwoInts.cs
│ │ │ └── AddTwoInts.cs.meta
│ │ ├── actionlib_msgs.meta
│ │ ├── actionlib_msgs
│ │ │ ├── GoalID.cs
│ │ │ ├── GoalID.cs.meta
│ │ │ ├── GoalStatus.cs
│ │ │ ├── GoalStatus.cs.meta
│ │ │ ├── GoalStatusArray.cs
│ │ │ └── GoalStatusArray.cs.meta
│ │ ├── baxter_core_msgs.meta
│ │ ├── baxter_core_msgs
│ │ │ ├── AnalogIOState.cs
│ │ │ ├── AnalogIOState.cs.meta
│ │ │ ├── AnalogIOStates.cs
│ │ │ ├── AnalogIOStates.cs.meta
│ │ │ ├── AnalogOutputCommand.cs
│ │ │ ├── AnalogOutputCommand.cs.meta
│ │ │ ├── AssemblyState.cs
│ │ │ ├── AssemblyState.cs.meta
│ │ │ ├── AssemblyStates.cs
│ │ │ ├── AssemblyStates.cs.meta
│ │ │ ├── CameraControl.cs
│ │ │ ├── CameraControl.cs.meta
│ │ │ ├── CameraSettings.cs
│ │ │ ├── CameraSettings.cs.meta
│ │ │ ├── CloseCamera.cs
│ │ │ ├── CloseCamera.cs.meta
│ │ │ ├── CollisionAvoidanceState.cs
│ │ │ ├── CollisionAvoidanceState.cs.meta
│ │ │ ├── CollisionDetectionState.cs
│ │ │ ├── CollisionDetectionState.cs.meta
│ │ │ ├── DigitalIOState.cs
│ │ │ ├── DigitalIOState.cs.meta
│ │ │ ├── DigitalIOStates.cs
│ │ │ ├── DigitalIOStates.cs.meta
│ │ │ ├── DigitalOutputCommand.cs
│ │ │ ├── DigitalOutputCommand.cs.meta
│ │ │ ├── EndEffectorCommand.cs
│ │ │ ├── EndEffectorCommand.cs.meta
│ │ │ ├── EndEffectorProperties.cs
│ │ │ ├── EndEffectorProperties.cs.meta
│ │ │ ├── EndEffectorState.cs
│ │ │ ├── EndEffectorState.cs.meta
│ │ │ ├── EndpointState.cs
│ │ │ ├── EndpointState.cs.meta
│ │ │ ├── EndpointStates.cs
│ │ │ ├── EndpointStates.cs.meta
│ │ │ ├── HeadPanCommand.cs
│ │ │ ├── HeadPanCommand.cs.meta
│ │ │ ├── HeadState.cs
│ │ │ ├── HeadState.cs.meta
│ │ │ ├── ITBState.cs
│ │ │ ├── ITBState.cs.meta
│ │ │ ├── ITBStates.cs
│ │ │ ├── ITBStates.cs.meta
│ │ │ ├── JointCommand.cs
│ │ │ ├── JointCommand.cs.meta
│ │ │ ├── ListCameras.cs
│ │ │ ├── ListCameras.cs.meta
│ │ │ ├── NavigatorState.cs
│ │ │ ├── NavigatorState.cs.meta
│ │ │ ├── NavigatorStates.cs
│ │ │ ├── NavigatorStates.cs.meta
│ │ │ ├── OpenCamera.cs
│ │ │ ├── OpenCamera.cs.meta
│ │ │ ├── RobustControllerStatus.cs
│ │ │ ├── RobustControllerStatus.cs.meta
│ │ │ ├── SEAJointState.cs
│ │ │ ├── SEAJointState.cs.meta
│ │ │ ├── SolvePositionIK.cs
│ │ │ └── SolvePositionIK.cs.meta
│ │ ├── control_msgs.meta
│ │ ├── control_msgs
│ │ │ ├── FollowJointTrajectoryAction.cs
│ │ │ ├── FollowJointTrajectoryAction.cs.meta
│ │ │ ├── FollowJointTrajectoryActionFeedback.cs
│ │ │ ├── FollowJointTrajectoryActionFeedback.cs.meta
│ │ │ ├── FollowJointTrajectoryActionGoal.cs
│ │ │ ├── FollowJointTrajectoryActionGoal.cs.meta
│ │ │ ├── FollowJointTrajectoryActionResult.cs
│ │ │ ├── FollowJointTrajectoryActionResult.cs.meta
│ │ │ ├── FollowJointTrajectoryFeedback.cs
│ │ │ ├── FollowJointTrajectoryFeedback.cs.meta
│ │ │ ├── FollowJointTrajectoryGoal.cs
│ │ │ ├── FollowJointTrajectoryGoal.cs.meta
│ │ │ ├── FollowJointTrajectoryResult.cs
│ │ │ ├── FollowJointTrajectoryResult.cs.meta
│ │ │ ├── GripperCommand.cs
│ │ │ ├── GripperCommand.cs.meta
│ │ │ ├── GripperCommandAction.cs
│ │ │ ├── GripperCommandAction.cs.meta
│ │ │ ├── GripperCommandActionFeedback.cs
│ │ │ ├── GripperCommandActionFeedback.cs.meta
│ │ │ ├── GripperCommandActionGoal.cs
│ │ │ ├── GripperCommandActionGoal.cs.meta
│ │ │ ├── GripperCommandActionResult.cs
│ │ │ ├── GripperCommandActionResult.cs.meta
│ │ │ ├── GripperCommandFeedback.cs
│ │ │ ├── GripperCommandFeedback.cs.meta
│ │ │ ├── GripperCommandGoal.cs
│ │ │ ├── GripperCommandGoal.cs.meta
│ │ │ ├── GripperCommandResult.cs
│ │ │ ├── GripperCommandResult.cs.meta
│ │ │ ├── JointControllerState.cs
│ │ │ ├── JointControllerState.cs.meta
│ │ │ ├── JointTolerance.cs
│ │ │ ├── JointTolerance.cs.meta
│ │ │ ├── JointTrajectoryAction.cs
│ │ │ ├── JointTrajectoryAction.cs.meta
│ │ │ ├── JointTrajectoryActionFeedback.cs
│ │ │ ├── JointTrajectoryActionFeedback.cs.meta
│ │ │ ├── JointTrajectoryActionGoal.cs
│ │ │ ├── JointTrajectoryActionGoal.cs.meta
│ │ │ ├── JointTrajectoryActionResult.cs
│ │ │ ├── JointTrajectoryActionResult.cs.meta
│ │ │ ├── JointTrajectoryControllerState.cs
│ │ │ ├── JointTrajectoryControllerState.cs.meta
│ │ │ ├── JointTrajectoryFeedback.cs
│ │ │ ├── JointTrajectoryFeedback.cs.meta
│ │ │ ├── JointTrajectoryGoal.cs
│ │ │ ├── JointTrajectoryGoal.cs.meta
│ │ │ ├── JointTrajectoryResult.cs
│ │ │ ├── JointTrajectoryResult.cs.meta
│ │ │ ├── PidState.cs
│ │ │ ├── PidState.cs.meta
│ │ │ ├── PointHeadAction.cs
│ │ │ ├── PointHeadAction.cs.meta
│ │ │ ├── PointHeadActionFeedback.cs
│ │ │ ├── PointHeadActionFeedback.cs.meta
│ │ │ ├── PointHeadActionGoal.cs
│ │ │ ├── PointHeadActionGoal.cs.meta
│ │ │ ├── PointHeadActionResult.cs
│ │ │ ├── PointHeadActionResult.cs.meta
│ │ │ ├── PointHeadFeedback.cs
│ │ │ ├── PointHeadFeedback.cs.meta
│ │ │ ├── PointHeadGoal.cs
│ │ │ ├── PointHeadGoal.cs.meta
│ │ │ ├── PointHeadResult.cs
│ │ │ ├── PointHeadResult.cs.meta
│ │ │ ├── QueryCalibrationState.cs
│ │ │ ├── QueryCalibrationState.cs.meta
│ │ │ ├── QueryTrajectoryState.cs
│ │ │ ├── QueryTrajectoryState.cs.meta
│ │ │ ├── SingleJointPositionAction.cs
│ │ │ ├── SingleJointPositionAction.cs.meta
│ │ │ ├── SingleJointPositionActionFeedback.cs
│ │ │ ├── SingleJointPositionActionFeedback.cs.meta
│ │ │ ├── SingleJointPositionActionGoal.cs
│ │ │ ├── SingleJointPositionActionGoal.cs.meta
│ │ │ ├── SingleJointPositionActionResult.cs
│ │ │ ├── SingleJointPositionActionResult.cs.meta
│ │ │ ├── SingleJointPositionFeedback.cs
│ │ │ ├── SingleJointPositionFeedback.cs.meta
│ │ │ ├── SingleJointPositionGoal.cs
│ │ │ ├── SingleJointPositionGoal.cs.meta
│ │ │ ├── SingleJointPositionResult.cs
│ │ │ └── SingleJointPositionResult.cs.meta
│ │ ├── custom_msgs.meta
│ │ ├── custom_msgs
│ │ │ ├── arrayofdeez.cs
│ │ │ ├── arrayofdeez.cs.meta
│ │ │ ├── arraytest.cs
│ │ │ ├── arraytest.cs.meta
│ │ │ ├── cgeo.cs
│ │ │ ├── cgeo.cs.meta
│ │ │ ├── ptz.cs
│ │ │ ├── ptz.cs.meta
│ │ │ ├── robotMortality.cs
│ │ │ ├── robotMortality.cs.meta
│ │ │ ├── servosPos.cs
│ │ │ ├── servosPos.cs.meta
│ │ │ ├── simpleintarray.cs
│ │ │ └── simpleintarray.cs.meta
│ │ ├── dynamic_reconfigure.meta
│ │ ├── dynamic_reconfigure
│ │ │ ├── BoolParameter.cs
│ │ │ ├── BoolParameter.cs.meta
│ │ │ ├── Config.cs
│ │ │ ├── Config.cs.meta
│ │ │ ├── ConfigDescription.cs
│ │ │ ├── ConfigDescription.cs.meta
│ │ │ ├── DoubleParameter.cs
│ │ │ ├── DoubleParameter.cs.meta
│ │ │ ├── Group.cs
│ │ │ ├── Group.cs.meta
│ │ │ ├── GroupState.cs
│ │ │ ├── GroupState.cs.meta
│ │ │ ├── IntParameter.cs
│ │ │ ├── IntParameter.cs.meta
│ │ │ ├── ParamDescription.cs
│ │ │ ├── ParamDescription.cs.meta
│ │ │ ├── Reconfigure.cs
│ │ │ ├── Reconfigure.cs.meta
│ │ │ ├── SensorLevels.cs
│ │ │ ├── SensorLevels.cs.meta
│ │ │ ├── StrParameter.cs
│ │ │ └── StrParameter.cs.meta
│ │ ├── dynamixel_msgs.meta
│ │ ├── dynamixel_msgs
│ │ │ ├── JointState.cs
│ │ │ └── JointState.cs.meta
│ │ ├── experiment.meta
│ │ ├── experiment
│ │ │ ├── SimonSays.cs
│ │ │ └── SimonSays.cs.meta
│ │ ├── gazebo_msgs.meta
│ │ ├── gazebo_msgs
│ │ │ ├── ApplyBodyWrench.cs
│ │ │ ├── ApplyBodyWrench.cs.meta
│ │ │ ├── ApplyJointEffort.cs
│ │ │ ├── ApplyJointEffort.cs.meta
│ │ │ ├── BodyRequest.cs
│ │ │ ├── BodyRequest.cs.meta
│ │ │ ├── ContactState.cs
│ │ │ ├── ContactState.cs.meta
│ │ │ ├── ContactsState.cs
│ │ │ ├── ContactsState.cs.meta
│ │ │ ├── DeleteModel.cs
│ │ │ ├── DeleteModel.cs.meta
│ │ │ ├── GetJointProperties.cs
│ │ │ ├── GetJointProperties.cs.meta
│ │ │ ├── GetLinkProperties.cs
│ │ │ ├── GetLinkProperties.cs.meta
│ │ │ ├── GetLinkState.cs
│ │ │ ├── GetLinkState.cs.meta
│ │ │ ├── GetModelProperties.cs
│ │ │ ├── GetModelProperties.cs.meta
│ │ │ ├── GetModelState.cs
│ │ │ ├── GetModelState.cs.meta
│ │ │ ├── GetPhysicsProperties.cs
│ │ │ ├── GetPhysicsProperties.cs.meta
│ │ │ ├── GetWorldProperties.cs
│ │ │ ├── GetWorldProperties.cs.meta
│ │ │ ├── JointRequest.cs
│ │ │ ├── JointRequest.cs.meta
│ │ │ ├── LinkState.cs
│ │ │ ├── LinkState.cs.meta
│ │ │ ├── LinkStates.cs
│ │ │ ├── LinkStates.cs.meta
│ │ │ ├── ModelState.cs
│ │ │ ├── ModelState.cs.meta
│ │ │ ├── ModelStates.cs
│ │ │ ├── ModelStates.cs.meta
│ │ │ ├── ODEJointProperties.cs
│ │ │ ├── ODEJointProperties.cs.meta
│ │ │ ├── ODEPhysics.cs
│ │ │ ├── ODEPhysics.cs.meta
│ │ │ ├── SetJointProperties.cs
│ │ │ ├── SetJointProperties.cs.meta
│ │ │ ├── SetJointTrajectory.cs
│ │ │ ├── SetJointTrajectory.cs.meta
│ │ │ ├── SetLinkProperties.cs
│ │ │ ├── SetLinkProperties.cs.meta
│ │ │ ├── SetLinkState.cs
│ │ │ ├── SetLinkState.cs.meta
│ │ │ ├── SetModelConfiguration.cs
│ │ │ ├── SetModelConfiguration.cs.meta
│ │ │ ├── SetModelState.cs
│ │ │ ├── SetModelState.cs.meta
│ │ │ ├── SetPhysicsProperties.cs
│ │ │ ├── SetPhysicsProperties.cs.meta
│ │ │ ├── SpawnModel.cs
│ │ │ ├── SpawnModel.cs.meta
│ │ │ ├── WorldState.cs
│ │ │ └── WorldState.cs.meta
│ │ ├── geometry_msgs.meta
│ │ ├── geometry_msgs
│ │ │ ├── Point.cs
│ │ │ ├── Point.cs.meta
│ │ │ ├── Point32.cs
│ │ │ ├── Point32.cs.meta
│ │ │ ├── PointStamped.cs
│ │ │ ├── PointStamped.cs.meta
│ │ │ ├── Polygon.cs
│ │ │ ├── Polygon.cs.meta
│ │ │ ├── PolygonStamped.cs
│ │ │ ├── PolygonStamped.cs.meta
│ │ │ ├── Pose.cs
│ │ │ ├── Pose.cs.meta
│ │ │ ├── Pose2D.cs
│ │ │ ├── Pose2D.cs.meta
│ │ │ ├── PoseArray.cs
│ │ │ ├── PoseArray.cs.meta
│ │ │ ├── PoseStamped.cs
│ │ │ ├── PoseStamped.cs.meta
│ │ │ ├── PoseWithCovariance.cs
│ │ │ ├── PoseWithCovariance.cs.meta
│ │ │ ├── PoseWithCovarianceStamped.cs
│ │ │ ├── PoseWithCovarianceStamped.cs.meta
│ │ │ ├── Quaternion.cs
│ │ │ ├── Quaternion.cs.meta
│ │ │ ├── QuaternionStamped.cs
│ │ │ ├── QuaternionStamped.cs.meta
│ │ │ ├── Transform.cs
│ │ │ ├── Transform.cs.meta
│ │ │ ├── TransformStamped.cs
│ │ │ ├── TransformStamped.cs.meta
│ │ │ ├── Twist.cs
│ │ │ ├── Twist.cs.meta
│ │ │ ├── TwistStamped.cs
│ │ │ ├── TwistStamped.cs.meta
│ │ │ ├── TwistWithCovariance.cs
│ │ │ ├── TwistWithCovariance.cs.meta
│ │ │ ├── TwistWithCovarianceStamped.cs
│ │ │ ├── TwistWithCovarianceStamped.cs.meta
│ │ │ ├── Vector3.cs
│ │ │ ├── Vector3.cs.meta
│ │ │ ├── Vector3Stamped.cs
│ │ │ ├── Vector3Stamped.cs.meta
│ │ │ ├── Wrench.cs
│ │ │ ├── Wrench.cs.meta
│ │ │ ├── WrenchStamped.cs
│ │ │ └── WrenchStamped.cs.meta
│ │ ├── histogram_msgs.meta
│ │ ├── histogram_msgs
│ │ │ ├── MCLSnapshot.cs
│ │ │ ├── MCLSnapshot.cs.meta
│ │ │ ├── histogramsnapshot.cs
│ │ │ └── histogramsnapshot.cs.meta
│ │ ├── humanoid_nav_msgs.meta
│ │ ├── humanoid_nav_msgs
│ │ │ ├── ClipFootstep.cs
│ │ │ ├── ClipFootstep.cs.meta
│ │ │ ├── ExecFootstepsAction.cs
│ │ │ ├── ExecFootstepsAction.cs.meta
│ │ │ ├── ExecFootstepsActionFeedback.cs
│ │ │ ├── ExecFootstepsActionFeedback.cs.meta
│ │ │ ├── ExecFootstepsActionGoal.cs
│ │ │ ├── ExecFootstepsActionGoal.cs.meta
│ │ │ ├── ExecFootstepsActionResult.cs
│ │ │ ├── ExecFootstepsActionResult.cs.meta
│ │ │ ├── ExecFootstepsFeedback.cs
│ │ │ ├── ExecFootstepsFeedback.cs.meta
│ │ │ ├── ExecFootstepsGoal.cs
│ │ │ ├── ExecFootstepsGoal.cs.meta
│ │ │ ├── ExecFootstepsResult.cs
│ │ │ ├── ExecFootstepsResult.cs.meta
│ │ │ ├── PlanFootsteps.cs
│ │ │ ├── PlanFootsteps.cs.meta
│ │ │ ├── PlanFootstepsBetweenFeet.cs
│ │ │ ├── PlanFootstepsBetweenFeet.cs.meta
│ │ │ ├── StepTarget.cs
│ │ │ ├── StepTarget.cs.meta
│ │ │ ├── StepTargetService.cs
│ │ │ └── StepTargetService.cs.meta
│ │ ├── map_msgs.meta
│ │ ├── map_msgs
│ │ │ ├── GetMapROI.cs
│ │ │ ├── GetMapROI.cs.meta
│ │ │ ├── GetPointMap.cs
│ │ │ ├── GetPointMap.cs.meta
│ │ │ ├── GetPointMapROI.cs
│ │ │ ├── GetPointMapROI.cs.meta
│ │ │ ├── OccupancyGridUpdate.cs
│ │ │ ├── OccupancyGridUpdate.cs.meta
│ │ │ ├── PointCloud2Update.cs
│ │ │ ├── PointCloud2Update.cs.meta
│ │ │ ├── ProjectedMap.cs
│ │ │ ├── ProjectedMap.cs.meta
│ │ │ ├── ProjectedMapInfo.cs
│ │ │ ├── ProjectedMapInfo.cs.meta
│ │ │ ├── ProjectedMapsInfo.cs
│ │ │ ├── ProjectedMapsInfo.cs.meta
│ │ │ ├── SaveMap.cs
│ │ │ ├── SaveMap.cs.meta
│ │ │ ├── SetMapProjections.cs
│ │ │ └── SetMapProjections.cs.meta
│ │ ├── move_base_msgs.meta
│ │ ├── move_base_msgs
│ │ │ ├── MoveBaseAction.cs
│ │ │ ├── MoveBaseAction.cs.meta
│ │ │ ├── MoveBaseActionFeedback.cs
│ │ │ ├── MoveBaseActionFeedback.cs.meta
│ │ │ ├── MoveBaseActionGoal.cs
│ │ │ ├── MoveBaseActionGoal.cs.meta
│ │ │ ├── MoveBaseActionResult.cs
│ │ │ ├── MoveBaseActionResult.cs.meta
│ │ │ ├── MoveBaseFeedback.cs
│ │ │ ├── MoveBaseFeedback.cs.meta
│ │ │ ├── MoveBaseGoal.cs
│ │ │ ├── MoveBaseGoal.cs.meta
│ │ │ ├── MoveBaseResult.cs
│ │ │ └── MoveBaseResult.cs.meta
│ │ ├── nav_msgs.meta
│ │ ├── nav_msgs
│ │ │ ├── GetMap.cs
│ │ │ ├── GetMap.cs.meta
│ │ │ ├── GetMapAction.cs
│ │ │ ├── GetMapAction.cs.meta
│ │ │ ├── GetMapActionFeedback.cs
│ │ │ ├── GetMapActionFeedback.cs.meta
│ │ │ ├── GetMapActionGoal.cs
│ │ │ ├── GetMapActionGoal.cs.meta
│ │ │ ├── GetMapActionResult.cs
│ │ │ ├── GetMapActionResult.cs.meta
│ │ │ ├── GetMapFeedback.cs
│ │ │ ├── GetMapFeedback.cs.meta
│ │ │ ├── GetMapGoal.cs
│ │ │ ├── GetMapGoal.cs.meta
│ │ │ ├── GetMapResult.cs
│ │ │ ├── GetMapResult.cs.meta
│ │ │ ├── GetPlan.cs
│ │ │ ├── GetPlan.cs.meta
│ │ │ ├── GridCells.cs
│ │ │ ├── GridCells.cs.meta
│ │ │ ├── MapMetaData.cs
│ │ │ ├── MapMetaData.cs.meta
│ │ │ ├── OccupancyGrid.cs
│ │ │ ├── OccupancyGrid.cs.meta
│ │ │ ├── Odometry.cs
│ │ │ ├── Odometry.cs.meta
│ │ │ ├── Path.cs
│ │ │ ├── Path.cs.meta
│ │ │ ├── SetMap.cs
│ │ │ └── SetMap.cs.meta
│ │ ├── object_recognition_msgs.meta
│ │ ├── object_recognition_msgs
│ │ │ ├── GetObjectInformation.cs
│ │ │ ├── GetObjectInformation.cs.meta
│ │ │ ├── ObjectInformation.cs
│ │ │ ├── ObjectInformation.cs.meta
│ │ │ ├── ObjectRecognitionAction.cs
│ │ │ ├── ObjectRecognitionAction.cs.meta
│ │ │ ├── ObjectRecognitionActionFeedback.cs
│ │ │ ├── ObjectRecognitionActionFeedback.cs.meta
│ │ │ ├── ObjectRecognitionActionGoal.cs
│ │ │ ├── ObjectRecognitionActionGoal.cs.meta
│ │ │ ├── ObjectRecognitionActionResult.cs
│ │ │ ├── ObjectRecognitionActionResult.cs.meta
│ │ │ ├── ObjectRecognitionFeedback.cs
│ │ │ ├── ObjectRecognitionFeedback.cs.meta
│ │ │ ├── ObjectRecognitionGoal.cs
│ │ │ ├── ObjectRecognitionGoal.cs.meta
│ │ │ ├── ObjectRecognitionResult.cs
│ │ │ ├── ObjectRecognitionResult.cs.meta
│ │ │ ├── ObjectType.cs
│ │ │ ├── ObjectType.cs.meta
│ │ │ ├── RecognizedObject.cs
│ │ │ ├── RecognizedObject.cs.meta
│ │ │ ├── RecognizedObjectArray.cs
│ │ │ ├── RecognizedObjectArray.cs.meta
│ │ │ ├── Table.cs
│ │ │ ├── Table.cs.meta
│ │ │ ├── TableArray.cs
│ │ │ └── TableArray.cs.meta
│ │ ├── octomap_msgs.meta
│ │ ├── octomap_msgs
│ │ │ ├── BoundingBoxQuery.cs
│ │ │ ├── BoundingBoxQuery.cs.meta
│ │ │ ├── GetOctomap.cs
│ │ │ ├── GetOctomap.cs.meta
│ │ │ ├── Octomap.cs
│ │ │ ├── Octomap.cs.meta
│ │ │ ├── OctomapWithPose.cs
│ │ │ └── OctomapWithPose.cs.meta
│ │ ├── pcl_msgs.meta
│ │ ├── pcl_msgs
│ │ │ ├── ModelCoefficients.cs
│ │ │ ├── ModelCoefficients.cs.meta
│ │ │ ├── PointIndices.cs
│ │ │ ├── PointIndices.cs.meta
│ │ │ ├── PolygonMesh.cs
│ │ │ ├── PolygonMesh.cs.meta
│ │ │ ├── Vertices.cs
│ │ │ └── Vertices.cs.meta
│ │ ├── rock_publisher.meta
│ │ ├── rock_publisher
│ │ │ ├── imgData.cs
│ │ │ ├── imgData.cs.meta
│ │ │ ├── imgDataArray.cs
│ │ │ ├── imgDataArray.cs.meta
│ │ │ ├── recalibrateMsg.cs
│ │ │ └── recalibrateMsg.cs.meta
│ │ ├── roscpp_tutorials.meta
│ │ ├── roscpp_tutorials
│ │ │ ├── TwoInts.cs
│ │ │ └── TwoInts.cs.meta
│ │ ├── roscsharp.meta
│ │ ├── roscsharp
│ │ │ ├── GetLoggers.cs
│ │ │ ├── GetLoggers.cs.meta
│ │ │ ├── Logger.cs
│ │ │ ├── Logger.cs.meta
│ │ │ ├── SetLoggerLevel.cs
│ │ │ └── SetLoggerLevel.cs.meta
│ │ ├── rosgraph_msgs.meta
│ │ ├── rosgraph_msgs
│ │ │ ├── Clock.cs
│ │ │ ├── Clock.cs.meta
│ │ │ ├── Log.cs
│ │ │ └── Log.cs.meta
│ │ ├── sample_acquisition.meta
│ │ ├── sample_acquisition
│ │ │ ├── ArmMovement.cs
│ │ │ ├── ArmMovement.cs.meta
│ │ │ ├── ArmStatus.cs
│ │ │ └── ArmStatus.cs.meta
│ │ ├── sensor_msgs.meta
│ │ ├── sensor_msgs
│ │ │ ├── BatteryState.cs
│ │ │ ├── BatteryState.cs.meta
│ │ │ ├── CameraInfo.cs
│ │ │ ├── CameraInfo.cs.meta
│ │ │ ├── ChannelFloat32.cs
│ │ │ ├── ChannelFloat32.cs.meta
│ │ │ ├── CompressedImage.cs
│ │ │ ├── CompressedImage.cs.meta
│ │ │ ├── FluidPressure.cs
│ │ │ ├── FluidPressure.cs.meta
│ │ │ ├── Illuminance.cs
│ │ │ ├── Illuminance.cs.meta
│ │ │ ├── Image.cs
│ │ │ ├── Image.cs.meta
│ │ │ ├── Imu.cs
│ │ │ ├── Imu.cs.meta
│ │ │ ├── JointState.cs
│ │ │ ├── JointState.cs.meta
│ │ │ ├── Joy.cs
│ │ │ ├── Joy.cs.meta
│ │ │ ├── JoyFeedback.cs
│ │ │ ├── JoyFeedback.cs.meta
│ │ │ ├── JoyFeedbackArray.cs
│ │ │ ├── JoyFeedbackArray.cs.meta
│ │ │ ├── LaserEcho.cs
│ │ │ ├── LaserEcho.cs.meta
│ │ │ ├── LaserScan.cs
│ │ │ ├── LaserScan.cs.meta
│ │ │ ├── MagneticField.cs
│ │ │ ├── MagneticField.cs.meta
│ │ │ ├── MultiDOFJointState.cs
│ │ │ ├── MultiDOFJointState.cs.meta
│ │ │ ├── MultiEchoLaserScan.cs
│ │ │ ├── MultiEchoLaserScan.cs.meta
│ │ │ ├── NavSatFix.cs
│ │ │ ├── NavSatFix.cs.meta
│ │ │ ├── NavSatStatus.cs
│ │ │ ├── NavSatStatus.cs.meta
│ │ │ ├── PointCloud.cs
│ │ │ ├── PointCloud.cs.meta
│ │ │ ├── PointCloud2.cs
│ │ │ ├── PointCloud2.cs.meta
│ │ │ ├── PointField.cs
│ │ │ ├── PointField.cs.meta
│ │ │ ├── Range.cs
│ │ │ ├── Range.cs.meta
│ │ │ ├── RegionOfInterest.cs
│ │ │ ├── RegionOfInterest.cs.meta
│ │ │ ├── RelativeHumidity.cs
│ │ │ ├── RelativeHumidity.cs.meta
│ │ │ ├── SetCameraInfo.cs
│ │ │ ├── SetCameraInfo.cs.meta
│ │ │ ├── Temperature.cs
│ │ │ ├── Temperature.cs.meta
│ │ │ ├── TimeReference.cs
│ │ │ └── TimeReference.cs.meta
│ │ ├── shape_msgs.meta
│ │ ├── shape_msgs
│ │ │ ├── Mesh.cs
│ │ │ ├── Mesh.cs.meta
│ │ │ ├── MeshTriangle.cs
│ │ │ ├── MeshTriangle.cs.meta
│ │ │ ├── Plane.cs
│ │ │ ├── Plane.cs.meta
│ │ │ ├── SolidPrimitive.cs
│ │ │ └── SolidPrimitive.cs.meta
│ │ ├── stanford_msgs.meta
│ │ ├── stanford_msgs
│ │ │ ├── ExampleCustom.cs
│ │ │ └── ExampleCustom.cs.meta
│ │ ├── std_msgs.meta
│ │ ├── std_msgs
│ │ │ ├── Bool.cs
│ │ │ ├── Bool.cs.meta
│ │ │ ├── Byte.cs
│ │ │ ├── Byte.cs.meta
│ │ │ ├── ByteMultiArray.cs
│ │ │ ├── ByteMultiArray.cs.meta
│ │ │ ├── Char.cs
│ │ │ ├── Char.cs.meta
│ │ │ ├── ColorRGBA.cs
│ │ │ ├── ColorRGBA.cs.meta
│ │ │ ├── Duration.cs
│ │ │ ├── Duration.cs.meta
│ │ │ ├── Empty.cs
│ │ │ ├── Empty.cs.meta
│ │ │ ├── Float32.cs
│ │ │ ├── Float32.cs.meta
│ │ │ ├── Float32MultiArray.cs
│ │ │ ├── Float32MultiArray.cs.meta
│ │ │ ├── Float64.cs
│ │ │ ├── Float64.cs.meta
│ │ │ ├── Float64MultiArray.cs
│ │ │ ├── Float64MultiArray.cs.meta
│ │ │ ├── Header.cs
│ │ │ ├── Header.cs.meta
│ │ │ ├── Int16.cs
│ │ │ ├── Int16.cs.meta
│ │ │ ├── Int16MultiArray.cs
│ │ │ ├── Int16MultiArray.cs.meta
│ │ │ ├── Int32.cs
│ │ │ ├── Int32.cs.meta
│ │ │ ├── Int32MultiArray.cs
│ │ │ ├── Int32MultiArray.cs.meta
│ │ │ ├── Int64.cs
│ │ │ ├── Int64.cs.meta
│ │ │ ├── Int64MultiArray.cs
│ │ │ ├── Int64MultiArray.cs.meta
│ │ │ ├── Int8.cs
│ │ │ ├── Int8.cs.meta
│ │ │ ├── Int8MultiArray.cs
│ │ │ ├── Int8MultiArray.cs.meta
│ │ │ ├── MultiArrayDimension.cs
│ │ │ ├── MultiArrayDimension.cs.meta
│ │ │ ├── MultiArrayLayout.cs
│ │ │ ├── MultiArrayLayout.cs.meta
│ │ │ ├── String.cs
│ │ │ ├── String.cs.meta
│ │ │ ├── Time.cs
│ │ │ ├── Time.cs.meta
│ │ │ ├── UInt16.cs
│ │ │ ├── UInt16.cs.meta
│ │ │ ├── UInt16MultiArray.cs
│ │ │ ├── UInt16MultiArray.cs.meta
│ │ │ ├── UInt32.cs
│ │ │ ├── UInt32.cs.meta
│ │ │ ├── UInt32MultiArray.cs
│ │ │ ├── UInt32MultiArray.cs.meta
│ │ │ ├── UInt64.cs
│ │ │ ├── UInt64.cs.meta
│ │ │ ├── UInt64MultiArray.cs
│ │ │ ├── UInt64MultiArray.cs.meta
│ │ │ ├── UInt8.cs
│ │ │ ├── UInt8.cs.meta
│ │ │ ├── UInt8MultiArray.cs
│ │ │ └── UInt8MultiArray.cs.meta
│ │ ├── std_srvs.meta
│ │ ├── std_srvs
│ │ │ ├── Empty.cs
│ │ │ ├── Empty.cs.meta
│ │ │ ├── SetBool.cs
│ │ │ ├── SetBool.cs.meta
│ │ │ ├── Trigger.cs
│ │ │ └── Trigger.cs.meta
│ │ ├── tf.meta
│ │ ├── tf
│ │ │ ├── FrameGraph.cs
│ │ │ ├── FrameGraph.cs.meta
│ │ │ ├── tfMessage.cs
│ │ │ └── tfMessage.cs.meta
│ │ ├── tf2_msgs.meta
│ │ ├── tf2_msgs
│ │ │ ├── FrameGraph.cs
│ │ │ ├── FrameGraph.cs.meta
│ │ │ ├── LookupTransformAction.cs
│ │ │ ├── LookupTransformAction.cs.meta
│ │ │ ├── LookupTransformActionFeedback.cs
│ │ │ ├── LookupTransformActionFeedback.cs.meta
│ │ │ ├── LookupTransformActionGoal.cs
│ │ │ ├── LookupTransformActionGoal.cs.meta
│ │ │ ├── LookupTransformActionResult.cs
│ │ │ ├── LookupTransformActionResult.cs.meta
│ │ │ ├── LookupTransformFeedback.cs
│ │ │ ├── LookupTransformFeedback.cs.meta
│ │ │ ├── LookupTransformGoal.cs
│ │ │ ├── LookupTransformGoal.cs.meta
│ │ │ ├── LookupTransformResult.cs
│ │ │ ├── LookupTransformResult.cs.meta
│ │ │ ├── TF2Error.cs
│ │ │ ├── TF2Error.cs.meta
│ │ │ ├── TFMessage.cs
│ │ │ └── TFMessage.cs.meta
│ │ ├── theora_image_transport.meta
│ │ ├── theora_image_transport
│ │ │ ├── Packet.cs
│ │ │ └── Packet.cs.meta
│ │ ├── topic_tools.meta
│ │ ├── topic_tools
│ │ │ ├── DemuxAdd.cs
│ │ │ ├── DemuxAdd.cs.meta
│ │ │ ├── DemuxDelete.cs
│ │ │ ├── DemuxDelete.cs.meta
│ │ │ ├── DemuxList.cs
│ │ │ ├── DemuxList.cs.meta
│ │ │ ├── DemuxSelect.cs
│ │ │ ├── DemuxSelect.cs.meta
│ │ │ ├── MuxAdd.cs
│ │ │ ├── MuxAdd.cs.meta
│ │ │ ├── MuxDelete.cs
│ │ │ ├── MuxDelete.cs.meta
│ │ │ ├── MuxList.cs
│ │ │ ├── MuxList.cs.meta
│ │ │ ├── MuxSelect.cs
│ │ │ └── MuxSelect.cs.meta
│ │ ├── trajectory_msgs.meta
│ │ ├── trajectory_msgs
│ │ │ ├── JointTrajectory.cs
│ │ │ ├── JointTrajectory.cs.meta
│ │ │ ├── JointTrajectoryPoint.cs
│ │ │ ├── JointTrajectoryPoint.cs.meta
│ │ │ ├── MultiDOFJointTrajectory.cs
│ │ │ ├── MultiDOFJointTrajectory.cs.meta
│ │ │ ├── MultiDOFJointTrajectoryPoint.cs
│ │ │ └── MultiDOFJointTrajectoryPoint.cs.meta
│ │ ├── trust_msgs.meta
│ │ ├── trust_msgs
│ │ │ ├── InterfaceCommand.cs
│ │ │ ├── InterfaceCommand.cs.meta
│ │ │ ├── RunDescription.cs
│ │ │ └── RunDescription.cs.meta
│ │ ├── uvc_camera.meta
│ │ ├── uvc_camera
│ │ │ ├── camera_sliders.cs
│ │ │ └── camera_sliders.cs.meta
│ │ ├── whosonfirst.meta
│ │ ├── whosonfirst
│ │ │ ├── Dibs.cs
│ │ │ └── Dibs.cs.meta
│ │ ├── wpf_msgs.meta
│ │ └── wpf_msgs
│ │ │ ├── Point2.cs
│ │ │ ├── Point2.cs.meta
│ │ │ ├── Waypoints.cs
│ │ │ ├── Waypoints.cs.meta
│ │ │ ├── WindowState.cs
│ │ │ └── WindowState.cs.meta
│ │ ├── ROS_Comm.meta
│ │ ├── ROS_Comm
│ │ ├── AdvertiseOptions.cs
│ │ ├── AdvertiseOptions.cs.meta
│ │ ├── AdvertiseServiceOptions.cs
│ │ ├── AdvertiseServiceOptions.cs.meta
│ │ ├── CallbackInterface.cs
│ │ ├── CallbackInterface.cs.meta
│ │ ├── CallbackQueue.cs
│ │ ├── CallbackQueue.cs.meta
│ │ ├── Connection.cs
│ │ ├── Connection.cs.meta
│ │ ├── ConnectionManager.cs
│ │ ├── ConnectionManager.cs.meta
│ │ ├── Header.cs
│ │ ├── Header.cs.meta
│ │ ├── LocalPublisherLink.cs
│ │ ├── LocalPublisherLink.cs.meta
│ │ ├── LocalSubscriberLink.cs
│ │ ├── LocalSubscriberLink.cs.meta
│ │ ├── Master.cs
│ │ ├── Master.cs.meta
│ │ ├── MessageAndSerializerFunc.cs
│ │ ├── MessageAndSerializerFunc.cs.meta
│ │ ├── NodeHandle.cs
│ │ ├── NodeHandle.cs.meta
│ │ ├── Param.cs
│ │ ├── Param.cs.meta
│ │ ├── PendingConnection.cs
│ │ ├── PendingConnection.cs.meta
│ │ ├── PollManager.cs
│ │ ├── PollManager.cs.meta
│ │ ├── PollSet.cs
│ │ ├── PollSet.cs.meta
│ │ ├── Publication.cs
│ │ ├── Publication.cs.meta
│ │ ├── Publisher.cs
│ │ ├── Publisher.cs.meta
│ │ ├── PublisherLink.cs
│ │ ├── PublisherLink.cs.meta
│ │ ├── RemappingHelper.cs
│ │ ├── RemappingHelper.cs.meta
│ │ ├── RosOutAppender.cs
│ │ ├── RosOutAppender.cs.meta
│ │ ├── ScopedTimer.cs
│ │ ├── ScopedTimer.cs.meta
│ │ ├── Service.cs
│ │ ├── Service.cs.meta
│ │ ├── ServiceCallbackHelper.cs
│ │ ├── ServiceCallbackHelper.cs.meta
│ │ ├── ServiceClient.cs
│ │ ├── ServiceClient.cs.meta
│ │ ├── ServiceClientLink.cs
│ │ ├── ServiceClientLink.cs.meta
│ │ ├── ServiceClientOptions.cs
│ │ ├── ServiceClientOptions.cs.meta
│ │ ├── ServiceManager.cs
│ │ ├── ServiceManager.cs.meta
│ │ ├── ServicePublication.cs
│ │ ├── ServicePublication.cs.meta
│ │ ├── ServiceServer.cs
│ │ ├── ServiceServer.cs.meta
│ │ ├── ServiceServerLink.cs
│ │ ├── ServiceServerLink.cs.meta
│ │ ├── SingleSubscriberPublisher.cs
│ │ ├── SingleSubscriberPublisher.cs.meta
│ │ ├── Socket.cs
│ │ ├── Socket.cs.meta
│ │ ├── Spinner.cs
│ │ ├── Spinner.cs.meta
│ │ ├── SubscribeOptions.cs
│ │ ├── SubscribeOptions.cs.meta
│ │ ├── Subscriber.cs
│ │ ├── Subscriber.cs.meta
│ │ ├── SubscriberCallbacks.cs
│ │ ├── SubscriberCallbacks.cs.meta
│ │ ├── SubscriberLink.cs
│ │ ├── SubscriberLink.cs.meta
│ │ ├── Subscription.cs
│ │ ├── Subscription.cs.meta
│ │ ├── SubscriptionCallbackHelper.cs
│ │ ├── SubscriptionCallbackHelper.cs.meta
│ │ ├── TcpTransport.cs
│ │ ├── TcpTransport.cs.meta
│ │ ├── Time.cs
│ │ ├── Time.cs.meta
│ │ ├── TimerManager.cs
│ │ ├── TimerManager.cs.meta
│ │ ├── TopicInfo.cs
│ │ ├── TopicInfo.cs.meta
│ │ ├── TopicManager.cs
│ │ ├── TopicManager.cs.meta
│ │ ├── TransportPublisherLink.cs
│ │ ├── TransportPublisherLink.cs.meta
│ │ ├── TransportSubscriberLink.cs
│ │ ├── TransportSubscriberLink.cs.meta
│ │ ├── XmlRpcManager.cs
│ │ ├── XmlRpcManager.cs.meta
│ │ ├── _Init.cs
│ │ ├── _Init.cs.meta
│ │ ├── names.cs
│ │ ├── names.cs.meta
│ │ ├── network.cs
│ │ ├── network.cs.meta
│ │ ├── this_node.cs
│ │ └── this_node.cs.meta
│ │ ├── XmlRpc_Wrapper.meta
│ │ └── XmlRpc_Wrapper
│ │ ├── AsyncXmlRpcConnection.cs
│ │ ├── AsyncXmlRpcConnection.cs.meta
│ │ ├── XMLRPCCallWrapper.cs
│ │ ├── XMLRPCCallWrapper.cs.meta
│ │ ├── XmlRpcClient.cs
│ │ ├── XmlRpcClient.cs.meta
│ │ ├── XmlRpcDispatch.cs
│ │ ├── XmlRpcDispatch.cs.meta
│ │ ├── XmlRpcServer.cs
│ │ ├── XmlRpcServer.cs.meta
│ │ ├── XmlRpcServerConnection.cs
│ │ ├── XmlRpcServerConnection.cs.meta
│ │ ├── XmlRpcSource.cs
│ │ ├── XmlRpcSource.cs.meta
│ │ ├── XmlRpcUtil.cs
│ │ ├── XmlRpcUtil.cs.meta
│ │ ├── XmlRpcValue.cs
│ │ └── XmlRpcValue.cs.meta
├── Scenes.meta
├── Scenes
│ ├── SampleScene.unity
│ └── SampleScene.unity.meta
├── Scripts.meta
├── Scripts
│ ├── ROSController.cs
│ └── ROSController.cs.meta
├── mcs.rsp
└── mcs.rsp.meta
├── Packages
└── manifest.json
├── ProjectSettings
├── AudioManager.asset
├── ClusterInputManager.asset
├── DynamicsManager.asset
├── EditorBuildSettings.asset
├── EditorSettings.asset
├── GraphicsSettings.asset
├── InputManager.asset
├── NavMeshAreas.asset
├── NetworkManager.asset
├── Physics2DSettings.asset
├── PresetManager.asset
├── ProjectSettings.asset
├── ProjectVersion.txt
├── QualitySettings.asset
├── TagManager.asset
├── TimeManager.asset
└── UnityConnectSettings.asset
├── README.md
├── ROSNetUnity
├── .ROS_NOBUILD
├── CompressedImageView
│ ├── App.xaml
│ ├── App.xaml.cs
│ ├── CompressedImageView.csproj
│ ├── MainWindow.xaml
│ ├── MainWindow.xaml.cs
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ └── app.config
├── DynamicReconfigure
│ ├── DynamicReconfigure.cs
│ ├── DynamicReconfigure.csproj
│ └── Properties
│ │ └── AssemblyInfo.cs
├── DynamicReconfigureSharp
│ ├── App.xaml
│ ├── App.xaml.cs
│ ├── DynamicReconfigureCheckbox.xaml
│ ├── DynamicReconfigureCheckbox.xaml.cs
│ ├── DynamicReconfigureGroup.xaml
│ ├── DynamicReconfigureGroup.xaml.cs
│ ├── DynamicReconfigurePage.xaml
│ ├── DynamicReconfigurePage.xaml.cs
│ ├── DynamicReconfigureSharp.csproj
│ ├── DynamicReconfigureSlider.xaml
│ ├── DynamicReconfigureSlider.xaml.cs
│ ├── DynamicReconfigureStringBox.xaml
│ ├── DynamicReconfigureStringBox.xaml.cs
│ ├── DynamicReconfigureStringDropdown.xaml
│ ├── DynamicReconfigureStringDropdown.xaml.cs
│ ├── IDynamicReconfigureLayout.cs
│ ├── MainWindow.xaml
│ ├── MainWindow.xaml.cs
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ └── app.config
├── DynamicReconfigure_dotNET.sln
├── Icon.png
├── LICENSE
├── Listener
│ ├── Listener.csproj
│ ├── Program.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ └── app.config
├── Logo.png
├── MD5SumTest
│ ├── MD5SumTest.csproj
│ ├── MD5Test.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── bin
│ │ └── Debug
│ │ │ ├── Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll
│ │ │ ├── XmlRpc_Wrapper.dll
│ │ │ ├── XmlRpc_Wrapper.pdb
│ │ │ ├── YAMLParser.exe
│ │ │ ├── YAMLParser.exe.config
│ │ │ └── YAMLParser.pdb
│ ├── msg_sums.txt
│ ├── srv_sums.txt
│ ├── test_resources.Designer.cs
│ └── test_resources.resx
├── MeshLib
│ ├── MeshLib.csproj
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── RobotDescriptionParser.cs
│ └── collada_schema_1_4.cs
├── MessageSerializationTests
│ ├── MessageSerializationTests.csproj
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── RandomizeSerializeDeserializeTestClass.cs
│ └── bin
│ │ └── Debug
│ │ ├── Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll
│ │ ├── YAMLParser.exe
│ │ ├── YAMLParser.exe.config
│ │ └── YAMLParser.pdb
├── README.md
├── ROS_Comm
│ ├── AdvertiseOptions.cs
│ ├── AdvertiseServiceOptions.cs
│ ├── CallbackInterface.cs
│ ├── CallbackQueue.cs
│ ├── Connection.cs
│ ├── ConnectionManager.cs
│ ├── Header.cs
│ ├── LocalPublisherLink.cs
│ ├── LocalSubscriberLink.cs
│ ├── Master.cs
│ ├── MessageAndSerializerFunc.cs
│ ├── NodeHandle.cs
│ ├── Param.cs
│ ├── PendingConnection.cs
│ ├── PollManager.cs
│ ├── PollSet.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── Publication.cs
│ ├── Publisher.cs
│ ├── PublisherLink.cs
│ ├── ROS_C-Sharp.csproj
│ ├── ROS_C-Sharp_UNITY.csproj
│ ├── RemappingHelper.cs
│ ├── RosOutAppender.cs
│ ├── ScopedTimer.cs
│ ├── Service.cs
│ ├── ServiceCallbackHelper.cs
│ ├── ServiceClient.cs
│ ├── ServiceClientLink.cs
│ ├── ServiceClientOptions.cs
│ ├── ServiceManager.cs
│ ├── ServicePublication.cs
│ ├── ServiceServer.cs
│ ├── ServiceServerLink.cs
│ ├── SingleSubscriberPublisher.cs
│ ├── Socket.cs
│ ├── Spinner.cs
│ ├── SubscribeOptions.cs
│ ├── Subscriber.cs
│ ├── SubscriberCallbacks.cs
│ ├── SubscriberLink.cs
│ ├── Subscription.cs
│ ├── SubscriptionCallbackHelper.cs
│ ├── TcpTransport.cs
│ ├── Time.cs
│ ├── TimerManager.cs
│ ├── TopicInfo.cs
│ ├── TopicManager.cs
│ ├── TransportPublisherLink.cs
│ ├── TransportSubscriberLink.cs
│ ├── XmlRpcManager.cs
│ ├── _Init.cs
│ ├── bin
│ │ └── Debug
│ │ │ ├── XmlRpc_Wrapper.dll
│ │ │ ├── XmlRpc_Wrapper.pdb
│ │ │ ├── YAMLParser.exe
│ │ │ ├── YAMLParser.exe.config
│ │ │ └── YAMLParser.pdb
│ ├── names.cs
│ ├── network.cs
│ └── this_node.cs
├── ROS_ImageUtils
│ ├── CompressedImageControl.xaml
│ ├── CompressedImageControl.xaml.cs
│ ├── GenericImage.xaml
│ ├── GenericImage.xaml.cs
│ ├── ImageControl.xaml
│ ├── ImageControl.xaml.cs
│ ├── MapControl.xaml
│ ├── MapControl.xaml.cs
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ ├── ROS_ImageWPF.csproj
│ ├── WindowScraper.cs
│ ├── bin
│ │ └── Debug
│ │ │ ├── XmlRpc_Wrapper.dll
│ │ │ └── XmlRpc_Wrapper.pdb
│ └── iROSImage.cs
├── ROS_dotNET.sln
├── ROS_dotNET_ROS_SAMPLES.sln
├── RosParamClient
│ ├── Program.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── RosParamClient.csproj
│ ├── app.config
│ └── bin
│ │ └── Debug
│ │ ├── XmlRpc_Wrapper.dll
│ │ ├── XmlRpc_Wrapper.pdb
│ │ └── rosparam.exe.config
├── RosoutDebugUC
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ ├── RDUC.xaml
│ ├── RDUC.xaml.cs
│ └── RosoutDebugUC.csproj
├── ServiceClientSample
│ ├── App.xaml
│ ├── App.xaml.cs
│ ├── MainWindow.xaml
│ ├── MainWindow.xaml.cs
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ ├── ServiceClientSample.csproj
│ └── app.config
├── ServiceServerSample
│ ├── App.xaml
│ ├── App.xaml.cs
│ ├── MainWindow.xaml
│ ├── MainWindow.xaml.cs
│ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ ├── ServiceServerSample.csproj
│ └── app.config
├── SimplePublisher
│ ├── SimplePublisher.sln
│ └── SimplePublisher
│ │ ├── App.xaml
│ │ ├── App.xaml.cs
│ │ ├── MainWindow.xaml
│ │ ├── MainWindow.xaml.cs
│ │ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ │ ├── SimplePublisher.csproj
│ │ └── app.config
├── SimpleSubscriber
│ ├── SimpleSubscriber.sln
│ └── SimpleSubscriber
│ │ ├── App.xaml
│ │ ├── App.xaml.cs
│ │ ├── MainWindow.xaml
│ │ ├── MainWindow.xaml.cs
│ │ ├── Properties
│ │ ├── AssemblyInfo.cs
│ │ ├── Resources.Designer.cs
│ │ ├── Resources.resx
│ │ ├── Settings.Designer.cs
│ │ └── Settings.settings
│ │ ├── SimpleSubscriber.csproj
│ │ └── app.config
├── Talker
│ ├── Program.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── Talker.csproj
│ └── app.config
├── Template_ROS_dotNET.sln
├── TransformTest
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── TransformTest.csproj
│ └── UnitTest1.cs
├── TransformTestLib
│ ├── Class1.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ └── TransformTestLib.csproj
├── XNA_Image_Example
│ ├── XNA_Image_Example.sln
│ ├── XNA_Image_Example
│ │ ├── Game.ico
│ │ ├── Game1.cs
│ │ ├── GameThumbnail.png
│ │ ├── Program.cs
│ │ ├── Properties
│ │ │ └── AssemblyInfo.cs
│ │ └── XNA_Image_Example.csproj
│ └── XNA_Image_ExampleContent
│ │ └── XNA_Image_ExampleContent.contentproj
├── XmlRpc_Wrapper
│ ├── AsyncXmlRpcConnection.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── XMLRPCCallWrapper.cs
│ ├── XmlRpcClient.cs
│ ├── XmlRpcDispatch.cs
│ ├── XmlRpcServer.cs
│ ├── XmlRpcServerConnection.cs
│ ├── XmlRpcSource.cs
│ ├── XmlRpcUtil.cs
│ ├── XmlRpcValue.cs
│ ├── XmlRpc_Wrapper.csproj
│ ├── XmlRpc_Wrapper_UNITY.csproj
│ └── bin
│ │ └── Debug
│ │ ├── XmlRpc_Wrapper.dll
│ │ └── XmlRpc_Wrapper.pdb
├── YAMLParser
│ ├── FileUtils.cs
│ ├── GenerationGuts.cs
│ ├── GenerationGuts.tmp.cs
│ ├── MD5.cs
│ ├── MessageTypes.cs
│ ├── MsgFileLocator.cs
│ ├── PInvokeAllUpInYoGrill.cs
│ ├── Program.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── ROS_MESSAGES
│ │ └── README.txt
│ ├── TemplateProject
│ │ ├── AssemblyInfo._cs
│ │ ├── Interfaces.cs
│ │ ├── Messages._csproj
│ │ ├── PlaceHolder._cs
│ │ ├── SecondPass.cs
│ │ ├── SrvPlaceHolder._cs
│ │ ├── String.cs
│ │ ├── TempMessages._csproj
│ │ └── Time.cs
│ ├── Templates.Designer.cs
│ ├── Templates.resx
│ ├── YAMLParser.csproj
│ ├── YAMLParser_UNITY.csproj
│ ├── app.config
│ └── bin
│ │ └── Debug
│ │ ├── YAMLParser.exe
│ │ ├── YAMLParser.exe.config
│ │ └── YAMLParser.pdb
├── common_msgs
│ ├── ServiceTest
│ │ └── AddTwoInts.srv
│ ├── actionlib_msgs
│ │ ├── GoalID.msg
│ │ ├── GoalStatus.msg
│ │ └── GoalStatusArray.msg
│ ├── baxter_core_msgs
│ │ ├── msg
│ │ │ ├── AnalogIOState.msg
│ │ │ ├── AnalogIOStates.msg
│ │ │ ├── AnalogOutputCommand.msg
│ │ │ ├── AssemblyState.msg
│ │ │ ├── AssemblyStates.msg
│ │ │ ├── CameraControl.msg
│ │ │ ├── CameraSettings.msg
│ │ │ ├── CollisionAvoidanceState.msg
│ │ │ ├── CollisionDetectionState.msg
│ │ │ ├── DigitalIOState.msg
│ │ │ ├── DigitalIOStates.msg
│ │ │ ├── DigitalOutputCommand.msg
│ │ │ ├── EndEffectorCommand.msg
│ │ │ ├── EndEffectorProperties.msg
│ │ │ ├── EndEffectorState.msg
│ │ │ ├── EndpointState.msg
│ │ │ ├── EndpointStates.msg
│ │ │ ├── HeadPanCommand.msg
│ │ │ ├── HeadState.msg
│ │ │ ├── ITBState.msg
│ │ │ ├── ITBStates.msg
│ │ │ ├── JointCommand.msg
│ │ │ ├── NavigatorState.msg
│ │ │ ├── NavigatorStates.msg
│ │ │ ├── RobustControllerStatus.msg
│ │ │ └── SEAJointState.msg
│ │ └── srv
│ │ │ ├── CloseCamera.srv
│ │ │ ├── ListCameras.srv
│ │ │ ├── OpenCamera.srv
│ │ │ └── SolvePositionIK.srv
│ ├── control_msgs
│ │ ├── action
│ │ │ ├── FollowJointTrajectory.action
│ │ │ ├── GripperCommand.action
│ │ │ ├── JointTrajectory.action
│ │ │ ├── PointHead.action
│ │ │ └── SingleJointPosition.action
│ │ ├── msg
│ │ │ ├── FollowJointTrajectoryAction.msg
│ │ │ ├── FollowJointTrajectoryActionFeedback.msg
│ │ │ ├── FollowJointTrajectoryActionGoal.msg
│ │ │ ├── FollowJointTrajectoryActionResult.msg
│ │ │ ├── FollowJointTrajectoryFeedback.msg
│ │ │ ├── FollowJointTrajectoryGoal.msg
│ │ │ ├── FollowJointTrajectoryResult.msg
│ │ │ ├── GripperCommand.msg
│ │ │ ├── GripperCommandAction.msg
│ │ │ ├── GripperCommandActionFeedback.msg
│ │ │ ├── GripperCommandActionGoal.msg
│ │ │ ├── GripperCommandActionResult.msg
│ │ │ ├── GripperCommandFeedback.msg
│ │ │ ├── GripperCommandGoal.msg
│ │ │ ├── GripperCommandResult.msg
│ │ │ ├── JointControllerState.msg
│ │ │ ├── JointTolerance.msg
│ │ │ ├── JointTrajectoryAction.msg
│ │ │ ├── JointTrajectoryActionFeedback.msg
│ │ │ ├── JointTrajectoryActionGoal.msg
│ │ │ ├── JointTrajectoryActionResult.msg
│ │ │ ├── JointTrajectoryControllerState.msg
│ │ │ ├── JointTrajectoryFeedback.msg
│ │ │ ├── JointTrajectoryGoal.msg
│ │ │ ├── JointTrajectoryResult.msg
│ │ │ ├── PidState.msg
│ │ │ ├── PointHeadAction.msg
│ │ │ ├── PointHeadActionFeedback.msg
│ │ │ ├── PointHeadActionGoal.msg
│ │ │ ├── PointHeadActionResult.msg
│ │ │ ├── PointHeadFeedback.msg
│ │ │ ├── PointHeadGoal.msg
│ │ │ ├── PointHeadResult.msg
│ │ │ ├── SingleJointPositionAction.msg
│ │ │ ├── SingleJointPositionActionFeedback.msg
│ │ │ ├── SingleJointPositionActionGoal.msg
│ │ │ ├── SingleJointPositionActionResult.msg
│ │ │ ├── SingleJointPositionFeedback.msg
│ │ │ ├── SingleJointPositionGoal.msg
│ │ │ └── SingleJointPositionResult.msg
│ │ └── srv
│ │ │ ├── QueryCalibrationState.srv
│ │ │ └── QueryTrajectoryState.srv
│ ├── custom_msgs
│ │ ├── arrayofdeez.msg
│ │ ├── arraytest.msg
│ │ ├── cgeo.msg
│ │ ├── ptz.msg
│ │ ├── robotMortality.msg
│ │ ├── servosPos.msg
│ │ └── simpleintarray.msg
│ ├── dynamic_reconfigure
│ │ ├── msg
│ │ │ ├── BoolParameter.msg
│ │ │ ├── Config.msg
│ │ │ ├── ConfigDescription.msg
│ │ │ ├── DoubleParameter.msg
│ │ │ ├── Group.msg
│ │ │ ├── GroupState.msg
│ │ │ ├── IntParameter.msg
│ │ │ ├── ParamDescription.msg
│ │ │ ├── SensorLevels.msg
│ │ │ └── StrParameter.msg
│ │ └── srv
│ │ │ └── Reconfigure.srv
│ ├── dynamixel_msgs
│ │ └── JointState.msg
│ ├── experiment
│ │ └── SimonSays.msg
│ ├── gazebo_msgs
│ │ ├── msg
│ │ │ ├── ContactState.msg
│ │ │ ├── ContactsState.msg
│ │ │ ├── LinkState.msg
│ │ │ ├── LinkStates.msg
│ │ │ ├── ModelState.msg
│ │ │ ├── ModelStates.msg
│ │ │ ├── ODEJointProperties.msg
│ │ │ ├── ODEPhysics.msg
│ │ │ └── WorldState.msg
│ │ └── srv
│ │ │ ├── ApplyBodyWrench.srv
│ │ │ ├── ApplyJointEffort.srv
│ │ │ ├── BodyRequest.srv
│ │ │ ├── DeleteModel.srv
│ │ │ ├── GetJointProperties.srv
│ │ │ ├── GetLinkProperties.srv
│ │ │ ├── GetLinkState.srv
│ │ │ ├── GetModelProperties.srv
│ │ │ ├── GetModelState.srv
│ │ │ ├── GetPhysicsProperties.srv
│ │ │ ├── GetWorldProperties.srv
│ │ │ ├── JointRequest.srv
│ │ │ ├── SetJointProperties.srv
│ │ │ ├── SetJointTrajectory.srv
│ │ │ ├── SetLinkProperties.srv
│ │ │ ├── SetLinkState.srv
│ │ │ ├── SetModelConfiguration.srv
│ │ │ ├── SetModelState.srv
│ │ │ ├── SetPhysicsProperties.srv
│ │ │ └── SpawnModel.srv
│ ├── geometry_msgs
│ │ ├── Point.msg
│ │ ├── Point32.msg
│ │ ├── PointStamped.msg
│ │ ├── Polygon.msg
│ │ ├── PolygonStamped.msg
│ │ ├── Pose.msg
│ │ ├── Pose2D.msg
│ │ ├── PoseArray.msg
│ │ ├── PoseStamped.msg
│ │ ├── PoseWithCovariance.msg
│ │ ├── PoseWithCovarianceStamped.msg
│ │ ├── Quaternion.msg
│ │ ├── QuaternionStamped.msg
│ │ ├── Transform.msg
│ │ ├── TransformStamped.msg
│ │ ├── Twist.msg
│ │ ├── TwistStamped.msg
│ │ ├── TwistWithCovariance.msg
│ │ ├── TwistWithCovarianceStamped.msg
│ │ ├── Vector3.msg
│ │ ├── Vector3Stamped.msg
│ │ ├── Wrench.msg
│ │ └── WrenchStamped.msg
│ ├── histogram_msgs
│ │ ├── MCLSnapshot.msg
│ │ └── histogramsnapshot.msg
│ ├── humanoid_nav_msgs
│ │ ├── action
│ │ │ └── ExecFootsteps.action
│ │ ├── msg
│ │ │ ├── ExecFootstepsAction.msg
│ │ │ ├── ExecFootstepsActionFeedback.msg
│ │ │ ├── ExecFootstepsActionGoal.msg
│ │ │ ├── ExecFootstepsActionResult.msg
│ │ │ ├── ExecFootstepsFeedback.msg
│ │ │ ├── ExecFootstepsGoal.msg
│ │ │ ├── ExecFootstepsResult.msg
│ │ │ └── StepTarget.msg
│ │ └── srv
│ │ │ ├── ClipFootstep.srv
│ │ │ ├── PlanFootsteps.srv
│ │ │ ├── PlanFootstepsBetweenFeet.srv
│ │ │ └── StepTargetService.srv
│ ├── map_msgs
│ │ ├── msg
│ │ │ ├── OccupancyGridUpdate.msg
│ │ │ ├── PointCloud2Update.msg
│ │ │ ├── ProjectedMap.msg
│ │ │ └── ProjectedMapInfo.msg
│ │ └── srv
│ │ │ ├── GetMapROI.srv
│ │ │ ├── GetPointMap.srv
│ │ │ ├── GetPointMapROI.srv
│ │ │ ├── ProjectedMapsInfo.srv
│ │ │ ├── SaveMap.srv
│ │ │ └── SetMapProjections.srv
│ ├── move_base_msgs
│ │ ├── action
│ │ │ └── MoveBase.action
│ │ └── msg
│ │ │ ├── MoveBaseAction.msg
│ │ │ ├── MoveBaseActionFeedback.msg
│ │ │ ├── MoveBaseActionGoal.msg
│ │ │ ├── MoveBaseActionResult.msg
│ │ │ ├── MoveBaseFeedback.msg
│ │ │ ├── MoveBaseGoal.msg
│ │ │ └── MoveBaseResult.msg
│ ├── nav_msgs
│ │ ├── action
│ │ │ └── GetMap.action
│ │ ├── msg
│ │ │ ├── GetMapAction.msg
│ │ │ ├── GetMapActionFeedback.msg
│ │ │ ├── GetMapActionGoal.msg
│ │ │ ├── GetMapActionResult.msg
│ │ │ ├── GetMapFeedback.msg
│ │ │ ├── GetMapGoal.msg
│ │ │ ├── GetMapResult.msg
│ │ │ ├── GridCells.msg
│ │ │ ├── MapMetaData.msg
│ │ │ ├── OccupancyGrid.msg
│ │ │ ├── Odometry.msg
│ │ │ └── Path.msg
│ │ └── srv
│ │ │ ├── GetMap.srv
│ │ │ ├── GetPlan.srv
│ │ │ └── SetMap.srv
│ ├── object_recognition_msgs
│ │ ├── action
│ │ │ └── ObjectRecognition.action
│ │ ├── msg
│ │ │ ├── ObjectInformation.msg
│ │ │ ├── ObjectRecognitionAction.msg
│ │ │ ├── ObjectRecognitionActionFeedback.msg
│ │ │ ├── ObjectRecognitionActionGoal.msg
│ │ │ ├── ObjectRecognitionActionResult.msg
│ │ │ ├── ObjectRecognitionFeedback.msg
│ │ │ ├── ObjectRecognitionGoal.msg
│ │ │ ├── ObjectRecognitionResult.msg
│ │ │ ├── ObjectType.msg
│ │ │ ├── RecognizedObject.msg
│ │ │ ├── RecognizedObjectArray.msg
│ │ │ ├── Table.msg
│ │ │ └── TableArray.msg
│ │ └── srv
│ │ │ └── GetObjectInformation.srv
│ ├── octomap_msgs
│ │ ├── msg
│ │ │ ├── Octomap.msg
│ │ │ └── OctomapWithPose.msg
│ │ └── srv
│ │ │ ├── BoundingBoxQuery.srv
│ │ │ └── GetOctomap.srv
│ ├── pcl_msgs
│ │ └── msg
│ │ │ ├── ModelCoefficients.msg
│ │ │ ├── PointIndices.msg
│ │ │ ├── PolygonMesh.msg
│ │ │ └── Vertices.msg
│ ├── rock_publisher
│ │ ├── imgData.msg
│ │ ├── imgDataArray.msg
│ │ └── recalibrateMsg.msg
│ ├── roscpp_tutorials
│ │ └── TwoInts.srv
│ ├── roscsharp
│ │ ├── GetLoggers.srv
│ │ ├── Logger.msg
│ │ └── SetLoggerLevel.srv
│ ├── rosgraph_msgs
│ │ ├── Clock.msg
│ │ └── Log.msg
│ ├── sample_acquisition
│ │ ├── ArmMovement.msg
│ │ └── ArmStatus.msg
│ ├── sensor_msgs
│ │ ├── msg
│ │ │ ├── BatteryState.msg
│ │ │ ├── CameraInfo.msg
│ │ │ ├── ChannelFloat32.msg
│ │ │ ├── CompressedImage.msg
│ │ │ ├── FluidPressure.msg
│ │ │ ├── Illuminance.msg
│ │ │ ├── Image.msg
│ │ │ ├── Imu.msg
│ │ │ ├── JointState.msg
│ │ │ ├── Joy.msg
│ │ │ ├── JoyFeedback.msg
│ │ │ ├── JoyFeedbackArray.msg
│ │ │ ├── LaserEcho.msg
│ │ │ ├── LaserScan.msg
│ │ │ ├── MagneticField.msg
│ │ │ ├── MultiDOFJointState.msg
│ │ │ ├── MultiEchoLaserScan.msg
│ │ │ ├── NavSatFix.msg
│ │ │ ├── NavSatStatus.msg
│ │ │ ├── PointCloud.msg
│ │ │ ├── PointCloud2.msg
│ │ │ ├── PointField.msg
│ │ │ ├── Range.msg
│ │ │ ├── RegionOfInterest.msg
│ │ │ ├── RelativeHumidity.msg
│ │ │ ├── Temperature.msg
│ │ │ └── TimeReference.msg
│ │ └── srv
│ │ │ └── SetCameraInfo.srv
│ ├── shape_msgs
│ │ └── msg
│ │ │ ├── Mesh.msg
│ │ │ ├── MeshTriangle.msg
│ │ │ ├── Plane.msg
│ │ │ └── SolidPrimitive.msg
│ ├── stanford_msgs
│ │ └── ExampleCustom.msg
│ ├── std_msgs
│ │ └── msg
│ │ │ ├── Bool.msg
│ │ │ ├── Byte.msg
│ │ │ ├── ByteMultiArray.msg
│ │ │ ├── Char.msg
│ │ │ ├── ColorRGBA.msg
│ │ │ ├── Duration.msg
│ │ │ ├── Empty.msg
│ │ │ ├── Float32.msg
│ │ │ ├── Float32MultiArray.msg
│ │ │ ├── Float64.msg
│ │ │ ├── Float64MultiArray.msg
│ │ │ ├── Header.msg
│ │ │ ├── Int16.msg
│ │ │ ├── Int16MultiArray.msg
│ │ │ ├── Int32.msg
│ │ │ ├── Int32MultiArray.msg
│ │ │ ├── Int64.msg
│ │ │ ├── Int64MultiArray.msg
│ │ │ ├── Int8.msg
│ │ │ ├── Int8MultiArray.msg
│ │ │ ├── MultiArrayDimension.msg
│ │ │ ├── MultiArrayLayout.msg
│ │ │ ├── String.msg
│ │ │ ├── Time.msg
│ │ │ ├── UInt16.msg
│ │ │ ├── UInt16MultiArray.msg
│ │ │ ├── UInt32.msg
│ │ │ ├── UInt32MultiArray.msg
│ │ │ ├── UInt64.msg
│ │ │ ├── UInt64MultiArray.msg
│ │ │ ├── UInt8.msg
│ │ │ └── UInt8MultiArray.msg
│ ├── std_srvs
│ │ └── srv
│ │ │ ├── Empty.srv
│ │ │ ├── SetBool.srv
│ │ │ └── Trigger.srv
│ ├── tf
│ │ ├── msg
│ │ │ └── tfMessage.msg
│ │ └── srv
│ │ │ └── FrameGraph.srv
│ ├── tf2_msgs
│ │ ├── action
│ │ │ └── LookupTransform.action
│ │ ├── msg
│ │ │ ├── LookupTransformAction.msg
│ │ │ ├── LookupTransformActionFeedback.msg
│ │ │ ├── LookupTransformActionGoal.msg
│ │ │ ├── LookupTransformActionResult.msg
│ │ │ ├── LookupTransformFeedback.msg
│ │ │ ├── LookupTransformGoal.msg
│ │ │ ├── LookupTransformResult.msg
│ │ │ ├── TF2Error.msg
│ │ │ └── TFMessage.msg
│ │ └── srv
│ │ │ └── FrameGraph.srv
│ ├── theora_image_transport
│ │ └── msg
│ │ │ └── Packet.msg
│ ├── topic_tools
│ │ └── srv
│ │ │ ├── DemuxAdd.srv
│ │ │ ├── DemuxDelete.srv
│ │ │ ├── DemuxList.srv
│ │ │ ├── DemuxSelect.srv
│ │ │ ├── MuxAdd.srv
│ │ │ ├── MuxDelete.srv
│ │ │ ├── MuxList.srv
│ │ │ └── MuxSelect.srv
│ ├── trajectory_msgs
│ │ └── msg
│ │ │ ├── JointTrajectory.msg
│ │ │ ├── JointTrajectoryPoint.msg
│ │ │ ├── MultiDOFJointTrajectory.msg
│ │ │ └── MultiDOFJointTrajectoryPoint.msg
│ ├── trust_msgs
│ │ ├── InterfaceCommand.msg
│ │ └── RunDescription.msg
│ ├── uvc_camera
│ │ └── camera_sliders.msg
│ ├── whosonfirst
│ │ └── Dibs.msg
│ └── wpf_msgs
│ │ ├── Point2.msg
│ │ ├── Waypoints.msg
│ │ └── WindowState.msg
├── rosmaster
│ ├── Clock.cs
│ ├── Master.cs
│ ├── Master_API.cs
│ ├── Names.cs
│ ├── ParamServer.cs
│ ├── PendingConnection.cs
│ ├── Program.cs
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── Registrations.cs
│ ├── ReturnStruct.cs
│ ├── RosOut.cs
│ ├── XmlRpcManager.cs
│ ├── app.config
│ ├── bin
│ │ └── Debug
│ │ │ ├── XmlRpc_Wrapper.dll
│ │ │ ├── XmlRpc_Wrapper.pdb
│ │ │ └── rosmaster.exe.config
│ ├── main.cs
│ ├── manager.cs
│ ├── rosmaster.csproj
│ └── rosmaster.sln
├── tf.net
│ ├── Properties
│ │ └── AssemblyInfo.cs
│ ├── TimeCache.cs
│ ├── TransformAccum.cs
│ ├── TransformTypes.cs
│ ├── Transformer.cs
│ ├── Util.cs
│ ├── tf.net.csproj
│ └── tf.net_UNITY.csproj
└── tf_example
│ ├── Program.cs
│ ├── Properties
│ └── AssemblyInfo.cs
│ ├── app.config
│ └── tf_example.csproj
├── _config.yml
└── ros
├── .catkin_workspace
└── src
├── CMakeLists.txt
└── stanford_msgs
├── CMakeLists.txt
├── launch
└── stanford.launch
├── msg
└── ExampleCustom.msg
├── package.xml
└── src
└── example_custom_node.cpp
/Assets/ROS.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 02b06f098dcef864da4ab4d85963fa77
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 72532bf53ee3cda43b4e129a79aa9d8d
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7c06e77446596ea4baebb93ba7bb44ce
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/Interfaces.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5647f9ef1d8ef824597ebfacb973488b
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/MessageTypes.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ca18993737cd696408f140b1f4722e58
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/SerializationHelper.cs:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/Assets/ROS/Plugins/Messages/SerializationHelper.cs
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/SerializationHelper.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a38a56f23f7fa3c4ba9575523332f490
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/ServiceTest.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 03d4c83e141797d44a3a2dfab05ff2a5
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/ServiceTest/AddTwoInts.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: cad24924b9f645145aff0e15ec1b1675
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/actionlib_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5d5bb9c30a6877f4fad06db39074bf79
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/actionlib_msgs/GoalID.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 68966e7691ebdcc468b84a19277b1153
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/actionlib_msgs/GoalStatus.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fedf45f8e23899b48aa7735043f6d2aa
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: dadd544861ea25c4f8bff601d460f9a2
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/CloseCamera.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 96756e43781dcf744ba2dafde8d301d6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/HeadState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 101a43655d5da6b4cb6c060246bedde2
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/ITBState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 66136553680bcc34ca87a83cb183ab53
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/ITBStates.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 08431c87c0059ea48a748f89b8ce9669
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/ListCameras.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2336d6b7cb9971e4eb47967dd98497d2
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/baxter_core_msgs/OpenCamera.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fb850369d3240b742bda21216037a719
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f13e2c943aabfd241858a3188e0cb723
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/GripperCommand.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e0427d69f80f0484fb058370de220337
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/JointTolerance.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d82c1921444f77846aee8991a62824b1
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/PidState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f936e25cd10f3064694c74b85dd63a03
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/PointHeadAction.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8363fd72a7f83a245b6f314203abf081
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/PointHeadGoal.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 77c4d3701f2c3bf40bcdef85e3e7d418
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/control_msgs/PointHeadResult.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 55603e0efa9fb854b849919ddba37517
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 84723ab5abb1e5b48b7586bc75c71463
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/arrayofdeez.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1503a1a391a898947a430feb61b507c9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/arraytest.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1edc1f1c3a9c0224a82e3500f1f7cafb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/cgeo.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ac551857ae52ad34eb0f33fa2776bd63
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/ptz.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1251795fef7268145a2c6c5e56bf649d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/robotMortality.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 20c96179dc63d104da640b89ff9b46a5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/servosPos.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4d2d96a1c09b302459fe7ba3d879b4aa
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/custom_msgs/simpleintarray.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 371ab19f2da589046b4297710c896911
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/dynamic_reconfigure.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e8a5c81b4db22d042935f5fbb865fd40
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/dynamic_reconfigure/Config.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 89757467b70f2fb47805075080e541ce
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/dynamic_reconfigure/Group.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 17c10a3f158394343a01919303a8d551
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/dynamixel_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f5d29f44f8a8f424b9ff5d90fa3fd012
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/dynamixel_msgs/JointState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1e03ede95f5b5104aace480b7edd8a05
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/experiment.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0a510e1f2c448a24584f01a4e3689787
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/experiment/SimonSays.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 83cee6401404ca94abd56b64b7af81b0
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c484e2101754ca148b645e7d01b3ee84
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ApplyBodyWrench.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: eed574cca49a40a4b8f7133e5f4e5efb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ApplyJointEffort.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0fa68c4adc8fcae4184b4e04e4995967
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/BodyRequest.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 73e59968262089a44a38159a44836781
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ContactState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 38813b2b5d454d14981a9d6da1ac5ebd
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ContactsState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0c736d8b560859a4c96376185859104c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/DeleteModel.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b547aaa4080bb7a4c904388f396b0ffa
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/GetLinkState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 751cf3a03c9c00c4583980273ac92890
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/GetModelState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9c215fd37ed1f3d4abb2a952b1fe50f9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/JointRequest.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: bb4953f45489e904e8d4e93f75ef6143
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/LinkState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7bf879b278ac7f349b588e85d33f6c34
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/LinkStates.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2ff877166c350be47a68a710de058107
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ModelState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 74156345f971db843847ba4669a9c8be
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ModelStates.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fd41cae5fa79a2544bb81453349b7165
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/ODEPhysics.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 00f83061efe109e4c84472bd23b6bdc0
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/SetLinkState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2ea1c1e7819273d42b40dba819da057e
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/SetModelState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1c5e6e3cdd09f8442886a81c2ea8ee8e
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/SpawnModel.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 75a8c8dcd250dee439c60c91baa76d7c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/gazebo_msgs/WorldState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 846fbb1053572794d8ccfd8ea0110a9c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4c701968ff0aa2e46b98a51e47ff0dac
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Point.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5f6e37fac1a77094aa8733002f30c799
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Point32.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e6f433e7daeca5b49b3806cb14c79ce3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/PointStamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8d09e73852ff77c43ab840e4fe949006
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Polygon.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f16a303a3a6d72e49acf2ca8458986ab
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/PolygonStamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e39d4793cb9e37f408f261fc5e9aa9c0
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Pose.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c51a5e552fdeea248ba197a209dfaa2f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Pose2D.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 516976f07841a3a4d96930591062d5bd
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/PoseArray.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 38ffccdf735dc144189693864bc52cbf
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/PoseStamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4a754b8e268e77d4283c998e6b198bc7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Quaternion.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e6f21a73a1018ee4e8788a275456f0b5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Transform.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5b87caaf3375fd445b3e2060796d2124
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Twist.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 32c3f1c06ddcf924081bcc046497c2f9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/TwistStamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b106dad3aa97bc04babe84b5de9b7d61
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Vector3.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: cf999c1b1364fd244baea5f4f145c4c3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Vector3Stamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 603f7a808186c5a4bae7d6707fbd4e43
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/Wrench.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 27be569f166f8604fb80cbb46aa250b9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/geometry_msgs/WrenchStamped.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 13fc13632e852f345b988eff6cf0889b
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/histogram_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f523a383323bf9d48808645234fbab1c
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/histogram_msgs/MCLSnapshot.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: aba25eac6a4585640b903b99103c43e9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/humanoid_nav_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b6c90da2240482e4abfd3adbe92f7bb5
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/humanoid_nav_msgs/StepTarget.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 43e353718ef14014db1e7cd5638ec380
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f69b0af44ff754d4ba23d80492ba6fd2
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/GetMapROI.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 60b9d64b272d52649a9fe1d73c544e2a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/GetPointMap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 446a212e2f471404a8342d3e67c3e48d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/GetPointMapROI.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d4d316b5a7ddc4f41a670fe72836ace5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/OccupancyGridUpdate.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 3246624a19466634781d527c452cf136
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/PointCloud2Update.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a6fb537b07d009543879198151abffb2
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/ProjectedMap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2135ca104126a144e910bb5c6987a1b1
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/ProjectedMapInfo.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 68bb99f911e3cfb49a3b51b82cd2cb0e
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/ProjectedMapsInfo.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: cbdc5c703fee40b46a6d6579198d1f20
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/SaveMap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 667ee97f995b05a47a5f72eebe5e486f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/map_msgs/SetMapProjections.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0812282c567cf774b836d50c8558d682
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/move_base_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a7d7edd53439d3c49b87c29225aa0c27
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/move_base_msgs/MoveBaseGoal.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1374f705c654d5645894707d380282a6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d90cec2a38040fb4d973c6eafa3276bb
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a79bbd8979bef5c4f89fafb49961668f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapAction.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 125df538492972c48b35d018f2092326
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapActionGoal.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ad276591c02a825429641fbf5712b3cb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapActionResult.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 05ca82ec4cea25543aa9632af3c13f15
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapFeedback.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4509115f0d62b684cb7177e35a75cfdc
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapGoal.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 23339ce3d4f340c44a6514255797fc91
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetMapResult.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e0e6cb3415b097645b987e8ae4bb3e12
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GetPlan.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ac699bfcac0505b4aa65d42091b26568
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/GridCells.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9dd1045da4a624f409a2ff229667202d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/MapMetaData.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 82f3b5fd132c83643b669a0fd41ddb67
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/OccupancyGrid.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 82bab3bd8d081b14d8f05d51dc681b08
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/Odometry.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d23ce4413d6cbf24c889c86944eb3cf6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/Path.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 765a3bd5a6a773c4ca0b3eafab6e8033
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/nav_msgs/SetMap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b5388b2f26e6e3b4b873590975ed6f92
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/object_recognition_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 830f802f8627acf4db4c5b1542d84c15
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/octomap_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1613b04f9fd71604dac28feee67bd6b7
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/octomap_msgs/GetOctomap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fcb3df6e3d6e562429214e5f63c1040d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/octomap_msgs/Octomap.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2aa159e8d5bcb304f8a193b54e282175
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/octomap_msgs/OctomapWithPose.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7958708e9d56cf74ca8f0d91e9dd722f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/pcl_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c72256261e3627d4fa120c13747b885f
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/pcl_msgs/ModelCoefficients.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1b452fc949068fe4a90a253b7ed14c8f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/pcl_msgs/PointIndices.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fe1911b1507c3a9438cc98f91644c4f4
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/pcl_msgs/PolygonMesh.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d8ff3cbbb15e9af46b6b33d55fc6985a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/pcl_msgs/Vertices.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b7ccfe1237894594eb9fd13d9b9f3edc
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rock_publisher.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f9305dbaaa73ccd4ab19fbaeca468087
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rock_publisher/imgData.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 11af1fed768b6b248b73543e9e67106d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rock_publisher/imgDataArray.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 922b4157b79df104fa5f6dfb92c326d6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/roscpp_tutorials.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 95e5c308361bd464f9aa79e84e65b660
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/roscpp_tutorials/TwoInts.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 98f4dad9788695445889177d071d9e1a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/roscsharp.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 641d904dd7d077c4aaa2270132633a77
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/roscsharp/GetLoggers.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1f8821fec23a2a44dbe05c8412c7a3a4
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/roscsharp/Logger.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: faef7f3da456eaa42b6c5008b0f98ed2
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rosgraph_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d81fdeb4b0fe9d64684dedf916214855
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rosgraph_msgs/Clock.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 72d03ce510a66804791082ff61872b78
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/rosgraph_msgs/Log.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 800e87d9d9540cb4b86f44e1dcd529c3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sample_acquisition.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c379943f64399ea4d98ca7ec13a927c0
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 729622ce74ce8f240b88bc07b7487068
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/CameraInfo.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fbc489bac176b2e40ba5a45715d5c3ee
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Illuminance.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 12e39b76a91e3af45bbc119d1ce2a967
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Image.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f40ab54b09580e44cbaaf7fb1b0cbfe6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Imu.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ea7aa9b331620e24194afa80eb9f8fe5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/JointState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 755f28b1aed3a2a48889e856dff6cd23
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Joy.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d4d4528d248952144b8054b89035e4db
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/JoyFeedback.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 3169de9b8267e014a8d56ef3f484f3e7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/LaserEcho.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c1656cbaa3e717748a528d24b9fa244f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/LaserScan.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5c00fc9dc7746544b9522aa2415bb9de
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/NavSatFix.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: bf625a04456c6784c88ffbec09e1c4d4
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/PointCloud.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ed65f9449c892304d8d62044bfac8cc7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/PointCloud2.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: da205efe3b227be46ad429941408a61c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/PointField.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 463daa78690d3de4aab548362d3a4c75
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Range.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2de8970e210d3934baf7e798fdd3138d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/sensor_msgs/Temperature.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4c5ea96af582d864587c45346f473b07
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/shape_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e5d3090b8b736f74098cd5dbeaf21497
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/shape_msgs/Mesh.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8aa687a15eab9504f93939e75d9f64de
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/shape_msgs/MeshTriangle.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9b6a8aa9c6600e4409c4c7d8a70eb492
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/shape_msgs/Plane.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 068a938a0caa76d4fb63a35c7235f04d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/stanford_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: badd10b394bfde74d93e5a2a466b395e
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1e039706a7de68444904318377a20061
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Bool.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4d07459b8018ddd49ae80b8cff652542
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Byte.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 279e51756ea2f0d4f80e7bd9486019fd
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/ByteMultiArray.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: deedae1fbd6bacb419d29a4150e02ac9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Char.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4f58aa4858151e34d985dec3ce4435f1
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/ColorRGBA.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 87566f0eb791f674b897c7977f3453c2
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Duration.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 470dbca498ca924428a910a4ccbd8a82
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Empty.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a6e9cf398bcd62445b7a534eeec82c67
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Float32.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f4294de763f4fa04cb277859331ca7b3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Float64.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1a53f31277f657743adf65bf93d81a56
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Header.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4a272ba78497e4d449096c38f8203d15
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Int16.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e0ee079a55d07c64facf51b9e7dd1e08
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Int32.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c45216f9cbfe31f4d91da92c1a22ac10
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Int64.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 3f66afee10b395947b3fe6957ae3184d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Int8.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: fbcc27880a1fbf141941ed7b0c5d6f34
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Int8MultiArray.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a2ca941e36ca5ff40a8e723eba51dfd7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/String.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8494eef6fc3debc4090bf824f4df1f91
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/Time.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e7556bf8d8adc8b418211bc95b516fe8
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/UInt16.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ea4c3fe3b6b567047b530dedc4da34a8
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/UInt32.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: de1c4f6c5e450e5498191c2f3c91f8e0
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/UInt64.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 15ead079c0caebf40aa8717b27c4ec46
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_msgs/UInt8.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 52baf2ad2d2e6dc4ca3a668e8ffdae5a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_srvs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5af2f8dbab3d3d54a8039d0fd9ab6d2e
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_srvs/Empty.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 66fd291dd2f473246be168264789a69a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_srvs/SetBool.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 884956eca3f19144398f1a857e70cf72
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/std_srvs/Trigger.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7e9b0f36bc1e5d24b868e3e73525a8eb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a14f09923d097f64da7ec5a83cc9d171
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf/FrameGraph.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9b149f7324960124687d9e1f6d7b12d8
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf/tfMessage.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: af04bd334013b3f4fa9a628cc9f02dfe
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf2_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 13818ce799fe0e041b961d32d9ed96a3
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf2_msgs/FrameGraph.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 15f362e7d9cf31a4193ec10ef1cce615
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf2_msgs/TF2Error.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 100f7bc3f06492f47ad2855b9199f57f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/tf2_msgs/TFMessage.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: de1051ebf8776ae4eba879cb4def7f03
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/theora_image_transport.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ffb400ea64b0f7d4eb32c6730707ee38
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 69db969e75ce0724084fd4ef66c0d5cd
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/DemuxAdd.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d30678a862dbc064f919027742aea8ef
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/DemuxDelete.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1ef2f876d89e6214e864a320954025ff
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/DemuxList.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5232c95a88e902c48891406a1527d4c8
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/DemuxSelect.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5a85c46eae1a248408034cd878f2b819
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/MuxAdd.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 34904fc3400105f41b4e06e04dc6e9ac
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/MuxDelete.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: cf778a5607e12c04b998744e9ad9b225
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/MuxList.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 3cdeff9835e395c4b8289dac3e46796f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/topic_tools/MuxSelect.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c34a44dc84b9a844daa0400a20fbdb02
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/trajectory_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 6fcb5a0f20ed72344ba966ec856d901a
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/trust_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d5d6fcaa357c2b5489a655af57739843
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/uvc_camera.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a59260186329e4a46b5bfa7cd41f2102
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/whosonfirst.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c20981a56fda38845a66a7fef9fefd18
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/whosonfirst/Dibs.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 338e3c1f121d36142b6d2400956933ce
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/wpf_msgs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 97d7753f076462e4d8de89dcc5385153
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/wpf_msgs/Point2.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d9e5943755bf82b49bc214de756f4c6f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/wpf_msgs/Waypoints.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c6f4b02c99545114e90dbcc3017190a7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/Messages/wpf_msgs/WindowState.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1a0cbea5290d31d4e8498bd0efc321bf
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a680b65d033af814eb1ad00cf730a145
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/AdvertiseOptions.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5c6be31126c70794bb0b1f5160943b52
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/AdvertiseServiceOptions.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7999bbb790033824184607f9f78e1e6d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/CallbackInterface.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9cffa234e6ed7534fb4cfa5e112cec14
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/CallbackQueue.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 305948d2e5cee9942ba387c2505475bb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Connection.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b1938696ef9700d4582bb15913f05d0b
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ConnectionManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0cfd753ccf705d845b9fbefd2461b7ad
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Header.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 259ac76328f3b5f409c37aeed75a02a7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/LocalPublisherLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 332ad7f2580e21c4aac0849d87c29ab7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/LocalSubscriberLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a00cc818f3ec74e459b5eff9cb6ef4d4
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Master.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: e3821ae5e1e8f0d4c995bde6e098c8c8
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/NodeHandle.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 6ee27cb43ec49a24fac76d85d560c036
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Param.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: df9ed0070d402ca42b2c9aa0647aa1a3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/PendingConnection.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8452f26068eae5845b39d005c6f1b71c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/PollManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: d8d6314fa49f75a4a890c483f56605db
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/PollSet.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 93e6ba9ebd90c6745a10dde6ec49cacc
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Publication.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 79daa24ee07ab2844aa85f8a37a11c66
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Publisher.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 14d1745b22655f74ab04270c53da3a0f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/PublisherLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c13e0f7f781deb943ab7f4e064ce00fd
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/RemappingHelper.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: c7ab1b08ec4d88b4592525f565e7cb3c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/RosOutAppender.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ccc648f736bb87e4eaf901de9f834c62
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ScopedTimer.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: b1606bbbe34811840a0139bf2b0c8353
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Service.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 6f803a557dd1041458e91c28761eedcb
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceCallbackHelper.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: dd70839e34694ff47aac29d06e17f511
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceClient.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 499928679f0364d45accab20a856b227
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceClientLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f51ae9d3e3e68074a95db75a13449585
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceClientOptions.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: ac3e179c492f4d5448882b78f13d67ca
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 7911e0de785a66841bb1a155a65eb0d3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServicePublication.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 32583c4b0e0d153438aa423bfef77f33
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceServer.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 153dde1e4c7e43a48bd70877ed67b398
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/ServiceServerLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2474b28d770b57843a0f5c6f4c59843a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Socket.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 50b187af98874a945bb5cdb4e0247d0d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Spinner.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1e4bff32d220c9e40a17ddec57c41f52
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/SubscribeOptions.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 276841aa459f80e4b8ecc345fe8efd26
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Subscriber.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 3ba10bda78950f94186f65da0d0d0a83
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/SubscriberCallbacks.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f9ab412433a63bb40bffaa47bacf1885
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/SubscriberLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 8f5a0bebffe3be7449658c75e59dec5c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Subscription.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0983718b806082e4f972f05a072c8df3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TcpTransport.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: dedc6ec68dcfe054eb9eaa59f1be1b44
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/Time.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 9215ee36e6fcfec4b976c75be2358d55
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TimerManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 97b51c23c33eb914b881b43c72055bb6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TopicInfo.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: cae0b9be706a1d342ae3d46456cb10c6
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TopicManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 45f2279e87b7204439fac9ff294c25d9
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TransportPublisherLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 726c1331d1b04bf4eb8cc5010f3abd6d
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/TransportSubscriberLink.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 2052c1027b5432e4aa597ab3336d938a
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/XmlRpcManager.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 235fe7d5047203f49a105cad0fb00040
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/_Init.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a9c80efe95769584ebc44add005edb81
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/names.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 6779ab93816ad9b42a16fadfb250ac6e
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/network.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a230cd5b1e8201d4dbe3847e01c01c33
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/ROS_Comm/this_node.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 6985f5bafe12b494abb7f44069facdf5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 0087ff8bdea500b43922dac334e4ac67
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XMLRPCCallWrapper.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: f44f0240fd91cc94b9a5c5e7e100c31c
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcClient.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: a9bfe560e5f29f74fb4a09ec07700c3f
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcDispatch.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5f90957bb6790dc429c2972e333c09c5
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcServer.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 04e14cc33834b174087ea3307f6ada7b
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcSource.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4c9394e7b9d25284495794dc2e36f83e
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcUtil.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 1fe0db736e89cce4a8eeda44d1548c84
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/ROS/Plugins/XmlRpc_Wrapper/XmlRpcValue.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 84c6eca5cdae1554fbe851125ba536a3
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/Scenes.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 4f704ae4b4f98ae41a0bce26658850c1
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/Scenes/SampleScene.unity.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 99c9720ab356a0642a771bea13969a05
3 | DefaultImporter:
4 | externalObjects: {}
5 | userData:
6 | assetBundleName:
7 | assetBundleVariant:
8 |
--------------------------------------------------------------------------------
/Assets/Scripts.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 5f4c8a1dfcc022a4ebd360255a367ec9
3 | folderAsset: yes
4 | DefaultImporter:
5 | externalObjects: {}
6 | userData:
7 | assetBundleName:
8 | assetBundleVariant:
9 |
--------------------------------------------------------------------------------
/Assets/Scripts/ROSController.cs.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 03c820e475a64374cb4ce4b7a2733ab7
3 | MonoImporter:
4 | externalObjects: {}
5 | serializedVersion: 2
6 | defaultReferences: []
7 | executionOrder: 0
8 | icon: {instanceID: 0}
9 | userData:
10 | assetBundleName:
11 | assetBundleVariant:
12 |
--------------------------------------------------------------------------------
/Assets/mcs.rsp:
--------------------------------------------------------------------------------
1 | -nowarn:0649
2 | -nowarn:0414
3 | -nowarn:0168
4 | -nowarn:0219
5 | -nowarn:0618
6 | -nowarn:0675
--------------------------------------------------------------------------------
/Assets/mcs.rsp.meta:
--------------------------------------------------------------------------------
1 | fileFormatVersion: 2
2 | guid: 93b23010313d29c47b9f3011f110775b
3 | DefaultImporter:
4 | externalObjects: {}
5 | userData:
6 | assetBundleName:
7 | assetBundleVariant:
8 |
--------------------------------------------------------------------------------
/Packages/manifest.json:
--------------------------------------------------------------------------------
1 | {
2 | "dependencies": {
3 | }
4 | }
5 |
--------------------------------------------------------------------------------
/ProjectSettings/ClusterInputManager.asset:
--------------------------------------------------------------------------------
1 | %YAML 1.1
2 | %TAG !u! tag:unity3d.com,2011:
3 | --- !u!236 &1
4 | ClusterInputManager:
5 | m_ObjectHideFlags: 0
6 | m_Inputs: []
7 |
--------------------------------------------------------------------------------
/ProjectSettings/EditorBuildSettings.asset:
--------------------------------------------------------------------------------
1 | %YAML 1.1
2 | %TAG !u! tag:unity3d.com,2011:
3 | --- !u!1045 &1
4 | EditorBuildSettings:
5 | m_ObjectHideFlags: 0
6 | serializedVersion: 2
7 | m_Scenes:
8 | - enabled: 1
9 | path: Assets/Scenes/SampleScene.unity
10 | guid: 99c9720ab356a0642a771bea13969a05
11 | m_configObjects: {}
12 |
--------------------------------------------------------------------------------
/ProjectSettings/NetworkManager.asset:
--------------------------------------------------------------------------------
1 | %YAML 1.1
2 | %TAG !u! tag:unity3d.com,2011:
3 | --- !u!149 &1
4 | NetworkManager:
5 | m_ObjectHideFlags: 0
6 | m_DebugLevel: 0
7 | m_Sendrate: 15
8 | m_AssetToPrefab: {}
9 |
--------------------------------------------------------------------------------
/ProjectSettings/ProjectVersion.txt:
--------------------------------------------------------------------------------
1 | m_EditorVersion: 2018.1.0f2
2 |
--------------------------------------------------------------------------------
/ProjectSettings/TimeManager.asset:
--------------------------------------------------------------------------------
1 | %YAML 1.1
2 | %TAG !u! tag:unity3d.com,2011:
3 | --- !u!5 &1
4 | TimeManager:
5 | m_ObjectHideFlags: 0
6 | Fixed Timestep: 0.0167
7 | Maximum Allowed Timestep: 0.1
8 | m_TimeScale: 1
9 | Maximum Particle Timestep: 0.03
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/.ROS_NOBUILD:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/.ROS_NOBUILD
--------------------------------------------------------------------------------
/ROSNetUnity/CompressedImageView/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/CompressedImageView/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/DynamicReconfigureSharp/App.xaml.cs:
--------------------------------------------------------------------------------
1 | #region USINGZ
2 |
3 | using System.Windows;
4 |
5 | #endregion
6 |
7 | namespace DynamicReconfigureTest
8 | {
9 | ///
10 | /// Interaction logic for App.xaml
11 | ///
12 | public partial class App : Application
13 | {
14 | }
15 | }
--------------------------------------------------------------------------------
/ROSNetUnity/DynamicReconfigureSharp/IDynamicReconfigureLayout.cs:
--------------------------------------------------------------------------------
1 | namespace DynamicReconfigureSharp
2 | {
3 | public interface IDynamicReconfigureLayout
4 | {
5 | double getDescriptionWidth();
6 | void setDescriptionWidth(double w);
7 | }
8 | }
--------------------------------------------------------------------------------
/ROSNetUnity/DynamicReconfigureSharp/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/DynamicReconfigureSharp/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/Icon.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/Icon.png
--------------------------------------------------------------------------------
/ROSNetUnity/Listener/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/Logo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/Logo.png
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MD5SumTest/bin/Debug/Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MD5SumTest/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MD5SumTest/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/YAMLParser.exe:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MD5SumTest/bin/Debug/YAMLParser.exe
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/YAMLParser.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/MD5SumTest/bin/Debug/YAMLParser.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MD5SumTest/bin/Debug/YAMLParser.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/MessageSerializationTests/bin/Debug/Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MessageSerializationTests/bin/Debug/Microsoft.VisualStudio.QualityTools.UnitTestFramework.dll
--------------------------------------------------------------------------------
/ROSNetUnity/MessageSerializationTests/bin/Debug/YAMLParser.exe:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MessageSerializationTests/bin/Debug/YAMLParser.exe
--------------------------------------------------------------------------------
/ROSNetUnity/MessageSerializationTests/bin/Debug/YAMLParser.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/MessageSerializationTests/bin/Debug/YAMLParser.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/MessageSerializationTests/bin/Debug/YAMLParser.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_Comm/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_Comm/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_Comm/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_Comm/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_Comm/bin/Debug/YAMLParser.exe:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_Comm/bin/Debug/YAMLParser.exe
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_Comm/bin/Debug/YAMLParser.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_Comm/bin/Debug/YAMLParser.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_Comm/bin/Debug/YAMLParser.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_ImageUtils/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_ImageUtils/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_ImageUtils/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/ROS_ImageUtils/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/ROS_ImageUtils/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/RosParamClient/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/RosParamClient/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/RosParamClient/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/RosParamClient/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/RosParamClient/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/RosParamClient/bin/Debug/rosparam.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/RosoutDebugUC/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/ServiceClientSample/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/ServiceClientSample/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/ServiceServerSample/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/ServiceServerSample/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/SimplePublisher/SimplePublisher/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/SimplePublisher/SimplePublisher/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/SimpleSubscriber/SimpleSubscriber/Properties/Settings.settings:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/SimpleSubscriber/SimpleSubscriber/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/Talker/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/XNA_Image_Example/XNA_Image_Example/Game.ico:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/XNA_Image_Example/XNA_Image_Example/Game.ico
--------------------------------------------------------------------------------
/ROSNetUnity/XNA_Image_Example/XNA_Image_Example/GameThumbnail.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/XNA_Image_Example/XNA_Image_Example/GameThumbnail.png
--------------------------------------------------------------------------------
/ROSNetUnity/XmlRpc_Wrapper/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/XmlRpc_Wrapper/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/XmlRpc_Wrapper/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/XmlRpc_Wrapper/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/ROS_MESSAGES/README.txt:
--------------------------------------------------------------------------------
1 | This folder's sole purpose is now to prevent YOUR message definitions from getting killed by git.
2 |
3 | Project directories can now have "msg" and "srv" folders like ROS packages.
4 |
5 | All of the official ROS.NET's previous ROS_MESSAGES messages are now in the common_msgs directory.
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/TemplateProject/String.cs:
--------------------------------------------------------------------------------
1 | namespace Messages.std_msgs
2 | {
3 | [System.Diagnostics.DebuggerStepThrough]
4 | internal class String
5 | {
6 | //placeholder
7 | }
8 | }
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/bin/Debug/YAMLParser.exe:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/YAMLParser/bin/Debug/YAMLParser.exe
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/bin/Debug/YAMLParser.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/YAMLParser/bin/Debug/YAMLParser.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/YAMLParser/bin/Debug/YAMLParser.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/ServiceTest/AddTwoInts.srv:
--------------------------------------------------------------------------------
1 | int32 a
2 | int32 b
3 | ---
4 | int32 sum
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/actionlib_msgs/GoalStatusArray.msg:
--------------------------------------------------------------------------------
1 | # Stores the statuses for goals that are currently being tracked
2 | # by an action server
3 | Header header
4 | GoalStatus[] status_list
5 |
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/AnalogIOState.msg:
--------------------------------------------------------------------------------
1 | time timestamp
2 | float64 value
3 | bool isInputOnly
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/AnalogIOStates.msg:
--------------------------------------------------------------------------------
1 | string[] names
2 | AnalogIOState[] states
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/AnalogOutputCommand.msg:
--------------------------------------------------------------------------------
1 | ##the name of the output
2 | string name
3 | ##the value to set output
4 | uint16 value
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/AssemblyStates.msg:
--------------------------------------------------------------------------------
1 | string[] names
2 | AssemblyState[] states
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/CameraSettings.msg:
--------------------------------------------------------------------------------
1 | int32 width
2 | int32 height
3 | float32 fps
4 | CameraControl[] controls
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/CollisionAvoidanceState.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | bool other_arm
3 | string[] collision_object
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/CollisionDetectionState.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | bool collision_state
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/DigitalIOState.msg:
--------------------------------------------------------------------------------
1 | int8 state
2 | bool isInputOnly
3 |
4 | int8 OFF = 0
5 | int8 ON = 1
6 | int8 PRESSED = 1
7 | int8 UNPRESSED = 0
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/DigitalIOStates.msg:
--------------------------------------------------------------------------------
1 | string[] names
2 | DigitalIOState[] states
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/DigitalOutputCommand.msg:
--------------------------------------------------------------------------------
1 | ##the name of the output
2 | string name
3 | ##the value to set output
4 | bool value
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/EndpointState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | geometry_msgs/Pose pose
3 | geometry_msgs/Twist twist
4 | geometry_msgs/Wrench wrench
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/EndpointStates.msg:
--------------------------------------------------------------------------------
1 | string[] names
2 | EndpointState[] states
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/HeadPanCommand.msg:
--------------------------------------------------------------------------------
1 | #Header header
2 | float32 target # radians for target, 0 str
3 | int32 speed # between 0 and 100, 100 = max
4 |
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/HeadState.msg:
--------------------------------------------------------------------------------
1 | float32 pan
2 | bool isPanning
3 | bool isNodding
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/ITBState.msg:
--------------------------------------------------------------------------------
1 | bool[4] buttons
2 | bool up
3 | bool down
4 | bool left
5 | bool right
6 | uint8 wheel
7 |
8 | # true if the inner light is on, false if not
9 | bool innerLight
10 |
11 | # true if the outer light is on, false if not
12 | bool outerLight
13 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/ITBStates.msg:
--------------------------------------------------------------------------------
1 | # used when publishing multiple itbs
2 | string[] names
3 | ITBState[] states
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/JointCommand.msg:
--------------------------------------------------------------------------------
1 | int32 mode
2 | float64[] command
3 | string[] names
4 |
5 | int32 POSITION_MODE=1
6 | int32 VELOCITY_MODE=2
7 | int32 TORQUE_MODE=3
8 | int32 RAW_POSITION_MODE=4
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/NavigatorState.msg:
--------------------------------------------------------------------------------
1 | # buttons
2 | string[] button_names
3 | bool[] buttons
4 |
5 | # wheel position
6 | uint8 wheel
7 |
8 | # true if the light is on, false if not
9 | # lights map to button names
10 | string[] light_names
11 | bool[] lights
12 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/msg/NavigatorStates.msg:
--------------------------------------------------------------------------------
1 | # used when publishing multiple navigators
2 | string[] names
3 | NavigatorState[] states
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/srv/CloseCamera.srv:
--------------------------------------------------------------------------------
1 | string name
2 | ---
3 | int32 err
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/srv/ListCameras.srv:
--------------------------------------------------------------------------------
1 | ---
2 | string[] cameras
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/baxter_core_msgs/srv/OpenCamera.srv:
--------------------------------------------------------------------------------
1 | string name
2 | CameraSettings settings
3 | ---
4 | int32 err
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/action/JointTrajectory.action:
--------------------------------------------------------------------------------
1 | trajectory_msgs/JointTrajectory trajectory
2 | ---
3 | ---
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/action/PointHead.action:
--------------------------------------------------------------------------------
1 | geometry_msgs/PointStamped target
2 | geometry_msgs/Vector3 pointing_axis
3 | string pointing_frame
4 | duration min_duration
5 | float64 max_velocity
6 | ---
7 | ---
8 | float64 pointing_angle_error
9 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/action/SingleJointPosition.action:
--------------------------------------------------------------------------------
1 | float64 position
2 | duration min_duration
3 | float64 max_velocity
4 | ---
5 | ---
6 | Header header
7 | float64 position
8 | float64 velocity
9 | float64 error
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/FollowJointTrajectoryAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | FollowJointTrajectoryActionGoal action_goal
4 | FollowJointTrajectoryActionResult action_result
5 | FollowJointTrajectoryActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/FollowJointTrajectoryActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | FollowJointTrajectoryFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/FollowJointTrajectoryActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | FollowJointTrajectoryGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/FollowJointTrajectoryActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | FollowJointTrajectoryResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/FollowJointTrajectoryFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | Header header
3 | string[] joint_names
4 | trajectory_msgs/JointTrajectoryPoint desired
5 | trajectory_msgs/JointTrajectoryPoint actual
6 | trajectory_msgs/JointTrajectoryPoint error
7 |
8 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommand.msg:
--------------------------------------------------------------------------------
1 | float64 position
2 | float64 max_effort
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommandAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | GripperCommandActionGoal action_goal
4 | GripperCommandActionResult action_result
5 | GripperCommandActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommandActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | GripperCommandFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommandActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | GripperCommandGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommandActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | GripperCommandResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/GripperCommandGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | GripperCommand command
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointControllerState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | float64 set_point
3 | float64 process_value
4 | float64 process_value_dot
5 | float64 error
6 | float64 time_step
7 | float64 command
8 | float64 p
9 | float64 i
10 | float64 d
11 | float64 i_clamp
12 | bool antiwindup
13 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | JointTrajectoryActionGoal action_goal
4 | JointTrajectoryActionResult action_result
5 | JointTrajectoryActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | JointTrajectoryFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | JointTrajectoryGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | JointTrajectoryResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryControllerState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string[] joint_names
3 | trajectory_msgs/JointTrajectoryPoint desired
4 | trajectory_msgs/JointTrajectoryPoint actual
5 | trajectory_msgs/JointTrajectoryPoint error # Redundant, but useful
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | trajectory_msgs/JointTrajectory trajectory
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/JointTrajectoryResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PidState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | duration timestep
3 | float64 error
4 | float64 error_dot
5 | float64 p_error
6 | float64 i_error
7 | float64 d_error
8 | float64 p_term
9 | float64 i_term
10 | float64 d_term
11 | float64 i_max
12 | float64 i_min
13 | float64 output
14 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | PointHeadActionGoal action_goal
4 | PointHeadActionResult action_result
5 | PointHeadActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | PointHeadFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | PointHeadGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | PointHeadResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | float64 pointing_angle_error
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | geometry_msgs/PointStamped target
3 | geometry_msgs/Vector3 pointing_axis
4 | string pointing_frame
5 | duration min_duration
6 | float64 max_velocity
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/PointHeadResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | SingleJointPositionActionGoal action_goal
4 | SingleJointPositionActionResult action_result
5 | SingleJointPositionActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | SingleJointPositionFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | SingleJointPositionGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | SingleJointPositionResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | Header header
3 | float64 position
4 | float64 velocity
5 | float64 error
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | float64 position
3 | duration min_duration
4 | float64 max_velocity
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/msg/SingleJointPositionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/srv/QueryCalibrationState.srv:
--------------------------------------------------------------------------------
1 | ---
2 | bool is_calibrated
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/control_msgs/srv/QueryTrajectoryState.srv:
--------------------------------------------------------------------------------
1 | time time
2 | ---
3 | string[] name
4 | float64[] position
5 | float64[] velocity
6 | float64[] acceleration
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/arrayofdeez.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/Pose[] nuts
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/arraytest.msg:
--------------------------------------------------------------------------------
1 | int32[2] integers
2 | int32[] lengthlessintegers
3 | string teststring
4 | string[2] teststringarray
5 | string[] teststringarraylengthless
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/cgeo.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/Vector3[] vec
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/ptz.msg:
--------------------------------------------------------------------------------
1 | float32 x
2 | float32 y
3 | int32 CAM_ABS=0
4 | int32 CAM_REL=1
5 | int32 CAM_VEL=2
6 | int32 CAM_MODE
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/robotMortality.msg:
--------------------------------------------------------------------------------
1 | int32 keep_alive=0
2 | int32 going_up=1
3 | int32 going_down=2
4 | int32 status
5 | int32 robot_id
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/servosPos.msg:
--------------------------------------------------------------------------------
1 | float32 x
2 | float32 y
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/custom_msgs/simpleintarray.msg:
--------------------------------------------------------------------------------
1 | int16[3] knownlengtharray
2 | int16[] unknownlengtharray
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/BoolParameter.msg:
--------------------------------------------------------------------------------
1 | string name
2 | bool value
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/Config.msg:
--------------------------------------------------------------------------------
1 | BoolParameter[] bools
2 | IntParameter[] ints
3 | StrParameter[] strs
4 | DoubleParameter[] doubles
5 | GroupState[] groups
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/ConfigDescription.msg:
--------------------------------------------------------------------------------
1 | Group[] groups
2 | Config max
3 | Config min
4 | Config dflt
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/DoubleParameter.msg:
--------------------------------------------------------------------------------
1 | string name
2 | float64 value
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/Group.msg:
--------------------------------------------------------------------------------
1 | string name
2 | string type
3 | ParamDescription[] parameters
4 | int32 parent
5 | int32 id
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/GroupState.msg:
--------------------------------------------------------------------------------
1 | string name
2 | bool state
3 | int32 id
4 | int32 parent
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/IntParameter.msg:
--------------------------------------------------------------------------------
1 | string name
2 | int32 value
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/ParamDescription.msg:
--------------------------------------------------------------------------------
1 | string name
2 | string type
3 | uint32 level
4 | string description
5 | string edit_method
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/msg/StrParameter.msg:
--------------------------------------------------------------------------------
1 | string name
2 | string value
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamic_reconfigure/srv/Reconfigure.srv:
--------------------------------------------------------------------------------
1 | Config config
2 | ---
3 | Config config
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/dynamixel_msgs/JointState.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | string name
3 | int32[] motor_ids
4 | int32[] motor_temps
5 | float64 goal_pos
6 | float64 current_pos
7 | float64 error
8 | float64 velocity
9 | float64 load
10 | bool is_moving
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/experiment/SimonSays.msg:
--------------------------------------------------------------------------------
1 | int32 correct
2 | int32 presses
3 | int32 unresponded
4 | int32 stepspresented
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/msg/ContactsState.msg:
--------------------------------------------------------------------------------
1 | Header header # stamp
2 | gazebo_msgs/ContactState[] states # array of geom pairs in contact
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/msg/LinkStates.msg:
--------------------------------------------------------------------------------
1 | # broadcast all link states in world frame
2 | string[] name # link names
3 | geometry_msgs/Pose[] pose # desired pose in world frame
4 | geometry_msgs/Twist[] twist # desired twist in world frame
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/msg/ModelStates.msg:
--------------------------------------------------------------------------------
1 | # broadcast all model states in world frame
2 | string[] name # model names
3 | geometry_msgs/Pose[] pose # desired pose in world frame
4 | geometry_msgs/Twist[] twist # desired twist in world frame
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/srv/BodyRequest.srv:
--------------------------------------------------------------------------------
1 | string body_name # name of the body requested. body names are prefixed by model name, e.g. pr2::base_link
2 | ---
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/srv/DeleteModel.srv:
--------------------------------------------------------------------------------
1 | string model_name # name of the Gazebo Model to be deleted
2 | ---
3 | bool success # return true if deletion is successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/srv/JointRequest.srv:
--------------------------------------------------------------------------------
1 | string joint_name # name of the joint requested
2 | ---
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/srv/SetLinkState.srv:
--------------------------------------------------------------------------------
1 | gazebo_msgs/LinkState link_state
2 | ---
3 | bool success # return true if set wrench successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/gazebo_msgs/srv/SetModelState.srv:
--------------------------------------------------------------------------------
1 | gazebo_msgs/ModelState model_state
2 | ---
3 | bool success # return true if setting state successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Point.msg:
--------------------------------------------------------------------------------
1 | # This contains the position of a point in free space
2 | float64 x
3 | float64 y
4 | float64 z
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/PointStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Point with reference coordinate frame and timestamp
2 | Header header
3 | Point point
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Polygon.msg:
--------------------------------------------------------------------------------
1 | #A specification of a polygon where the first and last points are assumed to be connected
2 | geometry_msgs/Point32[] points
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/PolygonStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Polygon with reference coordinate frame and timestamp
2 | Header header
3 | Polygon polygon
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Pose.msg:
--------------------------------------------------------------------------------
1 | # A representation of pose in free space, composed of postion and orientation.
2 | Point position
3 | Quaternion orientation
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Pose2D.msg:
--------------------------------------------------------------------------------
1 | # This expresses a position and orientation on a 2D manifold.
2 |
3 | float64 x
4 | float64 y
5 | float64 theta
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/PoseArray.msg:
--------------------------------------------------------------------------------
1 | # An array of poses with a header for global reference.
2 | Header header
3 | geometry_msgs/Pose[] poses
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/PoseStamped.msg:
--------------------------------------------------------------------------------
1 | # A Pose with reference coordinate frame and timestamp
2 | Header header
3 | Pose pose
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/PoseWithCovarianceStamped.msg:
--------------------------------------------------------------------------------
1 | # This expresses an estimated pose with a reference coordinate frame and timestamp
2 |
3 | Header header
4 | PoseWithCovariance pose
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Quaternion.msg:
--------------------------------------------------------------------------------
1 | # This represents an orientation in free space in quaternion form.
2 |
3 | float64 x
4 | float64 y
5 | float64 z
6 | float64 w
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/QuaternionStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents an orientation with reference coordinate frame and timestamp.
2 |
3 | Header header
4 | Quaternion quaternion
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Transform.msg:
--------------------------------------------------------------------------------
1 | # This represents the transform between two coordinate frames in free space.
2 |
3 | Vector3 translation
4 | Quaternion rotation
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Twist.msg:
--------------------------------------------------------------------------------
1 | # This expresses velocity in free space broken into it's linear and angular parts.
2 | Vector3 linear
3 | Vector3 angular
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/TwistStamped.msg:
--------------------------------------------------------------------------------
1 | # A twist with reference coordinate frame and timestamp
2 | Header header
3 | Twist twist
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/TwistWithCovarianceStamped.msg:
--------------------------------------------------------------------------------
1 | # This represents an estimate twist with reference coordinate frame and timestamp.
2 | Header header
3 | TwistWithCovariance twist
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Vector3.msg:
--------------------------------------------------------------------------------
1 | # This represents a vector in free space.
2 |
3 | float64 x
4 | float64 y
5 | float64 z
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Vector3Stamped.msg:
--------------------------------------------------------------------------------
1 | # This represents a Vector3 with reference coordinate frame and timestamp
2 | Header header
3 | Vector3 vector
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/Wrench.msg:
--------------------------------------------------------------------------------
1 | # This represents force in free space, seperated into
2 | # it's linear and angular parts.
3 | Vector3 force
4 | Vector3 torque
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/geometry_msgs/WrenchStamped.msg:
--------------------------------------------------------------------------------
1 | # A wrench with reference coordinate frame and timestamp
2 | Header header
3 | Wrench wrench
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/histogram_msgs/MCLSnapshot.msg:
--------------------------------------------------------------------------------
1 | float32[] positions
2 | float32[] weights
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/histogram_msgs/histogramsnapshot.msg:
--------------------------------------------------------------------------------
1 | float32[] belief
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/action/ExecFootsteps.action:
--------------------------------------------------------------------------------
1 | # Define the goal
2 | humanoid_nav_msgs/StepTarget[] footsteps
3 | float64 feedback_frequency
4 | ---
5 | # Define the result
6 | humanoid_nav_msgs/StepTarget[] executed_footsteps
7 | ---
8 | # Define a feedback message
9 | humanoid_nav_msgs/StepTarget[] executed_footsteps
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | ExecFootstepsActionGoal action_goal
4 | ExecFootstepsActionResult action_result
5 | ExecFootstepsActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | ExecFootstepsFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | ExecFootstepsGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | ExecFootstepsResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Define a feedback message
3 | humanoid_nav_msgs/StepTarget[] executed_footsteps
4 |
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Define the goal
3 | humanoid_nav_msgs/StepTarget[] footsteps
4 | float64 feedback_frequency
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/msg/ExecFootstepsResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Define the result
3 | humanoid_nav_msgs/StepTarget[] executed_footsteps
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/srv/ClipFootstep.srv:
--------------------------------------------------------------------------------
1 | StepTarget step
2 | ---
3 | StepTarget step
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/srv/PlanFootsteps.srv:
--------------------------------------------------------------------------------
1 | geometry_msgs/Pose2D start
2 | geometry_msgs/Pose2D goal
3 | ---
4 | bool result
5 | humanoid_nav_msgs/StepTarget[] footsteps
6 | float64 costs
7 | float64 final_eps
8 | float64 planning_time
9 | int64 expanded_states
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/humanoid_nav_msgs/srv/StepTargetService.srv:
--------------------------------------------------------------------------------
1 | # Step target as service:
2 | humanoid_nav_msgs/StepTarget step
3 | ---
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/msg/OccupancyGridUpdate.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | int32 x
3 | int32 y
4 | uint32 width
5 | uint32 height
6 | int8[] data
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/msg/PointCloud2Update.msg:
--------------------------------------------------------------------------------
1 | uint32 ADD=0
2 | uint32 DELETE=1
3 | Header header
4 | uint32 type # type of update, one of ADD or DELETE
5 | sensor_msgs/PointCloud2 points
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/msg/ProjectedMap.msg:
--------------------------------------------------------------------------------
1 | nav_msgs/OccupancyGrid map
2 | float64 min_z
3 | float64 max_z
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/msg/ProjectedMapInfo.msg:
--------------------------------------------------------------------------------
1 | string frame_id
2 | float64 x
3 | float64 y
4 | float64 width
5 | float64 height
6 | float64 min_z
7 | float64 max_z
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/GetMapROI.srv:
--------------------------------------------------------------------------------
1 | float64 x
2 | float64 y
3 | float64 l_x
4 | float64 l_y
5 | ---
6 | nav_msgs/OccupancyGrid sub_map
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/GetPointMap.srv:
--------------------------------------------------------------------------------
1 | # Get the map as a sensor_msgs/PointCloud2
2 | ---
3 | sensor_msgs/PointCloud2 map
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/GetPointMapROI.srv:
--------------------------------------------------------------------------------
1 | float64 x
2 | float64 y
3 | float64 z
4 | float64 r # if != 0, circular ROI of radius r
5 | float64 l_x # if r == 0, length of AABB on x
6 | float64 l_y # if r == 0, length of AABB on y
7 | float64 l_z # if r == 0, length of AABB on z
8 | ---
9 | sensor_msgs/PointCloud2 sub_map
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/ProjectedMapsInfo.srv:
--------------------------------------------------------------------------------
1 | map_msgs/ProjectedMapInfo[] projected_maps_info
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/SaveMap.srv:
--------------------------------------------------------------------------------
1 | # Save the map to the filesystem
2 | string filename
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/map_msgs/srv/SetMapProjections.srv:
--------------------------------------------------------------------------------
1 | ---
2 | map_msgs/ProjectedMapInfo[] projected_maps_info
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/action/MoveBase.action:
--------------------------------------------------------------------------------
1 | geometry_msgs/PoseStamped target_pose
2 | ---
3 | ---
4 | geometry_msgs/PoseStamped base_position
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | MoveBaseActionGoal action_goal
4 | MoveBaseActionResult action_result
5 | MoveBaseActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | MoveBaseFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | MoveBaseGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | MoveBaseResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | geometry_msgs/PoseStamped base_position
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | geometry_msgs/PoseStamped target_pose
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/move_base_msgs/msg/MoveBaseResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/action/GetMap.action:
--------------------------------------------------------------------------------
1 | # Get the map as a nav_msgs/OccupancyGrid
2 | ---
3 | nav_msgs/OccupancyGrid map
4 | ---
5 | # no feedback
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | GetMapActionGoal action_goal
4 | GetMapActionResult action_result
5 | GetMapActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | GetMapFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | GetMapGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | GetMapResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # no feedback
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Get the map as a nav_msgs/OccupancyGrid
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GetMapResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | nav_msgs/OccupancyGrid map
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/GridCells.msg:
--------------------------------------------------------------------------------
1 | #an array of cells in a 2D grid
2 | Header header
3 | float32 cell_width
4 | float32 cell_height
5 | geometry_msgs/Point[] cells
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/msg/Path.msg:
--------------------------------------------------------------------------------
1 | #An array of poses that represents a Path for a robot to follow
2 | Header header
3 | geometry_msgs/PoseStamped[] poses
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/srv/GetMap.srv:
--------------------------------------------------------------------------------
1 | # Get the map as a nav_msgs/OccupancyGrid
2 | ---
3 | nav_msgs/OccupancyGrid map
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/nav_msgs/srv/SetMap.srv:
--------------------------------------------------------------------------------
1 | # Set a new map together with an initial pose
2 | nav_msgs/OccupancyGrid map
3 | geometry_msgs/PoseWithCovarianceStamped initial_pose
4 | ---
5 | bool success
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/action/ObjectRecognition.action:
--------------------------------------------------------------------------------
1 | # Optional ROI to use for the object detection
2 | bool use_roi
3 | float32[] filter_limits
4 | ---
5 | # Send the found objects, see the msg files for docs
6 | object_recognition_msgs/RecognizedObjectArray recognized_objects
7 | ---
8 | #no feedback
9 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | ObjectRecognitionActionGoal action_goal
4 | ObjectRecognitionActionResult action_result
5 | ObjectRecognitionActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | ObjectRecognitionFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalID goal_id
5 | ObjectRecognitionGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | Header header
4 | actionlib_msgs/GoalStatus status
5 | ObjectRecognitionResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | #no feedback
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Optional ROI to use for the object detection
3 | bool use_roi
4 | float32[] filter_limits
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/ObjectRecognitionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | # Send the found objects, see the msg files for docs
3 | object_recognition_msgs/RecognizedObjectArray recognized_objects
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/msg/TableArray.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | # Just an array of tables
4 | object_recognition_msgs/Table[] tables
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/object_recognition_msgs/srv/GetObjectInformation.srv:
--------------------------------------------------------------------------------
1 | # Retrieve extra data from the DB for a given object
2 |
3 | # The type of the object to retrieve info from
4 | object_recognition_msgs/ObjectType type
5 |
6 | ---
7 |
8 | # Extra object info
9 | object_recognition_msgs/ObjectInformation information
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/octomap_msgs/msg/OctomapWithPose.msg:
--------------------------------------------------------------------------------
1 | # A 3D map in binary format, as Octree
2 | Header header
3 |
4 | # The pose of the octree with respect to the header frame
5 | geometry_msgs/Pose origin
6 |
7 | # The actual octree msg
8 | octomap_msgs/Octomap octomap
9 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/octomap_msgs/srv/GetOctomap.srv:
--------------------------------------------------------------------------------
1 | # Get the map as a octomap
2 | ---
3 | octomap_msgs/Octomap map
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/pcl_msgs/msg/ModelCoefficients.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | float32[] values
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/pcl_msgs/msg/PointIndices.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | int32[] indices
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/pcl_msgs/msg/PolygonMesh.msg:
--------------------------------------------------------------------------------
1 | # Separate header for the polygonal surface
2 | Header header
3 | # Vertices of the mesh as a point cloud
4 | sensor_msgs/PointCloud2 cloud
5 | # List of polygons
6 | Vertices[] polygons
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/pcl_msgs/msg/Vertices.msg:
--------------------------------------------------------------------------------
1 | # List of point indices
2 | uint32[] vertices
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/rock_publisher/imgData.msg:
--------------------------------------------------------------------------------
1 | int32 x
2 | int32 y
3 | int32 width
4 | int32 height
5 | ColorRGBA color
6 | int32 cameraID
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/rock_publisher/imgDataArray.msg:
--------------------------------------------------------------------------------
1 | imgData[] rockData
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/rock_publisher/recalibrateMsg.msg:
--------------------------------------------------------------------------------
1 | imgData data
2 | sensor_msgs/CompressedImage img
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/roscpp_tutorials/TwoInts.srv:
--------------------------------------------------------------------------------
1 | int64 a
2 | int64 b
3 | ---
4 | int64 sum
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/roscsharp/GetLoggers.srv:
--------------------------------------------------------------------------------
1 | ---
2 | Logger[] loggers
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/roscsharp/Logger.msg:
--------------------------------------------------------------------------------
1 | string name
2 | string level
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/roscsharp/SetLoggerLevel.srv:
--------------------------------------------------------------------------------
1 | string logger
2 | string level
3 | ---
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/rosgraph_msgs/Clock.msg:
--------------------------------------------------------------------------------
1 | time clock
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/sample_acquisition/ArmMovement.msg:
--------------------------------------------------------------------------------
1 | # ArmMovement.msg
2 | # [ml] Message type for controlling the arm and reporting arm status.
3 |
4 | bool gripper_open
5 |
6 | # Each of the following has a range of [-1,1]
7 | float64 pan_motor_velocity
8 | float64 tilt_motor_velocity
9 |
10 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/sample_acquisition/ArmStatus.msg:
--------------------------------------------------------------------------------
1 | int64 pan_position
2 | int64 tilt_position
3 | int64 cable_position
4 | bool engaged
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/sensor_msgs/msg/Joy.msg:
--------------------------------------------------------------------------------
1 | # Reports the state of a joysticks axes and buttons.
2 | Header header # timestamp in the header is the time the data is received from the joystick
3 | float32[] axes # the axes measurements from a joystick
4 | int32[] buttons # the buttons measurements from a joystick
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/sensor_msgs/msg/JoyFeedbackArray.msg:
--------------------------------------------------------------------------------
1 | # This message publishes values for multiple feedback at once.
2 | JoyFeedback[] array
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/sensor_msgs/msg/LaserEcho.msg:
--------------------------------------------------------------------------------
1 | # This message is a submessage of MultiEchoLaserScan and is not intended
2 | # to be used separately.
3 |
4 | float32[] echoes # Multiple values of ranges or intensities.
5 | # Each array represents data from the same angle increment.
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/shape_msgs/msg/Mesh.msg:
--------------------------------------------------------------------------------
1 | # Definition of a mesh
2 |
3 | # list of triangles; the index values refer to positions in vertices[]
4 | MeshTriangle[] triangles
5 |
6 | # the actual vertices that make up the mesh
7 | geometry_msgs/Point[] vertices
8 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/shape_msgs/msg/MeshTriangle.msg:
--------------------------------------------------------------------------------
1 | # Definition of a triangle's vertices
2 | uint32[3] vertex_indices
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/shape_msgs/msg/Plane.msg:
--------------------------------------------------------------------------------
1 | # Representation of a plane, using the plane equation ax + by + cz + d = 0
2 |
3 | # a := coef[0]
4 | # b := coef[1]
5 | # c := coef[2]
6 | # d := coef[3]
7 |
8 | float64[4] coef
9 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/stanford_msgs/ExampleCustom.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/Vector3 input
2 | geometry_msgs/Vector3 output
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Bool.msg:
--------------------------------------------------------------------------------
1 | bool data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Byte.msg:
--------------------------------------------------------------------------------
1 | byte data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/ByteMultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | byte[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Char.msg:
--------------------------------------------------------------------------------
1 | char data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/ColorRGBA.msg:
--------------------------------------------------------------------------------
1 | float32 r
2 | float32 g
3 | float32 b
4 | float32 a
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Duration.msg:
--------------------------------------------------------------------------------
1 | duration data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Empty.msg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/common_msgs/std_msgs/msg/Empty.msg
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Float32.msg:
--------------------------------------------------------------------------------
1 | float32 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Float32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | float32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Float64.msg:
--------------------------------------------------------------------------------
1 | float64 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Float64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | float64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int16.msg:
--------------------------------------------------------------------------------
1 | int16 data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int16MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int16[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int32.msg:
--------------------------------------------------------------------------------
1 | int32 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int64.msg:
--------------------------------------------------------------------------------
1 | int64 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int8.msg:
--------------------------------------------------------------------------------
1 | int8 data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Int8MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | int8[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/MultiArrayDimension.msg:
--------------------------------------------------------------------------------
1 | string label # label of given dimension
2 | uint32 size # size of given dimension (in type units)
3 | uint32 stride # stride of given dimension
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/String.msg:
--------------------------------------------------------------------------------
1 | string data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/Time.msg:
--------------------------------------------------------------------------------
1 | time data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt16.msg:
--------------------------------------------------------------------------------
1 | uint16 data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt16MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint16[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt32.msg:
--------------------------------------------------------------------------------
1 | uint32 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt32MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint32[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt64.msg:
--------------------------------------------------------------------------------
1 | uint64 data
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt64MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint64[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt8.msg:
--------------------------------------------------------------------------------
1 | uint8 data
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_msgs/msg/UInt8MultiArray.msg:
--------------------------------------------------------------------------------
1 | # Please look at the MultiArrayLayout message definition for
2 | # documentation on all multiarrays.
3 |
4 | MultiArrayLayout layout # specification of data layout
5 | uint8[] data # array of data
6 |
7 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_srvs/srv/Empty.srv:
--------------------------------------------------------------------------------
1 | ---
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_srvs/srv/SetBool.srv:
--------------------------------------------------------------------------------
1 | bool data # e.g. for hardware enabling / disabling
2 | ---
3 | bool success # indicate successful run of triggered service
4 | string message # informational, e.g. for error messages
5 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/std_srvs/srv/Trigger.srv:
--------------------------------------------------------------------------------
1 | ---
2 | bool success # indicate successful run of triggered service
3 | string message # informational, e.g. for error messages
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf/msg/tfMessage.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/TransformStamped[] transforms
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf/srv/FrameGraph.srv:
--------------------------------------------------------------------------------
1 | ---
2 | string dot_graph
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformAction.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | LookupTransformActionGoal action_goal
4 | LookupTransformActionResult action_result
5 | LookupTransformActionFeedback action_feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformActionFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | std_msgs/Header header
4 | actionlib_msgs/GoalStatus status
5 | LookupTransformFeedback feedback
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformActionGoal.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | std_msgs/Header header
4 | actionlib_msgs/GoalID goal_id
5 | LookupTransformGoal goal
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformActionResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 | std_msgs/Header header
4 | actionlib_msgs/GoalStatus status
5 | LookupTransformResult result
6 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformFeedback.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 |
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/LookupTransformResult.msg:
--------------------------------------------------------------------------------
1 | # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
2 | geometry_msgs/TransformStamped transform
3 | tf2_msgs/TF2Error error
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/TF2Error.msg:
--------------------------------------------------------------------------------
1 | uint8 NO_ERROR = 0
2 | uint8 LOOKUP_ERROR = 1
3 | uint8 CONNECTIVITY_ERROR = 2
4 | uint8 EXTRAPOLATION_ERROR = 3
5 | uint8 INVALID_ARGUMENT_ERROR = 4
6 | uint8 TIMEOUT_ERROR = 5
7 | uint8 TRANSFORM_ERROR = 6
8 |
9 | uint8 error
10 | string error_string
11 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/msg/TFMessage.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/TransformStamped[] transforms
2 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/tf2_msgs/srv/FrameGraph.srv:
--------------------------------------------------------------------------------
1 | ---
2 | string frame_yaml
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/DemuxAdd.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/DemuxDelete.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/DemuxList.srv:
--------------------------------------------------------------------------------
1 | ---
2 | string[] topics
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/DemuxSelect.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 | string prev_topic
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/MuxAdd.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/MuxDelete.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/MuxList.srv:
--------------------------------------------------------------------------------
1 | ---
2 | string[] topics
3 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/topic_tools/srv/MuxSelect.srv:
--------------------------------------------------------------------------------
1 | string topic
2 | ---
3 | string prev_topic
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/trajectory_msgs/msg/JointTrajectory.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 | string[] joint_names
3 | JointTrajectoryPoint[] points
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/trust_msgs/RunDescription.msg:
--------------------------------------------------------------------------------
1 | # Encodes information describing single run in the experiment.
2 |
3 | string participant_id
4 | string run_id
5 | string map_id
6 | string run_reliability
7 | string school_id
8 | string experiment_type
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/uvc_camera/camera_sliders.msg:
--------------------------------------------------------------------------------
1 | int32 brightness
2 | int32 contrast
3 | int32 exposure
4 | int32 gain
5 | int32 saturation
6 | int32 wbt
7 | int32 focus
8 | int32 focus_auto
9 | int32 exposure_auto
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/whosonfirst/Dibs.msg:
--------------------------------------------------------------------------------
1 | int32 manualRobot
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/wpf_msgs/Point2.msg:
--------------------------------------------------------------------------------
1 | float64 x
2 | float64 y
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/wpf_msgs/Waypoints.msg:
--------------------------------------------------------------------------------
1 | int32[] robots
2 | # these coordinates should transformed to the map already!
3 | Point2[] path
--------------------------------------------------------------------------------
/ROSNetUnity/common_msgs/wpf_msgs/WindowState.msg:
--------------------------------------------------------------------------------
1 | # map's position in window
2 | Point2 topleft
3 | Point2 bottomright
4 |
5 | #window size
6 | float32 width
7 | float32 height
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/Clock.cs:
--------------------------------------------------------------------------------
1 | using System;
2 | using System.Collections.Generic;
3 | using System.Linq;
4 | using System.Text;
5 | using Ros_CSharp;
6 | using XmlRpc_Wrapper;
7 | using Messages;
8 | using Messages.rosgraph_msgs;
9 |
10 | namespace rosmaster
11 | {
12 | class Clock
13 | {
14 |
15 | }
16 | }
17 |
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/Program.cs:
--------------------------------------------------------------------------------
1 | using System;
2 | using System.Collections.Generic;
3 | using System.Linq;
4 | using System.Text;
5 |
6 | namespace rosmaster
7 | {
8 | class Program
9 | {
10 | }
11 | }
12 |
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/bin/Debug/XmlRpc_Wrapper.dll:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/rosmaster/bin/Debug/XmlRpc_Wrapper.dll
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/bin/Debug/XmlRpc_Wrapper.pdb:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/luminartech/UnityROS/12a92185122fcc260e1cd383999ea6ac2b39153e/ROSNetUnity/rosmaster/bin/Debug/XmlRpc_Wrapper.pdb
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/bin/Debug/rosmaster.exe.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/ROSNetUnity/rosmaster/manager.cs:
--------------------------------------------------------------------------------
1 | using System;
2 | using System.Collections.Generic;
3 | using System.Linq;
4 | using System.Text;
5 | using XmlRpc_Wrapper;
6 |
7 | namespace rosmaster
8 | {
9 | class manager
10 | {
11 |
12 |
13 | }
14 | }
15 |
--------------------------------------------------------------------------------
/ROSNetUnity/tf_example/app.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/_config.yml:
--------------------------------------------------------------------------------
1 | theme: jekyll-theme-hacker
--------------------------------------------------------------------------------
/ros/.catkin_workspace:
--------------------------------------------------------------------------------
1 | # This file currently only serves to mark the location of a catkin workspace for tool integration
2 |
--------------------------------------------------------------------------------
/ros/src/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake
--------------------------------------------------------------------------------
/ros/src/stanford_msgs/launch/stanford.launch:
--------------------------------------------------------------------------------
1 |
2 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/ros/src/stanford_msgs/msg/ExampleCustom.msg:
--------------------------------------------------------------------------------
1 | geometry_msgs/Vector3 input
2 | geometry_msgs/Vector3 output
3 |
--------------------------------------------------------------------------------