├── .gitignore ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── README.md ├── diagnostic_msgs ├── CMakeLists.txt ├── msg │ ├── DiagnosticArray.idl │ ├── DiagnosticStatus.idl │ └── KeyValue.idl └── srv │ ├── AddDiagnostics_Request.idl │ ├── AddDiagnostics_Response.idl │ ├── SelfTest_Request.idl │ └── SelfTest_Response.idl ├── gazebo_msgs ├── CMakeLists.txt ├── msg │ ├── ContactState.idl │ ├── ContactsState.idl │ ├── LinkState.idl │ ├── LinkStates.idl │ ├── ModelState.idl │ ├── ModelStates.idl │ ├── ODEJointProperties.idl │ ├── ODEPhysics.idl │ └── WorldState.idl └── srv │ ├── ApplyBodyWrench_Request.idl │ ├── ApplyJointEffort_Request.idl │ ├── Body_Request.idl │ ├── Default_Response.idl │ ├── DeleteLight_Request.idl │ ├── DeleteModel_Request.idl │ ├── GetJointProperties_Request.idl │ ├── GetJointProperties_Response.idl │ ├── GetLightProperties_Request.idl │ ├── GetLightProperties_Response.idl │ ├── GetLinkProperties_Request.idl │ ├── GetLinkProperties_Response.idl │ ├── GetLinkState_Request.idl │ ├── GetLinkState_Response.idl │ ├── GetModelProperties_Request.idl │ ├── GetModelProperties_Response.idl │ ├── GetModelState_Request.idl │ ├── GetModelState_Response.idl │ ├── GetPhysicsProperties_Response.idl │ ├── GetWorldProperties_Response.idl │ ├── Joint_Request.idl │ ├── SetJointProperties_Request.idl │ ├── SetJointTrajectory_Request.idl │ ├── SetLightProperties_Request.idl │ ├── SetLinkProperties_Request.idl │ ├── SetLinkState_Request.idl │ ├── SetModelConfiguration_Request.idl │ ├── SetModelState_Request.idl │ ├── SetPhysicsProperties_Request.idl │ └── SpawnModel_Request.idl ├── geometry_msgs ├── CMakeLists.txt └── msg │ ├── Accel.idl │ ├── AccelStamped.idl │ ├── AccelWithCovariance.idl │ ├── AccelWithCovarianceStamped.idl │ ├── Inertia.idl │ ├── InertiaStamped.idl │ ├── Point.idl │ ├── Point32.idl │ ├── PointStamped.idl │ ├── Polygon.idl │ ├── PolygonStamped.idl │ ├── Pose.idl │ ├── Pose2D.idl │ ├── PoseArray.idl │ ├── PoseStamped.idl │ ├── PoseWithCovariance.idl │ ├── PoseWithCovarianceStamped.idl │ ├── Quaternion.idl │ ├── QuaternionStamped.idl │ ├── Transform.idl │ ├── TransformStamped.idl │ ├── Twist.idl │ ├── TwistStamped.idl │ ├── TwistWithCovariance.idl │ ├── TwistWithCovarianceStamped.idl │ ├── Vector3.idl │ ├── Vector3Stamped.idl │ ├── Wrench.idl │ └── WrenchStamped.idl ├── lifecycle_msgs ├── CMakeLists.txt ├── msg │ ├── State.idl │ ├── Transition.idl │ ├── TransitionDescription.idl │ └── TransitionEvent.idl └── srv │ ├── ChangeState_Request.idl │ ├── ChangeState_Response.idl │ ├── GetAvailableStates_Request.idl │ ├── GetAvailableStates_Response.idl │ ├── GetAvailableTransitions_Request.idl │ ├── GetAvailableTransitions_Response.idl │ ├── GetState_Request.idl │ └── GetState_Response.idl ├── nav_msgs ├── CMakeLists.txt ├── msg │ ├── GridCells.idl │ ├── MapMetaData.idl │ ├── OccupancyGrid.idl │ ├── Odometry.idl │ └── Path.idl └── srv │ ├── GetMap_Request.idl │ ├── GetMap_Response.idl │ ├── GetPlan_Request.idl │ ├── GetPlan_Response.idl │ ├── SetMap_Request.idl │ └── SetMap_Response.idl ├── pendulum_msgs ├── CMakeLists.txt └── msg │ ├── JointCommand.idl │ ├── JointState.idl │ └── RttestResults.idl ├── resources └── cmake │ ├── Config.cmake.in │ ├── ConnextDdsArgumentChecks.cmake │ ├── ConnextDdsCodegen.cmake │ ├── ConnextDdsRosDdsTypes.cmake │ └── FindRTIConnextDDS.cmake ├── sensor_msgs ├── CMakeLists.txt ├── msg │ ├── BatteryState.idl │ ├── CameraInfo.idl │ ├── ChannelFloat32.idl │ ├── CompressedImage.idl │ ├── FluidPressure.idl │ ├── Illuminance.idl │ ├── Image.idl │ ├── Imu.idl │ ├── JointState.idl │ ├── Joy.idl │ ├── JoyFeedback.idl │ ├── JoyFeedbackArray.idl │ ├── LaserEcho.idl │ ├── LaserScan.idl │ ├── MagneticField.idl │ ├── MultiDOFJointState.idl │ ├── MultiEchoLaserScan.idl │ ├── NavSatFix.idl │ ├── NavSatStatus.idl │ ├── PointCloud.idl │ ├── PointCloud2.idl │ ├── PointField.idl │ ├── Range.idl │ ├── RegionOfInterest.idl │ ├── RelativeHumidity.idl │ ├── Temperature.idl │ └── TimeReference.idl └── srv │ ├── SetCameraInfo_Request.idl │ └── SetCameraInfo_Response.idl ├── shape_msgs ├── CMakeLists.txt └── msg │ ├── Mesh.idl │ ├── MeshTriangle.idl │ ├── Plane.idl │ └── SolidPrimitive.idl ├── std_msgs ├── CMakeLists.txt ├── msg │ ├── Bool.idl │ ├── Byte.idl │ ├── ByteMultiArray.idl │ ├── Char.idl │ ├── ColorRGBA.idl │ ├── Duration.idl │ ├── Empty.idl │ ├── Float32.idl │ ├── Float32MultiArray.idl │ ├── Float64.idl │ ├── Float64MultiArray.idl │ ├── Header.idl │ ├── Int16.idl │ ├── Int16MultiArray.idl │ ├── Int32.idl │ ├── Int32MultiArray.idl │ ├── Int64.idl │ ├── Int64MultiArray.idl │ ├── Int8.idl │ ├── Int8MultiArray.idl │ ├── MultiArrayDimension.idl │ ├── MultiArrayLayout.idl │ ├── String.idl │ ├── Time.idl │ ├── UInt16.idl │ ├── UInt16MultiArray.idl │ ├── UInt32.idl │ ├── UInt32MultiArray.idl │ ├── UInt64.idl │ ├── UInt64MultiArray.idl │ ├── UInt8.idl │ └── UInt8MultiArray.idl └── srv │ ├── Empty_Request.idl │ ├── Empty_Response.idl │ ├── SetBool_Request.idl │ ├── SetBool_Response.idl │ ├── Trigger_Request.idl │ └── Trigger_Response.idl ├── stereo_msgs ├── CMakeLists.txt └── msg │ └── DisparityImage.idl ├── test_msgs ├── CMakeLists.txt ├── msg │ ├── BoundedArrayNested.idl │ ├── BoundedArrayPrimitives.idl │ ├── Builtins.idl │ ├── DynamicArrayNested.idl │ ├── DynamicArrayPrimitives.idl │ ├── DynamicArrayPrimitivesNested.idl │ ├── Empty.idl │ ├── Nested.idl │ ├── Primitives.idl │ ├── StaticArrayNested.idl │ └── StaticArrayPrimitives.idl └── srv │ ├── Empty_Request.idl │ ├── Empty_Response.idl │ ├── Primitives_Request.idl │ └── Primitives_Response.idl ├── tf2_msgs ├── CMakeLists.txt ├── msg │ ├── TF2Error.idl │ └── TFMessage.idl └── srv │ ├── FrameGraph_Request.idl │ └── FrameGraph_Response.idl ├── trajectory_msgs ├── CMakeLists.txt └── msg │ ├── JointTrajectory.idl │ ├── JointTrajectoryPoint.idl │ ├── MultiDOFJointTrajectory.idl │ └── MultiDOFJointTrajectoryPoint.idl └── visualization_msgs ├── CMakeLists.txt └── msg ├── ImageMarker.idl ├── InteractiveMarker.idl ├── InteractiveMarkerControl.idl ├── InteractiveMarkerFeedback.idl ├── InteractiveMarkerInit.idl ├── InteractiveMarkerPose.idl ├── InteractiveMarkerUpdate.idl ├── Marker.idl ├── MarkerArray.idl └── MenuEntry.idl /.gitignore: -------------------------------------------------------------------------------- 1 | build/ -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | # Contributing to ROS Data Types 2 | 3 | ## Contribution Process 4 | 5 | If you wish to contribute enhancements or additional data types, fork 6 | the repository and submit a pull request. 7 | 8 | ## Contributor License Agreement (CLA) 9 | 10 | In order to accept your pull request, we need you to sign a Contributor License Agreement (CLA). Complete your CLA here: https://community.rti.com/cla. You 11 | only need to do this once, we cross-check your Github username with the list 12 | of contributors who have signed the CLA. 13 | 14 | ## License 15 | 16 | The ROS Data Types repository is distributed under the terms of the Apache 17 | Version 2.0. Please refer to the corresponding [LICENSE file](https://github.com/rticommunity/ros-data-types/blob/master/LICENSE) 18 | for the full list of terms and conditions for use, reproduction, and 19 | distribution of this software. 20 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__msg__DiagnosticArray__idl__ 18 | #define __diagnostic_msgs__msg__DiagnosticArray__idl__ 19 | 20 | #include "DiagnosticStatus.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module diagnostic_msgs { module msg { 24 | 25 | struct DiagnosticArray { 26 | std_msgs::msg::Header header; 27 | sequence status; 28 | }; 29 | 30 | }; }; // module msg::diagnostic_msgs 31 | 32 | #endif // __diagnostic_msgs__msg__DiagnosticArray__idl__ 33 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticStatus.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__msg__DiagnosticStatus__idl__ 18 | #define __diagnostic_msgs__msg__DiagnosticStatus__idl__ 19 | 20 | #include "KeyValue.idl" 21 | 22 | module diagnostic_msgs { module msg { 23 | 24 | const octet DiagnosticStatus__OK = 0; 25 | const octet DiagnosticStatus__WARN = 1; 26 | const octet DiagnosticStatus__ERROR = 2; 27 | const octet DiagnosticStatus__STALE = 3; 28 | 29 | struct DiagnosticStatus { 30 | octet level; 31 | string name; 32 | string message; 33 | string hardware_id; 34 | sequence values; 35 | }; 36 | 37 | }; }; // module msg::diagnostic_msgs 38 | 39 | #endif // __diagnostic_msgs__msg__DiagnosticStatus__idl__ 40 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/KeyValue.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__msg__KeyValue__idl__ 18 | #define __diagnostic_msgs__msg__KeyValue__idl__ 19 | 20 | module diagnostic_msgs { module msg { 21 | 22 | struct KeyValue { 23 | string key; 24 | string value; 25 | }; 26 | 27 | }; }; // module msg::diagnostic_msgs 28 | 29 | #endif // __diagnostic_msgs__msg__KeyValue__idl__ 30 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/AddDiagnostics_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__srv__AddDiagnostics_Request__idl__ 18 | #define __diagnostic_msgs__srv__AddDiagnostics_Request__idl__ 19 | 20 | module diagnostic_msgs { module srv { 21 | 22 | struct AddDiagnostics_Request { 23 | string load_namespace; 24 | }; 25 | 26 | }; }; // module srv::diagnostic_msgs 27 | 28 | #endif // __diagnostic_msgs__srv__AddDiagnostics_Request__idl__ 29 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/AddDiagnostics_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__srv__AddDiagnostics_Response__idl__ 18 | #define __diagnostic_msgs__srv__AddDiagnostics_Response__idl__ 19 | 20 | module diagnostic_msgs { module srv { 21 | 22 | struct AddDiagnostics_Response { 23 | boolean success; 24 | string message; 25 | }; 26 | 27 | }; }; // module srv::diagnostic_msgs 28 | 29 | #endif // __diagnostic_msgs__srv__AddDiagnostics_Response__idl__ 30 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/SelfTest_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__srv__SelfTest_Request__idl__ 18 | #define __diagnostic_msgs__srv__SelfTest_Request__idl__ 19 | 20 | module diagnostic_msgs { module srv { 21 | 22 | struct SelfTest_Request { 23 | boolean _dummy; 24 | }; 25 | 26 | }; }; // module srv::diagnostic_msgs 27 | 28 | #endif // __diagnostic_msgs__srv__SelfTest_Request__idl__ 29 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/SelfTest_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __diagnostic_msgs__srv__SelfTest_Response__idl__ 18 | #define __diagnostic_msgs__srv__SelfTest_Response__idl__ 19 | 20 | #include "diagnostic_msgs/msg/DiagnosticStatus.idl" 21 | 22 | module diagnostic_msgs { module srv { 23 | 24 | struct SelfTest_Response { 25 | string id; 26 | octet passed; 27 | sequence status; 28 | }; 29 | 30 | }; }; // module srv::diagnostic_msgs 31 | 32 | #endif // __diagnostic_msgs__srv__SelfTest_Response__idl__ 33 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ContactState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Vector3.idl" 18 | #include "geometry_msgs/msg/Wrench.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct ContactState { 23 | string info; 24 | string collision1_name; 25 | string collision2_name; 26 | sequence wrenches; 27 | geometry_msgs::msg::Wrench total_wrench; 28 | sequence contact_positions; 29 | sequence contact_normals; 30 | sequence depths; 31 | }; 32 | 33 | }; }; // module msg::gazebo_msgs 34 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ContactsState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "ContactState.idl" 18 | #include "std_msgs/msg/Header.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct ContactsState { 23 | std_msgs::msg::Header header; 24 | sequence states; 25 | }; 26 | 27 | }; }; // module msg::gazebo_msgs 28 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/LinkState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | #include "geometry_msgs/msg/Twist.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct LinkState { 23 | string link_name; 24 | geometry_msgs::msg::Pose pose; 25 | geometry_msgs::msg::Twist twist; 26 | string reference_frame; 27 | }; 28 | 29 | }; }; // module msg::gazebo_msgs 30 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/LinkStates.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | #include "geometry_msgs/msg/Twist.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct LinkStates { 23 | sequence name; 24 | sequence pose; 25 | sequence twist; 26 | }; 27 | 28 | }; }; // module msg::gazebo_msgs 29 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ModelState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | #include "geometry_msgs/msg/Twist.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct ModelState { 23 | string model_name; 24 | geometry_msgs::msg::Pose pose; 25 | geometry_msgs::msg::Twist twist; 26 | string reference_frame; 27 | }; 28 | 29 | }; }; // module msg::gazebo_msgs 30 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ModelStates.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | #include "geometry_msgs/msg/Twist.idl" 19 | 20 | module gazebo_msgs { module msg { 21 | 22 | struct ModelStates { 23 | sequence name; 24 | sequence pose; 25 | sequence twist; 26 | }; 27 | 28 | }; }; // module msg::gazebo_msgs 29 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ODEJointProperties.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module msg { 18 | 19 | struct ODEJointProperties { 20 | sequence damping; 21 | sequence hiStop; 22 | sequence loStop; 23 | sequence erp; 24 | sequence cfm; 25 | sequence stop_erp; 26 | sequence stop_cfm; 27 | sequence fudge_factor; 28 | sequence fmax; 29 | sequence vel; 30 | }; 31 | 32 | }; }; // module msg::gazebo_msgs 33 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/ODEPhysics.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module msg { 18 | 19 | struct ODEPhysics { 20 | boolean auto_disable_bodies; 21 | unsigned long sor_pgs_precon_iters; 22 | unsigned long sor_pgs_iters; 23 | double psor_pgs_w; 24 | double sor_pgs_rms_error_tol; 25 | double contact_surface_layer; 26 | double contact_max_correcting_vel; 27 | double cfm; 28 | double erp; 29 | unsigned long max_contacts; 30 | }; 31 | 32 | }; }; // module msg::gazebo_msgs 33 | -------------------------------------------------------------------------------- /gazebo_msgs/msg/WorldState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/Header.idl" 18 | #include "geometry_msgs/msg/Pose.idl" 19 | #include "geometry_msgs/msg/Twist.idl" 20 | #include "geometry_msgs/msg/Wrench.idl" 21 | 22 | module gazebo_msgs { module msg { 23 | 24 | struct WorldState { 25 | std_msgs::msg::Header header; 26 | sequence name; 27 | sequence pose; 28 | sequence twist; 29 | sequence wrench; 30 | }; 31 | 32 | }; }; // module msg::gazebo_msgs 33 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/ApplyBodyWrench_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/Time.idl" 18 | #include "std_msgs/msg/Duration.idl" 19 | #include "geometry_msgs/msg/Wrench.idl" 20 | #include "geometry_msgs/msg/Point.idl" 21 | 22 | module gazebo_msgs { module srv { 23 | 24 | struct ApplyBodyWrench_Request { 25 | string body_name; 26 | string reference_frame; 27 | geometry_msgs::msg::Point reference_point; 28 | geometry_msgs::msg::Wrench wrench; 29 | std_msgs::msg::Time start_time; 30 | std_msgs::msg::Duration duration; 31 | }; 32 | 33 | }; }; // module srv::gazebo_msgs 34 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/ApplyJointEffort_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/Time.idl" 18 | #include "std_msgs/msg/Duration.idl" 19 | 20 | module gazebo_msgs { module srv { 21 | 22 | struct ApplyJointEffort_Request { 23 | string joint_name; 24 | double effort; 25 | std_msgs::msg::Time start_time; 26 | std_msgs::msg::Duration duration; 27 | }; 28 | 29 | }; }; // module srv::gazebo_msgs 30 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/Body_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct BodyRequest { 20 | string body_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/Default_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct Default_Response { 20 | boolean success; 21 | string status_message; 22 | }; 23 | 24 | }; }; // module srv::gazebo_msgs 25 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/DeleteLight_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct DeleteLight_Request { 20 | string light_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/DeleteModel_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct DeleteModel_Request { 20 | string model_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetJointProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetJointProperties_Request { 20 | string joint_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetJointProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | enum Type { REVOLUTE, CONTINUOUS, PRISMATIC, FIXED, BALL, UNIVERSAL }; 20 | 21 | struct GetJointProperties_Response { 22 | sequence damping; 23 | sequence position; 24 | sequence rate; 25 | boolean success; 26 | Type type; 27 | string status_message; 28 | }; 29 | 30 | }; }; // module srv::gazebo_msgs 31 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLightProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetLightProperties_Request { 20 | string light_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLightProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/ColorRGBA.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct GetLightProperties_Response { 22 | std_msgs::msg::ColorRGBA diffuse; 23 | double attenuation_constant; 24 | double attenuation_linear; 25 | double attenuation_quadratic; 26 | boolean success; 27 | string status_message; 28 | }; 29 | 30 | }; }; // module srv::gazebo_msgs 31 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLinkProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetLinkProperties_Request { 20 | string link_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLinkProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct GetLinkProperties_Response { 22 | geometry_msgs::msg::Pose com; 23 | boolean gravity_mode; 24 | double mass; 25 | double ixx; 26 | double ixy; 27 | double ixz; 28 | double iyy; 29 | double iyz; 30 | double izz; 31 | boolean success; 32 | string status_message; 33 | }; 34 | 35 | }; }; // module srv::gazebo_msgs 36 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLinkState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetLinkState_Request { 20 | string link_name; 21 | string reference_frame; 22 | }; 23 | 24 | }; }; // module srv::gazebo_msgs 25 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetLinkState_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "gazebo_msgs/msg/LinkState.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct GetLinkState_Response { 22 | gazebo_msgs::msg::LinkState link_state; 23 | boolean success; 24 | string status_message; 25 | }; 26 | 27 | }; }; // module srv::gazebo_msgs 28 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetModelProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetModelProperties_Request { 20 | string model_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetModelProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetModelProperties_Response { 20 | string parent_model_name; 21 | string canonical_body_name; 22 | sequence body_names; 23 | sequence geom_names; 24 | sequence joint_names; 25 | sequence child_model_names; 26 | boolean is_static; 27 | boolean success; 28 | string status_message; 29 | }; 30 | 31 | }; }; // module srv::gazebo_msgs 32 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetModelState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetModelState_Request { 20 | string model_name; 21 | string relative_entity_name; 22 | }; 23 | 24 | }; }; // module srv::gazebo_msgs 25 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetModelState_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/Header.idl" 18 | #include "geometry_msgs/msg/Pose.idl" 19 | #include "geometry_msgs/msg/Twist.idl" 20 | 21 | module gazebo_msgs { module srv { 22 | 23 | struct GetModelState_Response { 24 | std_msgs::msg::Header header; 25 | geometry_msgs::msg::Pose pose; 26 | geometry_msgs::msg::Twist twist; 27 | boolean success; 28 | string status_message; 29 | }; 30 | 31 | }; }; // module srv::gazebo_msgs 32 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetPhysicsProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "gazebo_msgs/msg/ODEPhysics.idl" 18 | #include "geometry_msgs/msg/Vector3.idl" 19 | 20 | module gazebo_msgs { module srv { 21 | 22 | struct GetPhysicsProperties_Response { 23 | double time_step; 24 | boolean pause; 25 | double max_update_rate; 26 | geometry_msgs::msg::Vector3 gravity; 27 | gazebo_msgs::msg::ODEPhysics ode_config; 28 | boolean success; 29 | string status_message; 30 | }; 31 | 32 | }; }; // module srv::gazebo_msgs 33 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/GetWorldProperties_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct GetWorldProperties_Response { 20 | double sim_time; 21 | sequence model_names; 22 | boolean rendering_enabled; 23 | boolean success; 24 | string status_message; 25 | }; 26 | 27 | }; }; // module srv::gazebo_msgs 28 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/Joint_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct JointRequest { 20 | string joint_name; 21 | }; 22 | 23 | }; }; // module srv::gazebo_msgs 24 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetJointProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "gazebo_msgs/msg/ODEJointProperties.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SetJointProperties_Request { 22 | string joint_name; 23 | gazebo_msgs::msg::ODEJointProperties ode_joint_config; 24 | }; 25 | 26 | }; }; // module srv::gazebo_msgs 27 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetJointTrajectory_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "trajectory_msgs/msg/JointTrajectory.idl" 18 | #include "geometry_msgs/msg/Pose.idl" 19 | 20 | module gazebo_msgs { module srv { 21 | 22 | struct SetJointTrajectory_Request { 23 | string model_name; 24 | trajectory_msgs::msg::JointTrajectory joint_trajectory; 25 | geometry_msgs::msg::Pose model_pose; 26 | boolean set_model_pose; 27 | boolean disable_physics_updates; 28 | }; 29 | 30 | }; }; // module srv::gazebo_msgs 31 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetLightProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "std_msgs/msg/ColorRGBA.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SetLightProperties_Request { 22 | string light_name; 23 | std_msgs::msg::ColorRGBA diffuse; 24 | double attenuation_constant; 25 | double attenuation_linear; 26 | double attenuation_quadratic; 27 | }; 28 | 29 | }; }; // module srv::gazebo_msgs 30 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetLinkProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SetLinkProperties_Request { 22 | string link_name; 23 | geometry_msgs::msg::Pose com; 24 | boolean gravity_mode; 25 | double mass; 26 | double ixx; 27 | double ixy; 28 | double ixz; 29 | double iyy; 30 | double iyz; 31 | double izz; 32 | }; 33 | 34 | }; }; // module srv::gazebo_msgs 35 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetLinkState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "gazebo_msgs/msg/LinkState.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SetLinkState_Request { 22 | gazebo_msgs::msg::LinkState link_state; 23 | }; 24 | 25 | }; }; // module srv::gazebo_msgs 26 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetModelConfiguration_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | module gazebo_msgs { module srv { 18 | 19 | struct SetModelConfiguration_Request { 20 | string model_name; 21 | string urdf_param_name; 22 | sequence joint_names; 23 | sequence joint_positions; 24 | }; 25 | 26 | }; }; // module srv::gazebo_msgs 27 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetModelState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "gazebo_msgs/msg/ModelState.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SetModelState_Request { 22 | gazebo_msgs::msg::ModelState model_state; 23 | }; 24 | 25 | }; }; // module srv::gazebo_msgs 26 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SetPhysicsProperties_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Vector3.idl" 18 | #include "gazebo_msgs/msg/ODEPhysics.idl" 19 | 20 | module gazebo_msgs { module srv { 21 | 22 | struct SetPhysicsProperties_Request { 23 | double time_step; 24 | double max_update_rate; 25 | geometry_msgs::msg::Vector3 gravity; 26 | gazebo_msgs::msg::ODEPhysics ode_config; 27 | }; 28 | 29 | }; }; // module srv::gazebo_msgs 30 | -------------------------------------------------------------------------------- /gazebo_msgs/srv/SpawnModel_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #include "geometry_msgs/msg/Pose.idl" 18 | 19 | module gazebo_msgs { module srv { 20 | 21 | struct SpawnModel_Request { 22 | string model_name; 23 | string model_xml; 24 | string robot_namespace; 25 | geometry_msgs::msg::Pose initial_pose; 26 | string reference_frame; 27 | }; 28 | 29 | }; }; // module srv::gazebo_msgs 30 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Accel.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Accel__idl 18 | #define __geometry_msgs__msg__Accel__idl 19 | 20 | #include "Vector3.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | struct Accel { 25 | geometry_msgs::msg::Vector3 linear; 26 | geometry_msgs::msg::Vector3 angular; 27 | }; 28 | 29 | }; }; // module msg::geometry_msgs 30 | 31 | #endif // __geometry_msgs__msg__Accel__idl 32 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__AccelStamped__idl 18 | #define __geometry_msgs__msg__AccelStamped__idl 19 | 20 | #include "Accel.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct AccelStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Accel accel; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__AccelStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovariance.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__AccelWithCovariance__idl 18 | #define __geometry_msgs__msg__AccelWithCovariance__idl 19 | 20 | #include "Accel.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | typedef double geometry_msgs__AccelWithCovariance__double_array_36[36]; 25 | 26 | struct AccelWithCovariance { 27 | geometry_msgs::msg::Accel accel; 28 | geometry_msgs__AccelWithCovariance__double_array_36 covariance; 29 | }; 30 | 31 | }; }; // module msg::geometry_msgs 32 | 33 | #endif // __geometry_msgs__msg__AccelWithCovariance__idl 34 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovarianceStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__AccelWithCovarianceStamped__idl 18 | #define __geometry_msgs__msg__AccelWithCovarianceStamped__idl 19 | 20 | #include "AccelWithCovariance.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct AccelWithCovarianceStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::AccelWithCovariance accel; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__AccelWithCovarianceStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Inertia.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Inertia__idl 18 | #define __geometry_msgs__msg__Inertia__idl 19 | 20 | #include "Vector3.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | struct Inertia { 25 | double m; 26 | geometry_msgs::msg::Vector3 com; 27 | double ixx; 28 | double ixy; 29 | double ixz; 30 | double iyy; 31 | double iyz; 32 | double izz; 33 | }; 34 | 35 | }; }; // module msg::geometry_msgs 36 | 37 | #endif // __geometry_msgs__msg__Inertia__idl 38 | -------------------------------------------------------------------------------- /geometry_msgs/msg/InertiaStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__InertiaStamped__idl 18 | #define __geometry_msgs__msg__InertiaStamped__idl 19 | 20 | #include "Inertia.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct InertiaStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Inertia inertia; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__InertiaStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Point__idl 18 | #define __geometry_msgs__msg__Point__idl 19 | 20 | module geometry_msgs { module msg { 21 | 22 | struct Point { 23 | double x; 24 | double y; 25 | double z; 26 | }; 27 | 28 | }; }; // module msg::geometry_msgs 29 | 30 | #endif // __geometry_msgs__msg__Point__idl 31 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point32.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Point32__idl 18 | #define __geometry_msgs__msg__Point32__idl 19 | 20 | module geometry_msgs { module msg { 21 | 22 | struct Point32 { 23 | float x; 24 | float y; 25 | float z; 26 | }; 27 | 28 | }; }; // module msg::geometry_msgs 29 | 30 | #endif // __geometry_msgs__msg__Point32__idl 31 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PointStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PointStamped__idl 18 | #define __geometry_msgs__msg__PointStamped__idl 19 | 20 | #include "Point.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct PointStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Point point; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__PointStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Polygon.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Polygon__idl 18 | #define __geometry_msgs__msg__Polygon__idl 19 | 20 | #include "Point32.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | struct Polygon { 25 | sequence points; 26 | }; 27 | 28 | }; }; // module msg::geometry_msgs 29 | 30 | #endif // __geometry_msgs__msg__Polygon__idl 31 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PolygonStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PolygonStamped__idl 18 | #define __geometry_msgs__msg__PolygonStamped__idl 19 | 20 | #include "Polygon.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct PolygonStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Polygon polygon; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__PolygonStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Pose__idl 18 | #define __geometry_msgs__msg__Pose__idl 19 | 20 | #include "Point.idl" 21 | #include "Quaternion.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct Pose { 26 | geometry_msgs::msg::Point position; 27 | geometry_msgs::msg::Quaternion orientation; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__Pose__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose2D.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Pose2D__idl 18 | #define __geometry_msgs__msg__Pose2D__idl 19 | 20 | module geometry_msgs { module msg { 21 | 22 | struct Pose2D { 23 | double x; 24 | double y; 25 | double theta; 26 | }; // struct Pose2D 27 | 28 | }; }; // module msg::geometry_msgs 29 | 30 | #endif // __geometry_msgs__msg__Pose2D__idl 31 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PoseArray__idl 18 | #define __geometry_msgs__msg__PoseArray__idl 19 | 20 | #include "Pose.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct PoseArray { 26 | std_msgs::msg::Header header; 27 | sequence poses; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__PoseArray__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PoseStamped__idl 18 | #define __geometry_msgs__msg__PoseStamped__idl 19 | 20 | #include "Pose.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct PoseStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Pose pose; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__PoseStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovariance.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PoseWithCovariance__idl 18 | #define __geometry_msgs__msg__PoseWithCovariance__idl 19 | 20 | #include "Pose.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | typedef double geometry_msgs__PoseWithCovariance__double_array_36[36]; 25 | 26 | struct PoseWithCovariance { 27 | geometry_msgs::msg::Pose pose; 28 | geometry_msgs__PoseWithCovariance__double_array_36 covariance; 29 | }; 30 | 31 | }; }; // module msg::geometry_msgs 32 | 33 | #endif // __geometry_msgs__msg__PoseWithCovariance__idl 34 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovarianceStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__PoseWithCovarianceStamped__idl 18 | #define __geometry_msgs__msg__PoseWithCovarianceStamped__idl 19 | 20 | #include "PoseWithCovariance.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct PoseWithCovarianceStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::PoseWithCovariance pose; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__PoseWithCovarianceStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Quaternion.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Quaternion__idl 18 | #define __geometry_msgs__msg__Quaternion__idl 19 | 20 | module geometry_msgs { module msg { 21 | 22 | struct Quaternion { 23 | double x; 24 | double y; 25 | double z; 26 | double w; 27 | }; 28 | 29 | }; }; // module msg::geometry_msgs 30 | 31 | #endif // __geometry_msgs__msg__Quaternion__idl 32 | -------------------------------------------------------------------------------- /geometry_msgs/msg/QuaternionStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__QuaternionStamped__idl 18 | #define __geometry_msgs__msg__QuaternionStamped__idl 19 | 20 | #include "Quaternion.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct QuaternionStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Quaternion quaternion; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__QuaternionStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Transform.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Transform__idl 18 | #define __geometry_msgs__msg__Transform__idl 19 | 20 | #include "Quaternion.idl" 21 | #include "Vector3.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct Transform { 26 | geometry_msgs::msg::Vector3 translation; 27 | geometry_msgs::msg::Quaternion rotation; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__Transform__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TransformStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__TransformStamped__idl 18 | #define __geometry_msgs__msg__TransformStamped__idl 19 | 20 | #include "Transform.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct TransformStamped { 26 | std_msgs::msg::Header header; 27 | string child_frame_id; 28 | geometry_msgs::msg::Transform transform; 29 | }; 30 | 31 | }; }; // module msg::geometry_msgs 32 | 33 | #endif // __geometry_msgs__msg__TransformStamped__idl 34 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Twist.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Twist__idl 18 | #define __geometry_msgs__msg__Twist__idl 19 | 20 | #include "Vector3.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | struct Twist { 25 | geometry_msgs::msg::Vector3 linear; 26 | geometry_msgs::msg::Vector3 angular; 27 | }; 28 | 29 | }; }; // module msg::geometry_msgs 30 | 31 | #endif // __geometry_msgs__msg__Twist__idl 32 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__TwistStamped__idl 18 | #define __geometry_msgs__msg__TwistStamped__idl 19 | 20 | #include "Twist.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct TwistStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Twist twist; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__TwistStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovariance.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__TwistWithCovariance__idl 18 | #define __geometry_msgs__msg__TwistWithCovariance__idl 19 | 20 | #include "Twist.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | typedef double geometry_msgs__TwistWithCovariance__double_array_36[36]; 25 | 26 | struct TwistWithCovariance { 27 | geometry_msgs::msg::Twist twist; 28 | geometry_msgs__TwistWithCovariance__double_array_36 covariance; 29 | }; 30 | 31 | }; }; // module msg::geometry_msgs 32 | 33 | #endif // __geometry_msgs__msg__TwistWithCovariance__idl 34 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovarianceStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__TwistWithCovarianceStamped__idl 18 | #define __geometry_msgs__msg__TwistWithCovarianceStamped__idl 19 | 20 | #include "TwistWithCovariance.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct TwistWithCovarianceStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::TwistWithCovariance twist; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__TwistWithCovarianceStamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Vector3__idl 18 | #define __geometry_msgs__msg__Vector3__idl 19 | 20 | module geometry_msgs { module msg { 21 | 22 | struct Vector3 { 23 | double x; 24 | double y; 25 | double z; 26 | }; 27 | 28 | }; }; // module msg::geometry_msgs 29 | 30 | #endif // __geometry_msgs__msg__Vector3__idl 31 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3Stamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Vector3Stamped__idl 18 | #define __geometry_msgs__msg__Vector3Stamped__idl 19 | 20 | #include "Vector3.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct Vector3Stamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Vector3 vector; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__Vector3Stamped__idl 33 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Wrench.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__Wrench__idl 18 | #define __geometry_msgs__msg__Wrench__idl 19 | 20 | #include "Vector3.idl" 21 | 22 | module geometry_msgs { module msg { 23 | 24 | struct Wrench { 25 | geometry_msgs::msg::Vector3 force; 26 | geometry_msgs::msg::Vector3 torque; 27 | }; 28 | 29 | }; }; // module msg::geometry_msgs 30 | 31 | #endif // __geometry_msgs__msg__Wrench__idl 32 | -------------------------------------------------------------------------------- /geometry_msgs/msg/WrenchStamped.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __geometry_msgs__msg__WrenchStamped__idl 18 | #define __geometry_msgs__msg__WrenchStamped__idl 19 | 20 | #include "Wrench.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module geometry_msgs { module msg { 24 | 25 | struct WrenchStamped { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Wrench wrench; 28 | }; 29 | 30 | }; }; // module msg::geometry_msgs 31 | 32 | #endif // __geometry_msgs__msg__WrenchStamped__idl 33 | -------------------------------------------------------------------------------- /lifecycle_msgs/msg/TransitionDescription.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__msg__TransitionDescription__idl 18 | #define __lifecycle_msgs__msg__TransitionDescription__idl 19 | 20 | #include "State.idl" 21 | #include "Transition.idl" 22 | 23 | module lifecycle_msgs { module msg { 24 | 25 | struct TransitionDescription { 26 | lifecycle_msgs::msg::Transition transition; 27 | lifecycle_msgs::msg::State start_state; 28 | lifecycle_msgs::msg::State goal_state; 29 | }; 30 | 31 | }; }; // module msg::lifecycle_msgs 32 | 33 | #endif // __lifecycle_msgs__msg__TransitionDescription__idl 34 | -------------------------------------------------------------------------------- /lifecycle_msgs/msg/TransitionEvent.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__msg__TransitionEvent__idl 18 | #define __lifecycle_msgs__msg__TransitionEvent__idl 19 | 20 | #include "State.idl" 21 | #include "Transition.idl" 22 | 23 | module lifecycle_msgs { module msg { 24 | 25 | struct TransitionEvent { 26 | unsigned long long timestamp; 27 | lifecycle_msgs::msg::Transition transition; 28 | lifecycle_msgs::msg::State start_state; 29 | lifecycle_msgs::msg::State goal_state; 30 | }; 31 | 32 | }; }; // module msg::lifecycle_msgs 33 | 34 | #endif // __lifecycle_msgs__msg__TransitionEvent__idl 35 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/ChangeState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__ChangeState_Request__idl 18 | #define __lifecycle_msgs__srv__ChangeState_Request__idl 19 | 20 | #include "lifecycle_msgs/msg/Transition.idl" 21 | 22 | module lifecycle_msgs { module srv { 23 | 24 | struct ChangeState_Request { 25 | string node_name; 26 | lifecycle_msgs::msg::Transition transition; 27 | }; 28 | 29 | }; }; // module srv::lifecycle_msgs 30 | 31 | #endif // __lifecycle_msgs__srv__ChangeState_Request__idl 32 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/ChangeState_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__ChangeState_Response__idl 18 | #define __lifecycle_msgs__srv__ChangeState_Response__idl 19 | 20 | module lifecycle_msgs { module srv { 21 | 22 | struct ChangeState_Response { 23 | boolean success; 24 | }; 25 | 26 | }; }; // module srv::lifecycle_msgs 27 | 28 | #endif // __lifecycle_msgs__srv__ChangeState_Response__idl 29 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetAvailableStates_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetAvailableStates_Request__idl 18 | #define __lifecycle_msgs__srv__GetAvailableStates_Request__idl 19 | 20 | module lifecycle_msgs { module srv { 21 | 22 | struct GetAvailableStates_Request { 23 | string node_name; 24 | }; 25 | 26 | }; }; // module srv::lifecycle_msgs 27 | 28 | #endif // __lifecycle_msgs__srv__GetAvailableStates_Request__idl 29 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetAvailableStates_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetAvailableStates_Response__idl 18 | #define __lifecycle_msgs__srv__GetAvailableStates_Response__idl 19 | 20 | #include "lifecycle_msgs/msg/State.idl" 21 | 22 | module lifecycle_msgs { module srv { 23 | 24 | struct GetAvailableStates_Response { 25 | sequence available_states; 26 | }; 27 | 28 | }; }; // module srv::lifecycle_msgs 29 | 30 | #endif // __lifecycle_msgs__srv__GetAvailableStates_Response__idl 31 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetAvailableTransitions_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetAvailableTransitions_Request__idl 18 | #define __lifecycle_msgs__srv__GetAvailableTransitions_Request__idl 19 | 20 | module lifecycle_msgs { module srv { 21 | 22 | struct GetAvailableTransitions_Request { 23 | string node_name; 24 | }; 25 | 26 | }; }; // module srv::lifecycle_msgs 27 | 28 | #endif // __lifecycle_msgs__srv__GetAvailableTransitions_Request__idl 29 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetAvailableTransitions_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetAvailableTransitions_Response__idl 18 | #define __lifecycle_msgs__srv__GetAvailableTransitions_Response__idl 19 | 20 | #include "lifecycle_msgs/msg/TransitionDescription.idl" 21 | 22 | module lifecycle_msgs { module srv { 23 | 24 | struct GetAvailableTransitions_Response { 25 | sequence available_transitions; 26 | }; 27 | 28 | }; }; // module srv::lifecycle_msgs 29 | 30 | #endif // __lifecycle_msgs__srv__GetAvailableTransitions_Response__idl 31 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetState_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetState_Request__idl 18 | #define __lifecycle_msgs__srv__GetState_Request__idl 19 | 20 | module lifecycle_msgs { module srv { 21 | 22 | struct GetState_Request { 23 | string node_name; 24 | }; 25 | 26 | }; }; // module srv::lifecycle_msgs 27 | 28 | #endif // __lifecycle_msgs__srv__GetState_Request__idl 29 | -------------------------------------------------------------------------------- /lifecycle_msgs/srv/GetState_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __lifecycle_msgs__srv__GetState_Response__idl 18 | #define __lifecycle_msgs__srv__GetState_Response__idl 19 | 20 | #include "lifecycle_msgs/msg/State.idl" 21 | 22 | module lifecycle_msgs { module srv { 23 | 24 | struct GetState_Response { 25 | lifecycle_msgs::msg::State current_state; 26 | }; 27 | 28 | }; }; // module srv::lifecycle_msgs 29 | 30 | #endif // __lifecycle_msgs__srv__GetState_Response__idl 31 | -------------------------------------------------------------------------------- /nav_msgs/msg/GridCells.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__msg__GridCells__idl 18 | #define __nav_msgs__msg__GridCells__idl 19 | 20 | #include "geometry_msgs/msg/Point.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module nav_msgs { module msg { 24 | 25 | struct GridCells { 26 | std_msgs::msg::Header header; 27 | float cell_width; 28 | float cell_height; 29 | sequence cells; 30 | }; 31 | 32 | }; }; // module msg::nav_msgs 33 | 34 | #endif // __nav_msgs__msg__GridCells__idl 35 | -------------------------------------------------------------------------------- /nav_msgs/msg/MapMetaData.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__msg__MapMetaData__idl 18 | #define __nav_msgs__msg__MapMetaData__idl 19 | 20 | #include "std_msgs/msg/Time.idl" 21 | #include "geometry_msgs/msg/Pose.idl" 22 | 23 | module nav_msgs { module msg { 24 | 25 | struct MapMetaData { 26 | std_msgs::msg::Time map_load_time; 27 | float resolution; 28 | unsigned long width; 29 | unsigned long height; 30 | geometry_msgs::msg::Pose origin; 31 | }; 32 | 33 | }; }; // module msg::nav_msgs 34 | 35 | #endif // __nav_msgs__msg__MapMetaData__idl 36 | -------------------------------------------------------------------------------- /nav_msgs/msg/OccupancyGrid.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__msg__OccupancyGrid__idl 18 | #define __nav_msgs__msg__OccupancyGrid__idl 19 | 20 | #include "MapMetaData.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module nav_msgs { module msg { 24 | 25 | struct OccupancyGrid { 26 | std_msgs::msg::Header header; 27 | nav_msgs::msg::MapMetaData info; 28 | sequence data; 29 | }; 30 | 31 | }; }; // module msg::nav_msgs 32 | 33 | #endif // __nav_msgs__msg__OccupancyGrid__idl 34 | -------------------------------------------------------------------------------- /nav_msgs/msg/Odometry.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__msg__Odometry__idl 18 | #define __nav_msgs__msg__Odometry__idl 19 | 20 | #include "geometry_msgs/msg/PoseWithCovariance.idl" 21 | #include "geometry_msgs/msg/TwistWithCovariance.idl" 22 | #include "std_msgs/msg/Header.idl" 23 | 24 | module nav_msgs { module msg { 25 | 26 | struct Odometry { 27 | std_msgs::msg::Header header; 28 | string child_frame_id; 29 | geometry_msgs::msg::PoseWithCovariance pose; 30 | geometry_msgs::msg::TwistWithCovariance twist; 31 | }; 32 | 33 | }; }; // module msg::nav_msgs 34 | 35 | #endif // __nav_msgs__msg__Odometry__idl 36 | -------------------------------------------------------------------------------- /nav_msgs/msg/Path.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__msg__Path__idl 18 | #define __nav_msgs__msg__Path__idl 19 | 20 | #include "geometry_msgs/msg/PoseStamped.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module nav_msgs { module msg { 24 | 25 | struct Path { 26 | std_msgs::msg::Header header; 27 | sequence poses; 28 | }; 29 | 30 | }; }; // module msg::nav_msgs 31 | 32 | #endif // __nav_msgs__msg__Path__idl 33 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetMap_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__GetMap_Request__idl 18 | #define __nav_msgs__srv__GetMap_Request__idl 19 | 20 | module nav_msgs { module srv { 21 | 22 | struct GetMap_Request { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module srv::nav_msgs 27 | 28 | #endif // __nav_msgs__srv__GetMap_Request__idl 29 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetMap_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__GetMap_Response__idl 18 | #define __nav_msgs__srv__GetMap_Response__idl 19 | 20 | #include "nav_msgs/msg/OccupancyGrid.idl" 21 | 22 | module nav_msgs { module srv { 23 | 24 | struct GetMap_Response { 25 | nav_msgs::msg::OccupancyGrid map; 26 | }; 27 | 28 | }; }; // module srv::nav_msgs 29 | 30 | #endif // __nav_msgs__srv__GetMap_Response__idl 31 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetPlan_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__GetPlan_Request__idl 18 | #define __nav_msgs__srv__GetPlan_Request__idl 19 | 20 | #include "geometry_msgs/msg/PoseStamped.idl" 21 | 22 | module nav_msgs { module srv { 23 | 24 | struct GetPlan_Request { 25 | geometry_msgs::msg::PoseStamped start; 26 | geometry_msgs::msg::PoseStamped goal; 27 | float tolerance; 28 | }; 29 | 30 | }; }; // module srv::nav_msgs 31 | 32 | #endif // __nav_msgs__srv__GetPlan_Request__idl 33 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetPlan_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__GetPlan_Response__idl 18 | #define __nav_msgs__srv__GetPlan_Response__idl 19 | 20 | #include "nav_msgs/msg/Path.idl" 21 | 22 | module nav_msgs { module srv { 23 | 24 | struct GetPlan_Response { 25 | nav_msgs::msg::Path plan; 26 | }; 27 | 28 | }; }; // module srv::nav_msgs 29 | 30 | #endif // __nav_msgs__srv__GetPlan_Response__idl 31 | -------------------------------------------------------------------------------- /nav_msgs/srv/SetMap_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__SetMap_Request__idl 18 | #define __nav_msgs__srv__SetMap_Request__idl 19 | 20 | #include "geometry_msgs/msg/PoseWithCovarianceStamped.idl" 21 | #include "nav_msgs/msg/OccupancyGrid.idl" 22 | 23 | module nav_msgs { module srv { 24 | 25 | struct SetMap_Request { 26 | nav_msgs::msg::OccupancyGrid map; 27 | geometry_msgs::msg::PoseWithCovarianceStamped initial_pose; 28 | }; 29 | 30 | }; }; // module srv::nav_msgs 31 | 32 | #endif // __nav_msgs__srv__SetMap_Request__idl 33 | -------------------------------------------------------------------------------- /nav_msgs/srv/SetMap_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __nav_msgs__srv__SetMap_Response__idl 18 | #define __nav_msgs__srv__SetMap_Response__idl 19 | 20 | module nav_msgs { module srv { 21 | 22 | struct SetMap_Response { 23 | boolean success; 24 | }; 25 | 26 | }; }; // module srv::nav_msgs 27 | 28 | #endif // __nav_msgs__srv__SetMap_Response__idl 29 | -------------------------------------------------------------------------------- /pendulum_msgs/msg/JointCommand.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __pendulum_msgs__msg__JointCommand__idl 18 | #define __pendulum_msgs__msg__JointCommand__idl 19 | 20 | module pendulum_msgs { module msg { 21 | 22 | struct JointCommand { 23 | double position; 24 | }; 25 | 26 | }; }; // module msg::pendulum_msgs 27 | 28 | #endif // __pendulum_msgs__msg__JointCommand__idl 29 | -------------------------------------------------------------------------------- /pendulum_msgs/msg/JointState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __pendulum_msgs__msg__JointState__idl 18 | #define __pendulum_msgs__msg__JointState__idl 19 | 20 | module pendulum_msgs { module msg { 21 | 22 | struct JointState { 23 | double position; 24 | double velocity; 25 | double effort; 26 | }; 27 | 28 | }; }; // module msg::pendulum_msgs 29 | 30 | #endif // __pendulum_msgs__msg__JointState__idl 31 | -------------------------------------------------------------------------------- /resources/cmake/Config.cmake.in: -------------------------------------------------------------------------------- 1 | @PACKAGE_INIT@ 2 | 3 | include("${CMAKE_CURRENT_LIST_DIR}/@TARGETS_EXPORT_NAME@.cmake") 4 | check_required_components("@PROJECT_NAME@") 5 | -------------------------------------------------------------------------------- /resources/cmake/ConnextDdsArgumentChecks.cmake: -------------------------------------------------------------------------------- 1 | # (c) 2017-2018 Copyright, Real-Time Innovations, Inc. All rights reserved. 2 | # No duplications, whole or partial, manual or electronic, may be made 3 | # without express written permission. Any such copies, or revisions thereof, 4 | # must display this notice unaltered. 5 | # This code contains trade secrets of Real-Time Innovations, Inc. 6 | 7 | #[[.rst: 8 | .. _connextdds_argument_checks: 9 | 10 | ConnextDdsArgumentChecks 11 | ------------------------ 12 | 13 | Function helpers to check function arguments 14 | 15 | ``connextdds_check_required_arguments`` 16 | Checks that all of the arguments are present and defined 17 | 18 | #]] 19 | 20 | function(connextdds_check_required_arguments) 21 | foreach(arg ${ARGN}) 22 | if(NOT ${arg}) 23 | message(FATAL_ERROR "Argument ${arg} is missing") 24 | endif() 25 | endforeach() 26 | endfunction() 27 | 28 | macro(connextdds_check_no_extra_arguments) 29 | if(ARGN) 30 | message(FATAL_ERROR "Function has more arguments than expected") 31 | endif() 32 | endmacro() 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/ChannelFloat32.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__ChannelFloat32__idl 18 | #define __sensor_msgs__msg__ChannelFloat32__idl 19 | 20 | module sensor_msgs { module msg { 21 | 22 | struct ChannelFloat32 { 23 | string name; 24 | sequence values; 25 | }; 26 | 27 | }; }; // module msg::sensor_msgs 28 | 29 | #endif // __sensor_msgs__msg__ChannelFloat32__idl 30 | -------------------------------------------------------------------------------- /sensor_msgs/msg/CompressedImage.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__CompressedImage__idl 18 | #define __sensor_msgs__msg__CompressedImage__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct CompressedImage { 25 | std_msgs::msg::Header header; 26 | string format; 27 | sequence data; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__CompressedImage__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/FluidPressure.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__FluidPressure__idl 18 | #define __sensor_msgs__msg__FluidPressure__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct FluidPressure { 25 | std_msgs::msg::Header header; 26 | double fluid_pressure; 27 | double variance; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__FluidPressure__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Illuminance.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__Illuminance__idl 18 | #define __sensor_msgs__msg__Illuminance__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct Illuminance { 25 | std_msgs::msg::Header header; 26 | double illuminance; 27 | double variance; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__Illuminance__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Image.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__Image__idl 18 | #define __sensor_msgs__msg__Image__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct Image { 25 | std_msgs::msg::Header header; 26 | unsigned long height; 27 | unsigned long width; 28 | string encoding; 29 | octet is_bigendian; 30 | unsigned long step; 31 | sequence data; 32 | }; 33 | 34 | }; }; // module msg::sensor_msgs 35 | 36 | #endif // __sensor_msgs__msg__Image__idl 37 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JointState.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__JointState__idl 18 | #define __sensor_msgs__msg__JointState__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct JointState { 25 | std_msgs::msg::Header header; 26 | sequence name; 27 | sequence position; 28 | sequence velocity; 29 | sequence effort; 30 | }; 31 | 32 | }; }; // module msg::sensor_msgs 33 | 34 | #endif // __sensor_msgs__msg__JointState__idl 35 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Joy.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__Joy__idl 18 | #define __sensor_msgs__msg__Joy__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct Joy { 25 | std_msgs::msg::Header header; 26 | sequence axes; 27 | sequence buttons; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__Joy__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedback.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__JoyFeedback__idl 18 | #define __sensor_msgs__msg__JoyFeedback__idl 19 | 20 | module sensor_msgs { module msg { 21 | 22 | const octet JoyFeedback__TYPE_LED = 0; 23 | const octet JoyFeedback__TYPE_RUMBLE = 1; 24 | const octet JoyFeedback__TYPE_BUZZER = 2; 25 | 26 | struct JoyFeedback { 27 | octet type; 28 | octet id; 29 | float intensity; 30 | }; 31 | 32 | }; }; // module msg::sensor_msgs 33 | 34 | #endif // __sensor_msgs__msg__JoyFeedback__idl 35 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedbackArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__JoyFeedbackArray__idl 18 | #define __sensor_msgs__msg__JoyFeedbackArray__idl 19 | 20 | #include "JoyFeedback.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct JoyFeedbackArray { 25 | sequence array; 26 | }; 27 | 28 | }; }; // module msg::sensor_msgs 29 | 30 | #endif // __sensor_msgs__msg__JoyFeedbackArray__idl 31 | -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserEcho.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__LaserEcho__idl 18 | #define __sensor_msgs__msg__LaserEcho__idl 19 | 20 | module sensor_msgs { module msg { 21 | 22 | struct LaserEcho { 23 | sequence echoes; 24 | }; 25 | 26 | }; }; // module msg::sensor_msgs 27 | 28 | #endif // __sensor_msgs__msg__LaserEcho__idl 29 | -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserScan.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__LaserScan__idl 18 | #define __sensor_msgs__msg__LaserScan__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct LaserScan { 25 | std_msgs::msg::Header header; 26 | float angle_min; 27 | float angle_max; 28 | float angle_increment; 29 | float time_increment; 30 | float scan_time; 31 | float range_min; 32 | float range_max; 33 | sequence ranges; 34 | sequence intensities; 35 | }; 36 | 37 | }; }; // module msg::sensor_msgs 38 | 39 | #endif // __sensor_msgs__msg__LaserScan__idl 40 | -------------------------------------------------------------------------------- /sensor_msgs/msg/MagneticField.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__MagneticField__idl 18 | #define __sensor_msgs__msg__MagneticField__idl 19 | 20 | #include "geometry_msgs/msg/Vector3.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module sensor_msgs { module msg { 24 | 25 | typedef double sensor_msgs__MagneticField__double_array_9[9]; 26 | 27 | struct MagneticField { 28 | std_msgs::msg::Header header; 29 | geometry_msgs::msg::Vector3 magnetic_field; 30 | sensor_msgs__MagneticField__double_array_9 magnetic_field_covariance; 31 | }; 32 | 33 | }; }; // module msg::sensor_msgs 34 | 35 | #endif // __sensor_msgs__msg__MagneticField__idl 36 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__PointCloud__idl 18 | #define __sensor_msgs__msg__PointCloud__idl 19 | 20 | #include "geometry_msgs/msg/Point32.idl" 21 | #include "ChannelFloat32.idl" 22 | #include "std_msgs/msg/Header.idl" 23 | 24 | module sensor_msgs { module msg { 25 | 26 | struct PointCloud { 27 | std_msgs::msg::Header header; 28 | sequence points; 29 | sequence channels; 30 | }; 31 | 32 | }; }; // module msg::sensor_msgs 33 | 34 | #endif // __sensor_msgs__msg__PointCloud__idl 35 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud2.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__PointCloud2__idl 18 | #define __sensor_msgs__msg__PointCloud2__idl 19 | 20 | #include "PointField.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module sensor_msgs { module msg { 24 | 25 | struct PointCloud2 { 26 | std_msgs::msg::Header header; 27 | unsigned long height; 28 | unsigned long width; 29 | sequence fields; 30 | boolean is_bigendian; 31 | unsigned long point_step; 32 | unsigned long row_step; 33 | sequence data; 34 | boolean is_dense; 35 | }; 36 | 37 | }; }; // module msg::sensor_msgs 38 | 39 | #endif // __sensor_msgs__msg__PointCloud2__idl 40 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointField.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__PointField__idl 18 | #define __sensor_msgs__msg__PointField__idl 19 | 20 | module sensor_msgs { module msg { 21 | 22 | const octet PointField__INT8 = 1; 23 | const octet PointField__UINT8 = 2; 24 | const octet PointField__INT16 = 3; 25 | const octet PointField__UINT16 = 4; 26 | const octet PointField__INT32 = 5; 27 | const octet PointField__UINT32 = 6; 28 | const octet PointField__FLOAT32 = 7; 29 | const octet PointField__FLOAT64 = 8; 30 | 31 | struct PointField { 32 | string name; 33 | unsigned long offset; 34 | octet datatype; 35 | unsigned long count; 36 | }; 37 | 38 | }; }; // module msg::sensor_msgs 39 | 40 | #endif // __sensor_msgs__msg__PointField__idl 41 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Range.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__Range__idl 18 | #define __sensor_msgs__msg__Range__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | const octet Range__ULTRASOUND = 0; 25 | const octet Range__INFRARED = 1; 26 | 27 | struct Range { 28 | std_msgs::msg::Header header; 29 | octet radiation_type; 30 | float field_of_view; 31 | float min_range; 32 | float max_range; 33 | float range; 34 | }; 35 | 36 | }; }; // module msg::sensor_msgs 37 | 38 | #endif // __sensor_msgs__msg__Range__idl 39 | -------------------------------------------------------------------------------- /sensor_msgs/msg/RegionOfInterest.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__RegionOfInterest__idl 18 | #define __sensor_msgs__msg__RegionOfInterest__idl 19 | 20 | module sensor_msgs { module msg { 21 | 22 | struct RegionOfInterest { 23 | unsigned long x_offset; 24 | unsigned long y_offset; 25 | unsigned long height; 26 | unsigned long width; 27 | boolean do_rectify; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__RegionOfInterest__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/RelativeHumidity.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__RelativeHumidity__idl 18 | #define __sensor_msgs__msg__RelativeHumidity__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct RelativeHumidity { 25 | std_msgs::msg::Header header; 26 | double relative_humidity; 27 | double variance; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__RelativeHumidity__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Temperature.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__Temperature__idl 18 | #define __sensor_msgs__msg__Temperature__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | 22 | module sensor_msgs { module msg { 23 | 24 | struct Temperature { 25 | std_msgs::msg::Header header; 26 | double temperature; 27 | double variance; 28 | }; 29 | 30 | }; }; // module msg::sensor_msgs 31 | 32 | #endif // __sensor_msgs__msg__Temperature__idl 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/TimeReference.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__msg__TimeReference__idl 18 | #define __sensor_msgs__msg__TimeReference__idl 19 | 20 | #include "std_msgs/msg/Time.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module sensor_msgs { module msg { 24 | 25 | struct TimeReference { 26 | std_msgs::msg::Header header; 27 | std_msgs::msg::Time time_ref; 28 | string source; 29 | }; 30 | 31 | }; }; // module msg::sensor_msgs 32 | 33 | #endif // __sensor_msgs__msg__TimeReference__idl 34 | -------------------------------------------------------------------------------- /sensor_msgs/srv/SetCameraInfo_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__srv__SetCameraInfo_Request__idl 18 | #define __sensor_msgs__srv__SetCameraInfo_Request__idl 19 | 20 | #include "sensor_msgs/msg/CameraInfo.idl" 21 | 22 | module sensor_msgs { module srv { 23 | 24 | struct SetCameraInfo_Request { 25 | sensor_msgs::msg::CameraInfo camera_info; 26 | }; 27 | 28 | }; }; // module srv::sensor_msgs 29 | 30 | #endif // __sensor_msgs__srv__SetCameraInfo_Request__idl 31 | -------------------------------------------------------------------------------- /sensor_msgs/srv/SetCameraInfo_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __sensor_msgs__srv__SetCameraInfo_Response__idl 18 | #define __sensor_msgs__srv__SetCameraInfo_Response__idl 19 | 20 | module sensor_msgs { module srv { 21 | 22 | struct SetCameraInfo_Response { 23 | boolean success; 24 | string status_message; 25 | }; 26 | 27 | }; }; // module srv::sensor_msgs 28 | 29 | #endif // __sensor_msgs__srv__SetCameraInfo_Response__idl 30 | -------------------------------------------------------------------------------- /shape_msgs/msg/Mesh.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __shape_msgs__msg__Mesh__idl 18 | #define __shape_msgs__msg__Mesh__idl 19 | 20 | #include "geometry_msgs/msg/Point.idl" 21 | #include "MeshTriangle.idl" 22 | 23 | module shape_msgs { module msg { 24 | 25 | struct Mesh { 26 | sequence triangles; 27 | sequence vertices; 28 | }; 29 | 30 | }; }; // module msg::shape_msgs 31 | 32 | #endif // __shape_msgs__msg__Mesh__idl 33 | -------------------------------------------------------------------------------- /shape_msgs/msg/MeshTriangle.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __shape_msgs__msg__MeshTriangle__idl 18 | #define __shape_msgs__msg__MeshTriangle__idl 19 | 20 | module shape_msgs { module msg { 21 | 22 | typedef unsigned long shape_msgs__MeshTriangle__unsigned_long_array_3[3]; 23 | 24 | struct MeshTriangle { 25 | shape_msgs__MeshTriangle__unsigned_long_array_3 vertex_indices; 26 | }; 27 | 28 | }; }; // module msg::shape_msgs 29 | 30 | #endif // __shape_msgs__msg__MeshTriangle__idl 31 | -------------------------------------------------------------------------------- /shape_msgs/msg/Plane.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __shape_msgs__msg__Plane__idl 18 | #define __shape_msgs__msg__Plane__idl 19 | 20 | module shape_msgs { module msg { 21 | 22 | typedef double shape_msgs__Plane__double_array_4[4]; 23 | 24 | struct Plane { 25 | shape_msgs__Plane__double_array_4 coef; 26 | }; 27 | 28 | }; }; // module msg::shape_msgs 29 | 30 | #endif // __shape_msgs__msg__Plane__idl 31 | -------------------------------------------------------------------------------- /std_msgs/msg/Bool.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Bool__idl 18 | #define __std_msgs__msg__Bool__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Bool { 23 | boolean data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Bool__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Byte.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Byte__idl 18 | #define __std_msgs__msg__Byte__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Byte { 23 | octet data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Byte__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/ByteMultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__ByteMultiArray__idl 18 | #define __std_msgs__msg__ByteMultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct ByteMultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__ByteMultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Char.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Char__idl 18 | #define __std_msgs__msg__Char__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Char { 23 | char data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Char__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/ColorRGBA.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__ColorRGBA__idl 18 | #define __std_msgs__msg__ColorRGBA__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct ColorRGBA { 23 | float r; 24 | float g; 25 | float b; 26 | float a; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__ColorRGBA__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Duration.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Duration__idl 18 | #define __std_msgs__msg__Duration__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Duration { 23 | long sec; 24 | unsigned long nanosec; 25 | }; 26 | 27 | }; }; // module msg::std_msgs 28 | 29 | #endif // __std_msgs__msg__Duration__idl 30 | -------------------------------------------------------------------------------- /std_msgs/msg/Empty.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Empty__idl 18 | #define __std_msgs__msg__Empty__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Empty { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Empty__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Float32.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Float32__idl 18 | #define __std_msgs__msg__Float32__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Float32 { 23 | float data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Float32__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Float32MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Float32MultiArray__idl 18 | #define __std_msgs__msg__Float32MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Float32MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Float32MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Float64.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Float64__idl 18 | #define __std_msgs__msg__Float64__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Float64 { 23 | double data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Float64__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Float64MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Float64MultiArray__idl 18 | #define __std_msgs__msg__Float64MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Float64MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Float64MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Header.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Header__idl 18 | #define __std_msgs__msg__Header__idl 19 | 20 | #include "Time.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Header { 25 | std_msgs::msg::Time stamp; 26 | string frame_id; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Header__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Int16.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int16__idl 18 | #define __std_msgs__msg__Int16__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Int16 { 23 | short data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Int16__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Int16MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int16MultiArray__idl 18 | #define __std_msgs__msg__Int16MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Int16MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Int16MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Int32.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int32__idl 18 | #define __std_msgs__msg__Int32__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Int32 { 23 | long data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Int32__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Int32MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int32MultiArray__idl 18 | #define __std_msgs__msg__Int32MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Int32MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Int32MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Int64.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int64__idl 18 | #define __std_msgs__msg__Int64__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Int64 { 23 | long long data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Int64__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Int64MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int64MultiArray__idl 18 | #define __std_msgs__msg__Int64MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Int64MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Int64MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/Int8.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int8__idl 18 | #define __std_msgs__msg__Int8__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct Int8 { 23 | octet data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__Int8__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Int8MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Int8MultiArray__idl 18 | #define __std_msgs__msg__Int8MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct Int8MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__Int8MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/MultiArrayDimension.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__MultiArrayDimension__idl 18 | #define __std_msgs__msg__MultiArrayDimension__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct MultiArrayDimension { 23 | string label; 24 | unsigned long size; 25 | unsigned long stride; 26 | }; 27 | 28 | }; }; // module msg::std_msgs 29 | 30 | #endif // __std_msgs__msg__MultiArrayDimension__idl 31 | -------------------------------------------------------------------------------- /std_msgs/msg/MultiArrayLayout.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__MultiArrayLayout__idl 18 | #define __std_msgs__msg__MultiArrayLayout__idl 19 | 20 | #include "MultiArrayDimension.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct MultiArrayLayout { 25 | sequence dim; 26 | unsigned long data_offset; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__MultiArrayLayout__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/String.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__String__idl 18 | #define __std_msgs__msg__String__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct String { 23 | string data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__String__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/Time.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__Time__idl 18 | #define __std_msgs__msg__Time__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | @nested 23 | struct Time { 24 | long sec; 25 | unsigned long nanosec; 26 | }; 27 | 28 | }; }; // module msg::std_msgs 29 | 30 | #endif // __std_msgs__msg__Time__idl 31 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt16.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt16__idl 18 | #define __std_msgs__msg__UInt16__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct UInt16 { 23 | unsigned short data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__UInt16__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt16MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt16MultiArray__idl 18 | #define __std_msgs__msg__UInt16MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct UInt16MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__UInt16MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt32.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt32__idl 18 | #define __std_msgs__msg__UInt32__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct UInt32 { 23 | unsigned long data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__UInt32__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt32MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt32MultiArray__idl 18 | #define __std_msgs__msg__UInt32MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct UInt32MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__UInt32MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt64.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt64__idl 18 | #define __std_msgs__msg__UInt64__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct UInt64 { 23 | unsigned long long data; 24 | }; 25 | 26 | 27 | }; }; // module msg::std_msgs 28 | 29 | #endif // __std_msgs__msg__UInt64__idl 30 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt64MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt64MultiArray__idl 18 | #define __std_msgs__msg__UInt64MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct UInt64MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__UInt64MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt8.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt8__idl 18 | #define __std_msgs__msg__UInt8__idl 19 | 20 | module std_msgs { module msg { 21 | 22 | struct UInt8 { 23 | octet data; 24 | }; 25 | 26 | }; }; // module msg::std_msgs 27 | 28 | #endif // __std_msgs__msg__UInt8__idl 29 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt8MultiArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_msgs__msg__UInt8MultiArray__idl 18 | #define __std_msgs__msg__UInt8MultiArray__idl 19 | 20 | #include "MultiArrayLayout.idl" 21 | 22 | module std_msgs { module msg { 23 | 24 | struct UInt8MultiArray { 25 | std_msgs::msg::MultiArrayLayout layout; 26 | sequence data; 27 | }; 28 | 29 | }; }; // module msg::std_msgs 30 | 31 | #endif // __std_msgs__msg__UInt8MultiArray__idl 32 | -------------------------------------------------------------------------------- /std_msgs/srv/Empty_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__Empty_Request__idl 18 | #define __std_srvs__srv__Empty_Request__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct Empty_Request { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module srv::std_srvs 27 | 28 | #endif // __std_srvs__srv__Empty_Request__idl 29 | -------------------------------------------------------------------------------- /std_msgs/srv/Empty_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__Empty_Response__idl 18 | #define __std_srvs__srv__Empty_Response__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct Empty_Response { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module srv::std_srvs 27 | 28 | #endif // __std_srvs__srv__Empty_Response__idl 29 | -------------------------------------------------------------------------------- /std_msgs/srv/SetBool_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__SetBool_Request__idl 18 | #define __std_srvs__srv__SetBool_Request__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct SetBool_Request { 23 | boolean data; 24 | }; 25 | 26 | }; }; // module srv::std_srvs 27 | 28 | #endif // __std_srvs__srv__SetBool_Request__idl 29 | -------------------------------------------------------------------------------- /std_msgs/srv/SetBool_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__SetBool_Response__idl 18 | #define __std_srvs__srv__SetBool_Response__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct SetBool_Response { 23 | boolean success; 24 | string message; 25 | }; 26 | 27 | }; }; // module srv::std_srvs 28 | 29 | #endif // __std_srvs__srv__SetBool_Response__idl 30 | -------------------------------------------------------------------------------- /std_msgs/srv/Trigger_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__Trigger_Request__idl 18 | #define __std_srvs__srv__Trigger_Request__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct Trigger_Request { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module srv::std_srvs 27 | 28 | #endif // __std_srvs__srv__Trigger_Request__idl 29 | -------------------------------------------------------------------------------- /std_msgs/srv/Trigger_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __std_srvs__srv__Trigger_Response__idl 18 | #define __std_srvs__srv__Trigger_Response__idl 19 | 20 | module std_srvs { module srv { 21 | 22 | struct Trigger_Response { 23 | boolean success; 24 | string message; 25 | }; 26 | 27 | }; }; // module srv::std_srvs 28 | 29 | #endif // __std_srvs__srv__Trigger_Response__idl 30 | -------------------------------------------------------------------------------- /stereo_msgs/msg/DisparityImage.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __stereo_msgs__msg__DisparityImage__idl 18 | #define __stereo_msgs__msg__DisparityImage__idl 19 | 20 | #include "sensor_msgs/msg/Image.idl" 21 | #include "sensor_msgs/msg/RegionOfInterest.idl" 22 | #include "std_msgs/msg/Header.idl" 23 | 24 | module stereo_msgs { module msg { 25 | 26 | struct DisparityImage { 27 | std_msgs::msg::Header header; 28 | sensor_msgs::msg::Image image; 29 | float f; 30 | float t; 31 | sensor_msgs::msg::RegionOfInterest valid_window; 32 | float min_disparity; 33 | float max_disparity; 34 | float delta_d; 35 | }; 36 | 37 | }; }; // module msg::stereo_msgs 38 | 39 | #endif // __stereo_msgs__msg__DisparityImage__idl 40 | -------------------------------------------------------------------------------- /test_msgs/msg/BoundedArrayNested.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__BoundedArrayNested__idl 18 | #define __test_msgs__msg__BoundedArrayNested__idl 19 | 20 | #include "Primitives.idl" 21 | 22 | module test_msgs { module msg { 23 | 24 | struct BoundedArrayNested { 25 | sequence primitive_values; 26 | }; 27 | 28 | }; }; // module msg::test_msgs 29 | 30 | #endif // __test_msgs__msg__BoundedArrayNested__idl 31 | -------------------------------------------------------------------------------- /test_msgs/msg/Builtins.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__Builtins__idl 18 | #define __test_msgs__msg__Builtins__idl 19 | 20 | #include "std_msgs/msg/Duration.idl" 21 | #include "std_msgs/msg/Time.idl" 22 | 23 | module test_msgs { module msg { 24 | 25 | struct Builtins { 26 | std_msgs::msg::Duration duration_value; 27 | std_msgs::msg::Time time_value; 28 | }; 29 | 30 | }; }; // module msg::test_msgs 31 | 32 | #endif // __test_msgs__msg__Builtins__idl 33 | -------------------------------------------------------------------------------- /test_msgs/msg/DynamicArrayNested.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__DynamicArrayNested__idl 18 | #define __test_msgs__msg__DynamicArrayNested__idl 19 | 20 | #include "Primitives.idl" 21 | 22 | module test_msgs { module msg { 23 | 24 | struct DynamicArrayNested { 25 | sequence primitive_values; 26 | }; 27 | 28 | }; }; // module msg::test_msgs 29 | 30 | #endif // __test_msgs__msg__DynamicArrayNested__idl 31 | -------------------------------------------------------------------------------- /test_msgs/msg/DynamicArrayPrimitivesNested.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__DynamicArrayPrimitivesNested__idl 18 | #define __test_msgs__msg__DynamicArrayPrimitivesNested__idl 19 | 20 | #include "DynamicArrayPrimitives.idl" 21 | 22 | module test_msgs { module msg { 23 | 24 | struct DynamicArrayPrimitivesNested { 25 | sequence dynamic_array_primitive_values; 26 | }; 27 | 28 | }; }; // module msg::test_msgs 29 | 30 | #endif // __test_msgs__msg__DynamicArrayPrimitivesNested__idl 31 | -------------------------------------------------------------------------------- /test_msgs/msg/Empty.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__Empty__idl 18 | #define __test_msgs__msg__Empty__idl 19 | 20 | module test_msgs { module msg { 21 | 22 | struct Empty { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module msg::test_msgs 27 | 28 | #endif // __test_msgs__msg__Empty__idl 29 | -------------------------------------------------------------------------------- /test_msgs/msg/Nested.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__Nested__idl 18 | #define __test_msgs__msg__Nested__idl 19 | 20 | #include "Primitives.idl" 21 | 22 | module test_msgs { module msg { 23 | 24 | struct Nested { 25 | test_msgs::msg::Primitives primitive_values; 26 | }; 27 | 28 | }; }; // module msg::test_msgs 29 | 30 | #endif // __test_msgs__msg__Nested__idl 31 | -------------------------------------------------------------------------------- /test_msgs/msg/Primitives.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__Primitives__idl 18 | #define __test_msgs__msg__Primitives__idl 19 | 20 | module test_msgs { module msg { 21 | 22 | struct Primitives { 23 | boolean bool_value; 24 | octet byte_value; 25 | char char_value; 26 | float float32_value; 27 | double float64_value; 28 | octet int8_value; 29 | octet uint8_value; 30 | short int16_value; 31 | unsigned short uint16_value; 32 | long int32_value; 33 | unsigned long uint32_value; 34 | long long int64_value; 35 | unsigned long long uint64_value; 36 | string string_value; 37 | }; 38 | 39 | }; }; // module msg::test_msgs 40 | 41 | #endif // __test_msgs__msg__Primitives__idl 42 | -------------------------------------------------------------------------------- /test_msgs/msg/StaticArrayNested.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__msg__StaticArrayNested__idl 18 | #define __test_msgs__msg__StaticArrayNested__idl 19 | 20 | #include "Primitives.idl" 21 | 22 | module test_msgs { module msg { 23 | 24 | typedef test_msgs::msg::Primitives test_msgs__StaticArrayNested__test_msgs__msg__dds___Primitives__array_4[4]; 25 | 26 | struct StaticArrayNested { 27 | test_msgs__StaticArrayNested__test_msgs__msg__dds___Primitives__array_4 primitive_values; 28 | }; 29 | 30 | }; }; // module msg::test_msgs 31 | 32 | #endif // __test_msgs__msg__StaticArrayNested__idl 33 | -------------------------------------------------------------------------------- /test_msgs/srv/Empty_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__srv__Empty_Request__idl 18 | #define __test_msgs__srv__Empty_Request__idl 19 | 20 | module test_msgs { module srv { 21 | 22 | struct Empty_Request { 23 | boolean _dummy; 24 | }; 25 | 26 | }; }; // module srv::test_msgs 27 | 28 | #endif // __test_msgs__srv__Empty_Request__idl 29 | -------------------------------------------------------------------------------- /test_msgs/srv/Empty_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __test_msgs__srv__Empty_Response__idl 18 | #define __test_msgs__srv__Empty_Response__idl 19 | 20 | module test_msgs { module srv { 21 | 22 | struct Empty_Response { 23 | boolean _dummy; 24 | }; 25 | 26 | }; }; // module srv::test_msgs 27 | 28 | #endif // __test_msgs__srv__Empty_Response__idl 29 | -------------------------------------------------------------------------------- /tf2_msgs/msg/TF2Error.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __tf2_msgs__msg__TF2Error__idl 18 | #define __tf2_msgs__msg__TF2Error__idl 19 | 20 | module tf2_msgs { module msg { 21 | 22 | const octet TF2Error__NO_ERROR = 0; 23 | const octet TF2Error__LOOKUP_ERROR = 1; 24 | const octet TF2Error__CONNECTIVITY_ERROR = 2; 25 | const octet TF2Error__EXTRAPOLATION_ERROR = 3; 26 | const octet TF2Error__INVALID_ARGUMENT_ERROR = 4; 27 | const octet TF2Error__TIMEOUT_ERROR = 5; 28 | const octet TF2Error__TRANSFORM_ERROR = 6; 29 | 30 | struct TF2Error { 31 | octet error; 32 | string error_string; 33 | }; 34 | 35 | }; }; // module msg::tf2_msgs 36 | 37 | #endif // __tf2_msgs__msg__TF2Error__idl 38 | -------------------------------------------------------------------------------- /tf2_msgs/msg/TFMessage.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __tf2_msgs__msg__TFMessage__idl 18 | #define __tf2_msgs__msg__TFMessage__idl 19 | 20 | #include "geometry_msgs/msg/TransformStamped.idl" 21 | 22 | module tf2_msgs { module msg { 23 | 24 | struct TFMessage { 25 | sequence transforms; 26 | }; 27 | 28 | }; }; // module msg::tf2_msgs 29 | 30 | #endif // __tf2_msgs__msg__TFMessage__idl 31 | -------------------------------------------------------------------------------- /tf2_msgs/srv/FrameGraph_Request.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __tf2_msgs__srv__FrameGraph_Request__idl 18 | #define __tf2_msgs__srv__FrameGraph_Request__idl 19 | 20 | module tf2_msgs { module srv { 21 | 22 | struct FrameGraph_Request { 23 | boolean dummy; 24 | }; 25 | 26 | }; }; // module srv::tf2_msgs 27 | 28 | #endif // __tf2_msgs__srv__FrameGraph_Request__idl 29 | -------------------------------------------------------------------------------- /tf2_msgs/srv/FrameGraph_Response.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __tf2_msgs__srv__FrameGraph_Response__idl 18 | #define __tf2_msgs__srv__FrameGraph_Response__idl 19 | 20 | module tf2_msgs { module srv { 21 | 22 | struct FrameGraph_Response { 23 | string frame_yaml; 24 | }; 25 | 26 | }; }; // module srv::tf2_msgs 27 | 28 | #endif // __tf2_msgs__srv__FrameGraph_Response__idl 29 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectory.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __trajectory_msgs__msg__JointTrajectory__idl 18 | #define __trajectory_msgs__msg__JointTrajectory__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | #include "JointTrajectoryPoint.idl" 22 | 23 | module trajectory_msgs { module msg { 24 | 25 | struct JointTrajectory { 26 | std_msgs::msg::Header header; 27 | sequence joint_names; 28 | sequence points; 29 | }; 30 | 31 | }; }; // module msg::trajectory_msgs 32 | 33 | #endif // __trajectory_msgs__msg__JointTrajectory__idl 34 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectoryPoint.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __trajectory_msgs__msg__JointTrajectoryPoint__idl 18 | #define __trajectory_msgs__msg__JointTrajectoryPoint__idl 19 | 20 | #include "std_msgs/msg/Duration.idl" 21 | 22 | module trajectory_msgs { module msg { 23 | 24 | struct JointTrajectoryPoint { 25 | sequence positions; 26 | sequence velocities; 27 | sequence accelerations; 28 | sequence effort; 29 | std_msgs::msg::Duration time_from_start; 30 | }; 31 | 32 | }; }; // module msg::trajectory_msgs 33 | 34 | #endif // __trajectory_msgs__msg__JointTrajectoryPoint__idl 35 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/MultiDOFJointTrajectory.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __trajectory_msgs__msg__MultiDOFJointTrajectory__idl 18 | #define __trajectory_msgs__msg__MultiDOFJointTrajectory__idl 19 | 20 | #include "std_msgs/msg/Header.idl" 21 | #include "MultiDOFJointTrajectoryPoint.idl" 22 | 23 | module trajectory_msgs { module msg { 24 | 25 | struct MultiDOFJointTrajectory { 26 | std_msgs::msg::Header header; 27 | sequence joint_names; 28 | sequence points; 29 | }; 30 | 31 | }; }; // module msg::trajectory_msgs 32 | 33 | #endif // __trajectory_msgs__msg__MultiDOFJointTrajectory__idl 34 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerInit.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __visualization_msgs__msg__InteractiveMarkerInit__idl 18 | #define __visualization_msgs__msg__InteractiveMarkerInit__idl 19 | 20 | #include "InteractiveMarker.idl" 21 | 22 | module visualization_msgs { module msg { 23 | 24 | struct InteractiveMarkerInit { 25 | string server_id; 26 | unsigned long long seq_num; 27 | sequence markers; 28 | }; 29 | 30 | }; }; // module msg::visualization_msgs 31 | 32 | #endif // __visualization_msgs__msg__InteractiveMarkerInit__idl 33 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerPose.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __visualization_msgs__msg__InteractiveMarkerPose__idl 18 | #define __visualization_msgs__msg__InteractiveMarkerPose__idl 19 | 20 | #include "geometry_msgs/msg/Pose.idl" 21 | #include "std_msgs/msg/Header.idl" 22 | 23 | module visualization_msgs { module msg { 24 | 25 | struct InteractiveMarkerPose { 26 | std_msgs::msg::Header header; 27 | geometry_msgs::msg::Pose pose; 28 | string name; 29 | }; 30 | 31 | }; }; // module msg::visualization_msgs 32 | 33 | #endif // __visualization_msgs__msg__InteractiveMarkerPose__idl 34 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MarkerArray.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __visualization_msgs__msg__MarkerArray__idl 18 | #define __visualization_msgs__msg__MarkerArray__idl 19 | 20 | #include "Marker.idl" 21 | 22 | module visualization_msgs { module msg { 23 | 24 | struct MarkerArray { 25 | sequence markers; 26 | }; 27 | 28 | }; }; // module msg::visualization_msgs 29 | 30 | #endif // __visualization_msgs__msg__MarkerArray__idl 31 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MenuEntry.idl: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2012-2018 Open Source Robotics Foundation 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef __visualization_msgs__msg__MenuEntry__idl 18 | #define __visualization_msgs__msg__MenuEntry__idl 19 | 20 | module visualization_msgs { module msg { 21 | 22 | const octet MenuEntry__FEEDBACK = 0; 23 | const octet MenuEntry__ROSRUN = 1; 24 | const octet MenuEntry__ROSLAUNCH = 2; 25 | 26 | struct MenuEntry { 27 | unsigned long id; 28 | unsigned long parent_id; 29 | string title; 30 | string command; 31 | octet command_type; 32 | }; 33 | 34 | }; }; // module msg::visualization_msgs 35 | 36 | #endif // __visualization_msgs__msg__MenuEntry__idl 37 | --------------------------------------------------------------------------------