├── .gitignore ├── .gitmodules ├── LICENSE ├── README.md ├── Resources ├── Icon.png └── Icon128.png ├── Source └── Unreal_ROS │ ├── Classes │ ├── CaptureActor.h │ ├── ROSActorPublisher.h │ ├── ROSServoActors.h │ ├── TopicTemplate.h │ └── ros_msg_test.h │ ├── Private │ ├── CaptureActor.cpp │ ├── ROSActorPublisher.cpp │ ├── ROSServoActors.cpp │ ├── TopicTemplate.cpp │ ├── Unreal_ROS_test.cpp │ └── ros_msg_test.cpp │ ├── Public │ └── Unreal_ROS.h │ └── Unreal_ROS.Build.cs ├── Unreal-ROS-Plugin.uplugin ├── example_ros_workspace ├── .catkin_workspace └── src │ └── CMakeLists.txt └── tools ├── FStructTemplate.cpp ├── FStructTemplate.h ├── data ├── actionlib_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── cmake │ │ ├── actionbuild.cmake │ │ └── actionlib_msgs-extras.cmake.em │ ├── msg │ │ ├── GoalID.msg │ │ ├── GoalStatus.msg │ │ └── GoalStatusArray.msg │ ├── package.xml │ └── scripts │ │ └── genaction.py ├── common_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── geometry_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── mainpage.dox │ ├── msg │ │ ├── Accel.msg │ │ ├── AccelStamped.msg │ │ ├── AccelWithCovariance.msg │ │ ├── AccelWithCovarianceStamped.msg │ │ ├── Inertia.msg │ │ ├── InertiaStamped.msg │ │ ├── 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 │ └── package.xml ├── nav_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── action │ │ └── GetMap.action │ ├── msg │ │ ├── GridCells.msg │ │ ├── MapMetaData.msg │ │ ├── OccupancyGrid.msg │ │ ├── Odometry.msg │ │ └── Path.msg │ ├── package.xml │ └── srv │ │ ├── GetMap.srv │ │ ├── GetPlan.srv │ │ └── SetMap.srv ├── sensor_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── include │ │ └── sensor_msgs │ │ │ ├── distortion_models.h │ │ │ ├── fill_image.h │ │ │ ├── image_encodings.h │ │ │ ├── impl │ │ │ └── point_cloud2_iterator.h │ │ │ ├── point_cloud2_iterator.h │ │ │ └── point_cloud_conversion.h │ ├── mainpage.dox │ ├── 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 │ ├── package.xml │ ├── setup.py │ ├── src │ │ └── sensor_msgs │ │ │ ├── __init__.py │ │ │ └── point_cloud2.py │ ├── srv │ │ └── SetCameraInfo.srv │ └── test │ │ ├── CMakeLists.txt │ │ └── main.cpp ├── std_msgs │ ├── .gitignore │ ├── CMakeLists.txt │ ├── include │ │ └── std_msgs │ │ │ ├── builtin_bool.h │ │ │ ├── builtin_double.h │ │ │ ├── builtin_float.h │ │ │ ├── builtin_int16.h │ │ │ ├── builtin_int32.h │ │ │ ├── builtin_int64.h │ │ │ ├── builtin_int8.h │ │ │ ├── builtin_string.h │ │ │ ├── builtin_uint16.h │ │ │ ├── builtin_uint32.h │ │ │ ├── builtin_uint64.h │ │ │ ├── builtin_uint8.h │ │ │ ├── header_deprecated_def.h │ │ │ └── trait_macros.h │ ├── 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 │ └── package.xml ├── stereo_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── mainpage.dox │ ├── msg │ │ └── DisparityImage.msg │ └── package.xml └── trajectory_msgs │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg │ ├── JointTrajectory.msg │ ├── JointTrajectoryPoint.msg │ ├── MultiDOFJointTrajectory.msg │ └── MultiDOFJointTrajectoryPoint.msg │ ├── package.xml │ └── rules │ └── JointTrajectoryPoint_Groovy2Hydro_08.10.2013.bmr ├── generate_msg.py ├── generate_msg_template.py ├── index.html └── websocketserver.py /.gitignore: -------------------------------------------------------------------------------- 1 | Binaries 2 | Intermediate 3 | # Compiled Object files 4 | *.slo 5 | *.lo 6 | *.o 7 | *.obj 8 | 9 | # Precompiled Headers 10 | *.gch 11 | *.pch 12 | 13 | # Compiled Dynamic libraries 14 | *.so 15 | *.dylib 16 | *.dll 17 | 18 | # Fortran module files 19 | *.mod 20 | 21 | # Compiled Static libraries 22 | *.lai 23 | *.la 24 | *.a 25 | *.lib 26 | 27 | # Executables 28 | *.exe 29 | *.out 30 | *.app 31 | example_ros_workspace/build 32 | example_ros_workspace/devel 33 | .idea 34 | *.log 35 | tools/data 36 | tools/data2 37 | Thirdparty/opencv -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "ThirdParty/rapidjson"] 2 | path = ThirdParty/rapidjson 3 | url = https://github.com/miloyip/rapidjson 4 | branch = master 5 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2015 XuHao 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | 23 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Unreal-ROS-Plugin 2 | An ROS plugin for unreal engine which let us work with ROS and Unreal Engine. 3 | 4 | We are trying to develop a tool which can work with Unreal Engine and ROS so we can more easily devleop a VR application which will be better than OpenGL or QT3D. 5 | 6 | For an example, I will use DJI Onboard SDK with ROS for testing. 7 | ## Framework 8 | 9 | Most Unreal applications (the video games) run on fast desktop or console systems, but ROS often runs on embedded systems like ARM Linux with the NVIDIA Tegra TK1. To get around this we use full roscpp client within Unreal, but rosbridge as the client. All the messages will pass through rosbridge via websocket to reduce the need to compile binaries. 10 | 11 | ## Roadmap 12 | 13 | ### Display 14 | First we will develop a controller which will pass odometry messages as to control for Unreal, and also a parameter from ROS to switch models. 15 | 16 | ### Control 17 | We will develop a method to synchronize and then pass the control signal from Unreal to ROS. 18 | 19 | ### Simulation 20 | Simulation is the easiest thing for Unreal. 21 | 22 | #### Msg2Unreal 23 | 24 | Generate USTRUCT or UCLASS from msg define. 25 | 26 | #### Service2Unreal 27 | 28 | Generate Function from Service 29 | 30 | #### Action2Unreal 31 | 32 | Generate Action (with callback) from action definition. 33 | -------------------------------------------------------------------------------- /Resources/Icon.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xuhao1/Unreal-ROS-Plugin/c61241f58b9b17c8f5a97f0be94aa60c263462b2/Resources/Icon.png -------------------------------------------------------------------------------- /Resources/Icon128.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xuhao1/Unreal-ROS-Plugin/c61241f58b9b17c8f5a97f0be94aa60c263462b2/Resources/Icon128.png -------------------------------------------------------------------------------- /Source/Unreal_ROS/Classes/CaptureActor.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "Unreal_ROS.h" 3 | #include "Engine.h" 4 | #include "Engine/SceneCapture2D.h" 5 | #include 6 | #include "CaptureActor.generated.h" 7 | 8 | UCLASS() 9 | class ACameraCapturer : public ASceneCapture2D 10 | { 11 | GENERATED_BODY() 12 | 13 | private_subobject: 14 | 15 | UTextureRenderTarget2D* TextureRenderTarget; 16 | 17 | std::string cam_id; 18 | public: 19 | ACameraCapturer(); 20 | void SetCameraID(std::string _cam_id); 21 | ~ACameraCapturer(); 22 | 23 | void BeginPlay() override; 24 | void ShowCameraView(std::string CameraID, UTextureRenderTarget2D* CameraTexture2D); 25 | void Tick(float DeltaSeconds) override; 26 | }; 27 | -------------------------------------------------------------------------------- /Source/Unreal_ROS/Classes/ROSActorPublisher.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "Unreal_ROS.h" 3 | #include "TopicTemplate.h" 4 | #include "ros_msg_test.h" 5 | #include "ROSActorPublisher.generated.h" 6 | 7 | UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) ) 8 | class UPhysicsPublisherComponent : public USceneComponent 9 | { 10 | 11 | GENERATED_UCLASS_BODY() 12 | 13 | public: 14 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 15 | int32 UpdateFrequency = 30; 16 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 17 | bool Enable = true; 18 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 19 | bool EnablePose = true; 20 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 21 | bool EnableTwist = true; 22 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 23 | bool EnableAccel = false; 24 | 25 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 26 | FString ActorName = "test-name"; 27 | U_geometry_msgs_PoseAdvertiser * PoseAd = nullptr; 28 | U_geometry_msgs_TwistAdvertiser * TwistAd = nullptr; 29 | U_geometry_msgs_AccelAdvertiser * AccelAd = nullptr; 30 | 31 | void TickComponent(float DeltaTime, enum ELevelTick TickType, FActorComponentTickFunction * ThisTickFunction) override; 32 | void BeginPlay() override; 33 | UPrimitiveComponent * root = nullptr; 34 | FBodyInstance * inst = nullptr; 35 | FCalculateCustomPhysics * delegate = nullptr; 36 | F_geometry_msgs_Pose pose_ros; 37 | F_geometry_msgs_Twist twist_ros; 38 | F_geometry_msgs_Accel accel_ros; 39 | int phys_tick = 0; 40 | float PhysTotalTime = 0; 41 | float LastReported = 0; 42 | }; -------------------------------------------------------------------------------- /Source/Unreal_ROS/Classes/ROSServoActors.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "Unreal_ROS.h" 4 | #include "TopicTemplate.h" 5 | #include "ros_msg_test.h" 6 | #include "PhysicsEngine/PhysicsConstraintComponent.h" 7 | #include "ROSServoActors.generated.h" 8 | 9 | UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) ) 10 | class UROSMotorConstrainComponent : public USceneComponent 11 | { 12 | GENERATED_UCLASS_BODY() 13 | public: 14 | void TickComponent(float DeltaTime, enum ELevelTick TickType, FActorComponentTickFunction * ThisTickFunction) override; 15 | void BeginPlay() override; 16 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="MOTOR") 17 | UPhysicsConstraintComponent * ConstrainComponent; 18 | UPrimitiveComponent * rotor; 19 | 20 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="MOTOR") 21 | float speed = 0; 22 | 23 | }; 24 | 25 | 26 | UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) ) 27 | class UROSPoseDriver : public USceneComponent 28 | { 29 | GENERATED_UCLASS_BODY() 30 | public: 31 | void TickComponent(float DeltaTime, enum ELevelTick TickType, FActorComponentTickFunction * ThisTickFunction) override; 32 | void BeginPlay() override; 33 | UPrimitiveComponent * root; 34 | 35 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="Robot OS") 36 | FString SubscribeTopic = ""; 37 | 38 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="Constrain") 39 | bool LockX = false; 40 | 41 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="Constrain") 42 | bool LockY = false; 43 | 44 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="Constrain") 45 | bool LockZ = false; 46 | 47 | UPROPERTY(BlueprintReadWrite, EditAnywhere,Category="Coordinate") 48 | bool UsingNED = false; 49 | 50 | UFUNCTION() 51 | void OnPoseData(F_geometry_msgs_Pose pose_ros); 52 | 53 | U_geometry_msgs_PoseSubscriber * PoseSub = nullptr; 54 | 55 | F_geometry_msgs_Pose pose_ros; 56 | ~UROSPoseDriver() 57 | { 58 | if (PoseSub!=nullptr) 59 | PoseSub = nullptr; 60 | } 61 | 62 | }; 63 | -------------------------------------------------------------------------------- /Source/Unreal_ROS/Classes/TopicTemplate.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "Unreal_ROS.h" 4 | #include "EngineMinimal.h" 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include "Runtime/Networking/Public/Networking.h" 10 | #include "Runtime/Networking/Public/Interfaces/IPv4/IPv4Endpoint.h" 11 | #include "Runtime/Networking/Public/Common/TcpSocketBuilder.h" 12 | #include "Runtime/Networking/Public/Common/UdpSocketBuilder.h" 13 | #include "Runtime/Networking/Public/Interfaces/IPv4/IPv4Address.h" 14 | #include "Runtime/Sockets/Public/Sockets.h" 15 | #if PLATFORM_WINDOWS 16 | #include "AllowWindowsPlatformTypes.h" 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include "HideWindowsPlatformTypes.h" 22 | #else 23 | #include 24 | #endif 25 | #include 26 | #include 27 | #include "Runtime/Networking/Public/Common/UdpSocketReceiver.h" 28 | #include "TopicTemplate.generated.h" 29 | 30 | typedef std::function SubscribeCB; 31 | #define isUDP 32 | 33 | class TCPClient 34 | { 35 | public: 36 | static FSocket * InitNetwork(FString _RosMaster, int ThePort) 37 | { 38 | auto addr = ISocketSubsystem::Get(PLATFORM_SOCKETSUBSYSTEM)->CreateInternetAddr(); 39 | bool isVaild = false; 40 | addr->SetIp(*_RosMaster,isVaild); 41 | addr->SetPort(ThePort); 42 | UE_LOG(LogTemp, Log, TEXT("Try to connect remote")); 43 | FSocket * sock = nullptr; 44 | sock = FUdpSocketBuilder(TEXT("test ros udp")) 45 | .AsReusable().AsNonBlocking(); 46 | sock->Connect(*addr); 47 | return sock; 48 | } 49 | static uint8* RapidJson2Buffer(rapidjson::Document & d, int32 & Count) 50 | { 51 | rapidjson::StringBuffer buffer; 52 | rapidjson::Writer writer(buffer); 53 | d.Accept(writer); 54 | Count = buffer.GetSize(); 55 | const char * str = buffer.GetString(); 56 | uint8 * res = new uint8[Count]; 57 | memcpy(res,str,sizeof(char)*Count); 58 | return res; 59 | } 60 | }; 61 | 62 | UCLASS() 63 | class UAdvertiser : public UObject 64 | { 65 | 66 | GENERATED_UCLASS_BODY() 67 | public: 68 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 69 | static void InitRos(FString _RosMaster, int32 _ThePort); 70 | 71 | //UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 72 | FString TopicName; 73 | FString TypeName; 74 | //UFUNCTION(BlueprintCallable, Category = "Robot OS") 75 | bool Advertise(); 76 | bool SendJson(rapidjson::Document &d); 77 | bool Advertised = false; 78 | 79 | FSocket * sock; 80 | 81 | ~UAdvertiser() 82 | { 83 | sock->Close(); 84 | delete sock; 85 | } 86 | }; 87 | 88 | 89 | UCLASS() 90 | class USubscriber : public UObject 91 | { 92 | GENERATED_UCLASS_BODY() 93 | public: 94 | FUdpSocketReceiver * Receiver = nullptr; 95 | std::mutex mtx; 96 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 97 | FString TopicName; 98 | FString TypeName; 99 | virtual void ProccessMsg(rapidjson::Value & obj); 100 | void Subscribe(); 101 | bool SendJson(rapidjson::Document &d); 102 | 103 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 104 | static USubscriber * CreateDebugSubscriber(FString _TopicName, FString _TypeName); 105 | FSocket * sock; 106 | std::thread * th = nullptr; 107 | bool Running = true; 108 | uint8 * Data = nullptr; 109 | bool Subscring = false; 110 | 111 | ~USubscriber() 112 | { 113 | Running = false; 114 | if (Receiver) 115 | Receiver->Stop(); 116 | if (th != nullptr) 117 | { 118 | th->join(); 119 | } 120 | sock->Close(); 121 | delete sock; 122 | } 123 | }; -------------------------------------------------------------------------------- /Source/Unreal_ROS/Private/CaptureActor.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | #include "CaptureActor.h" 3 | #include "Engine/TextureRenderTarget2D.h" 4 | //#include "opencv2/opencv.hpp" 5 | #include 6 | static int id_cam = 0; 7 | ACameraCapturer::ACameraCapturer() 8 | { 9 | //TextureRenderTarget = CreateDefaultSubobject(TEXT("Camera")); 10 | //TextureRenderTarget->InitAutoFormat(256, 256); 11 | //this->GetCaptureComponent2D()->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR; 12 | //this->GetCaptureComponent2D()->TextureTarget = TextureRenderTarget; 13 | //this->SetCameraID("fuck"); 14 | } 15 | void ACameraCapturer::SetCameraID(std::string _cam_id) 16 | { 17 | std::string camera_name = std::to_string(id_cam); 18 | cam_id = camera_name; 19 | id_cam ++; 20 | } 21 | ACameraCapturer::~ACameraCapturer() 22 | { 23 | } 24 | void ACameraCapturer::ShowCameraView(std::string CameraID, UTextureRenderTarget2D* CameraTexture2D) 25 | { 26 | TArray FormatedImageData; 27 | FRenderTarget* RenderTarget = CameraTexture2D->GameThread_GetRenderTargetResource(); 28 | if (RenderTarget) 29 | { 30 | if (RenderTarget->ReadPixels(FormatedImageData)) 31 | { 32 | if (FormatedImageData.Num() != 0) 33 | { 34 | //cv::Mat smallImage(cv::Size(256, 256), CV_8UC4, (unsigned char *)FormatedImageData.GetData()); 35 | //cv::imshow(CameraID.c_str(), smallImage); 36 | } 37 | } 38 | } 39 | } 40 | void ACameraCapturer::BeginPlay() 41 | { 42 | Super::BeginPlay(); 43 | } 44 | 45 | void ACameraCapturer::Tick(float DeltaSeconds) 46 | { 47 | this->GetCaptureComponent2D()->UpdateContent(); 48 | 49 | if (TextureRenderTarget->TextureReference.IsInitialized()) 50 | { 51 | ShowCameraView(cam_id, TextureRenderTarget); 52 | } 53 | 54 | Super::Tick(DeltaSeconds); 55 | } -------------------------------------------------------------------------------- /Source/Unreal_ROS/Private/ROSActorPublisher.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | #include "ROSActorPublisher.h" 3 | 4 | UPhysicsPublisherComponent::UPhysicsPublisherComponent(const FObjectInitializer& ObjectInitializer) 5 | : Super(ObjectInitializer) 6 | { 7 | bWantsBeginPlay = true; 8 | PrimaryComponentTick.bCanEverTick = true; 9 | } 10 | 11 | void UPhysicsPublisherComponent::BeginPlay() 12 | { 13 | auto comp = GetOwner()->GetRootComponent(); 14 | if (static_cast(comp) != nullptr) 15 | { 16 | UE_LOG(LogTemp, Log, TEXT("FUCK-ROOT")); 17 | root = static_cast(comp); 18 | inst = &root->BodyInstance; 19 | } 20 | else { 21 | UE_LOG(LogTemp, Log, TEXT("NO-FUCK-ROOT")); 22 | } 23 | 24 | delegate = new FCalculateCustomPhysics; 25 | delegate->BindLambda([&](float t, FBodyInstance* f) 26 | { 27 | PhysTotalTime += t; 28 | FTransform trans = f->GetUnrealWorldTransform(false); 29 | pose_ros.position.x = trans.GetLocation().X / 100; 30 | pose_ros.position.y = trans.GetLocation().Y / 100; 31 | pose_ros.position.z = - trans.GetLocation().Z / 100; 32 | pose_ros.orientation.w = trans.GetRotation().W; 33 | pose_ros.orientation.x = trans.GetRotation().X; 34 | pose_ros.orientation.y = trans.GetRotation().Y; 35 | pose_ros.orientation.z = trans.GetRotation().Z; 36 | 37 | FVector Vel = f->GetUnrealWorldVelocity(); 38 | FVector AngularVel = f->GetUnrealWorldAngularVelocity(); 39 | twist_ros.linear.x = Vel.X /100; 40 | twist_ros.linear.y = Vel.Y /100; 41 | twist_ros.linear.z = - Vel.Z/100; 42 | AngularVel = trans.GetRotation().UnrotateVector(AngularVel); 43 | twist_ros.angular.x = - AngularVel.X; 44 | twist_ros.angular.y = - AngularVel.Y; 45 | twist_ros.angular.z = - AngularVel.Z; 46 | 47 | float DelaT = 1.0 / (float)UpdateFrequency; 48 | if (PhysTotalTime - LastReported > DelaT) 49 | { 50 | LastReported = PhysTotalTime; 51 | if (EnablePose && PoseAd) 52 | { 53 | PoseAd->Publish(pose_ros); 54 | } 55 | if (EnableTwist && TwistAd) 56 | { 57 | TwistAd->Publish(twist_ros); 58 | } 59 | } 60 | }); 61 | } 62 | 63 | void UPhysicsPublisherComponent::TickComponent(float DeltaTime,enum ELevelTick TickType,FActorComponentTickFunction * ThisTickFunction) 64 | { 65 | if (root == nullptr) 66 | { 67 | UE_LOG(LogTemp, Log, TEXT("No root ")); 68 | return; 69 | } 70 | //Find if simulate phys 71 | if (!inst->bSimulatePhysics) 72 | { 73 | UE_LOG(LogTemp, Log, TEXT("Not simulate Phys ")); 74 | return; 75 | } 76 | if (EnablePose && PoseAd == nullptr) 77 | { 78 | UE_LOG(LogTemp, Log, TEXT("Create Pose Ad ")); 79 | PoseAd = U_geometry_msgs_PoseAdvertiser::Create_Pose_Advertiser(ActorName +"/pose"); 80 | } 81 | if (EnableTwist && TwistAd == nullptr) 82 | { 83 | TwistAd = U_geometry_msgs_TwistAdvertiser::Create_Twist_Advertiser(ActorName + "/twist"); 84 | } 85 | if (EnableAccel && AccelAd == nullptr) 86 | { 87 | AccelAd = U_geometry_msgs_AccelAdvertiser::Create_Accel_Advertiser(ActorName+"/accel"); 88 | } 89 | 90 | inst->AddCustomPhysics(*delegate); 91 | 92 | } -------------------------------------------------------------------------------- /Source/Unreal_ROS/Private/ROSServoActors.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | #include "ROSServoActors.h" 3 | 4 | UROSMotorConstrainComponent::UROSMotorConstrainComponent(const FObjectInitializer& ObjectInitializer) 5 | : Super(ObjectInitializer) 6 | { 7 | bWantsBeginPlay = true; 8 | PrimaryComponentTick.bCanEverTick = true; 9 | ConstrainComponent = CreateDefaultSubobject(TEXT("PhysicsConstraint")); 10 | } 11 | 12 | void UROSMotorConstrainComponent::BeginPlay() 13 | { 14 | UObjectPropertyBase* ObjProp = FindField(GetOwner()->GetClass(),ConstrainComponent->ComponentName2.ComponentName); 15 | if (ObjProp != nullptr) 16 | { 17 | rotor = Cast(ObjProp->GetObjectPropertyValue_InContainer(GetOwner())); 18 | } 19 | else { 20 | UE_LOG(LogTemp, Log, TEXT("NO rotor!!")); 21 | } 22 | 23 | } 24 | 25 | void UROSMotorConstrainComponent::TickComponent(float DeltaTime, enum ELevelTick TickType, FActorComponentTickFunction * ThisTickFunction) 26 | { 27 | if (rotor != nullptr) 28 | { 29 | FTransform trans = this->GetRelativeTransform(); 30 | FQuat rot = trans.GetRotation(); 31 | FVector speec = rot.RotateVector(FVector(speed, 0, 0)); 32 | rotor->GetBodyInstance()->SetAngularVelocity(speec,false); 33 | } 34 | } 35 | 36 | UROSPoseDriver::UROSPoseDriver(const FObjectInitializer& ObjectInitializer) 37 | : Super(ObjectInitializer) 38 | { 39 | bWantsBeginPlay = true; 40 | PrimaryComponentTick.bCanEverTick = true; 41 | } 42 | 43 | void UROSPoseDriver::BeginPlay() 44 | { 45 | root = GetOwner()->GetRootPrimitiveComponent(); 46 | 47 | if (root == nullptr) 48 | { 49 | UE_LOG(LogTemp, Log, TEXT("NO root!!")); 50 | } 51 | pose_ros.orientation.w = 1; 52 | } 53 | 54 | void UROSPoseDriver::TickComponent(float DeltaTime, enum ELevelTick TickType, FActorComponentTickFunction * ThisTickFunction) 55 | { 56 | if (root != nullptr ) 57 | { 58 | if (PoseSub == nullptr) 59 | { 60 | PoseSub = U_geometry_msgs_PoseSubscriber::Create_Pose_Subscriber(SubscribeTopic); 61 | PoseSub->OnPoseData.AddDynamic(this,&UROSPoseDriver::OnPoseData); 62 | } 63 | 64 | FVector loc; 65 | loc.X = pose_ros.position.x; 66 | loc.Y = pose_ros.position.y; 67 | if (UsingNED) 68 | loc.Z = - pose_ros.position.z; 69 | FQuat rot( 70 | pose_ros.orientation.x, 71 | pose_ros.orientation.y, 72 | pose_ros.orientation.z, 73 | pose_ros.orientation.w 74 | ); 75 | FTransform trans(rot,loc); 76 | root->GetBodyInstance()->SetBodyTransform(trans,true); 77 | } 78 | } 79 | void UROSPoseDriver::OnPoseData(F_geometry_msgs_Pose pose_ros) 80 | { 81 | this->pose_ros = pose_ros; 82 | UE_LOG(LogTemp,Log,TEXT("new pose come")); 83 | } 84 | -------------------------------------------------------------------------------- /Source/Unreal_ROS/Private/TopicTemplate.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | #include "TopicTemplate.h" 3 | #include "rapidjson/rapidjson.h" 4 | #include "rapidjson/document.h" 5 | #include 6 | #include 7 | 8 | FString RosMaster; 9 | int ThePort; 10 | struct ipvalue 11 | { 12 | #if PLATFORM_LITTLE_ENDIAN 13 | #if _MSC_VER 14 | uint8 D, C, B, A; 15 | #else 16 | uint8 D GCC_ALIGN(4); 17 | uint8 C, B, A; 18 | #endif 19 | #else 20 | uint8 A, B, C, D; 21 | #endif 22 | }; 23 | 24 | UAdvertiser::UAdvertiser(const FObjectInitializer& ObjectInitializer) 25 | : Super(ObjectInitializer) 26 | { 27 | 28 | } 29 | 30 | 31 | void UAdvertiser::InitRos(FString _RosMaster, int32 _ThePort) 32 | { 33 | RosMaster = _RosMaster; 34 | ThePort = _ThePort; 35 | } 36 | 37 | bool UAdvertiser::Advertise() 38 | { 39 | if (this->sock == nullptr) 40 | { 41 | this->sock = TCPClient::InitNetwork(RosMaster, ThePort); 42 | } 43 | rapidjson::Document d; 44 | d.SetObject(); 45 | d.AddMember("op", "advertise", d.GetAllocator()); 46 | d.AddMember("id", "fuck-id", d.GetAllocator()); 47 | //UE_LOG(LogTemp, Log, TEXT("tname %s"), *this->TopicName); 48 | rapidjson::Value RTopicName; 49 | std::string temTN = std::string(TCHAR_TO_UTF8(*this->TopicName)); 50 | RTopicName.SetString(rapidjson::StringRef(temTN.c_str())); 51 | d.AddMember("topic", RTopicName, d.GetAllocator()); 52 | rapidjson::Value TypeName; 53 | std::string temTY = std::string(TCHAR_TO_UTF8(*this->TypeName)); 54 | TypeName.SetString(rapidjson::StringRef(temTY.c_str())); 55 | d.AddMember("type", TypeName, d.GetAllocator()); 56 | return (Advertised = SendJson(d)); 57 | } 58 | 59 | bool UAdvertiser::SendJson(rapidjson::Document &d) 60 | { 61 | int len = -1; 62 | int sent = -1; 63 | auto str = TCPClient::RapidJson2Buffer(d, len); 64 | 65 | sock->Send(str, len, sent); 66 | delete str; 67 | if (len != sent) 68 | { 69 | return false; 70 | } 71 | else { 72 | return true; 73 | } 74 | } 75 | 76 | USubscriber::USubscriber(const FObjectInitializer& ObjectInitializer) 77 | : Super(ObjectInitializer) 78 | { 79 | Data = new uint8[1024 * 1024]; 80 | memset(Data, 0, sizeof(char) * 1024 * 1024); 81 | Running = true; 82 | } 83 | 84 | void USubscriber::Subscribe() 85 | { 86 | rapidjson::Document d; 87 | d.SetObject(); 88 | d.AddMember("op", "subscribe", d.GetAllocator()); 89 | d.AddMember("id", "fuck-id", d.GetAllocator()); 90 | rapidjson::Value RTopicName; 91 | std::string temTN = std::string(TCHAR_TO_UTF8(*this->TopicName)); 92 | //std::string temTN = ""; 93 | RTopicName.SetString(rapidjson::StringRef(temTN.c_str())); 94 | d.AddMember("topic", RTopicName, d.GetAllocator()); 95 | rapidjson::Value TypeName; 96 | std::string temTY = std::string(TCHAR_TO_UTF8(*this->TypeName)); 97 | TypeName.SetString(rapidjson::StringRef(temTY.c_str())); 98 | d.AddMember("type", TypeName, d.GetAllocator()); 99 | if (this->sock == nullptr) 100 | { 101 | this->sock = TCPClient::InitNetwork(RosMaster, ThePort); 102 | Receiver = new FUdpSocketReceiver(this->sock, 0, TEXT("nothing")); 103 | Receiver->OnDataReceived().BindLambda([&](FArrayReaderPtr ptr,FIPv4Endpoint ip) { 104 | memcpy(Data, ptr->GetData(), sizeof(char)*ptr->Num()); 105 | FString fstr = UTF8_TO_TCHAR(Data); 106 | rapidjson::Document d; 107 | d.Parse((char *)Data); 108 | memset(Data, 0, sizeof(char)*ptr->Num()); 109 | 110 | if (d.HasParseError()) 111 | { 112 | UE_LOG(LogTemp, Log, TEXT("Wrong data")); 113 | } 114 | else 115 | { 116 | if (d.HasMember("op") && d["op"].GetType() == rapidjson::kStringType 117 | && std::string(d["op"].GetString()) == "publish" 118 | &&d.HasMember("msg") && d["msg"].GetType() == rapidjson::kObjectType 119 | ) 120 | { 121 | ProccessMsg(d["msg"]); 122 | } 123 | } 124 | }); 125 | } 126 | this->Subscring = this->SendJson(d); 127 | } 128 | 129 | bool USubscriber::SendJson(rapidjson::Document &d) 130 | { 131 | int len = -1; 132 | int sent = -1; 133 | auto str = TCPClient::RapidJson2Buffer(d, len); 134 | sock->Send(str, len, sent); 135 | delete str; 136 | if (len != sent) 137 | { 138 | return false; 139 | } 140 | else { 141 | return true; 142 | } 143 | } 144 | 145 | 146 | void USubscriber::ProccessMsg(rapidjson::Value & obj) 147 | { 148 | UE_LOG(LogTemp, Log, TEXT("Recv Msg")); 149 | } 150 | 151 | USubscriber * USubscriber::CreateDebugSubscriber(FString _TopicName, FString _TypeName) 152 | { 153 | USubscriber * sub = NewObject(); 154 | sub->TopicName = _TopicName; 155 | sub->TypeName = _TypeName; 156 | sub->Subscribe(); 157 | return sub; 158 | } -------------------------------------------------------------------------------- /Source/Unreal_ROS/Private/Unreal_ROS_test.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | 3 | class FROSPlugin : public IROSPlugin 4 | { 5 | /** IModuleInterface implementation */ 6 | virtual void StartupModule() override; 7 | virtual void ShutdownModule() override; 8 | }; 9 | 10 | IMPLEMENT_MODULE(FROSPlugin, Unreal_ROS) 11 | 12 | 13 | 14 | void FROSPlugin::StartupModule() 15 | { 16 | // This code will execute after your module is loaded into memory (but after global variables are initialized, of course.) 17 | } 18 | 19 | 20 | void FROSPlugin::ShutdownModule() 21 | { 22 | // This function may be called during shutdown to clean up your module. For modules that support dynamic reloading, 23 | // we call this function before unloading the module. 24 | } 25 | 26 | 27 | -------------------------------------------------------------------------------- /Source/Unreal_ROS/Public/Unreal_ROS.h: -------------------------------------------------------------------------------- 1 | #ifndef __CppTestADV_H__ 2 | #define __CppTestADV_H__ 3 | 4 | #include "ModuleManager.h" 5 | 6 | 7 | /** 8 | * The public interface to this module 9 | */ 10 | class IROSPlugin : public IModuleInterface 11 | { 12 | 13 | public: 14 | 15 | /** 16 | * Singleton-like access to this module's interface. This is just for convenience! 17 | * Beware of calling this during the shutdown phase, though. Your module might have been unloaded already. 18 | * 19 | * @return Returns singleton instance, loading the module on demand if needed 20 | */ 21 | static inline IROSPlugin& Get() 22 | { 23 | return FModuleManager::LoadModuleChecked< IROSPlugin >("Unreal_ROS"); 24 | } 25 | 26 | /** 27 | * Checks to see if this module is loaded and ready. It is only valid to call Get() if IsAvailable() returns true. 28 | * 29 | * @return True if the module is loaded and ready to use 30 | */ 31 | static inline bool IsAvailable() 32 | { 33 | return FModuleManager::Get().IsModuleLoaded("Unreal_ROS"); 34 | } 35 | }; 36 | 37 | 38 | 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /Source/Unreal_ROS/Unreal_ROS.Build.cs: -------------------------------------------------------------------------------- 1 | // Copyright 1998-2015 Epic Games, Inc. All Rights Reserved. 2 | using UnrealBuildTool; 3 | using System.IO; 4 | using System.Diagnostics; 5 | 6 | namespace UnrealBuildTool.Rules 7 | { 8 | public class Unreal_ROS : ModuleRules 9 | { 10 | private string ThirdPartyPath 11 | { 12 | get 13 | { 14 | return Path.GetFullPath(Path.Combine(ModuleDirectory, "../../ThirdParty/")); 15 | } 16 | } 17 | public bool LoadOpenCV(TargetInfo Target) 18 | { 19 | bool isLibrarySupported = false; 20 | 21 | if ((Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32)) 22 | { 23 | isLibrarySupported = true; 24 | PublicIncludePaths.Add(Path.Combine(ThirdPartyPath, "opencv","include")); 25 | string PlatformString = (Target.Platform == UnrealTargetPlatform.Win64) ? "x64" : "x86"; 26 | string LibrariesPath = Path.Combine(ThirdPartyPath, "opencv", PlatformString, "vc12", "lib"); 27 | foreach (var file in Directory.EnumerateFiles(LibrariesPath, "*.lib", SearchOption.AllDirectories)) 28 | { 29 | PublicAdditionalLibraries.Add(file); 30 | Debug.Print("Including Lib : " + file); 31 | } 32 | } 33 | else if(Target.Platform == UnrealTargetPlatform.Mac) 34 | { 35 | isLibrarySupported = true; 36 | PublicIncludePaths.Add("/usr/local/Cellar/opencv/2.4.12/include"); 37 | string LibrariesPath = Path.Combine("/usr/local/Cellar/opencv/2.4.12", "lib"); 38 | foreach (var file in Directory.EnumerateFiles(LibrariesPath, "*.dylib", SearchOption.AllDirectories)) 39 | { 40 | PublicAdditionalLibraries.Add(file); 41 | Debug.Print("Including Lib : " + file); 42 | } 43 | } 44 | 45 | 46 | Debug.Print("Included Third Part : " + Path.Combine(ThirdPartyPath, "opencv")); 47 | return isLibrarySupported; 48 | } 49 | 50 | public Unreal_ROS(TargetInfo Target) 51 | { 52 | //PrivateIncludePaths.AddRange( 53 | // ); 54 | 55 | PrivateDependencyModuleNames.AddRange( 56 | new string[] 57 | { 58 | "Core", 59 | "Networking", 60 | "Sockets" 61 | } 62 | ); 63 | string rapidjson_path = Path.Combine(ThirdPartyPath, "rapidjson", "include"); 64 | 65 | System.Diagnostics.Debug.Write(rapidjson_path); 66 | PublicIncludePaths.AddRange(new string[] { rapidjson_path }); 67 | PrivateIncludePaths.AddRange(new string[] { rapidjson_path }); 68 | //LoadOpenCV(Target); 69 | 70 | if (UEBuildConfiguration.bBuildEditor == true) 71 | { 72 | PrivateDependencyModuleNames.Add("UnrealEd"); 73 | } 74 | 75 | PrivateDependencyModuleNames.AddRange( 76 | new string[] 77 | { 78 | "Core", 79 | "CoreUObject", 80 | "Engine", 81 | "InputCore" 82 | } 83 | ); 84 | 85 | 86 | } 87 | } 88 | } 89 | -------------------------------------------------------------------------------- /Unreal-ROS-Plugin.uplugin: -------------------------------------------------------------------------------- 1 | { 2 | "FileVersion" : 3, 3 | "FriendlyName" : "Unreal-ROS-Plugin", 4 | 5 | "Modules" : 6 | [ 7 | { 8 | "Name" : "Unreal_ROS", 9 | "Type" : "Runtime" 10 | } 11 | ] 12 | } 13 | -------------------------------------------------------------------------------- /example_ros_workspace/.catkin_workspace: -------------------------------------------------------------------------------- 1 | # This file currently only serves to mark the location of a catkin workspace for tool integration 2 | -------------------------------------------------------------------------------- /example_ros_workspace/src/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /Users/xuhao/.ros_env/ros_catkin_ws/src/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /tools/FStructTemplate.cpp: -------------------------------------------------------------------------------- 1 | #include "Unreal_ROS.h" 2 | #include "{{Header}}" 3 | 4 | {% for Struct in StructList%} 5 | {% set TypeName = Struct.name %} 6 | {% set TypeNameFull = Struct.namefull %} 7 | {% set Props = Struct.props %} 8 | {% set FName = "F_"+Struct.GeneratedName %} 9 | {% set ADName = "U_"+Struct.GeneratedName + "Advertiser" %} 10 | 11 | void {{FName}}::Unserialization(rapidjson::Value & v) 12 | { 13 | 14 | {% for item in Props %} 15 | {% set iname = item.name %} 16 | {% if item.Array and (not item.Constant) %} 17 | if (v.HasMember("{{iname}}") && v["{{iname}}"].IsArray()) 18 | { 19 | rapidjson::Value & A{{iname}} = v["{{iname}}"]; 20 | for (rapidjson::SizeType i = 0;i < A{{iname}}.Size();i++) 21 | { 22 | rapidjson::Value & kv = A{{iname}}[i]; 23 | {%if item.type in Primitivelist %} 24 | {% if (item.type != "string") %} 25 | if (kv.Is{{JsonType[item.type]}}()) 26 | this->{{iname}}.Add(kv.Get{{JsonType[item.type]}}()); 27 | {% else %} 28 | if (kv.IsString()) 29 | this->{{iname}}.Add(FString( kv.GetString())); 30 | {% endif %} 31 | {% else %} 32 | if (kv.IsObject()) 33 | { 34 | {{item.UTypeElement}} e; 35 | e.Unserialization(kv); 36 | this->{{iname}}.Add(e); 37 | } 38 | {%endif%} 39 | } 40 | } 41 | 42 | {% elif not item.Constant %} 43 | {%if item.type in Primitivelist%} 44 | {% if (item.type != "string") %} 45 | if (v.HasMember("{{iname}}") && v["{{iname}}"].Is{{JsonType[item.type]}}()) 46 | this->{{iname}} = v["{{iname}}"].Get{{JsonType[item.type]}}(); 47 | {% else %} 48 | if (v.HasMember("{{iname}}") && v["{{iname}}"].IsString()) 49 | this->{{iname}} = FString( v["{{iname}}"].GetString()); 50 | {% endif %} 51 | {% else %} 52 | if (v.HasMember("{{iname}}") && v["{{iname}}"].IsObject()) 53 | this->{{iname}}.Unserialization(v["{{iname}}"]); 54 | {%endif%} 55 | {% endif %} 56 | {% endfor %} 57 | 58 | } 59 | 60 | rapidjson::Value {{FName}}::Serialization(rapidjson::Document & d) 61 | { 62 | rapidjson::Value s(rapidjson::kObjectType); 63 | {% for item in Props %} 64 | {% set iname = item.name %} 65 | rapidjson::Value t{{iname}}; 66 | t{{item.name}}.SetString("{{iname}}"); 67 | {% if item.Array %} 68 | rapidjson::Value A{{iname}}(rapidjson::kArrayType); 69 | for ({{item.UTypeElement}} Element : {{iname}}) 70 | { 71 | {% set etype = item.UTypeElement %} 72 | {%if item.type in Primitivelist%} 73 | {% if (item.type != "string") %} 74 | A{{iname}}.PushBack(Element,d.GetAllocator()); 75 | {% else %} 76 | rapidjson::Value s{{iname}}; 77 | std::string fuck_{{iname}} = TCHAR_TO_UTF8( * Element); 78 | s{{iname}}.SetString(rapidjson::StringRef(fuck_{{iname}}.c_str())); 79 | A{{iname}}.PushBack(s{{iname}}, d.GetAllocator()); 80 | {% endif %} 81 | {% else %} 82 | A{{iname}}.PushBack(Element.Serialization(d), d.GetAllocator()); 83 | {% endif %} 84 | } 85 | s.AddMember(t{{iname}},A{{iname}},d.GetAllocator()); 86 | {% else %} 87 | {%if item.type in Primitivelist%} 88 | {% if (item.type != "string") %} 89 | s.AddMember(t{{iname}},this->{{iname}},d.GetAllocator()); 90 | {% else %} 91 | rapidjson::Value s{{iname}}; 92 | std::string fuck_{{iname}} = TCHAR_TO_UTF8( * this->{{iname}}); 93 | s{{iname}}.SetString(rapidjson::StringRef(fuck_{{iname}}.c_str())); 94 | s.AddMember(t{{iname}},s{{iname}}, d.GetAllocator()); 95 | {% endif %} 96 | {% else %} 97 | s.AddMember(t{{iname}}, this->{{iname}}.Serialization(d), d.GetAllocator()); 98 | {% endif %} 99 | {% endif %} 100 | {% endfor %} 101 | return s; 102 | } 103 | 104 | {{ADName}} * {{ADName}}::Create_{{TypeName}}_Advertiser(FString TopicName) 105 | { 106 | {{ADName}} * c = NewObject<{{ADName}}>(); 107 | c->TopicName = TopicName; 108 | c->Advertise(); 109 | return c; 110 | } 111 | 112 | void {{ADName}}::Publish({{FName}} Data) 113 | { 114 | if (!Advertised) 115 | { 116 | Advertise(); 117 | } 118 | rapidjson::Document d; 119 | d.SetObject(); 120 | d.AddMember("msg",Data.Serialization(d),d.GetAllocator()); 121 | rapidjson::Value TopicName; 122 | TopicName.SetString(rapidjson::StringRef(TCHAR_TO_UTF8(*this->TopicName))); 123 | d.AddMember("topic", TopicName, d.GetAllocator()); 124 | d.AddMember("op","publish",d.GetAllocator()); 125 | SendJson(d); 126 | } 127 | 128 | {{ADName}}::{{ADName}}(const FObjectInitializer& ObjectInitializer) 129 | : Super(ObjectInitializer) 130 | { 131 | this->TypeName = FString("{{TypeNameFull}}"); 132 | } 133 | 134 | {% set SBName = "U_"+Struct.GeneratedName + "Subscriber" %} 135 | {{SBName}}::{{SBName}}(const FObjectInitializer& ObjectInitializer) 136 | : Super(ObjectInitializer) 137 | { 138 | this->TypeName = FString("{{TypeNameFull}}"); 139 | } 140 | void {{SBName}}::ProccessMsg(rapidjson::Value & obj) 141 | { 142 | {{FName}} fdata; 143 | fdata.Unserialization(obj); 144 | On{{TypeName}}Data.Broadcast(fdata); 145 | OnRecieve(fdata); 146 | } 147 | 148 | void {{SBName}}::OnRecieve({{FName}} Data) 149 | { 150 | } 151 | 152 | {{SBName}} * {{SBName}}::Create_{{TypeName}}_Subscriber(FString _TopicName) 153 | { 154 | {{SBName}} * sub = NewObject<{{SBName}}>(); 155 | sub->TopicName = _TopicName; 156 | sub->Subscribe(); 157 | return sub; 158 | } 159 | 160 | {% endfor %} 161 | -------------------------------------------------------------------------------- /tools/FStructTemplate.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "Unreal_ROS.h" 4 | #include "TopicTemplate.h" 5 | #include 6 | #include 7 | #include 8 | #include "ros_msg_test.generated.h" 9 | 10 | {% for Struct in StructList%} 11 | struct F_{{Struct.GeneratedName}}; 12 | {% endfor %} 13 | 14 | 15 | {% for Struct in StructList%} 16 | {% set TypeName = Struct.name %} 17 | {% set TypeNameFull = Struct.namefull %} 18 | {% set Props = Struct.props %} 19 | {% set FName = "F_"+Struct.GeneratedName %} 20 | {% set ADName = "U_"+Struct.GeneratedName + "Advertiser" %} 21 | {% set SBName = "U_"+Struct.GeneratedName + "Subscriber" %} 22 | 23 | USTRUCT() 24 | struct {{FName}} 25 | { 26 | 27 | GENERATED_USTRUCT_BODY() 28 | 29 | {% for item in Props %} 30 | {% if item.Constant %} 31 | UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category = "Robot OS") 32 | {{item.UType }} {{ item.name }} = {{item.ConstantField}}; 33 | {% else %} 34 | UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Robot OS") 35 | {{item.UType }} {{ item.name }}; 36 | {% endif %} 37 | {% endfor %} 38 | 39 | rapidjson::Value Serialization(rapidjson::Document & d); 40 | void Unserialization(rapidjson::Value & v); 41 | 42 | std::string TypeName = "{{TypeNameFull}}"; 43 | 44 | }; 45 | 46 | 47 | UCLASS() 48 | class {{ADName}} : public UAdvertiser 49 | { 50 | 51 | GENERATED_UCLASS_BODY() 52 | 53 | public: 54 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 55 | static {{ADName}} * Create_{{TypeName}}_Advertiser(FString TopicName); 56 | 57 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 58 | void Publish({{FName}} Data); 59 | }; 60 | 61 | DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam({{FName}}Delegate, {{FName}}, Data); 62 | 63 | UCLASS() 64 | class {{SBName}} : public USubscriber 65 | { 66 | GENERATED_UCLASS_BODY() 67 | public: 68 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 69 | static {{SBName}} * Create_{{TypeName}}_Subscriber(FString _TopicName); 70 | 71 | virtual void ProccessMsg(rapidjson::Value & obj); 72 | 73 | UPROPERTY(BlueprintAssignable, Category = "Robot OS") 74 | {{FName}}Delegate On{{TypeName}}Data; 75 | 76 | UFUNCTION(BlueprintCallable, Category = "Robot OS") 77 | virtual void OnRecieve({{FName}} Data); 78 | }; 79 | 80 | {% endfor %} 81 | 82 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package actionlib_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.3 (2015-04-20) 6 | ------------------- 7 | 8 | 1.12.2 (2015-03-21) 9 | ------------------- 10 | 11 | 1.12.1 (2015-03-17) 12 | ------------------- 13 | * updating outdated urls. fixes `#52 `_. 14 | * Contributors: Tully Foote 15 | 16 | 1.12.0 (2014-12-29) 17 | ------------------- 18 | 19 | 1.11.6 (2014-11-04) 20 | ------------------- 21 | 22 | 1.11.5 (2014-10-27) 23 | ------------------- 24 | 25 | 1.11.4 (2014-06-19) 26 | ------------------- 27 | 28 | 1.11.3 (2014-05-07) 29 | ------------------- 30 | * Export architecture_independent flag in package.xml 31 | * Contributors: Scott K Logan 32 | 33 | 1.11.2 (2014-04-24) 34 | ------------------- 35 | 36 | 1.11.1 (2014-04-16) 37 | ------------------- 38 | 39 | 1.11.0 (2014-03-04) 40 | ------------------- 41 | 42 | 1.10.6 (2014-02-27) 43 | ------------------- 44 | * fix actionlib_msgs for dry 45 | * use catkin_install_python() to install Python scripts `#29 `_ 46 | * Contributors: Dirk Thomas 47 | 48 | 1.10.5 (2014-02-25) 49 | ------------------- 50 | * removing usage of catkin function not guarenteed available fixes `#30 `_ 51 | * Contributors: Tully Foote 52 | 53 | 1.10.4 (2014-02-18) 54 | ------------------- 55 | * remove catkin usage from CMake extra file (fix `#27 `_) 56 | * Contributors: Dirk Thomas 57 | 58 | 1.10.3 (2014-01-07) 59 | ------------------- 60 | * python 3 compatibility 61 | * prefix invocation of python script with PYTHON_EXECUTABLE (`ros/genpy#23 `_) 62 | * make generated cmake relocatable 63 | 64 | 1.10.2 (2013-08-19) 65 | ------------------- 66 | 67 | 1.10.1 (2013-08-16) 68 | ------------------- 69 | 70 | 1.10.0 (2013-07-13) 71 | ------------------- 72 | 73 | 1.9.16 (2013-05-21) 74 | ------------------- 75 | * update email in package.xml 76 | 77 | 1.9.15 (2013-03-08) 78 | ------------------- 79 | * fix handling spaces in folder names (`ros/catkin#375 `_) 80 | 81 | 1.9.14 (2013-01-19) 82 | ------------------- 83 | * fix bug using ARGV in list(FIND) directly (`ros/genmsg#18 `_) 84 | 85 | 1.9.13 (2013-01-13) 86 | ------------------- 87 | 88 | 1.9.12 (2013-01-02) 89 | ------------------- 90 | 91 | 1.9.11 (2012-12-17) 92 | ------------------- 93 | * add message_generation as a run dep for downstream 94 | * modified dep type of catkin 95 | 96 | 1.9.10 (2012-12-13) 97 | ------------------- 98 | * add missing downstream depend 99 | * switched from langs to message_* packages 100 | 101 | 1.9.9 (2012-11-22) 102 | ------------------ 103 | 104 | 1.9.8 (2012-11-14) 105 | ------------------ 106 | * add globbing for action files 107 | * updated variable to latest catkin 108 | * refactored extra file from 'in' to 'em' 109 | 110 | 1.9.7 (2012-10-30) 111 | ------------------ 112 | * fix catkin function order 113 | 114 | 1.9.6 (2012-10-18) 115 | ------------------ 116 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 117 | 118 | 1.9.5 (2012-09-28) 119 | ------------------ 120 | 121 | 1.9.4 (2012-09-27 18:06) 122 | ------------------------ 123 | 124 | 1.9.3 (2012-09-27 17:39) 125 | ------------------------ 126 | * cleanup 127 | * updated to latest catkin 128 | * fixed dependencies and more 129 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 130 | 131 | 1.9.2 (2012-09-05) 132 | ------------------ 133 | * updated pkg-config in manifest.xml 134 | * updated catkin variables 135 | 136 | 1.9.1 (2012-09-04) 137 | ------------------ 138 | * use install destination variables, removed manual installation of manifests 139 | 140 | 1.9.0 (2012-08-29) 141 | ------------------ 142 | * updated to current catkin 143 | 144 | 1.8.13 (2012-07-26 18:34:15 +0000) 145 | ---------------------------------- 146 | 147 | 1.8.8 (2012-06-12 22:36) 148 | ------------------------ 149 | * make find_package REQUIRED 150 | * removed obsolete catkin tag from manifest files 151 | * Fix up install-time finding of script, plus add a missing genmsg import 152 | * Convert legacy rosbuild support to use newer genaction.py script 153 | * Expose old actionlib_msgs interface to dry users. Dry actionlib builds and 154 | tests cleanly. 155 | * adding manifest exports 156 | * removed depend, added catkin 157 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 158 | * install a file that rosbuild users have hardcoded an include for 159 | * bye bye vestigial MSG_DIRS 160 | * rosbuild2 -> catkin 161 | * no include dir in actionlib_msgs 162 | * actionlib_msgs: getting rid of other build files 163 | * adios rosbuild2 in manifest.xml 164 | * catkin updates 165 | * catkin_project 166 | * catkin: only generate .msg files if .action file has changed 167 | * catkin: changed actionlib_msg to generate .msg files at cmake time 168 | * Integrate actionlib_msgs into catkin 169 | * rosbuild2 on windows tweaks (more) 170 | * rosbuild2 windows tweaks 171 | * url fix 172 | * removed extra slashes that caused trouble on OSX 173 | * rosbuild2 taking shape 174 | * rosbuild2 taking shape 175 | * removing all the extra exports 176 | * msg folder generation now parallel safe. `#4286 `_ 177 | * Fixing build dependency race condition. Trac `#4255 `_ 178 | * Added Ubuntu platform tags to manifest 179 | * Now using /usr/bin/env python. Trac `#3863 `_ 180 | * Copying action generators from actionlib to actionlib_msgs 181 | * updating review status 182 | * Updating actionlib_msgs comments (`#3003 `_) 183 | * filling out manifest 184 | * Documenting GoalStatus message 185 | * Forgot to commit files to actionlib_msgs 186 | * Moving actionlib messages into common_msgs/actionlib_msgs. Trac `#2504 `_ 187 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(actionlib_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | GoalID.msg 10 | GoalStatus.msg 11 | GoalStatusArray.msg) 12 | generate_messages(DEPENDENCIES std_msgs) 13 | 14 | catkin_package( 15 | CATKIN_DEPENDS message_runtime std_msgs 16 | CFG_EXTRAS actionlib_msgs-extras.cmake) 17 | 18 | # install the .action -> .msg generator 19 | catkin_install_python(PROGRAMS scripts/genaction.py 20 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 21 | 22 | # install the legacy rosbuild cmake support 23 | install(FILES cmake/actionbuild.cmake 24 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake) 25 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/cmake/actionbuild.cmake: -------------------------------------------------------------------------------- 1 | # THIS FILE CANNOT BE MOVED. Users include it like so: 2 | # rosbuild_find_ros_package(actionlib_msgs) 3 | # include(${actionlib_msgs_PACKAGE_PATH}/cmake/actionbuild.cmake) 4 | 5 | macro(get_actions actionvar) 6 | file(GLOB _action_files RELATIVE "${PROJECT_SOURCE_DIR}/action" "${PROJECT_SOURCE_DIR}/action/*.action") 7 | message(STATUS "Action Files:" ${_action_files}) 8 | foreach(_action ${_action_files}) 9 | if(${_action} MATCHES "^[^\\.].*\\.action$") 10 | list(APPEND ${actionvar} ${_action}) 11 | endif(${_action} MATCHES "^[^\\.].*\\.action$") 12 | endforeach(_action) 13 | endmacro(get_actions) 14 | 15 | macro(genaction) 16 | if(ROSBUILD_init_called) 17 | message(FATAL_ERROR "genaction() cannot be called after rosbuild_init(), please change the order in your CMakeLists.txt file.") 18 | endif(ROSBUILD_init_called) 19 | get_actions(_actionlist) 20 | set(_autogen "") 21 | set(_autogen_msg_list "") 22 | foreach(_action ${_actionlist}) 23 | message(STATUS "Generating Messages for Action" ${_action}) 24 | #construct the path to the .action file 25 | set(_input ${PROJECT_SOURCE_DIR}/action/${_action}) 26 | 27 | string(REPLACE ".action" "" _action_bare ${_action}) 28 | 29 | # get path to action generator script 30 | find_package(catkin REQUIRED COMPONENTS actionlib_msgs) 31 | 32 | #We have to do this because message generation assumes filenames without full paths 33 | set(_base_output_action ${_action_bare}Action.msg) 34 | set(_base_output_goal ${_action_bare}Goal.msg) 35 | set(_base_output_action_goal ${_action_bare}ActionGoal.msg) 36 | set(_base_output_result ${_action_bare}Result.msg) 37 | set(_base_output_action_result ${_action_bare}ActionResult.msg) 38 | set(_base_output_feedback ${_action_bare}Feedback.msg) 39 | set(_base_output_action_feedback ${_action_bare}ActionFeedback.msg) 40 | 41 | set(_output_action ${PROJECT_SOURCE_DIR}/msg/${_base_output_action}) 42 | set(_output_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_goal}) 43 | set(_output_action_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_goal}) 44 | set(_output_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_result}) 45 | set(_output_action_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_result}) 46 | set(_output_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_feedback}) 47 | set(_output_action_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_feedback}) 48 | message(STATUS ${_output_action}) 49 | 50 | add_custom_command( 51 | OUTPUT ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback} 52 | COMMAND ${GENACTION_BIN} ${_input} -o ${PROJECT_SOURCE_DIR}/msg 53 | DEPENDS ${_input} ${GENACTION_BIN} ${ROS_MANIFEST_LIST} 54 | ) 55 | list(APPEND _autogen ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback}) 56 | list(APPEND _autogen_msg_list ${_base_output_action} ${_base_output_goal} ${_base_output_action_goal} ${_base_output_result} ${_base_output_action_result} ${_base_output_feedback} ${_base_output_action_feedback}) 57 | endforeach(_action) 58 | 59 | # Create a target that depends on the union of all the autogenerated files 60 | add_custom_target(ROSBUILD_genaction_msgs ALL DEPENDS ${_autogen}) 61 | add_custom_target(rosbuild_premsgsrvgen) 62 | add_dependencies(rosbuild_premsgsrvgen ROSBUILD_genaction_msgs) 63 | rosbuild_add_generated_msgs(${_autogen_msg_list}) 64 | endmacro(genaction) 65 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/cmake/actionlib_msgs-extras.cmake.em: -------------------------------------------------------------------------------- 1 | # need genmsg for _prepend_path() 2 | find_package(genmsg REQUIRED) 3 | 4 | include(CMakeParseArguments) 5 | 6 | @[if DEVELSPACE]@ 7 | # program in develspace 8 | set(GENACTION_BIN "@(CMAKE_CURRENT_SOURCE_DIR)/scripts/genaction.py") 9 | @[else]@ 10 | # program in installspace 11 | set(GENACTION_BIN "${actionlib_msgs_DIR}/../../../@(CATKIN_PACKAGE_BIN_DESTINATION)/genaction.py") 12 | @[end if]@ 13 | 14 | macro(add_action_files) 15 | cmake_parse_arguments(ARG "NOINSTALL" "DIRECTORY" "FILES" ${ARGN}) 16 | if(ARG_UNPARSED_ARGUMENTS) 17 | message(FATAL_ERROR "add_action_files() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}") 18 | endif() 19 | 20 | if(NOT ARG_DIRECTORY) 21 | set(ARG_DIRECTORY "action") 22 | endif() 23 | 24 | if(NOT IS_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}) 25 | message(FATAL_ERROR "add_action_files() directory not found: ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}") 26 | endif() 27 | 28 | # if FILES are not passed search action files in the given directory 29 | # note: ARGV is not variable, so it can not be passed to list(FIND) directly 30 | set(_argv ${ARGV}) 31 | list(FIND _argv "FILES" _index) 32 | if(_index EQUAL -1) 33 | file(GLOB ARG_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}" "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}/*.action") 34 | list(SORT ARG_FILES) 35 | endif() 36 | _prepend_path(${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY} "${ARG_FILES}" FILES_W_PATH) 37 | 38 | list(APPEND ${PROJECT_NAME}_ACTION_FILES ${FILES_W_PATH}) 39 | foreach(file ${FILES_W_PATH}) 40 | assert_file_exists(${file} "action file not found") 41 | endforeach() 42 | 43 | if(NOT ARG_NOINSTALL) 44 | install(FILES ${FILES_W_PATH} DESTINATION share/${PROJECT_NAME}/${ARG_DIRECTORY}) 45 | endif() 46 | 47 | foreach(actionfile ${FILES_W_PATH}) 48 | if(NOT CATKIN_DEVEL_PREFIX) 49 | message(FATAL_ERROR "Assertion failed: 'CATKIN_DEVEL_PREFIX' is not set") 50 | endif() 51 | get_filename_component(ACTION_SHORT_NAME ${actionfile} NAME_WE) 52 | set(MESSAGE_DIR ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/msg) 53 | set(OUTPUT_FILES 54 | ${ACTION_SHORT_NAME}Action.msg 55 | ${ACTION_SHORT_NAME}ActionGoal.msg 56 | ${ACTION_SHORT_NAME}ActionResult.msg 57 | ${ACTION_SHORT_NAME}ActionFeedback.msg 58 | ${ACTION_SHORT_NAME}Goal.msg 59 | ${ACTION_SHORT_NAME}Result.msg 60 | ${ACTION_SHORT_NAME}Feedback.msg) 61 | 62 | _prepend_path(${MESSAGE_DIR}/ "${OUTPUT_FILES}" OUTPUT_FILES_W_PATH) 63 | 64 | message(STATUS "Generating .msg files for action ${PROJECT_NAME}/${ACTION_SHORT_NAME} ${actionfile}") 65 | 66 | stamp(${actionfile}) 67 | 68 | if(NOT CATKIN_ENV) 69 | message(FATAL_ERROR "Assertion failed: 'CATKIN_ENV' is not set") 70 | endif() 71 | if(${actionfile} IS_NEWER_THAN ${MESSAGE_DIR}/${ACTION_SHORT_NAME}Action.msg) 72 | safe_execute_process(COMMAND ${CATKIN_ENV} ${PYTHON_EXECUTABLE} ${GENACTION_BIN} ${actionfile} -o ${MESSAGE_DIR}) 73 | endif() 74 | 75 | add_message_files( 76 | BASE_DIR ${MESSAGE_DIR} 77 | FILES ${OUTPUT_FILES}) 78 | endforeach() 79 | endmacro() 80 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/msg/GoalID.msg: -------------------------------------------------------------------------------- 1 | # The stamp should store the time at which this goal was requested. 2 | # It is used by an action server when it tries to preempt all 3 | # goals that were requested before a certain time 4 | time stamp 5 | 6 | # The id provides a way to associate feedback and 7 | # result message with specific goal requests. The id 8 | # specified must be unique. 9 | string id 10 | 11 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/msg/GoalStatus.msg: -------------------------------------------------------------------------------- 1 | GoalID goal_id 2 | uint8 status 3 | uint8 PENDING = 0 # The goal has yet to be processed by the action server 4 | uint8 ACTIVE = 1 # The goal is currently being processed by the action server 5 | uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 6 | # and has since completed its execution (Terminal State) 7 | uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 8 | uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 9 | # to some failure (Terminal State) 10 | uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 11 | # because the goal was unattainable or invalid (Terminal State) 12 | uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 13 | # and has not yet completed execution 14 | uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 15 | # but the action server has not yet confirmed that the goal is canceled 16 | uint8 RECALLED = 8 # The goal received a cancel request before it started executing 17 | # and was successfully cancelled (Terminal State) 18 | uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 19 | # sent over the wire by an action server 20 | 21 | #Allow for the user to associate a string with GoalStatus for debugging 22 | string text 23 | 24 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/msg/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 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | actionlib_msgs 3 | 1.12.3 4 | 5 | actionlib_msgs defines the common messages to interact with an 6 | action server and an action client. For full documentation of 7 | the actionlib API see 8 | the actionlib 9 | package. 10 | 11 | Tully Foote 12 | BSD 13 | 14 | http://wiki.ros.org/actionlib_msgs 15 | Vijay Pradeep 16 | 17 | catkin 18 | 19 | message_generation 20 | std_msgs 21 | 22 | message_generation 23 | message_runtime 24 | std_msgs 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /tools/data/actionlib_msgs/scripts/genaction.py: -------------------------------------------------------------------------------- 1 | #! /usr/bin/env python 2 | # Copyright (c) 2009, Willow Garage, Inc. 3 | # All rights reserved. 4 | # 5 | # Redistribution and use in source and binary forms, with or without 6 | # modification, are permitted provided that the following conditions are met: 7 | # 8 | # * Redistributions of source code must retain the above copyright 9 | # notice, this list of conditions and the following disclaimer. 10 | # * Redistributions in binary form must reproduce the above copyright 11 | # notice, this list of conditions and the following disclaimer in the 12 | # documentation and/or other materials provided with the distribution. 13 | # * Neither the name of the Willow Garage, Inc. nor the names of its 14 | # contributors may be used to endorse or promote products derived from 15 | # this software without specific prior written permission. 16 | # 17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | # POSSIBILITY OF SUCH DAMAGE. 28 | 29 | # Author: Stuart Glaser 30 | 31 | import sys 32 | try: 33 | from cStringIO import StringIO 34 | except ImportError: 35 | from io import StringIO 36 | import re 37 | import os, os.path 38 | import errno 39 | from optparse import OptionParser 40 | 41 | IODELIM = '---' 42 | AUTOGEN="# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n" 43 | 44 | class ActionSpecException(Exception): pass 45 | 46 | def parse_action_spec(text, package_context = ''): 47 | pieces = [StringIO()] 48 | for l in text.split('\n'): 49 | if l.startswith(IODELIM): 50 | pieces.append(StringIO()) 51 | else: 52 | pieces[-1].write(l + '\n') 53 | return [p.getvalue() for p in pieces] 54 | 55 | def write_file(filename, text): 56 | f = open(filename, 'w') 57 | f.write(text) 58 | f.close() 59 | 60 | def main(): 61 | 62 | parser = OptionParser("Actionlib generator") 63 | parser.add_option('-o', dest='output_dir', 64 | help='output directory') 65 | 66 | (options, args) = parser.parse_args(sys.argv) 67 | 68 | pkg = os.path.abspath(sys.argv[1]) 69 | filename = sys.argv[2] 70 | 71 | output_dir = options.output_dir 72 | 73 | # Try to make the directory, but silently continue if it already exists 74 | try: 75 | os.makedirs(output_dir) 76 | except OSError as e: 77 | if e.errno == errno.EEXIST: 78 | pass 79 | else: 80 | raise 81 | 82 | action_file = args[1] 83 | if not action_file.endswith('.action'): 84 | print("The file specified has the wrong extension. It must end in .action") 85 | else: 86 | filename = action_file 87 | 88 | f = open(filename) 89 | action_spec = f.read() 90 | f.close() 91 | 92 | name = os.path.basename(filename)[:-7] 93 | print("Generating for action %s" % name) 94 | 95 | pieces = parse_action_spec(action_spec) 96 | if len(pieces) != 3: 97 | raise ActionSpecException("%s: wrong number of pieces, %d"%(filename,len(pieces))) 98 | goal, result, feedback = pieces 99 | 100 | action_msg = AUTOGEN + """ 101 | %sActionGoal action_goal 102 | %sActionResult action_result 103 | %sActionFeedback action_feedback 104 | """ % (name, name, name) 105 | 106 | goal_msg = AUTOGEN + goal 107 | action_goal_msg = AUTOGEN + """ 108 | Header header 109 | actionlib_msgs/GoalID goal_id 110 | %sGoal goal 111 | """ % name 112 | 113 | result_msg = AUTOGEN + result 114 | action_result_msg = AUTOGEN + """ 115 | Header header 116 | actionlib_msgs/GoalStatus status 117 | %sResult result 118 | """ % name 119 | 120 | feedback_msg = AUTOGEN + feedback 121 | action_feedback_msg = AUTOGEN + """ 122 | Header header 123 | actionlib_msgs/GoalStatus status 124 | %sFeedback feedback 125 | """ % name 126 | 127 | write_file(os.path.join(output_dir, "%sAction.msg"%name), action_msg) 128 | write_file(os.path.join(output_dir, "%sGoal.msg"%name), goal_msg) 129 | write_file(os.path.join(output_dir, "%sActionGoal.msg"%name), action_goal_msg) 130 | write_file(os.path.join(output_dir, "%sResult.msg"%name), result_msg) 131 | write_file(os.path.join(output_dir, "%sActionResult.msg"%name), action_result_msg) 132 | write_file(os.path.join(output_dir, "%sFeedback.msg"%name), feedback_msg) 133 | write_file(os.path.join(output_dir, "%sActionFeedback.msg"%name), action_feedback_msg) 134 | 135 | 136 | if __name__ == '__main__': main() 137 | -------------------------------------------------------------------------------- /tools/data/common_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package common_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.3 (2015-04-20) 6 | ------------------- 7 | 8 | 1.12.2 (2015-03-21) 9 | ------------------- 10 | 11 | 1.12.1 (2015-03-17) 12 | ------------------- 13 | * updating outdated urls. fixes `#52 `_. 14 | * Contributors: Tully Foote 15 | 16 | 1.12.0 (2014-12-29) 17 | ------------------- 18 | 19 | 1.11.6 (2014-11-04) 20 | ------------------- 21 | 22 | 1.11.5 (2014-10-27) 23 | ------------------- 24 | 25 | 1.11.4 (2014-06-19) 26 | ------------------- 27 | 28 | 1.11.3 (2014-05-07) 29 | ------------------- 30 | 31 | 1.11.2 (2014-04-24) 32 | ------------------- 33 | 34 | 1.11.1 (2014-04-16) 35 | ------------------- 36 | 37 | 1.11.0 (2014-03-04) 38 | ------------------- 39 | 40 | 1.10.6 (2014-02-27) 41 | ------------------- 42 | 43 | 1.10.5 (2014-02-25) 44 | ------------------- 45 | 46 | 1.10.4 (2014-02-18) 47 | ------------------- 48 | 49 | 1.10.3 (2014-01-07) 50 | ------------------- 51 | 52 | 1.10.2 (2013-08-19) 53 | ------------------- 54 | 55 | 1.10.1 (2013-08-16) 56 | ------------------- 57 | 58 | 1.10.0 (2013-07-13) 59 | ------------------- 60 | 61 | 1.9.16 (2013-05-21) 62 | ------------------- 63 | * add buildtool dep on catkin for metapackage 64 | * update email in package.xml 65 | 66 | 1.9.15 (2013-03-08) 67 | ------------------- 68 | * add CMakeLists.txt for metapackage 69 | 70 | 1.9.14 (2013-01-19) 71 | ------------------- 72 | 73 | 1.9.13 (2013-01-13) 74 | ------------------- 75 | 76 | 1.9.12 (2013-01-02) 77 | ------------------- 78 | 79 | 1.9.11 (2012-12-17) 80 | ------------------- 81 | 82 | 1.9.10 (2012-12-13) 83 | ------------------- 84 | 85 | 1.9.9 (2012-11-22) 86 | ------------------ 87 | 88 | 1.9.8 (2012-11-14) 89 | ------------------ 90 | 91 | 1.9.7 (2012-10-30) 92 | ------------------ 93 | 94 | 1.9.6 (2012-10-18) 95 | ------------------ 96 | 97 | 1.9.5 (2012-09-28) 98 | ------------------ 99 | 100 | 1.9.4 (2012-09-27 18:06) 101 | ------------------------ 102 | * fix dependency name 103 | 104 | 1.9.3 (2012-09-27 17:39) 105 | ------------------------ 106 | * cleanup 107 | * cleaned up package.xml files 108 | * fixed dependencies and more 109 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 110 | 111 | 1.9.2 (2012-09-05) 112 | ------------------ 113 | 114 | 1.9.1 (2012-09-04) 115 | ------------------ 116 | 117 | 1.9.0 (2012-08-29) 118 | ------------------ 119 | 120 | 1.8.13 (2012-07-26 18:34:15 +0000) 121 | ---------------------------------- 122 | 123 | 1.8.8 (2012-06-12 22:36) 124 | ------------------------ 125 | -------------------------------------------------------------------------------- /tools/data/common_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(common_msgs) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /tools/data/common_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | common_msgs 3 | 1.12.3 4 | 5 | common_msgs contains messages that are widely used by other ROS packages. 6 | These includes messages for 7 | actions (actionlib_msgs), 8 | diagnostics (diagnostic_msgs), 9 | geometric primitives (geometry_msgs), 10 | robot navigation (nav_msgs), 11 | and common sensors (sensor_msgs), such as laser range finders, cameras, point clouds. 12 | 13 | Tully Foote 14 | BSD 15 | 16 | http://wiki.ros.org/common_msgs 17 | 18 | catkin 19 | 20 | actionlib_msgs 21 | diagnostic_msgs 22 | geometry_msgs 23 | nav_msgs 24 | sensor_msgs 25 | shape_msgs 26 | stereo_msgs 27 | trajectory_msgs 28 | visualization_msgs 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(geometry_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | Accel.msg 10 | AccelStamped.msg 11 | AccelWithCovariance.msg 12 | AccelWithCovarianceStamped.msg 13 | Inertia.msg 14 | InertiaStamped.msg 15 | Point.msg 16 | Point32.msg 17 | PointStamped.msg 18 | Polygon.msg 19 | PolygonStamped.msg 20 | Pose2D.msg 21 | Pose.msg 22 | PoseArray.msg 23 | PoseStamped.msg 24 | PoseWithCovariance.msg 25 | PoseWithCovarianceStamped.msg 26 | Quaternion.msg 27 | QuaternionStamped.msg 28 | Transform.msg 29 | TransformStamped.msg 30 | Twist.msg 31 | TwistStamped.msg 32 | TwistWithCovariance.msg 33 | TwistWithCovarianceStamped.msg 34 | Vector3.msg 35 | Vector3Stamped.msg 36 | Wrench.msg 37 | WrenchStamped.msg) 38 | 39 | generate_messages(DEPENDENCIES std_msgs) 40 | 41 | catkin_package(CATKIN_DEPENDS message_runtime std_msgs) 42 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b geometry_msgs is ... 6 | 7 | 14 | 15 | 16 | \section codeapi Code API 17 | 18 | 28 | 29 | \section rosapi ROS API 30 | 31 | 42 | 43 | 89 | 90 | 91 | 118 | 119 | */ -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Accel.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space broken into its linear and angular parts. 2 | Vector3 linear 3 | Vector3 angular 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/AccelStamped.msg: -------------------------------------------------------------------------------- 1 | # An accel with reference coordinate frame and timestamp 2 | Header header 3 | Accel accel 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/AccelWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space with uncertainty. 2 | 3 | Accel accel 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/AccelWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated accel with reference coordinate frame and timestamp. 2 | Header header 3 | AccelWithCovariance accel 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Inertia.msg: -------------------------------------------------------------------------------- 1 | # Mass [kg] 2 | float64 m 3 | 4 | # Center of mass [m] 5 | geometry_msgs/Vector3 com 6 | 7 | # Inertia Tensor [kg-m^2] 8 | # | ixx ixy ixz | 9 | # I = | ixy iyy iyz | 10 | # | ixz iyz izz | 11 | float64 ixx 12 | float64 ixy 13 | float64 ixz 14 | float64 iyy 15 | float64 iyz 16 | float64 izz 17 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/InertiaStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Inertia inertia 3 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Point.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space 2 | float64 x 3 | float64 y 4 | float64 z 5 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Point32.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space(with 32 bits of precision). 2 | # It is recommeded to use Point wherever possible instead of Point32. 3 | # 4 | # This recommendation is to promote interoperability. 5 | # 6 | # This message is designed to take up less space when sending 7 | # lots of points at once, as in the case of a PointCloud. 8 | 9 | float32 x 10 | float32 y 11 | float32 z -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PointStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Point with reference coordinate frame and timestamp 2 | Header header 3 | Point point 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Polygon.msg: -------------------------------------------------------------------------------- 1 | #A specification of a polygon where the first and last points are assumed to be connected 2 | Point32[] points 3 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PolygonStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Polygon with reference coordinate frame and timestamp 2 | Header header 3 | Polygon polygon 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Pose.msg: -------------------------------------------------------------------------------- 1 | # A representation of pose in free space, composed of postion and orientation. 2 | Point position 3 | Quaternion orientation 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Pose2D.msg: -------------------------------------------------------------------------------- 1 | # This expresses a position and orientation on a 2D manifold. 2 | 3 | float64 x 4 | float64 y 5 | float64 theta -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PoseArray.msg: -------------------------------------------------------------------------------- 1 | # An array of poses with a header for global reference. 2 | 3 | Header header 4 | 5 | Pose[] poses 6 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PoseStamped.msg: -------------------------------------------------------------------------------- 1 | # A Pose with reference coordinate frame and timestamp 2 | Header header 3 | Pose pose 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PoseWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This represents a pose in free space with uncertainty. 2 | 3 | Pose pose 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/PoseWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses an estimated pose with a reference coordinate frame and timestamp 2 | 3 | Header header 4 | PoseWithCovariance pose 5 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/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 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/QuaternionStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an orientation with reference coordinate frame and timestamp. 2 | 3 | Header header 4 | Quaternion quaternion 5 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Transform.msg: -------------------------------------------------------------------------------- 1 | # This represents the transform between two coordinate frames in free space. 2 | 3 | Vector3 translation 4 | Quaternion rotation 5 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/TransformStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses a transform from coordinate frame header.frame_id 2 | # to the coordinate frame child_frame_id 3 | # 4 | # This message is mostly used by the 5 | # tf package. 6 | # See its documentation for more information. 7 | 8 | Header header 9 | string child_frame_id # the frame id of the child frame 10 | Transform transform 11 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Twist.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space broken into its linear and angular parts. 2 | Vector3 linear 3 | Vector3 angular 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/TwistStamped.msg: -------------------------------------------------------------------------------- 1 | # A twist with reference coordinate frame and timestamp 2 | Header header 3 | Twist twist 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/TwistWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space with uncertainty. 2 | 3 | Twist twist 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/TwistWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated twist with reference coordinate frame and timestamp. 2 | Header header 3 | TwistWithCovariance twist 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Vector3.msg: -------------------------------------------------------------------------------- 1 | # This represents a vector in free space. 2 | # It is only meant to represent a direction. Therefore, it does not 3 | # make sense to apply a translation to it (e.g., when applying a 4 | # generic rigid transformation to a Vector3, tf2 will only apply the 5 | # rotation). If you want your data to be translatable too, use the 6 | # geometry_msgs/Point message instead. 7 | 8 | float64 x 9 | float64 y 10 | float64 z -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Vector3Stamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Vector3 with reference coordinate frame and timestamp 2 | Header header 3 | Vector3 vector 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/Wrench.msg: -------------------------------------------------------------------------------- 1 | # This represents force in free space, separated into 2 | # its linear and angular parts. 3 | Vector3 force 4 | Vector3 torque 5 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/msg/WrenchStamped.msg: -------------------------------------------------------------------------------- 1 | # A wrench with reference coordinate frame and timestamp 2 | Header header 3 | Wrench wrench 4 | -------------------------------------------------------------------------------- /tools/data/geometry_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | geometry_msgs 3 | 1.12.3 4 | 5 | geometry_msgs provides messages for common geometric primitives 6 | such as points, vectors, and poses. These primitives are designed 7 | to provide a common data type and facilitate interoperability 8 | throughout the system. 9 | 10 | Tully Foote 11 | BSD 12 | 13 | http://wiki.ros.org/geometry_msgs 14 | Tully Foote 15 | 16 | catkin 17 | 18 | message_generation 19 | std_msgs 20 | 21 | message_runtime 22 | std_msgs 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nav_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs actionlib_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | GridCells.msg 10 | MapMetaData.msg 11 | OccupancyGrid.msg 12 | Odometry.msg 13 | Path.msg) 14 | 15 | add_service_files( 16 | DIRECTORY srv 17 | FILES 18 | GetMap.srv 19 | GetPlan.srv 20 | SetMap.srv) 21 | 22 | add_action_files( 23 | FILES 24 | GetMap.action) 25 | 26 | generate_messages(DEPENDENCIES geometry_msgs std_msgs actionlib_msgs) 27 | 28 | catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs actionlib_msgs) 29 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/action/GetMap.action: -------------------------------------------------------------------------------- 1 | # Get the map as a nav_msgs/OccupancyGrid 2 | --- 3 | nav_msgs/OccupancyGrid map 4 | --- 5 | # no feedback -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/msg/MapMetaData.msg: -------------------------------------------------------------------------------- 1 | # This hold basic information about the characterists of the OccupancyGrid 2 | 3 | # The time at which the map was loaded 4 | time map_load_time 5 | # The map resolution [m/cell] 6 | float32 resolution 7 | # Map width [cells] 8 | uint32 width 9 | # Map height [cells] 10 | uint32 height 11 | # The origin of the map [m, m, rad]. This is the real-world pose of the 12 | # cell (0,0) in the map. 13 | geometry_msgs/Pose origin -------------------------------------------------------------------------------- /tools/data/nav_msgs/msg/OccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | # This represents a 2-D grid map, in which each cell represents the probability of 2 | # occupancy. 3 | 4 | Header header 5 | 6 | #MetaData for the map 7 | MapMetaData info 8 | 9 | # The map data, in row-major order, starting with (0,0). Occupancy 10 | # probabilities are in the range [0,100]. Unknown is -1. 11 | int8[] data 12 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/msg/Odometry.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimate of a position and velocity in free space. 2 | # The pose in this message should be specified in the coordinate frame given by header.frame_id. 3 | # The twist in this message should be specified in the coordinate frame given by the child_frame_id 4 | Header header 5 | string child_frame_id 6 | geometry_msgs/PoseWithCovariance pose 7 | geometry_msgs/TwistWithCovariance twist 8 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nav_msgs 3 | 1.12.3 4 | 5 | nav_msgs defines the common messages used to interact with the 6 | navigation stack. 7 | 8 | Tully Foote 9 | BSD 10 | 11 | http://wiki.ros.org/nav_msgs 12 | Tully Foote 13 | 14 | catkin 15 | 16 | geometry_msgs 17 | message_generation 18 | std_msgs 19 | actionlib_msgs 20 | 21 | geometry_msgs 22 | message_runtime 23 | std_msgs 24 | actionlib_msgs 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/srv/GetMap.srv: -------------------------------------------------------------------------------- 1 | # Get the map as a nav_msgs/OccupancyGrid 2 | --- 3 | nav_msgs/OccupancyGrid map 4 | -------------------------------------------------------------------------------- /tools/data/nav_msgs/srv/GetPlan.srv: -------------------------------------------------------------------------------- 1 | # Get a plan from the current position to the goal Pose 2 | 3 | # The start pose for the plan 4 | geometry_msgs/PoseStamped start 5 | 6 | # The final pose of the goal position 7 | geometry_msgs/PoseStamped goal 8 | 9 | # If the goal is obstructed, how many meters the planner can 10 | # relax the constraint in x and y before failing. 11 | float32 tolerance 12 | --- 13 | nav_msgs/Path plan 14 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(sensor_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) 5 | # We want boost/format.hpp, which isn't in its own component. 6 | find_package(Boost REQUIRED) 7 | 8 | # For point_cloud2.py 9 | catkin_python_setup() 10 | 11 | include_directories(include) 12 | 13 | add_message_files( 14 | DIRECTORY msg 15 | FILES 16 | CameraInfo.msg 17 | ChannelFloat32.msg 18 | CompressedImage.msg 19 | FluidPressure.msg 20 | Illuminance.msg 21 | Image.msg 22 | Imu.msg 23 | JointState.msg 24 | Joy.msg 25 | JoyFeedback.msg 26 | JoyFeedbackArray.msg 27 | LaserEcho.msg 28 | LaserScan.msg 29 | MagneticField.msg 30 | MultiDOFJointState.msg 31 | MultiEchoLaserScan.msg 32 | NavSatFix.msg 33 | NavSatStatus.msg 34 | PointCloud.msg 35 | PointCloud2.msg 36 | PointField.msg 37 | Range.msg 38 | RegionOfInterest.msg 39 | RelativeHumidity.msg 40 | Temperature.msg 41 | TimeReference.msg) 42 | 43 | add_service_files( 44 | DIRECTORY srv 45 | FILES SetCameraInfo.srv) 46 | 47 | generate_messages(DEPENDENCIES geometry_msgs std_msgs) 48 | 49 | catkin_package( 50 | INCLUDE_DIRS include 51 | CATKIN_DEPENDS geometry_msgs message_runtime std_msgs 52 | DEPENDS Boost) 53 | 54 | install(DIRECTORY include/${PROJECT_NAME}/ 55 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 56 | FILES_MATCHING PATTERN "*.h") 57 | 58 | if (CATKIN_ENABLE_TESTING) 59 | add_subdirectory(test) 60 | endif() 61 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/include/sensor_msgs/distortion_models.h: -------------------------------------------------------------------------------- 1 | 2 | /********************************************************************* 3 | * Software License Agreement (BSD License) 4 | * 5 | * Copyright (c) 2010, Willow Garage, Inc. 6 | * All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Willow Garage nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | *********************************************************************/ 35 | 36 | #ifndef SENSOR_MSGS_DISTORTION_MODELS_H 37 | #define SENSOR_MSGS_DISTORTION_MODELS_H 38 | 39 | #include 40 | 41 | namespace sensor_msgs 42 | { 43 | namespace distortion_models 44 | { 45 | const std::string PLUMB_BOB = "plumb_bob"; 46 | const std::string RATIONAL_POLYNOMIAL = "rational_polynomial"; 47 | } 48 | } 49 | 50 | #endif 51 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/include/sensor_msgs/fill_image.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2008, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | #ifndef FILLIMAGE_HH 36 | #define FILLIMAGE_HH 37 | 38 | #include "sensor_msgs/Image.h" 39 | #include "sensor_msgs/image_encodings.h" 40 | 41 | namespace sensor_msgs 42 | { 43 | 44 | static inline bool fillImage(Image& image, 45 | const std::string& encoding_arg, 46 | uint32_t rows_arg, 47 | uint32_t cols_arg, 48 | uint32_t step_arg, 49 | const void* data_arg) 50 | { 51 | image.encoding = encoding_arg; 52 | image.height = rows_arg; 53 | image.width = cols_arg; 54 | image.step = step_arg; 55 | size_t st0 = (step_arg * rows_arg); 56 | image.data.resize(st0); 57 | memcpy(&image.data[0], data_arg, st0); 58 | 59 | image.is_bigendian = 0; 60 | return true; 61 | } 62 | 63 | static inline void clearImage(Image& image) 64 | { 65 | image.data.resize(0); 66 | } 67 | } 68 | 69 | 70 | #endif 71 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b sensor_msgs is a package which collects the common message data types for 6 | robot sensors. It also provides a set of methods for conversion between these 7 | data types. 8 | 9 | 10 | */ 11 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/CameraInfo.msg: -------------------------------------------------------------------------------- 1 | # This message defines meta information for a camera. It should be in a 2 | # camera namespace on topic "camera_info" and accompanied by up to five 3 | # image topics named: 4 | # 5 | # image_raw - raw data from the camera driver, possibly Bayer encoded 6 | # image - monochrome, distorted 7 | # image_color - color, distorted 8 | # image_rect - monochrome, rectified 9 | # image_rect_color - color, rectified 10 | # 11 | # The image_pipeline contains packages (image_proc, stereo_image_proc) 12 | # for producing the four processed image topics from image_raw and 13 | # camera_info. The meaning of the camera parameters are described in 14 | # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. 15 | # 16 | # The image_geometry package provides a user-friendly interface to 17 | # common operations using this meta information. If you want to, e.g., 18 | # project a 3d point into image coordinates, we strongly recommend 19 | # using image_geometry. 20 | # 21 | # If the camera is uncalibrated, the matrices D, K, R, P should be left 22 | # zeroed out. In particular, clients may assume that K[0] == 0.0 23 | # indicates an uncalibrated camera. 24 | 25 | ####################################################################### 26 | # Image acquisition info # 27 | ####################################################################### 28 | 29 | # Time of image acquisition, camera coordinate frame ID 30 | Header header # Header timestamp should be acquisition time of image 31 | # Header frame_id should be optical frame of camera 32 | # origin of frame should be optical center of camera 33 | # +x should point to the right in the image 34 | # +y should point down in the image 35 | # +z should point into the plane of the image 36 | 37 | 38 | ####################################################################### 39 | # Calibration Parameters # 40 | ####################################################################### 41 | # These are fixed during camera calibration. Their values will be the # 42 | # same in all messages until the camera is recalibrated. Note that # 43 | # self-calibrating systems may "recalibrate" frequently. # 44 | # # 45 | # The internal parameters can be used to warp a raw (distorted) image # 46 | # to: # 47 | # 1. An undistorted image (requires D and K) # 48 | # 2. A rectified image (requires D, K, R) # 49 | # The projection matrix P projects 3D points into the rectified image.# 50 | ####################################################################### 51 | 52 | # The image dimensions with which the camera was calibrated. Normally 53 | # this will be the full camera resolution in pixels. 54 | uint32 height 55 | uint32 width 56 | 57 | # The distortion model used. Supported models are listed in 58 | # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a 59 | # simple model of radial and tangential distortion - is sufficent. 60 | string distortion_model 61 | 62 | # The distortion parameters, size depending on the distortion model. 63 | # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). 64 | float64[] D 65 | 66 | # Intrinsic camera matrix for the raw (distorted) images. 67 | # [fx 0 cx] 68 | # K = [ 0 fy cy] 69 | # [ 0 0 1] 70 | # Projects 3D points in the camera coordinate frame to 2D pixel 71 | # coordinates using the focal lengths (fx, fy) and principal point 72 | # (cx, cy). 73 | float64[9] K # 3x3 row-major matrix 74 | 75 | # Rectification matrix (stereo cameras only) 76 | # A rotation matrix aligning the camera coordinate system to the ideal 77 | # stereo image plane so that epipolar lines in both stereo images are 78 | # parallel. 79 | float64[9] R # 3x3 row-major matrix 80 | 81 | # Projection/camera matrix 82 | # [fx' 0 cx' Tx] 83 | # P = [ 0 fy' cy' Ty] 84 | # [ 0 0 1 0] 85 | # By convention, this matrix specifies the intrinsic (camera) matrix 86 | # of the processed (rectified) image. That is, the left 3x3 portion 87 | # is the normal camera intrinsic matrix for the rectified image. 88 | # It projects 3D points in the camera coordinate frame to 2D pixel 89 | # coordinates using the focal lengths (fx', fy') and principal point 90 | # (cx', cy') - these may differ from the values in K. 91 | # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will 92 | # also have R = the identity and P[1:3,1:3] = K. 93 | # For a stereo pair, the fourth column [Tx Ty 0]' is related to the 94 | # position of the optical center of the second camera in the first 95 | # camera's frame. We assume Tz = 0 so both cameras are in the same 96 | # stereo image plane. The first camera always has Tx = Ty = 0. For 97 | # the right (second) camera of a horizontal stereo pair, Ty = 0 and 98 | # Tx = -fx' * B, where B is the baseline between the cameras. 99 | # Given a 3D point [X Y Z]', the projection (x, y) of the point onto 100 | # the rectified image is given by: 101 | # [u v w]' = P * [X Y Z 1]' 102 | # x = u / w 103 | # y = v / w 104 | # This holds for both images of a stereo pair. 105 | float64[12] P # 3x4 row-major matrix 106 | 107 | 108 | ####################################################################### 109 | # Operational Parameters # 110 | ####################################################################### 111 | # These define the image region actually captured by the camera # 112 | # driver. Although they affect the geometry of the output image, they # 113 | # may be changed freely without recalibrating the camera. # 114 | ####################################################################### 115 | 116 | # Binning refers here to any camera setting which combines rectangular 117 | # neighborhoods of pixels into larger "super-pixels." It reduces the 118 | # resolution of the output image to 119 | # (width / binning_x) x (height / binning_y). 120 | # The default values binning_x = binning_y = 0 is considered the same 121 | # as binning_x = binning_y = 1 (no subsampling). 122 | uint32 binning_x 123 | uint32 binning_y 124 | 125 | # Region of interest (subwindow of full camera resolution), given in 126 | # full resolution (unbinned) image coordinates. A particular ROI 127 | # always denotes the same window of pixels on the camera sensor, 128 | # regardless of binning settings. 129 | # The default setting of roi (all values 0) is considered the same as 130 | # full resolution (roi.width = width, roi.height = height). 131 | RegionOfInterest roi 132 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/ChannelFloat32.msg: -------------------------------------------------------------------------------- 1 | # This message is used by the PointCloud message to hold optional data 2 | # associated with each point in the cloud. The length of the values 3 | # array should be the same as the length of the points array in the 4 | # PointCloud, and each value should be associated with the corresponding 5 | # point. 6 | 7 | # Channel names in existing practice include: 8 | # "u", "v" - row and column (respectively) in the left stereo image. 9 | # This is opposite to usual conventions but remains for 10 | # historical reasons. The newer PointCloud2 message has no 11 | # such problem. 12 | # "rgb" - For point clouds produced by color stereo cameras. uint8 13 | # (R,G,B) values packed into the least significant 24 bits, 14 | # in order. 15 | # "intensity" - laser or pixel intensity. 16 | # "distance" 17 | 18 | # The channel name should give semantics of the channel (e.g. 19 | # "intensity" instead of "value"). 20 | string name 21 | 22 | # The values array should be 1-1 with the elements of the associated 23 | # PointCloud. 24 | float32[] values 25 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/CompressedImage.msg: -------------------------------------------------------------------------------- 1 | # This message contains a compressed image 2 | 3 | Header header # Header timestamp should be acquisition time of image 4 | # Header frame_id should be optical frame of camera 5 | # origin of frame should be optical center of cameara 6 | # +x should point to the right in the image 7 | # +y should point down in the image 8 | # +z should point into to plane of the image 9 | 10 | string format # Specifies the format of the data 11 | # Acceptable values: 12 | # jpeg, png 13 | uint8[] data # Compressed image buffer 14 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/FluidPressure.msg: -------------------------------------------------------------------------------- 1 | # Single pressure reading. This message is appropriate for measuring the 2 | # pressure inside of a fluid (air, water, etc). This also includes 3 | # atmospheric or barometric pressure. 4 | 5 | # This message is not appropriate for force/pressure contact sensors. 6 | 7 | Header header # timestamp of the measurement 8 | # frame_id is the location of the pressure sensor 9 | 10 | float64 fluid_pressure # Absolute pressure reading in Pascals. 11 | 12 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/Illuminance.msg: -------------------------------------------------------------------------------- 1 | # Single photometric illuminance measurement. Light should be assumed to be 2 | # measured along the sensor's x-axis (the area of detection is the y-z plane). 3 | # The illuminance should have a 0 or positive value and be received with 4 | # the sensor's +X axis pointing toward the light source. 5 | 6 | # Photometric illuminance is the measure of the human eye's sensitivity of the 7 | # intensity of light encountering or passing through a surface. 8 | 9 | # All other Photometric and Radiometric measurements should 10 | # not use this message. 11 | # This message cannot represent: 12 | # Luminous intensity (candela/light source output) 13 | # Luminance (nits/light output per area) 14 | # Irradiance (watt/area), etc. 15 | 16 | Header header # timestamp is the time the illuminance was measured 17 | # frame_id is the location and direction of the reading 18 | 19 | float64 illuminance # Measurement of the Photometric Illuminance in Lux. 20 | 21 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/Image.msg: -------------------------------------------------------------------------------- 1 | # This message contains an uncompressed image 2 | # (0, 0) is at top-left corner of image 3 | # 4 | 5 | Header header # Header timestamp should be acquisition time of image 6 | # Header frame_id should be optical frame of camera 7 | # origin of frame should be optical center of cameara 8 | # +x should point to the right in the image 9 | # +y should point down in the image 10 | # +z should point into to plane of the image 11 | # If the frame_id here and the frame_id of the CameraInfo 12 | # message associated with the image conflict 13 | # the behavior is undefined 14 | 15 | uint32 height # image height, that is, number of rows 16 | uint32 width # image width, that is, number of columns 17 | 18 | # The legal values for encoding are in file src/image_encodings.cpp 19 | # If you want to standardize a new string format, join 20 | # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 21 | 22 | string encoding # Encoding of pixels -- channel meaning, ordering, size 23 | # taken from the list of strings in include/sensor_msgs/image_encodings.h 24 | 25 | uint8 is_bigendian # is this data bigendian? 26 | uint32 step # Full row length in bytes 27 | uint8[] data # actual matrix data, size is (step * rows) 28 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/Imu.msg: -------------------------------------------------------------------------------- 1 | # This is a message to hold data from an IMU (Inertial Measurement Unit) 2 | # 3 | # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec 4 | # 5 | # If the covariance of the measurement is known, it should be filled in (if all you know is the 6 | # variance of each measurement, e.g. from the datasheet, just put those along the diagonal) 7 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the 8 | # data a covariance will have to be assumed or gotten from some other source 9 | # 10 | # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation 11 | # estimate), please set element 0 of the associated covariance matrix to -1 12 | # If you are interpreting this message, please check for a value of -1 in the first element of each 13 | # covariance matrix, and disregard the associated estimate. 14 | 15 | Header header 16 | 17 | geometry_msgs/Quaternion orientation 18 | float64[9] orientation_covariance # Row major about x, y, z axes 19 | 20 | geometry_msgs/Vector3 angular_velocity 21 | float64[9] angular_velocity_covariance # Row major about x, y, z axes 22 | 23 | geometry_msgs/Vector3 linear_acceleration 24 | float64[9] linear_acceleration_covariance # Row major x, y z 25 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/JointState.msg: -------------------------------------------------------------------------------- 1 | # This is a message that holds data to describe the state of a set of torque controlled joints. 2 | # 3 | # The state of each joint (revolute or prismatic) is defined by: 4 | # * the position of the joint (rad or m), 5 | # * the velocity of the joint (rad/s or m/s) and 6 | # * the effort that is applied in the joint (Nm or N). 7 | # 8 | # Each joint is uniquely identified by its name 9 | # The header specifies the time at which the joint states were recorded. All the joint states 10 | # in one message have to be recorded at the same time. 11 | # 12 | # This message consists of a multiple arrays, one for each part of the joint state. 13 | # The goal is to make each of the fields optional. When e.g. your joints have no 14 | # effort associated with them, you can leave the effort array empty. 15 | # 16 | # All arrays in this message should have the same size, or be empty. 17 | # This is the only way to uniquely associate the joint name with the correct 18 | # states. 19 | 20 | 21 | Header header 22 | 23 | string[] name 24 | float64[] position 25 | float64[] velocity 26 | float64[] effort 27 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/JoyFeedback.msg: -------------------------------------------------------------------------------- 1 | # Declare of the type of feedback 2 | uint8 TYPE_LED = 0 3 | uint8 TYPE_RUMBLE = 1 4 | uint8 TYPE_BUZZER = 2 5 | 6 | uint8 type 7 | 8 | # This will hold an id number for each type of each feedback. 9 | # Example, the first led would be id=0, the second would be id=1 10 | uint8 id 11 | 12 | # Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is 13 | # actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. 14 | float32 intensity 15 | 16 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/JoyFeedbackArray.msg: -------------------------------------------------------------------------------- 1 | # This message publishes values for multiple feedback at once. 2 | JoyFeedback[] array -------------------------------------------------------------------------------- /tools/data/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. -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/LaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) 27 | float32[] intensities # intensity data [device-specific units]. If your 28 | # device does not provide intensities, please leave 29 | # the array empty. 30 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/MagneticField.msg: -------------------------------------------------------------------------------- 1 | # Measurement of the Magnetic Field vector at a specific location. 2 | 3 | # If the covariance of the measurement is known, it should be filled in 4 | # (if all you know is the variance of each measurement, e.g. from the datasheet, 5 | #just put those along the diagonal) 6 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", 7 | # and to use the data a covariance will have to be assumed or gotten from some 8 | # other source 9 | 10 | 11 | Header header # timestamp is the time the 12 | # field was measured 13 | # frame_id is the location and orientation 14 | # of the field measurement 15 | 16 | geometry_msgs/Vector3 magnetic_field # x, y, and z components of the 17 | # field vector in Tesla 18 | # If your sensor does not output 3 axes, 19 | # put NaNs in the components not reported. 20 | 21 | float64[9] magnetic_field_covariance # Row major about x, y, z axes 22 | # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/MultiDOFJointState.msg: -------------------------------------------------------------------------------- 1 | # Representation of state for joints with multiple degrees of freedom, 2 | # following the structure of JointState. 3 | # 4 | # It is assumed that a joint in a system corresponds to a transform that gets applied 5 | # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) 6 | # and those 3DOF can be expressed as a transformation matrix, and that transformation 7 | # matrix can be converted back to (x, y, yaw) 8 | # 9 | # Each joint is uniquely identified by its name 10 | # The header specifies the time at which the joint states were recorded. All the joint states 11 | # in one message have to be recorded at the same time. 12 | # 13 | # This message consists of a multiple arrays, one for each part of the joint state. 14 | # The goal is to make each of the fields optional. When e.g. your joints have no 15 | # wrench associated with them, you can leave the wrench array empty. 16 | # 17 | # All arrays in this message should have the same size, or be empty. 18 | # This is the only way to uniquely associate the joint name with the correct 19 | # states. 20 | 21 | Header header 22 | 23 | string[] joint_names 24 | geometry_msgs/Transform[] transforms 25 | geometry_msgs/Twist[] twist 26 | geometry_msgs/Wrench[] wrench 27 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/MultiEchoLaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a multi-echo planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded) 27 | # +Inf measurements are out of range 28 | # -Inf measurements are too close to determine exact distance. 29 | LaserEcho[] intensities # intensity data [device-specific units]. If your 30 | # device does not provide intensities, please leave 31 | # the array empty. -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/NavSatFix.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix for any Global Navigation Satellite System 2 | # 3 | # Specified using the WGS 84 reference ellipsoid 4 | 5 | # header.stamp specifies the ROS time for this measurement (the 6 | # corresponding satellite time may be reported using the 7 | # sensor_msgs/TimeReference message). 8 | # 9 | # header.frame_id is the frame of reference reported by the satellite 10 | # receiver, usually the location of the antenna. This is a 11 | # Euclidean frame relative to the vehicle, not a reference 12 | # ellipsoid. 13 | Header header 14 | 15 | # satellite fix status information 16 | NavSatStatus status 17 | 18 | # Latitude [degrees]. Positive is north of equator; negative is south. 19 | float64 latitude 20 | 21 | # Longitude [degrees]. Positive is east of prime meridian; negative is west. 22 | float64 longitude 23 | 24 | # Altitude [m]. Positive is above the WGS 84 ellipsoid 25 | # (quiet NaN if no altitude is available). 26 | float64 altitude 27 | 28 | # Position covariance [m^2] defined relative to a tangential plane 29 | # through the reported position. The components are East, North, and 30 | # Up (ENU), in row-major order. 31 | # 32 | # Beware: this coordinate system exhibits singularities at the poles. 33 | 34 | float64[9] position_covariance 35 | 36 | # If the covariance of the fix is known, fill it in completely. If the 37 | # GPS receiver provides the variance of each measurement, put them 38 | # along the diagonal. If only Dilution of Precision is available, 39 | # estimate an approximate covariance from that. 40 | 41 | uint8 COVARIANCE_TYPE_UNKNOWN = 0 42 | uint8 COVARIANCE_TYPE_APPROXIMATED = 1 43 | uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 44 | uint8 COVARIANCE_TYPE_KNOWN = 3 45 | 46 | uint8 position_covariance_type 47 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/NavSatStatus.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix status for any Global Navigation Satellite System 2 | 3 | # Whether to output an augmented fix is determined by both the fix 4 | # type and the last time differential corrections were received. A 5 | # fix is valid when status >= STATUS_FIX. 6 | 7 | int8 STATUS_NO_FIX = -1 # unable to fix position 8 | int8 STATUS_FIX = 0 # unaugmented fix 9 | int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation 10 | int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation 11 | 12 | int8 status 13 | 14 | # Bits defining which Global Navigation Satellite System signals were 15 | # used by the receiver. 16 | 17 | uint16 SERVICE_GPS = 1 18 | uint16 SERVICE_GLONASS = 2 19 | uint16 SERVICE_COMPASS = 4 # includes BeiDou. 20 | uint16 SERVICE_GALILEO = 8 21 | 22 | uint16 service 23 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/PointCloud.msg: -------------------------------------------------------------------------------- 1 | # This message holds a collection of 3d points, plus optional additional 2 | # information about each point. 3 | 4 | # Time of sensor data acquisition, coordinate frame ID. 5 | Header header 6 | 7 | # Array of 3d points. Each Point32 should be interpreted as a 3d point 8 | # in the frame given in the header. 9 | geometry_msgs/Point32[] points 10 | 11 | # Each channel should have the same number of elements as points array, 12 | # and the data in each channel should correspond 1:1 with each point. 13 | # Channel names in common practice are listed in ChannelFloat32.msg. 14 | ChannelFloat32[] channels 15 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/PointCloud2.msg: -------------------------------------------------------------------------------- 1 | # This message holds a collection of N-dimensional points, which may 2 | # contain additional information such as normals, intensity, etc. The 3 | # point data is stored as a binary blob, its layout described by the 4 | # contents of the "fields" array. 5 | 6 | # The point cloud data may be organized 2d (image-like) or 1d 7 | # (unordered). Point clouds organized as 2d images may be produced by 8 | # camera depth sensors such as stereo or time-of-flight. 9 | 10 | # Time of sensor data acquisition, and the coordinate frame ID (for 3d 11 | # points). 12 | Header header 13 | 14 | # 2D structure of the point cloud. If the cloud is unordered, height is 15 | # 1 and width is the length of the point cloud. 16 | uint32 height 17 | uint32 width 18 | 19 | # Describes the channels and their layout in the binary data blob. 20 | PointField[] fields 21 | 22 | bool is_bigendian # Is this data bigendian? 23 | uint32 point_step # Length of a point in bytes 24 | uint32 row_step # Length of a row in bytes 25 | uint8[] data # Actual point data, size is (row_step*height) 26 | 27 | bool is_dense # True if there are no invalid points 28 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/PointField.msg: -------------------------------------------------------------------------------- 1 | # This message holds the description of one point entry in the 2 | # PointCloud2 message format. 3 | uint8 INT8 = 1 4 | uint8 UINT8 = 2 5 | uint8 INT16 = 3 6 | uint8 UINT16 = 4 7 | uint8 INT32 = 5 8 | uint8 UINT32 = 6 9 | uint8 FLOAT32 = 7 10 | uint8 FLOAT64 = 8 11 | 12 | string name # Name of field 13 | uint32 offset # Offset from start of point struct 14 | uint8 datatype # Datatype enumeration, see above 15 | uint32 count # How many elements in the field 16 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/Range.msg: -------------------------------------------------------------------------------- 1 | # Single range reading from an active ranger that emits energy and reports 2 | # one range reading that is valid along an arc at the distance measured. 3 | # This message is not appropriate for laser scanners. See the LaserScan 4 | # message if you are working with a laser scanner. 5 | 6 | # This message also can represent a fixed-distance (binary) ranger. This 7 | # sensor will have min_range===max_range===distance of detection. 8 | # These sensors follow REP 117 and will output -Inf if the object is detected 9 | # and +Inf if the object is outside of the detection range. 10 | 11 | Header header # timestamp in the header is the time the ranger 12 | # returned the distance reading 13 | 14 | # Radiation type enums 15 | # If you want a value added to this list, send an email to the ros-users list 16 | uint8 ULTRASOUND=0 17 | uint8 INFRARED=1 18 | 19 | uint8 radiation_type # the type of radiation used by the sensor 20 | # (sound, IR, etc) [enum] 21 | 22 | float32 field_of_view # the size of the arc that the distance reading is 23 | # valid for [rad] 24 | # the object causing the range reading may have 25 | # been anywhere within -field_of_view/2 and 26 | # field_of_view/2 at the measured range. 27 | # 0 angle corresponds to the x-axis of the sensor. 28 | 29 | float32 min_range # minimum range value [m] 30 | float32 max_range # maximum range value [m] 31 | # Fixed distance rangers require min_range==max_range 32 | 33 | float32 range # range data [m] 34 | # (Note: values < range_min or > range_max 35 | # should be discarded) 36 | # Fixed distance rangers only output -Inf or +Inf. 37 | # -Inf represents a detection within fixed distance. 38 | # (Detection too close to the sensor to quantify) 39 | # +Inf represents no detection within the fixed distance. 40 | # (Object out of range) -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/RegionOfInterest.msg: -------------------------------------------------------------------------------- 1 | # This message is used to specify a region of interest within an image. 2 | # 3 | # When used to specify the ROI setting of the camera when the image was 4 | # taken, the height and width fields should either match the height and 5 | # width fields for the associated image; or height = width = 0 6 | # indicates that the full resolution image was captured. 7 | 8 | uint32 x_offset # Leftmost pixel of the ROI 9 | # (0 if the ROI includes the left edge of the image) 10 | uint32 y_offset # Topmost pixel of the ROI 11 | # (0 if the ROI includes the top edge of the image) 12 | uint32 height # Height of ROI 13 | uint32 width # Width of ROI 14 | 15 | # True if a distinct rectified ROI should be calculated from the "raw" 16 | # ROI in this message. Typically this should be False if the full image 17 | # is captured (ROI not used), and True if a subwindow is captured (ROI 18 | # used). 19 | bool do_rectify 20 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/RelativeHumidity.msg: -------------------------------------------------------------------------------- 1 | # Single reading from a relative humidity sensor. Defines the ratio of partial 2 | # pressure of water vapor to the saturated vapor pressure at a temperature. 3 | 4 | Header header # timestamp of the measurement 5 | # frame_id is the location of the humidity sensor 6 | 7 | float64 relative_humidity # Expression of the relative humidity 8 | # from 0.0 to 1.0. 9 | # 0.0 is no partial pressure of water vapor 10 | # 1.0 represents partial pressure of saturation 11 | 12 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/Temperature.msg: -------------------------------------------------------------------------------- 1 | # Single temperature reading. 2 | 3 | Header header # timestamp is the time the temperature was measured 4 | # frame_id is the location of the temperature reading 5 | 6 | float64 temperature # Measurement of the Temperature in Degrees Celsius 7 | 8 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /tools/data/sensor_msgs/msg/TimeReference.msg: -------------------------------------------------------------------------------- 1 | # Measurement from an external time source not actively synchronized with the system clock. 2 | 3 | Header header # stamp is system time for which measurement was valid 4 | # frame_id is not used 5 | 6 | time time_ref # corresponding time from this external source 7 | string source # (optional) name of time source 8 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | sensor_msgs 3 | 1.12.3 4 | 5 | This package defines messages for commonly used sensors, including 6 | cameras and scanning laser rangefinders. 7 | 8 | Tully Foote 9 | BSD 10 | 11 | http://ros.org/wiki/sensor_msgs 12 | 13 | catkin 14 | 15 | geometry_msgs 16 | message_generation 17 | std_msgs 18 | 19 | geometry_msgs 20 | message_runtime 21 | std_msgs 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/setup.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | from distutils.core import setup 4 | from catkin_pkg.python_setup import generate_distutils_setup 5 | 6 | d = generate_distutils_setup( 7 | ## don't do this unless you want a globally visible script 8 | # scripts=['bin/myscript'], 9 | packages=['sensor_msgs'], 10 | package_dir={'': 'src'} 11 | ) 12 | 13 | setup(**d) 14 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/src/sensor_msgs/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xuhao1/Unreal-ROS-Plugin/c61241f58b9b17c8f5a97f0be94aa60c263462b2/tools/data/sensor_msgs/src/sensor_msgs/__init__.py -------------------------------------------------------------------------------- /tools/data/sensor_msgs/src/sensor_msgs/point_cloud2.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | # Software License Agreement (BSD License) 4 | # 5 | # Copyright (c) 208, Willow Garage, Inc. 6 | # All rights reserved. 7 | # 8 | # Redistribution and use in source and binary forms, with or without 9 | # modification, are permitted provided that the following conditions 10 | # are met: 11 | # 12 | # * Redistributions of source code must retain the above copyright 13 | # notice, this list of conditions and the following disclaimer. 14 | # * Redistributions in binary form must reproduce the above 15 | # copyright notice, this list of conditions and the following 16 | # disclaimer in the documentation and/or other materials provided 17 | # with the distribution. 18 | # * Neither the name of Willow Garage, Inc. nor the names of its 19 | # contributors may be used to endorse or promote products derived 20 | # from this software without specific prior written permission. 21 | # 22 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | # POSSIBILITY OF SUCH DAMAGE. 34 | 35 | from __future__ import print_function 36 | 37 | """ 38 | Serialization of sensor_msgs.PointCloud2 messages. 39 | 40 | Author: Tim Field 41 | """ 42 | 43 | import ctypes 44 | import math 45 | import struct 46 | 47 | import roslib.message 48 | from sensor_msgs.msg import PointCloud2, PointField 49 | 50 | _DATATYPES = {} 51 | _DATATYPES[PointField.INT8] = ('b', 1) 52 | _DATATYPES[PointField.UINT8] = ('B', 1) 53 | _DATATYPES[PointField.INT16] = ('h', 2) 54 | _DATATYPES[PointField.UINT16] = ('H', 2) 55 | _DATATYPES[PointField.INT32] = ('i', 4) 56 | _DATATYPES[PointField.UINT32] = ('I', 4) 57 | _DATATYPES[PointField.FLOAT32] = ('f', 4) 58 | _DATATYPES[PointField.FLOAT64] = ('d', 8) 59 | 60 | def read_points(cloud, field_names=None, skip_nans=False, uvs=[]): 61 | """ 62 | Read points from a L{sensor_msgs.PointCloud2} message. 63 | 64 | @param cloud: The point cloud to read from. 65 | @type cloud: L{sensor_msgs.PointCloud2} 66 | @param field_names: The names of fields to read. If None, read all fields. [default: None] 67 | @type field_names: iterable 68 | @param skip_nans: If True, then don't return any point with a NaN value. 69 | @type skip_nans: bool [default: False] 70 | @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] 71 | @type uvs: iterable 72 | @return: Generator which yields a list of values for each point. 73 | @rtype: generator 74 | """ 75 | assert isinstance(cloud, roslib.message.Message) and cloud._type == 'sensor_msgs/PointCloud2', 'cloud is not a sensor_msgs.msg.PointCloud2' 76 | fmt = _get_struct_fmt(cloud.is_bigendian, cloud.fields, field_names) 77 | width, height, point_step, row_step, data, isnan = cloud.width, cloud.height, cloud.point_step, cloud.row_step, cloud.data, math.isnan 78 | unpack_from = struct.Struct(fmt).unpack_from 79 | 80 | if skip_nans: 81 | if uvs: 82 | for u, v in uvs: 83 | p = unpack_from(data, (row_step * v) + (point_step * u)) 84 | has_nan = False 85 | for pv in p: 86 | if isnan(pv): 87 | has_nan = True 88 | break 89 | if not has_nan: 90 | yield p 91 | else: 92 | for v in range(height): 93 | offset = row_step * v 94 | for u in range(width): 95 | p = unpack_from(data, offset) 96 | has_nan = False 97 | for pv in p: 98 | if isnan(pv): 99 | has_nan = True 100 | break 101 | if not has_nan: 102 | yield p 103 | offset += point_step 104 | else: 105 | if uvs: 106 | for u, v in uvs: 107 | yield unpack_from(data, (row_step * v) + (point_step * u)) 108 | else: 109 | for v in range(height): 110 | offset = row_step * v 111 | for u in range(width): 112 | yield unpack_from(data, offset) 113 | offset += point_step 114 | 115 | def create_cloud(header, fields, points): 116 | """ 117 | Create a L{sensor_msgs.msg.PointCloud2} message. 118 | 119 | @param header: The point cloud header. 120 | @type header: L{std_msgs.msg.Header} 121 | @param fields: The point cloud fields. 122 | @type fields: iterable of L{sensor_msgs.msg.PointField} 123 | @param points: The point cloud points. 124 | @type points: list of iterables, i.e. one iterable for each point, with the 125 | elements of each iterable being the values of the fields for 126 | that point (in the same order as the fields parameter) 127 | @return: The point cloud. 128 | @rtype: L{sensor_msgs.msg.PointCloud2} 129 | """ 130 | 131 | cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) 132 | 133 | buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) 134 | 135 | point_step, pack_into = cloud_struct.size, cloud_struct.pack_into 136 | offset = 0 137 | for p in points: 138 | pack_into(buff, offset, *p) 139 | offset += point_step 140 | 141 | return PointCloud2(header=header, 142 | height=1, 143 | width=len(points), 144 | is_dense=False, 145 | is_bigendian=False, 146 | fields=fields, 147 | point_step=cloud_struct.size, 148 | row_step=cloud_struct.size * len(points), 149 | data=buff.raw) 150 | 151 | def create_cloud_xyz32(header, points): 152 | """ 153 | Create a L{sensor_msgs.msg.PointCloud2} message with 3 float32 fields (x, y, z). 154 | 155 | @param header: The point cloud header. 156 | @type header: L{std_msgs.msg.Header} 157 | @param points: The point cloud points. 158 | @type points: iterable 159 | @return: The point cloud. 160 | @rtype: L{sensor_msgs.msg.PointCloud2} 161 | """ 162 | fields = [PointField('x', 0, PointField.FLOAT32, 1), 163 | PointField('y', 4, PointField.FLOAT32, 1), 164 | PointField('z', 8, PointField.FLOAT32, 1)] 165 | return create_cloud(header, fields, points) 166 | 167 | def _get_struct_fmt(is_bigendian, fields, field_names=None): 168 | fmt = '>' if is_bigendian else '<' 169 | 170 | offset = 0 171 | for field in (f for f in sorted(fields, key=lambda f: f.offset) if field_names is None or f.name in field_names): 172 | if offset < field.offset: 173 | fmt += 'x' * (field.offset - offset) 174 | offset = field.offset 175 | if field.datatype not in _DATATYPES: 176 | print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) 177 | else: 178 | datatype_fmt, datatype_length = _DATATYPES[field.datatype] 179 | fmt += field.count * datatype_fmt 180 | offset += field.count * datatype_length 181 | 182 | return fmt 183 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/srv/SetCameraInfo.srv: -------------------------------------------------------------------------------- 1 | # This service requests that a camera stores the given CameraInfo 2 | # as that camera's calibration information. 3 | # 4 | # The width and height in the camera_info field should match what the 5 | # camera is currently outputting on its camera_info topic, and the camera 6 | # will assume that the region of the imager that is being referred to is 7 | # the region that the camera is currently capturing. 8 | 9 | sensor_msgs/CameraInfo camera_info # The camera_info to store 10 | --- 11 | bool success # True if the call succeeded 12 | string status_message # Used to give details about success 13 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | include_directories(${catkin_INCLUDE_DIRS}) 2 | catkin_add_gtest(sensor_msgs_test main.cpp) 3 | -------------------------------------------------------------------------------- /tools/data/sensor_msgs/test/main.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2013, Open Source Robotics Foundation 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #include 36 | 37 | #include 38 | 39 | TEST(sensor_msgs, PointCloud2Iterator) 40 | { 41 | // Create a dummy PointCloud2 42 | int n_points = 4; 43 | sensor_msgs::PointCloud2 cloud_msg_1, cloud_msg_2; 44 | cloud_msg_1.height = n_points; 45 | cloud_msg_1.width = 1; 46 | sensor_msgs::PointCloud2Modifier modifier(cloud_msg_1); 47 | modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); 48 | cloud_msg_2 = cloud_msg_1; 49 | 50 | // Fill 1 by hand 51 | float point_data_raw[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0}; 52 | std::vector point_data(point_data_raw, point_data_raw + 3*n_points); 53 | // colors in RGB order 54 | uint8_t color_data_raw[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120}; 55 | std::vector color_data(color_data_raw, color_data_raw + 3*n_points); 56 | 57 | float *data = reinterpret_cast(&cloud_msg_1.data.front()); 58 | for(size_t n=0, i=0; n(data++); 64 | // add the colors in order BGRA like PCL 65 | size_t j_max = 2; 66 | for(size_t j = 0; j <= j_max; ++j) 67 | *(bgr++) = color_data[3*n+(j_max - j)]; 68 | // Add 3 extra floats of padding 69 | data += 3; 70 | } 71 | 72 | // Fill 2 using an iterator 73 | sensor_msgs::PointCloud2Iterator iter_x(cloud_msg_2, "x"); 74 | sensor_msgs::PointCloud2Iterator iter_r(cloud_msg_2, "r"); 75 | sensor_msgs::PointCloud2Iterator iter_g(cloud_msg_2, "g"); 76 | sensor_msgs::PointCloud2Iterator iter_b(cloud_msg_2, "b"); 77 | for(size_t i=0; i iter_const_1_x(cloud_msg_1, "x"), iter_const_2_x(cloud_msg_2, "x"); 88 | sensor_msgs::PointCloud2ConstIterator iter_const_1_y(cloud_msg_1, "y"), iter_const_2_y(cloud_msg_2, "y"); 89 | sensor_msgs::PointCloud2ConstIterator iter_const_1_z(cloud_msg_1, "z"), iter_const_2_z(cloud_msg_2, "z"); 90 | sensor_msgs::PointCloud2ConstIterator iter_const_1_r(cloud_msg_1, "r"), iter_const_2_r(cloud_msg_2, "r"); 91 | sensor_msgs::PointCloud2ConstIterator iter_const_1_g(cloud_msg_1, "g"), iter_const_2_g(cloud_msg_2, "g"); 92 | sensor_msgs::PointCloud2ConstIterator iter_const_1_b(cloud_msg_1, "b"), iter_const_2_b(cloud_msg_2, "b"); 93 | 94 | size_t i=0; 95 | for(; iter_const_1_x != iter_const_1_x.end(); ++i, ++iter_const_1_x, ++iter_const_2_x, ++iter_const_1_y, ++iter_const_2_y, 96 | ++iter_const_1_z, ++iter_const_2_z, ++iter_const_1_r, ++iter_const_1_g, ++iter_const_1_b) { 97 | EXPECT_EQ(*iter_const_1_x, *iter_const_2_x); 98 | EXPECT_EQ(*iter_const_1_x, point_data[0+3*i]); 99 | EXPECT_EQ(*iter_const_1_y, *iter_const_2_y); 100 | EXPECT_EQ(*iter_const_1_y, point_data[1+3*i]); 101 | EXPECT_EQ(*iter_const_1_z, *iter_const_2_z); 102 | EXPECT_EQ(*iter_const_1_z, point_data[2+3*i]); 103 | EXPECT_EQ(*iter_const_1_r, *iter_const_2_r); 104 | EXPECT_EQ(*iter_const_1_r, color_data[3*i+0]); 105 | EXPECT_EQ(*iter_const_1_g, *iter_const_2_g); 106 | EXPECT_EQ(*iter_const_1_g, color_data[3*i+1]); 107 | EXPECT_EQ(*iter_const_1_b, *iter_const_2_b); 108 | EXPECT_EQ(*iter_const_1_b, color_data[3*i+2]); 109 | // This is to test the different operators 110 | ++iter_const_2_r; 111 | iter_const_2_g += 1; 112 | iter_const_2_b = iter_const_2_b + 1; 113 | } 114 | EXPECT_EQ(i, n_points); 115 | } 116 | 117 | int main(int argc, char** argv) 118 | { 119 | ::testing::InitGoogleTest(&argc, argv); 120 | return RUN_ALL_TESTS(); 121 | } 122 | -------------------------------------------------------------------------------- /tools/data/std_msgs/.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | -------------------------------------------------------------------------------- /tools/data/std_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(std_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | Bool.msg 10 | Byte.msg 11 | ByteMultiArray.msg 12 | Char.msg 13 | ColorRGBA.msg 14 | Duration.msg 15 | Empty.msg 16 | Float32.msg 17 | Float32MultiArray.msg 18 | Float64.msg 19 | Float64MultiArray.msg 20 | Header.msg 21 | Int16.msg 22 | Int16MultiArray.msg 23 | Int32.msg 24 | Int32MultiArray.msg 25 | Int64.msg 26 | Int64MultiArray.msg 27 | Int8.msg 28 | Int8MultiArray.msg 29 | MultiArrayDimension.msg 30 | MultiArrayLayout.msg 31 | String.msg 32 | Time.msg 33 | UInt16.msg 34 | UInt16MultiArray.msg 35 | UInt32.msg 36 | UInt32MultiArray.msg 37 | UInt64.msg 38 | UInt64MultiArray.msg 39 | UInt8.msg 40 | UInt8MultiArray.msg 41 | ) 42 | 43 | generate_messages() 44 | 45 | catkin_package( 46 | INCLUDE_DIRS include 47 | CATKIN_DEPENDS message_runtime) 48 | 49 | install(DIRECTORY include/std_msgs/ 50 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 51 | PATTERN "*.h") 52 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_bool.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_BOOL_H 29 | #define STD_MSGS_BUILTIN_BOOL_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(bool, Bool, 0x8b94c1b53db61fb6ULL, 0xaed406028ad6332aULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_double.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_DOUBLE_H 29 | #define STD_MSGS_BUILTIN_DOUBLE_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(double, Float64, 0xfdb28210bfa9d7c9ULL, 0x1146260178d9a584ULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_float.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_FLOAT_H 29 | #define STD_MSGS_BUILTIN_FLOAT_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(float, Float32, 0x73fcbf46b49191e6ULL, 0x72908e50842a83d4ULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_int16.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT16_H 29 | #define STD_MSGS_BUILTIN_INT16_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int16_t, Int16, 0x8524586e34fbd7cbULL, 0x1c08c5f5f1ca0e57ULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_int32.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT32_H 29 | #define STD_MSGS_BUILTIN_INT32_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int32_t, Int32, 0xda5909fbe378aeafULL, 0x85e547e830cc1bb7ULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_int64.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT64_H 29 | #define STD_MSGS_BUILTIN_INT64_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int64_t, Int64, 0x34add168574510e6ULL, 0xe17f5d23ecc077efULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_int8.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_INT8_H 29 | #define STD_MSGS_BUILTIN_INT8_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(int8_t, Int8, 0x27ffa0c9c4b8fb84ULL, 0x92252bcad9e5c57bULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_string.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_STRING_H 29 | #define STD_MSGS_BUILTIN_STRING_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | namespace ros 35 | { 36 | namespace message_traits 37 | { 38 | 39 | template 40 | struct MD5Sum, ContainerAllocator> > 41 | { 42 | static const char* value() 43 | { 44 | ROS_STATIC_ASSERT(MD5Sum::static_value1 == 0x992ce8a1687cec8cULL); 45 | ROS_STATIC_ASSERT(MD5Sum::static_value2 == 0x8bd883ec73ca41d1ULL); 46 | return MD5Sum >::value(); 47 | } 48 | 49 | static const char* value(const std::basic_string, ContainerAllocator>&) 50 | { 51 | return value(); 52 | } 53 | }; 54 | 55 | template 56 | struct DataType, ContainerAllocator > > 57 | { 58 | static const char* value() 59 | { 60 | return DataType >::value(); 61 | } 62 | 63 | static const char* value(const std::basic_string, ContainerAllocator >&) 64 | { 65 | return value(); 66 | } 67 | }; 68 | 69 | template 70 | struct Definition, ContainerAllocator > > 71 | { 72 | static const char* value() 73 | { 74 | return Definition >::value(); 75 | } 76 | 77 | static const char* value(const std::basic_string, ContainerAllocator >&) 78 | { 79 | return value(); 80 | } 81 | }; 82 | 83 | } 84 | } 85 | 86 | #endif 87 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_uint16.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT16_H 29 | #define STD_MSGS_BUILTIN_UINT16_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint16_t, UInt16, 0x1df79edf208b629fULL, 0xe6b81923a544552dULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_uint32.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT32_H 29 | #define STD_MSGS_BUILTIN_UINT32_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint32_t, UInt32, 0x304a39449588c7f8ULL, 0xce2df6e8001c5fceULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_uint64.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT64_H 29 | #define STD_MSGS_BUILTIN_UINT64_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint64_t, UInt64, 0x1b2a79973e8bf53dULL, 0x7b53acb71299cb57ULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/builtin_uint8.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (C) 2009, Willow Garage, Inc. 3 | * 4 | * Redistribution and use in source and binary forms, with or without 5 | * modification, are permitted provided that the following conditions are met: 6 | * * Redistributions of source code must retain the above copyright notice, 7 | * this list of conditions and the following disclaimer. 8 | * * Redistributions in binary form must reproduce the above copyright 9 | * notice, this list of conditions and the following disclaimer in the 10 | * documentation and/or other materials provided with the distribution. 11 | * * Neither the names of Willow Garage, Inc. nor the names of its 12 | * contributors may be used to endorse or promote products derived from 13 | * this software without specific prior written permission. 14 | * 15 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 19 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | * POSSIBILITY OF SUCH DAMAGE. 26 | */ 27 | 28 | #ifndef STD_MSGS_BUILTIN_UINT8_H 29 | #define STD_MSGS_BUILTIN_UINT8_H 30 | 31 | #include "trait_macros.h" 32 | #include 33 | 34 | STD_MSGS_DEFINE_BUILTIN_TRAITS(uint8_t, UInt8, 0x7c8164229e7d2c17ULL, 0xeb95e9231617fdeeULL); 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /tools/data/std_msgs/include/std_msgs/trait_macros.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Copyright (C) 2009, Willow Garage, Inc. 4 | * 5 | * Redistribution and use in source and binary forms, with or without 6 | * modification, are permitted provided that the following conditions are met: 7 | * * Redistributions of source code must retain the above copyright notice, 8 | * this list of conditions and the following disclaimer. 9 | * * Redistributions in binary form must reproduce the above copyright 10 | * notice, this list of conditions and the following disclaimer in the 11 | * documentation and/or other materials provided with the distribution. 12 | * * Neither the names of Willow Garage, Inc. nor the names of its 13 | * contributors may be used to endorse or promote products derived from 14 | * this software without specific prior written permission. 15 | * 16 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 | * POSSIBILITY OF SUCH DAMAGE. 27 | */ 28 | 29 | #ifndef STD_MSGS_TRAIT_MACROS_H 30 | #define STD_MSGS_TRAIT_MACROS_H 31 | 32 | #define STD_MSGS_DEFINE_BUILTIN_TRAITS(builtin, msg, static_md5sum1, static_md5sum2) \ 33 | namespace ros \ 34 | { \ 35 | namespace message_traits \ 36 | { \ 37 | \ 38 | template<> struct MD5Sum \ 39 | { \ 40 | static const char* value() \ 41 | { \ 42 | return MD5Sum::value(); \ 43 | } \ 44 | \ 45 | static const char* value(const builtin&) \ 46 | { \ 47 | return value(); \ 48 | } \ 49 | }; \ 50 | \ 51 | template<> struct DataType \ 52 | { \ 53 | static const char* value() \ 54 | { \ 55 | return DataType::value(); \ 56 | } \ 57 | \ 58 | static const char* value(const builtin&) \ 59 | { \ 60 | return value(); \ 61 | } \ 62 | }; \ 63 | \ 64 | template<> struct Definition \ 65 | { \ 66 | static const char* value() \ 67 | { \ 68 | return Definition::value(); \ 69 | } \ 70 | \ 71 | static const char* value(const builtin&) \ 72 | { \ 73 | return value(); \ 74 | } \ 75 | }; \ 76 | \ 77 | } \ 78 | } 79 | 80 | #endif // STD_MSGS_TRAIT_MACROS_H 81 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Bool.msg: -------------------------------------------------------------------------------- 1 | bool data -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Byte.msg: -------------------------------------------------------------------------------- 1 | byte data 2 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Char.msg: -------------------------------------------------------------------------------- 1 | char data -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/ColorRGBA.msg: -------------------------------------------------------------------------------- 1 | float32 r 2 | float32 g 3 | float32 b 4 | float32 a 5 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Duration.msg: -------------------------------------------------------------------------------- 1 | duration data 2 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Empty.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/xuhao1/Unreal-ROS-Plugin/c61241f58b9b17c8f5a97f0be94aa60c263462b2/tools/data/std_msgs/msg/Empty.msg -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Float32.msg: -------------------------------------------------------------------------------- 1 | float32 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Float64.msg: -------------------------------------------------------------------------------- 1 | float64 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Header.msg: -------------------------------------------------------------------------------- 1 | # Standard metadata for higher-level stamped data types. 2 | # This is generally used to communicate timestamped data 3 | # in a particular coordinate frame. 4 | # 5 | # sequence ID: consecutively increasing ID 6 | uint32 seq 7 | #Two-integer timestamp that is expressed as: 8 | # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs') 9 | # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs') 10 | # time-handling sugar is provided by the client library 11 | time stamp 12 | #Frame this data is associated with 13 | # 0: no frame 14 | # 1: global frame 15 | string frame_id 16 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Int16.msg: -------------------------------------------------------------------------------- 1 | int16 data 2 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Int32.msg: -------------------------------------------------------------------------------- 1 | int32 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Int64.msg: -------------------------------------------------------------------------------- 1 | int64 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Int8.msg: -------------------------------------------------------------------------------- 1 | int8 data 2 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/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 -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/MultiArrayLayout.msg: -------------------------------------------------------------------------------- 1 | # The multiarray declares a generic multi-dimensional array of a 2 | # particular data type. Dimensions are ordered from outer most 3 | # to inner most. 4 | 5 | MultiArrayDimension[] dim # Array of dimension properties 6 | uint32 data_offset # padding bytes at front of data 7 | 8 | # Accessors should ALWAYS be written in terms of dimension stride 9 | # and specified outer-most dimension first. 10 | # 11 | # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] 12 | # 13 | # A standard, 3-channel 640x480 image with interleaved color channels 14 | # would be specified as: 15 | # 16 | # dim[0].label = "height" 17 | # dim[0].size = 480 18 | # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) 19 | # dim[1].label = "width" 20 | # dim[1].size = 640 21 | # dim[1].stride = 3*640 = 1920 22 | # dim[2].label = "channel" 23 | # dim[2].size = 3 24 | # dim[2].stride = 3 25 | # 26 | # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/String.msg: -------------------------------------------------------------------------------- 1 | string data 2 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/Time.msg: -------------------------------------------------------------------------------- 1 | time data 2 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/UInt16.msg: -------------------------------------------------------------------------------- 1 | uint16 data 2 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/UInt32.msg: -------------------------------------------------------------------------------- 1 | uint32 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/UInt64.msg: -------------------------------------------------------------------------------- 1 | uint64 data -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/msg/UInt8.msg: -------------------------------------------------------------------------------- 1 | uint8 data 2 | -------------------------------------------------------------------------------- /tools/data/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 | -------------------------------------------------------------------------------- /tools/data/std_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | std_msgs 3 | 0.5.9 4 | 5 | Standard ROS Messages including common message types representing primitive data types and other basic message constructs, such as multiarrays. 6 | For common, generic robot-specific message types, please see common_msgs. 7 | 8 | Tully Foote 9 | BSD 10 | 11 | http://www.ros.org/wiki/std_msgs 12 | https://github.com/ros/std_msgs 13 | https://github.com/ros/std_msgs/issues 14 | Morgan Quigley 15 | Ken Conley 16 | Jeremy Leibs 17 | 18 | catkin 19 | 20 | message_generation 21 | 22 | message_runtime 23 | 24 | -------------------------------------------------------------------------------- /tools/data/stereo_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package stereo_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.3 (2015-04-20) 6 | ------------------- 7 | 8 | 1.12.2 (2015-03-21) 9 | ------------------- 10 | 11 | 1.12.1 (2015-03-17) 12 | ------------------- 13 | * updating outdated urls. fixes `#52 `_. 14 | * Contributors: Tully Foote 15 | 16 | 1.12.0 (2014-12-29) 17 | ------------------- 18 | 19 | 1.11.6 (2014-11-04) 20 | ------------------- 21 | 22 | 1.11.5 (2014-10-27) 23 | ------------------- 24 | 25 | 1.11.4 (2014-06-19) 26 | ------------------- 27 | 28 | 1.11.3 (2014-05-07) 29 | ------------------- 30 | * Export architecture_independent flag in package.xml 31 | * Contributors: Scott K Logan 32 | 33 | 1.11.2 (2014-04-24) 34 | ------------------- 35 | 36 | 1.11.1 (2014-04-16) 37 | ------------------- 38 | 39 | 1.11.0 (2014-03-04) 40 | ------------------- 41 | 42 | 1.10.6 (2014-02-27) 43 | ------------------- 44 | 45 | 1.10.5 (2014-02-25) 46 | ------------------- 47 | 48 | 1.10.4 (2014-02-18) 49 | ------------------- 50 | 51 | 1.10.3 (2014-01-07) 52 | ------------------- 53 | 54 | 1.10.2 (2013-08-19) 55 | ------------------- 56 | 57 | 1.10.1 (2013-08-16) 58 | ------------------- 59 | 60 | 1.10.0 (2013-07-13) 61 | ------------------- 62 | 63 | 1.9.16 (2013-05-21) 64 | ------------------- 65 | * update email in package.xml 66 | 67 | 1.9.15 (2013-03-08) 68 | ------------------- 69 | 70 | 1.9.14 (2013-01-19) 71 | ------------------- 72 | 73 | 1.9.13 (2013-01-13) 74 | ------------------- 75 | 76 | 1.9.12 (2013-01-02) 77 | ------------------- 78 | 79 | 1.9.11 (2012-12-17) 80 | ------------------- 81 | * modified dep type of catkin 82 | 83 | 1.9.10 (2012-12-13) 84 | ------------------- 85 | * add missing downstream depend 86 | * switched from langs to message_* packages 87 | 88 | 1.9.9 (2012-11-22) 89 | ------------------ 90 | 91 | 1.9.8 (2012-11-14) 92 | ------------------ 93 | 94 | 1.9.7 (2012-10-30) 95 | ------------------ 96 | * fix catkin function order 97 | 98 | 1.9.6 (2012-10-18) 99 | ------------------ 100 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 101 | 102 | 1.9.5 (2012-09-28) 103 | ------------------ 104 | * fixed missing find genmsg 105 | 106 | 1.9.4 (2012-09-27 18:06) 107 | ------------------------ 108 | 109 | 1.9.3 (2012-09-27 17:39) 110 | ------------------------ 111 | * cleanup 112 | * updated to latest catkin 113 | * fixed dependencies and more 114 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 115 | 116 | 1.9.2 (2012-09-05) 117 | ------------------ 118 | * updated pkg-config in manifest.xml 119 | 120 | 1.9.1 (2012-09-04) 121 | ------------------ 122 | * use install destination variables, removed manual installation of manifests 123 | 124 | 1.9.0 (2012-08-29) 125 | ------------------ 126 | 127 | 1.8.13 (2012-07-26 18:34:15 +0000) 128 | ---------------------------------- 129 | 130 | 1.8.8 (2012-06-12 22:36) 131 | ------------------------ 132 | * removed obsolete catkin tag from manifest files 133 | * fixed package dependencies for several common messages (fixed `#3956 `_) 134 | * adding manifest exports 135 | * removed depend, added catkin 136 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 137 | * common_msgs: removing migration rules as all are over a year old 138 | * bye bye vestigial MSG_DIRS 139 | * stereo_msgs: catkin'd 140 | * adios rosbuild2 in manifest.xml 141 | * missing dependencies 142 | * updating bagmigration exports 143 | * rosbuild2 taking shape 144 | * removing old exports for msg/cpp and reving to 1.3.7 in preperation for release 145 | * stereo_msgs into common_msgs `#4637 `_ 146 | -------------------------------------------------------------------------------- /tools/data/stereo_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(stereo_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS sensor_msgs message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | DisparityImage.msg) 10 | 11 | generate_messages(DEPENDENCIES sensor_msgs std_msgs) 12 | 13 | catkin_package(CATKIN_DEPENDS message_runtime sensor_msgs std_msgs) 14 | -------------------------------------------------------------------------------- /tools/data/stereo_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b stereo_msgs contains messages for representing stereo-related data. 6 | 7 | */ 8 | -------------------------------------------------------------------------------- /tools/data/stereo_msgs/msg/DisparityImage.msg: -------------------------------------------------------------------------------- 1 | # Separate header for compatibility with current TimeSynchronizer. 2 | # Likely to be removed in a later release, use image.header instead. 3 | Header header 4 | 5 | # Floating point disparity image. The disparities are pre-adjusted for any 6 | # x-offset between the principal points of the two cameras (in the case 7 | # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) 8 | sensor_msgs/Image image 9 | 10 | # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. 11 | float32 f # Focal length, pixels 12 | float32 T # Baseline, world units 13 | 14 | # Subwindow of (potentially) valid disparity values. 15 | sensor_msgs/RegionOfInterest valid_window 16 | 17 | # The range of disparities searched. 18 | # In the disparity image, any disparity less than min_disparity is invalid. 19 | # The disparity search range defines the horopter, or 3D volume that the 20 | # stereo algorithm can "see". Points with Z outside of: 21 | # Z_min = fT / max_disparity 22 | # Z_max = fT / min_disparity 23 | # could not be found. 24 | float32 min_disparity 25 | float32 max_disparity 26 | 27 | # Smallest allowed disparity increment. The smallest achievable depth range 28 | # resolution is delta_Z = (Z^2/fT)*delta_d. 29 | float32 delta_d 30 | -------------------------------------------------------------------------------- /tools/data/stereo_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | stereo_msgs 3 | 1.12.3 4 | 5 | stereo_msgs contains messages specific to stereo processing, such as disparity images. 6 | 7 | Tully Foote 8 | BSD 9 | 10 | http://wiki.ros.org/stereo_msgs 11 | Patrick Mihelich 12 | Kurt Konolige 13 | 14 | catkin 15 | 16 | message_generation 17 | sensor_msgs 18 | std_msgs 19 | 20 | message_runtime 21 | sensor_msgs 22 | std_msgs 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package trajectory_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.3 (2015-04-20) 6 | ------------------- 7 | 8 | 1.12.2 (2015-03-21) 9 | ------------------- 10 | 11 | 1.12.1 (2015-03-17) 12 | ------------------- 13 | * updating outdated urls. fixes `#52 `_. 14 | * Contributors: Tully Foote 15 | 16 | 1.12.0 (2014-12-29) 17 | ------------------- 18 | 19 | 1.11.6 (2014-11-04) 20 | ------------------- 21 | 22 | 1.11.5 (2014-10-27) 23 | ------------------- 24 | 25 | 1.11.4 (2014-06-19) 26 | ------------------- 27 | 28 | 1.11.3 (2014-05-07) 29 | ------------------- 30 | * Export architecture_independent flag in package.xml 31 | * Contributors: Scott K Logan 32 | 33 | 1.11.2 (2014-04-24) 34 | ------------------- 35 | 36 | 1.11.1 (2014-04-16) 37 | ------------------- 38 | 39 | 1.11.0 (2014-03-04) 40 | ------------------- 41 | 42 | 1.10.6 (2014-02-27) 43 | ------------------- 44 | 45 | 1.10.5 (2014-02-25) 46 | ------------------- 47 | 48 | 1.10.4 (2014-02-18) 49 | ------------------- 50 | * make link to control messages a real link 51 | * Add a description to trajectory_msgs 52 | * Contributors: Michael Ferguson 53 | 54 | 1.10.3 (2014-01-07) 55 | ------------------- 56 | 57 | 1.10.2 (2013-08-19) 58 | ------------------- 59 | 60 | 1.10.1 (2013-08-16) 61 | ------------------- 62 | * add effort for JointTrajectoryPoint `#13 ` 63 | * fixing maintainer 64 | * updating maintainer 65 | 66 | 1.10.0 (2013-07-13) 67 | ------------------- 68 | * add MultiDOFJointTrajectory 69 | 70 | 1.9.16 (2013-05-21) 71 | ------------------- 72 | 73 | 1.9.15 (2013-03-08) 74 | ------------------- 75 | 76 | 1.9.14 (2013-01-19) 77 | ------------------- 78 | 79 | 1.9.13 (2013-01-13) 80 | ------------------- 81 | 82 | 1.9.12 (2013-01-02) 83 | ------------------- 84 | 85 | 1.9.11 (2012-12-17) 86 | ------------------- 87 | * modified dep type of catkin 88 | 89 | 1.9.10 (2012-12-13) 90 | ------------------- 91 | * add missing downstream depend 92 | * switched from langs to message_* packages 93 | 94 | 1.9.9 (2012-11-22) 95 | ------------------ 96 | 97 | 1.9.8 (2012-11-14) 98 | ------------------ 99 | 100 | 1.9.7 (2012-10-30) 101 | ------------------ 102 | * fix catkin function order 103 | 104 | 1.9.6 (2012-10-18) 105 | ------------------ 106 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 107 | 108 | 1.9.5 (2012-09-28) 109 | ------------------ 110 | * fixed missing find genmsg 111 | 112 | 1.9.4 (2012-09-27 18:06) 113 | ------------------------ 114 | 115 | 1.9.3 (2012-09-27 17:39) 116 | ------------------------ 117 | * cleanup 118 | * updated to latest catkin 119 | * fixed dependencies and more 120 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 121 | 122 | 1.9.2 (2012-09-05) 123 | ------------------ 124 | * updated pkg-config in manifest.xml 125 | 126 | 1.9.1 (2012-09-04) 127 | ------------------ 128 | * use install destination variables, removed manual installation of manifests 129 | 130 | 1.9.0 (2012-08-29) 131 | ------------------ 132 | 133 | 1.8.13 (2012-07-26 18:34:15 +0000) 134 | ---------------------------------- 135 | 136 | 1.8.8 (2012-06-12 22:36) 137 | ------------------------ 138 | * removed obsolete catkin tag from manifest files 139 | * add missing packages 140 | * adding manifest exports 141 | * removed depend, added catkin 142 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 143 | * trajectory_msgs: catkin'd 144 | * common_msgs: starting catkin conversion 145 | * adios rosbuild2 in manifest.xml 146 | * rosbuild2 taking shape 147 | * removing old exports for msg/cpp and reving to 1.3.7 in preperation for release 148 | * migrating trajectory_msgs to common_msgs from pr2_controllers `#4675 `_ 149 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(trajectory_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | JointTrajectory.msg 10 | JointTrajectoryPoint.msg 11 | MultiDOFJointTrajectory.msg 12 | MultiDOFJointTrajectoryPoint.msg 13 | ) 14 | 15 | generate_messages(DEPENDENCIES std_msgs geometry_msgs) 16 | 17 | catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs) 18 | 19 | install(DIRECTORY rules 20 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 21 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/msg/JointTrajectory.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string[] joint_names 3 | JointTrajectoryPoint[] points -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/msg/JointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each trajectory point specifies either positions[, velocities[, accelerations]] 2 | # or positions[, effort] for the trajectory to be executed. 3 | # All specified values are in the same order as the joint names in JointTrajectory.msg 4 | 5 | float64[] positions 6 | float64[] velocities 7 | float64[] accelerations 8 | float64[] effort 9 | duration time_from_start 10 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/msg/MultiDOFJointTrajectory.msg: -------------------------------------------------------------------------------- 1 | # The header is used to specify the coordinate frame and the reference time for the trajectory durations 2 | Header header 3 | 4 | # A representation of a multi-dof joint trajectory (each point is a transformation) 5 | # Each point along the trajectory will include an array of positions/velocities/accelerations 6 | # that has the same length as the array of joint names, and has the same order of joints as 7 | # the joint names array. 8 | 9 | string[] joint_names 10 | MultiDOFJointTrajectoryPoint[] points 11 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each multi-dof joint can specify a transform (up to 6 DOF) 2 | geometry_msgs/Transform[] transforms 3 | 4 | # There can be a velocity specified for the origin of the joint 5 | geometry_msgs/Twist[] velocities 6 | 7 | # There can be an acceleration specified for the origin of the joint 8 | geometry_msgs/Twist[] accelerations 9 | 10 | duration time_from_start 11 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | trajectory_msgs 3 | 1.12.3 4 | 5 | This package defines messages for defining robot trajectories. These messages are 6 | also the building blocks of most of the 7 | control_msgs actions. 8 | 9 | Tully Foote 10 | BSD 11 | 12 | http://wiki.ros.org/trajectory_msgs 13 | Stuart Glaser 14 | 15 | catkin 16 | 17 | message_generation 18 | geometry_msgs 19 | std_msgs 20 | 21 | message_runtime 22 | geometry_msgs 23 | std_msgs 24 | rosbag_migration_rule 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /tools/data/trajectory_msgs/rules/JointTrajectoryPoint_Groovy2Hydro_08.10.2013.bmr: -------------------------------------------------------------------------------- 1 | class update_trajectory_msgs_JointTrajectoryPoint_84fd2dcf68773c3dc0e9db894f4e8b40(MessageUpdateRule): 2 | old_type = "trajectory_msgs/JointTrajectoryPoint" 3 | old_full_text = """ 4 | float64[] positions 5 | float64[] velocities 6 | float64[] accelerations 7 | duration time_from_start 8 | """ 9 | 10 | new_type = "trajectory_msgs/JointTrajectoryPoint" 11 | new_full_text = """ 12 | # Each trajectory point specifies either positions[, velocities[, accelerations]] 13 | # or positions[, effort] for the trajectory to be executed. 14 | # All specified values are in the same order as the joint names in JointTrajectory.msg 15 | 16 | float64[] positions 17 | float64[] velocities 18 | float64[] accelerations 19 | float64[] effort 20 | duration time_from_start 21 | """ 22 | 23 | order = 0 24 | migrated_types = [] 25 | 26 | valid = True 27 | 28 | def update(self, old_msg, new_msg): 29 | new_msg.positions = old_msg.positions 30 | new_msg.velocities = old_msg.velocities 31 | new_msg.accelerations = old_msg.accelerations 32 | #No matching field name in old message 33 | new_msg.effort = [] 34 | new_msg.time_from_start = old_msg.time_from_start 35 | -------------------------------------------------------------------------------- /tools/generate_msg.py: -------------------------------------------------------------------------------- 1 | Primitivelist = { 2 | "bool": "bool", 3 | "int8": "int32", 4 | "uint8": "uint32", 5 | "int16": "int32", 6 | "uint16": "uint32", 7 | "int32": "int32", 8 | "uint32": "uint32", 9 | "int64": "int64", 10 | "uint64": "uint64", 11 | "float32": "float", 12 | "float64": "double", 13 | "string": "FString", 14 | "time": "ints32_t", 15 | "duration": "ints32_t" 16 | } 17 | 18 | UserTypeList = dict() 19 | 20 | import re 21 | 22 | 23 | def MakeProperty(var_type, var_name): 24 | if var_type in Primitivelist: 25 | return """UPROPERTY(EditAnywhere, BlueprintReadWrite,Category=\"Robot OS\") 26 | {0} {1};\n""".format(Primitivelist[var_type], var_name) 27 | elif var_type in UserTypeList: 28 | return """UPROPERTY(EditAnywhere, BlueprintReadWrite,Category=\"Robot OS\") 29 | {0} {1};\n""".format(UserTypeList[var_type], var_name) 30 | 31 | def MakeSerialization(varsdef): 32 | SerialCodes = "" 33 | for var_type, var_name in varsdef: 34 | if var_type in Primitivelist: 35 | if (var_type != "string"): 36 | SerialCodes += """ 37 | rapidjson::Value t{0}; 38 | t{0}.SetString("{0}"); 39 | s.AddMember(t{0}, this->{0}, d.GetAllocator()); 40 | """.format(var_name) 41 | else: 42 | SerialCodes += """ 43 | rapidjson::Value t{0},s{0}; 44 | t{0}.SetString("{0}"); 45 | char * fuck_{0} = TCHAR_TO_UTF8( * this->{0}); 46 | s{0}.SetString(rapidjson::StringRef(fuck_{0})); 47 | s.AddMember(t{0},s{0}, d.GetAllocator()); 48 | """.format(var_name) 49 | elif var_type in UserTypeList: 50 | SerialCodes += """ 51 | rapidjson::Value t{0},s{0}; 52 | t{0}.SetString("{0}"); 53 | s.AddMember(t{0}, this->{0}.Serialization(d), d.GetAllocator()); 54 | """.format(var_name) 55 | SerialFuncStr = """rapidjson::Value Serialization(rapidjson::Document & d){ 56 | rapidjson::Value s(rapidjson::kObjectType); 57 | 58 | %s 59 | 60 | return s; 61 | }""" % SerialCodes 62 | return SerialFuncStr 63 | 64 | 65 | def MakeUnserialization(varsdef): 66 | unserialcodes = "" 67 | for var_type, var_name in varsdef: 68 | unserialcodes += """\n if (v.HasMember(\"%s\"))""" % var_name 69 | RJsonType = "---" 70 | if var_type == "bool": 71 | RJsonType = "Bool" 72 | if var_type in ["int8", "int16", "int32"]: 73 | RJsonType = "Int" 74 | elif var_type == "int64": 75 | RJsonType = "Int64" 76 | elif var_type in ["uint8", "uint16", "uint32", "time", "duration"]: 77 | RJsonType = "UInt" 78 | elif var_type == "uint64": 79 | RJsonType = "UInt64" 80 | elif var_type == "float32": 81 | RJsonType = "Double" 82 | elif var_type == "float64": 83 | RJsonType = "Double" 84 | if RJsonType != "---": 85 | unserialcodes += """ 86 | if (v["%s"].Is%s()) 87 | this->%s = v["%s"].Get%s(); 88 | """ % (var_name, RJsonType, var_name, var_name, RJsonType) 89 | continue 90 | if var_type == "string": 91 | unserialcodes += """ 92 | if (v["%s"].IsString()) 93 | this->%s = FString(v["%s"].GetString()); 94 | """ % (var_name, var_name, var_name) 95 | 96 | if var_type in UserTypeList: 97 | unserialcodes += """ 98 | if (v["%s"].IsObject()) 99 | { 100 | this->%s.Unserialization(v["%s"]); 101 | }""" % (var_name, var_name, var_name) 102 | 103 | UnserialFuncStr = """ 104 | void Unserialization(rapidjson::Value & v) { 105 | %s 106 | }""" % unserialcodes 107 | return UnserialFuncStr 108 | 109 | 110 | def AnalyseMsgStr(fstr, name): 111 | defs = re.findall("^\s*(\w+)\s+(\w+)", fstr, re.M) 112 | varsdef = [MakeProperty(k, v) for k, v in defs] 113 | structdef = """USTRUCT() 114 | struct F%s 115 | { 116 | GENERATED_USTRUCT_BODY() 117 | 118 | %s 119 | %s 120 | %s 121 | };""" % (name, "\n ".join(varsdef), MakeSerialization(defs), MakeUnserialization(defs)) 122 | return structdef 123 | 124 | 125 | def AnalyseMsgFile(file_name): 126 | fstr = open(file_name).read() 127 | path_list = re.compile("[/\\\.]").split(file_name) 128 | name = path_list[len(path_list)-2] 129 | return "F"+name, AnalyseMsgStr(fstr, name) 130 | 131 | 132 | def AnalyseMsgDirectory(path): 133 | import glob 134 | title_text = """#ifndef UNREAL_ROS_STRUCTS 135 | #define UNREAL_ROS_STRUCTS 136 | #include 137 | #include "EngineMinimal.h" 138 | """ 139 | struct_text = "" 140 | for f in glob.glob(path+"/*.msg"): 141 | path_list = re.compile("[/\\\.]").split(f) 142 | name = path_list[len(path_list)-2] 143 | UserTypeList[name] = "F"+name 144 | for n, nstr in map(AnalyseMsgFile, glob.glob(path+"/*.msg")): 145 | title_text += "struct %s;\n" % n 146 | struct_text += "\n" + nstr + "\n" 147 | return title_text + struct_text + "\n\n#endif" 148 | 149 | if __name__ == "__main__": 150 | import sys 151 | argv = sys.argv 152 | if (len(argv) < 2): 153 | print "Generate From Data folder" 154 | print AnalyseMsgDirectory("data") 155 | else: 156 | print AnalyseMsgDirectory(sys.argv[1]) 157 | -------------------------------------------------------------------------------- /tools/generate_msg_template.py: -------------------------------------------------------------------------------- 1 | Primitivelist = { 2 | "byte" : "uint8", 3 | "char" : "uint8", 4 | "bool": "bool", 5 | "int8": "int32", 6 | "uint8": "uint8", 7 | "int16": "int32", 8 | "uint16": "int32", 9 | "int32": "int32", 10 | "uint32": "int32", 11 | "int64": "int32", 12 | "uint64": "int32", 13 | "float32": "float", 14 | "float64": "float", 15 | "string": "FString", 16 | "time": "int32", 17 | "duration": "int32" 18 | } 19 | 20 | 21 | JsonType = { 22 | "bool" : "Bool", 23 | "int8" : "Int", 24 | "int16" : "Int", 25 | "int32" : "Int", 26 | "int64" : "Int", 27 | "uint8": "Int", 28 | "uint16": "Int", 29 | "uint32": "Int", 30 | "uint64": "Int", 31 | "time" : "Int64", 32 | "duration" : "Int64", 33 | "float32" : "Double", 34 | "float64" : "Double", 35 | "byte" : "Int", 36 | "char" : "Int" 37 | } 38 | 39 | UserTypeList = dict() 40 | 41 | import re 42 | 43 | #TODO: 44 | #Support Const 45 | class MsgField: 46 | def __init__(self,name,type,pkg,Array = False,Constant = False,ConstantField = 0): 47 | self.name = name 48 | self.type = type 49 | self.Array = Array 50 | self.pkg = pkg 51 | self.Constant = Constant 52 | if Constant: 53 | self.ConstantField = ConstantField 54 | def Update(self,Msg): 55 | if self.type in Primitivelist: 56 | self.UType = Primitivelist[self.type] 57 | else: 58 | if self.pkg+"/"+self.type in UserTypeList: 59 | self.UType = "F_"+UserTypeList[self.pkg+"/"+self.type].GeneratedName 60 | UserTypeList[self.pkg+"/"+self.type].ReferenceBy.add(Msg) 61 | Msg.ReferenceTypes.add(self.pkg+"/"+self.type) 62 | elif "std_msgs" + "/" + self.type in UserTypeList: 63 | self.UType = "F_"+UserTypeList["std_msgs" + "/" + self.type].GeneratedName 64 | UserTypeList["std_msgs" + "/" + self.type].ReferenceBy.add(Msg) 65 | Msg.ReferenceTypes.add("std_msgs" + "/" + self.type) 66 | else: 67 | self.UType = "F_"+UserTypeList[self.type].GeneratedName 68 | UserTypeList[self.type].ReferenceBy.add(Msg) 69 | Msg.ReferenceTypes.add(self.type) 70 | if self.Constant: 71 | self.name = "CONSTANT_"+self.name 72 | if self.Array: 73 | self.UTypeElement = self.UType 74 | self.UType = "TArray<" + self.UType + ">" 75 | 76 | def __str__(self): 77 | return "Field {0} {1} + isArray : {2}".format(self.type,self.name,self.Array) 78 | 79 | class MsgType: 80 | def __init__(self,name,props,pkg): 81 | self.name = name 82 | self.namefull = pkg+"/"+name 83 | self.props = props 84 | self.ReferenceTypes = set() 85 | self.ReferenceBy = set() 86 | UserTypeList[pkg+"/"+self.name] = self 87 | self.GeneratedName = "{0}_{1}".format(pkg,name) 88 | 89 | def __str__(self): 90 | str = "Type:" + self.name + "\n" 91 | for k in self.props: 92 | str += (k.__str__() + "\n") 93 | return str + "" 94 | def Update(self): 95 | for k in self.props: 96 | k.Update(self) 97 | print "Update Type {0} as F_{1}".format(self.namefull,self.GeneratedName) 98 | print self 99 | 100 | def AnalyseMsgStr(pkg,fstr, name): 101 | print "Analyse {0}".format(name) 102 | defs = re.findall("^\s*([\w/]+)\s+(\w+)\s*(?:#.*)?$", fstr, re.M) 103 | defsArray = re.findall("^\s*([\w/]+)\[\]\s+(\w+)\s*(?:#.*)$", fstr, re.M) 104 | constantdefs = re.findall("^\s*(?!string)([\w/]+)\s+(\w+)\s*=\s*(\w+)$", fstr, re.M) 105 | constantdefstr = re.findall("^\s*(string)\s+(\w+)\s*=\s*(.*?)\s*$", fstr, re.M) 106 | print fstr 107 | print defs 108 | MsgList = [MsgField(v,k,pkg) for k,v in defs] 109 | MsgList.extend( [MsgField(v,k,pkg,Array = True) for k,v in defsArray]) 110 | MsgList.extend([MsgField(v,k,pkg,Constant=True,ConstantField=c) for k,v,c in constantdefs]) 111 | MsgList.extend([MsgField(v,k,pkg,Constant=True,ConstantField='"'+c+'"') for k,v,c in constantdefstr]) 112 | return MsgType(name,MsgList,pkg) 113 | 114 | 115 | def AnalyseMsgFile(pkg,file_name): 116 | fstr = open(file_name).read() 117 | path_list = re.compile("[/\\\.]").split(file_name) 118 | name = path_list[len(path_list)-2] 119 | return AnalyseMsgStr(pkg,fstr, name) 120 | 121 | import os 122 | def TopologicalSorting(msgs): 123 | NoReferenced = list() 124 | Poped = True 125 | TotalNum = len(msgs) 126 | while Poped: 127 | Poped = False 128 | for AMsg in msgs: 129 | if len(AMsg.ReferenceTypes) == 0: 130 | for k in AMsg.ReferenceBy: 131 | k.ReferenceTypes.remove(AMsg.namefull) 132 | Poped = True 133 | NoReferenced.append(AMsg) 134 | msgs.remove(AMsg) 135 | break 136 | 137 | print "Success Topoligical Sorting : {0}".format(len(NoReferenced) == TotalNum) 138 | return NoReferenced 139 | 140 | def AnalyseMsgDirectory(path,p1,p2): 141 | ros_pkgs = next(os.walk(path))[1] 142 | print "Analyse {0}".format(ros_pkgs) 143 | import glob 144 | MsgList = set() 145 | for pkg in ros_pkgs: 146 | msgs = map(lambda path: AnalyseMsgFile(pkg,path), glob.glob(path+'/'+pkg+'/msg'+"/*.msg")) 147 | MsgList = MsgList.union(msgs) 148 | for msg in MsgList: 149 | msg.Update() 150 | MsgListRight = TopologicalSorting(MsgList) 151 | #print MsgList 152 | fstr = open("FStructTemplate.h").read() 153 | fstrpp = open("FStructTemplate.cpp").read() 154 | 155 | from jinja2 import Template 156 | template = Template(fstr) 157 | templatepp = Template(fstrpp) 158 | 159 | 160 | rdict = { 161 | "Header" : "ros_msg_test.h", 162 | "StructList" : MsgListRight, 163 | "Primitivelist" : Primitivelist, 164 | "UserTypeList" : UserTypeList, 165 | "JsonType" : JsonType 166 | } 167 | f = open(p1,"w") 168 | fpp = open(p2,"w") 169 | f.write(template.render(**rdict)) 170 | fpp.write(templatepp.render(**rdict)) 171 | 172 | if __name__ == "__main__": 173 | import sys 174 | argv = sys.argv 175 | if (len(argv) < 2): 176 | print "Generate From Data folder" 177 | p1 = "../Source/Unreal_ROS/Classes/ros_msg_test.h" 178 | p2 = "../Source/Unreal_ROS/Private/ros_msg_test.cpp" 179 | 180 | print AnalyseMsgDirectory("data",p1,p2) 181 | else: 182 | print AnalyseMsgDirectory(sys.argv[1]) 183 | -------------------------------------------------------------------------------- /tools/index.html: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | 6 | 7 | 8 | 120 | 121 | 122 | 123 |

Simple roslib Example

124 |

125 | Run the following commands in the terminal then refresh this page. Check the JavaScript 126 | console for the output. 127 |

128 |
    129 |
  1. roscore
  2. 130 |
  3. rostopic pub /listener std_msgs/String "Hello, World"
  4. 131 |
  5. rostopic echo /cmd_vel
  6. 132 |
  7. rosrun rospy_tutorials add_two_ints_server
  8. 133 |
  9. roslaunch rosbridge_server rosbridge_websocket.launch
  10. 134 |
135 |
136 |

137 | Connecting to rosbridge... 138 |

139 | 142 | 145 | 148 |
149 | 150 | -------------------------------------------------------------------------------- /tools/websocketserver.py: -------------------------------------------------------------------------------- 1 | __author__ = 'hao' 2 | import tornado.ioloop 3 | import tornado.web 4 | import tornado.websocket 5 | 6 | clients = [] 7 | from time import sleep 8 | class IndexHandler(tornado.web.RequestHandler): 9 | @tornado.web.asynchronous 10 | def get(request): 11 | request.render("index.html") 12 | 13 | class WebSocketChatHandler(tornado.websocket.WebSocketHandler): 14 | def open(self, *args): 15 | print("open", "WebSocketChatHandler") 16 | clients.append(self) 17 | 18 | def on_message(self, message): 19 | print message 20 | for client in clients: 21 | client.write_message("Fuckkkkk") 22 | 23 | def on_close(self): 24 | clients.remove(self) 25 | 26 | app = tornado.web.Application([(r'/chat', WebSocketChatHandler), (r'/', IndexHandler)]) 27 | 28 | from twisted.internet.protocol import DatagramProtocol 29 | from twisted.internet import reactor 30 | 31 | class Helloer(DatagramProtocol): 32 | 33 | def startProtocol(self): 34 | #host = "192.168.1.1" 35 | #port = 1234 36 | # 37 | #self.transport.connect(host, port) 38 | #print "now we can only send to host %s port %d" % (host, port) 39 | #self.transport.write("hello") # no need for address 40 | pass 41 | print "connect" 42 | #self.transport.write("fuck") 43 | 44 | def datagramReceived(self, data, (host, port)): 45 | print "received %r from %s:%d" % (data, host, port) 46 | self.transport.write(data,(host,port)) 47 | 48 | 49 | # Possibly invoked if there is no server listening on the 50 | # address to which we are sending. 51 | def connectionRefused(self): 52 | print "No one listening" 53 | 54 | # 0 means any port, we don't care in this case 55 | reactor.listenUDP(9095, Helloer()) 56 | reactor.run() 57 | 58 | #app.listen(8080) 59 | #tornado.ioloop.IOLoop.instance().start() --------------------------------------------------------------------------------